From 2640fbd48aac93c431daf7c44f36a9d6ad4b634f Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 15 May 2016 19:25:58 +0200 Subject: [PATCH 001/248] Start replacing NULL constant by nullptr --- src/body/Body.cpp | 2 +- src/body/CollisionBody.cpp | 36 +++++++------- src/body/RigidBody.cpp | 20 ++++---- src/collision/CollisionDetection.cpp | 14 +++--- src/collision/ProxyShape.cpp | 4 +- src/collision/RaycastInfo.h | 2 +- .../broadphase/BroadPhaseAlgorithm.cpp | 10 ++-- .../narrowphase/ConcaveVsConvexAlgorithm.cpp | 2 +- .../narrowphase/DefaultCollisionDispatch.cpp | 2 +- .../narrowphase/EPA/EPAAlgorithm.cpp | 12 ++--- src/collision/narrowphase/EPA/EdgeEPA.cpp | 6 +-- .../narrowphase/EPA/TrianglesStore.h | 4 +- .../narrowphase/NarrowPhaseAlgorithm.cpp | 2 +- src/collision/shapes/ConeShape.cpp | 2 +- src/collision/shapes/ConvexMeshShape.cpp | 4 +- src/constraint/Joint.cpp | 4 +- src/constraint/Joint.h | 2 +- src/engine/CollisionWorld.cpp | 10 ++-- src/engine/ConstraintSolver.cpp | 6 +-- src/engine/ConstraintSolver.h | 12 ++--- src/engine/ContactSolver.cpp | 16 +++---- src/engine/ContactSolver.h | 8 ++-- src/engine/DynamicsWorld.cpp | 48 +++++++++---------- src/engine/DynamicsWorld.h | 2 +- src/engine/Island.cpp | 2 +- src/engine/Profiler.cpp | 22 ++++----- src/engine/Profiler.h | 4 +- src/engine/Timer.cpp | 2 +- src/memory/MemoryAllocator.cpp | 8 ++-- test/TestSuite.cpp | 16 +++---- test/tests/collision/TestRaycast.h | 6 +-- testbed/common/Box.cpp | 2 +- 32 files changed, 145 insertions(+), 147 deletions(-) diff --git a/src/body/Body.cpp b/src/body/Body.cpp index 7974a6b9..b143321e 100644 --- a/src/body/Body.cpp +++ b/src/body/Body.cpp @@ -36,7 +36,7 @@ using namespace reactphysics3d; */ Body::Body(bodyindex id) : mID(id), mIsAlreadyInIsland(false), mIsAllowedToSleep(true), mIsActive(true), - mIsSleeping(false), mSleepTime(0), mUserData(NULL) { + mIsSleeping(false), mSleepTime(0), mUserData(nullptr) { } diff --git a/src/body/CollisionBody.cpp b/src/body/CollisionBody.cpp index e5a51b91..83052131 100644 --- a/src/body/CollisionBody.cpp +++ b/src/body/CollisionBody.cpp @@ -38,14 +38,14 @@ using namespace reactphysics3d; * @param id ID of the body */ CollisionBody::CollisionBody(const Transform& transform, CollisionWorld& world, bodyindex id) - : Body(id), mType(DYNAMIC), mTransform(transform), mProxyCollisionShapes(NULL), - mNbCollisionShapes(0), mContactManifoldsList(NULL), mWorld(world) { + : Body(id), mType(DYNAMIC), mTransform(transform), mProxyCollisionShapes(nullptr), + mNbCollisionShapes(0), mContactManifoldsList(nullptr), mWorld(world) { } // Destructor CollisionBody::~CollisionBody() { - assert(mContactManifoldsList == NULL); + assert(mContactManifoldsList == nullptr); // Remove all the proxy collision shapes of the body removeAllCollisionShapes(); @@ -75,7 +75,7 @@ ProxyShape* CollisionBody::addCollisionShape(CollisionShape* collisionShape, transform, decimal(1)); // Add it to the list of proxy collision shapes of the body - if (mProxyCollisionShapes == NULL) { + if (mProxyCollisionShapes == nullptr) { mProxyCollisionShapes = proxyShape; } else { @@ -122,7 +122,7 @@ void CollisionBody::removeCollisionShape(const ProxyShape* proxyShape) { } // Look for the proxy shape that contains the collision shape in parameter - while(current->mNext != NULL) { + while(current->mNext != nullptr) { // If we have found the collision shape to remove if (current->mNext == proxyShape) { @@ -152,7 +152,7 @@ void CollisionBody::removeAllCollisionShapes() { ProxyShape* current = mProxyCollisionShapes; // Look for the proxy shape that contains the collision shape in parameter - while(current != NULL) { + while(current != nullptr) { // Remove the proxy collision shape ProxyShape* nextElement = current->mNext; @@ -168,7 +168,7 @@ void CollisionBody::removeAllCollisionShapes() { current = nextElement; } - mProxyCollisionShapes = NULL; + mProxyCollisionShapes = nullptr; } // Reset the contact manifold lists @@ -176,7 +176,7 @@ void CollisionBody::resetContactManifoldsList() { // Delete the linked list of contact manifolds of that body ContactManifoldListElement* currentElement = mContactManifoldsList; - while (currentElement != NULL) { + while (currentElement != nullptr) { ContactManifoldListElement* nextElement = currentElement->next; // Delete the current element @@ -185,14 +185,14 @@ void CollisionBody::resetContactManifoldsList() { currentElement = nextElement; } - mContactManifoldsList = NULL; + mContactManifoldsList = nullptr; } // Update the broad-phase state for this body (because it has moved for instance) void CollisionBody::updateBroadPhaseState() const { // For all the proxy collision shapes of the body - for (ProxyShape* shape = mProxyCollisionShapes; shape != NULL; shape = shape->mNext) { + for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) { // Update the proxy updateProxyShapeInBroadPhase(shape); @@ -225,7 +225,7 @@ void CollisionBody::setIsActive(bool isActive) { if (isActive) { // For each proxy shape of the body - for (ProxyShape* shape = mProxyCollisionShapes; shape != NULL; shape = shape->mNext) { + for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) { // Compute the world-space AABB of the new collision shape AABB aabb; @@ -238,7 +238,7 @@ void CollisionBody::setIsActive(bool isActive) { else { // If we have to deactivate the body // For each proxy shape of the body - for (ProxyShape* shape = mProxyCollisionShapes; shape != NULL; shape = shape->mNext) { + for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) { // Remove the proxy shape from the collision detection mWorld.mCollisionDetection.removeProxyCollisionShape(shape); @@ -254,7 +254,7 @@ void CollisionBody::setIsActive(bool isActive) { void CollisionBody::askForBroadPhaseCollisionCheck() const { // For all the proxy collision shapes of the body - for (ProxyShape* shape = mProxyCollisionShapes; shape != NULL; shape = shape->mNext) { + for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) { mWorld.mCollisionDetection.askForBroadPhaseCollisionCheck(shape); } @@ -271,7 +271,7 @@ int CollisionBody::resetIsAlreadyInIslandAndCountManifolds() { // Reset the mIsAlreadyInIsland variable of the contact manifolds for // this body ContactManifoldListElement* currentElement = mContactManifoldsList; - while (currentElement != NULL) { + while (currentElement != nullptr) { currentElement->contactManifold->mIsAlreadyInIsland = false; currentElement = currentElement->next; nbManifolds++; @@ -289,7 +289,7 @@ int CollisionBody::resetIsAlreadyInIslandAndCountManifolds() { bool CollisionBody::testPointInside(const Vector3& worldPoint) const { // For each collision shape of the body - for (ProxyShape* shape = mProxyCollisionShapes; shape != NULL; shape = shape->mNext) { + for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) { // Test if the point is inside the collision shape if (shape->testPointInside(worldPoint)) return true; @@ -315,7 +315,7 @@ bool CollisionBody::raycast(const Ray& ray, RaycastInfo& raycastInfo) { Ray rayTemp(ray); // For each collision shape of the body - for (ProxyShape* shape = mProxyCollisionShapes; shape != NULL; shape = shape->mNext) { + for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) { // Test if the ray hits the collision shape if (shape->raycast(rayTemp, raycastInfo)) { @@ -335,12 +335,12 @@ AABB CollisionBody::getAABB() const { AABB bodyAABB; - if (mProxyCollisionShapes == NULL) return bodyAABB; + if (mProxyCollisionShapes == nullptr) return bodyAABB; mProxyCollisionShapes->getCollisionShape()->computeAABB(bodyAABB, mTransform * mProxyCollisionShapes->getLocalToBodyTransform()); // For each proxy shape of the body - for (ProxyShape* shape = mProxyCollisionShapes->mNext; shape != NULL; shape = shape->mNext) { + for (ProxyShape* shape = mProxyCollisionShapes->mNext; shape != nullptr; shape = shape->mNext) { // Compute the world-space AABB of the collision shape AABB aabb; diff --git a/src/body/RigidBody.cpp b/src/body/RigidBody.cpp index 1a54b935..ff7fc8dd 100644 --- a/src/body/RigidBody.cpp +++ b/src/body/RigidBody.cpp @@ -42,7 +42,7 @@ RigidBody::RigidBody(const Transform& transform, CollisionWorld& world, bodyinde : CollisionBody(transform, world, id), mInitMass(decimal(1.0)), mCenterOfMassLocal(0, 0, 0), mCenterOfMassWorld(transform.getPosition()), mIsGravityEnabled(true), mLinearDamping(decimal(0.0)), mAngularDamping(decimal(0.0)), - mJointsList(NULL) { + mJointsList(nullptr) { // Compute the inverse mass mMassInverse = decimal(1.0) / mInitMass; @@ -50,7 +50,7 @@ RigidBody::RigidBody(const Transform& transform, CollisionWorld& world, bodyinde // Destructor RigidBody::~RigidBody() { - assert(mJointsList == NULL); + assert(mJointsList == nullptr); } // Set the type of the body @@ -168,8 +168,8 @@ void RigidBody::setMass(decimal mass) { // Remove a joint from the joints list void RigidBody::removeJointFromJointsList(MemoryAllocator& memoryAllocator, const Joint* joint) { - assert(joint != NULL); - assert(mJointsList != NULL); + assert(joint != nullptr); + assert(mJointsList != nullptr); // Remove the joint from the linked list of the joints of the first body if (mJointsList->joint == joint) { // If the first element is the one to remove @@ -180,7 +180,7 @@ void RigidBody::removeJointFromJointsList(MemoryAllocator& memoryAllocator, cons } else { // If the element to remove is not the first one in the list JointListElement* currentElement = mJointsList; - while (currentElement->next != NULL) { + while (currentElement->next != nullptr) { if (currentElement->next->joint == joint) { JointListElement* elementToRemove = currentElement->next; currentElement->next = elementToRemove->next; @@ -213,15 +213,13 @@ ProxyShape* RigidBody::addCollisionShape(CollisionShape* collisionShape, const Transform& transform, decimal mass) { - assert(mass > decimal(0.0)); - // Create a new proxy collision shape to attach the collision shape to the body ProxyShape* proxyShape = new (mWorld.mMemoryAllocator.allocate( sizeof(ProxyShape))) ProxyShape(this, collisionShape, transform, mass); // Add it to the list of proxy collision shapes of the body - if (mProxyCollisionShapes == NULL) { + if (mProxyCollisionShapes == nullptr) { mProxyCollisionShapes = proxyShape; } else { @@ -339,7 +337,7 @@ void RigidBody::recomputeMassInformation() { assert(mType == DYNAMIC); // Compute the total mass of the body - for (ProxyShape* shape = mProxyCollisionShapes; shape != NULL; shape = shape->mNext) { + for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) { mInitMass += shape->getMass(); mCenterOfMassLocal += shape->getLocalToBodyTransform().getPosition() * shape->getMass(); } @@ -358,7 +356,7 @@ void RigidBody::recomputeMassInformation() { mCenterOfMassWorld = mTransform * mCenterOfMassLocal; // Compute the total mass and inertia tensor using all the collision shapes - for (ProxyShape* shape = mProxyCollisionShapes; shape != NULL; shape = shape->mNext) { + for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) { // Get the inertia tensor of the collision shape in its local-space Matrix3x3 inertiaTensor; @@ -401,7 +399,7 @@ void RigidBody::updateBroadPhaseState() const { const Vector3 displacement = world.mTimeStep * mLinearVelocity; // For all the proxy collision shapes of the body - for (ProxyShape* shape = mProxyCollisionShapes; shape != NULL; shape = shape->mNext) { + for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) { // Recompute the world-space AABB of the collision shape AABB aabb; diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index ea469ccb..5e895c7f 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -140,7 +140,7 @@ void CollisionDetection::reportCollisionBetweenShapes(CollisionCallback* callbac contactPoint->getLocalPointOnBody2()); // Notify the collision callback about this new contact - if (callback != NULL) callback->notifyContact(contactInfo); + if (callback != nullptr) callback->notifyContact(contactInfo); } } } @@ -223,7 +223,7 @@ void CollisionDetection::computeNarrowPhase() { NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Type][shape2Type]; // If there is no collision algorithm between those two kinds of shapes - if (narrowPhaseAlgorithm == NULL) continue; + if (narrowPhaseAlgorithm == nullptr) continue; // Notify the narrow-phase algorithm about the overlapping pair we are going to test narrowPhaseAlgorithm->setCurrentOverlappingPair(pair); @@ -325,7 +325,7 @@ void CollisionDetection::computeNarrowPhaseBetweenShapes(CollisionCallback* call NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Type][shape2Type]; // If there is no collision algorithm between those two kinds of shapes - if (narrowPhaseAlgorithm == NULL) continue; + if (narrowPhaseAlgorithm == nullptr) continue; // Notify the narrow-phase algorithm about the overlapping pair we are going to test narrowPhaseAlgorithm->setCurrentOverlappingPair(pair); @@ -373,7 +373,7 @@ void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, Pro // Create the overlapping pair and add it into the set of overlapping pairs OverlappingPair* newPair = new (mWorld->mMemoryAllocator.allocate(sizeof(OverlappingPair))) OverlappingPair(shape1, shape2, nbMaxManifolds, mWorld->mMemoryAllocator); - assert(newPair != NULL); + assert(newPair != nullptr); #ifndef NDEBUG std::pair::iterator, bool> check = @@ -420,14 +420,14 @@ void CollisionDetection::notifyContact(OverlappingPair* overlappingPair, const C if (overlappingPair->getNbContactPoints() == 0) { // Trigger a callback event - if (mWorld->mEventListener != NULL) mWorld->mEventListener->beginContact(contactInfo); + if (mWorld->mEventListener != nullptr) mWorld->mEventListener->beginContact(contactInfo); } // Create a new contact createContact(overlappingPair, contactInfo); // Trigger a callback event for the new contact - if (mWorld->mEventListener != NULL) mWorld->mEventListener->newContact(contactInfo); + if (mWorld->mEventListener != nullptr) mWorld->mEventListener->newContact(contactInfo); } // Create a new contact @@ -463,7 +463,7 @@ void CollisionDetection::addAllContactManifoldsToBodies() { // in the corresponding contact void CollisionDetection::addContactManifoldToBody(OverlappingPair* pair) { - assert(pair != NULL); + assert(pair != nullptr); CollisionBody* body1 = pair->getShape1()->getBody(); CollisionBody* body2 = pair->getShape2()->getBody(); diff --git a/src/collision/ProxyShape.cpp b/src/collision/ProxyShape.cpp index 0e416370..50418011 100644 --- a/src/collision/ProxyShape.cpp +++ b/src/collision/ProxyShape.cpp @@ -37,7 +37,7 @@ using namespace reactphysics3d; */ ProxyShape::ProxyShape(CollisionBody* body, CollisionShape* shape, const Transform& transform, decimal mass) :mBody(body), mCollisionShape(shape), mLocalToBodyTransform(transform), mMass(mass), - mNext(NULL), mBroadPhaseID(-1), mCachedCollisionData(NULL), mUserData(NULL), + mNext(nullptr), mBroadPhaseID(-1), mCachedCollisionData(nullptr), mUserData(nullptr), mCollisionCategoryBits(0x0001), mCollideWithMaskBits(0xFFFF) { } @@ -46,7 +46,7 @@ ProxyShape::ProxyShape(CollisionBody* body, CollisionShape* shape, const Transfo ProxyShape::~ProxyShape() { // Release the cached collision data memory - if (mCachedCollisionData != NULL) { + if (mCachedCollisionData != nullptr) { free(mCachedCollisionData); } } diff --git a/src/collision/RaycastInfo.h b/src/collision/RaycastInfo.h index 1b86de54..753353f3 100644 --- a/src/collision/RaycastInfo.h +++ b/src/collision/RaycastInfo.h @@ -83,7 +83,7 @@ struct RaycastInfo { // -------------------- Methods -------------------- // /// Constructor - RaycastInfo() : meshSubpart(-1), triangleIndex(-1), body(NULL), proxyShape(NULL) { + RaycastInfo() : meshSubpart(-1), triangleIndex(-1), body(nullptr), proxyShape(nullptr) { } diff --git a/src/collision/broadphase/BroadPhaseAlgorithm.cpp b/src/collision/broadphase/BroadPhaseAlgorithm.cpp index cfb6acd8..781273e5 100644 --- a/src/collision/broadphase/BroadPhaseAlgorithm.cpp +++ b/src/collision/broadphase/BroadPhaseAlgorithm.cpp @@ -39,11 +39,11 @@ BroadPhaseAlgorithm::BroadPhaseAlgorithm(CollisionDetection& collisionDetection) // Allocate memory for the array of non-static proxy shapes IDs mMovedShapes = (int*) malloc(mNbAllocatedMovedShapes * sizeof(int)); - assert(mMovedShapes != NULL); + assert(mMovedShapes != nullptr); // Allocate memory for the array of potential overlapping pairs mPotentialPairs = (BroadPhasePair*) malloc(mNbAllocatedPotentialPairs * sizeof(BroadPhasePair)); - assert(mPotentialPairs != NULL); + assert(mPotentialPairs != nullptr); } // Destructor @@ -65,14 +65,14 @@ void BroadPhaseAlgorithm::addMovedCollisionShape(int broadPhaseID) { mNbAllocatedMovedShapes *= 2; int* oldArray = mMovedShapes; mMovedShapes = (int*) malloc(mNbAllocatedMovedShapes * sizeof(int)); - assert(mMovedShapes != NULL); + assert(mMovedShapes != nullptr); memcpy(mMovedShapes, oldArray, mNbMovedShapes * sizeof(int)); free(oldArray); } // Store the broad-phase ID into the array of shapes that have moved assert(mNbMovedShapes < mNbAllocatedMovedShapes); - assert(mMovedShapes != NULL); + assert(mMovedShapes != nullptr); mMovedShapes[mNbMovedShapes] = broadPhaseID; mNbMovedShapes++; } @@ -91,7 +91,7 @@ void BroadPhaseAlgorithm::removeMovedCollisionShape(int broadPhaseID) { mNbAllocatedMovedShapes /= 2; int* oldArray = mMovedShapes; mMovedShapes = (int*) malloc(mNbAllocatedMovedShapes * sizeof(int)); - assert(mMovedShapes != NULL); + assert(mMovedShapes != nullptr); uint nbElements = 0; for (uint i=0; igetType()); // If there is no collision algorithm between those two kinds of shapes - if (algo == NULL) return; + if (algo == nullptr) return; // Notify the narrow-phase algorithm about the overlapping pair we are going to test algo->setCurrentOverlappingPair(mOverlappingPair); diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.cpp b/src/collision/narrowphase/DefaultCollisionDispatch.cpp index 8e3f6930..0b0df8d7 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.cpp +++ b/src/collision/narrowphase/DefaultCollisionDispatch.cpp @@ -70,6 +70,6 @@ NarrowPhaseAlgorithm* DefaultCollisionDispatch::selectAlgorithm(int type1, int t return &mGJKAlgorithm; } else { - return NULL; + return nullptr; } } diff --git a/src/collision/narrowphase/EPA/EPAAlgorithm.cpp b/src/collision/narrowphase/EPA/EPAAlgorithm.cpp index 513ca367..03647182 100644 --- a/src/collision/narrowphase/EPA/EPAAlgorithm.cpp +++ b/src/collision/narrowphase/EPA/EPAAlgorithm.cpp @@ -231,7 +231,7 @@ void EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simple TriangleEPA* face3 = triangleStore.newTriangle(points, 1, 3, 2); // If the constructed tetrahedron is not correct - if (!((face0 != NULL) && (face1 != NULL) && (face2 != NULL) && (face3 != NULL) + if (!((face0 != nullptr) && (face1 != nullptr) && (face2 != nullptr) && (face3 != nullptr) && face0->getDistSquare() > 0.0 && face1->getDistSquare() > 0.0 && face2->getDistSquare() > 0.0 && face3->getDistSquare() > 0.0)) { return; @@ -289,10 +289,10 @@ void EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simple shape2->getLocalSupportPointWithMargin(rotateToBody2 * n, shape2CachedCollisionData); points[4] = suppPointsA[4] - suppPointsB[4]; - TriangleEPA* face0 = NULL; - TriangleEPA* face1 = NULL; - TriangleEPA* face2 = NULL; - TriangleEPA* face3 = NULL; + TriangleEPA* face0 = nullptr; + TriangleEPA* face1 = nullptr; + TriangleEPA* face2 = nullptr; + TriangleEPA* face3 = nullptr; // If the origin is in the first tetrahedron if (isOriginInTetrahedron(points[0], points[1], @@ -323,7 +323,7 @@ void EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simple } // If the constructed tetrahedron is not correct - if (!((face0 != NULL) && (face1 != NULL) && (face2 != NULL) && (face3 != NULL) + if (!((face0 != nullptr) && (face1 != nullptr) && (face2 != nullptr) && (face3 != nullptr) && face0->getDistSquare() > 0.0 && face1->getDistSquare() > 0.0 && face2->getDistSquare() > 0.0 && face3->getDistSquare() > 0.0)) { return; diff --git a/src/collision/narrowphase/EPA/EdgeEPA.cpp b/src/collision/narrowphase/EPA/EdgeEPA.cpp index d7abbaf6..098602da 100644 --- a/src/collision/narrowphase/EPA/EdgeEPA.cpp +++ b/src/collision/narrowphase/EPA/EdgeEPA.cpp @@ -78,7 +78,7 @@ bool EdgeEPA::computeSilhouette(const Vector3* vertices, uint indexNewVertex, getSourceVertexIndex()); // If the triangle has been created - if (triangle != NULL) { + if (triangle != nullptr) { halfLink(EdgeEPA(triangle, 1), *this); return true; } @@ -103,7 +103,7 @@ bool EdgeEPA::computeSilhouette(const Vector3* vertices, uint indexNewVertex, getSourceVertexIndex()); // If the triangle has been created - if (triangle != NULL) { + if (triangle != nullptr) { halfLink(EdgeEPA(triangle, 1), *this); return true; } @@ -122,7 +122,7 @@ bool EdgeEPA::computeSilhouette(const Vector3* vertices, uint indexNewVertex, getTargetVertexIndex(), getSourceVertexIndex()); - if (triangle != NULL) { + if (triangle != nullptr) { halfLink(EdgeEPA(triangle, 1), *this); return true; } diff --git a/src/collision/narrowphase/EPA/TrianglesStore.h b/src/collision/narrowphase/EPA/TrianglesStore.h index b207eb77..82f6b6a9 100644 --- a/src/collision/narrowphase/EPA/TrianglesStore.h +++ b/src/collision/narrowphase/EPA/TrianglesStore.h @@ -115,7 +115,7 @@ inline TriangleEPA& TrianglesStore::last() { // Create a new triangle inline TriangleEPA* TrianglesStore::newTriangle(const Vector3* vertices, uint v0,uint v1, uint v2) { - TriangleEPA* newTriangle = NULL; + TriangleEPA* newTriangle = nullptr; // If we have not reached the maximum number of triangles if (mNbTriangles != MAX_TRIANGLES) { @@ -123,7 +123,7 @@ inline TriangleEPA* TrianglesStore::newTriangle(const Vector3* vertices, new (newTriangle) TriangleEPA(v0, v1, v2); if (!newTriangle->computeClosestPoint(vertices)) { mNbTriangles--; - newTriangle = NULL; + newTriangle = nullptr; } } diff --git a/src/collision/narrowphase/NarrowPhaseAlgorithm.cpp b/src/collision/narrowphase/NarrowPhaseAlgorithm.cpp index d61d78e9..970905da 100644 --- a/src/collision/narrowphase/NarrowPhaseAlgorithm.cpp +++ b/src/collision/narrowphase/NarrowPhaseAlgorithm.cpp @@ -31,7 +31,7 @@ using namespace reactphysics3d; // Constructor NarrowPhaseAlgorithm::NarrowPhaseAlgorithm() - : mMemoryAllocator(NULL), mCurrentOverlappingPair(NULL) { + : mMemoryAllocator(nullptr), mCurrentOverlappingPair(nullptr) { } diff --git a/src/collision/shapes/ConeShape.cpp b/src/collision/shapes/ConeShape.cpp index 373061d2..cc956c73 100644 --- a/src/collision/shapes/ConeShape.cpp +++ b/src/collision/shapes/ConeShape.cpp @@ -137,7 +137,7 @@ bool ConeShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* pr } // If the origin of the ray is inside the cone, we return no hit - if (testPointInside(ray.point1, NULL)) return false; + if (testPointInside(ray.point1, nullptr)) return false; localHitPoint[0] = ray.point1 + tHit[0] * r; localHitPoint[1] = ray.point1 + tHit[1] * r; diff --git a/src/collision/shapes/ConvexMeshShape.cpp b/src/collision/shapes/ConvexMeshShape.cpp index e3643a97..5d0b651c 100644 --- a/src/collision/shapes/ConvexMeshShape.cpp +++ b/src/collision/shapes/ConvexMeshShape.cpp @@ -157,10 +157,10 @@ Vector3 ConvexMeshShape::getLocalSupportPointWithoutMargin(const Vector3& direct void** cachedCollisionData) const { assert(mNbVertices == mVertices.size()); - assert(cachedCollisionData != NULL); + assert(cachedCollisionData != nullptr); // Allocate memory for the cached collision data if not allocated yet - if ((*cachedCollisionData) == NULL) { + if ((*cachedCollisionData) == nullptr) { *cachedCollisionData = (int*) malloc(sizeof(int)); *((int*)(*cachedCollisionData)) = 0; } diff --git a/src/constraint/Joint.cpp b/src/constraint/Joint.cpp index 22f40932..5c6a98f7 100644 --- a/src/constraint/Joint.cpp +++ b/src/constraint/Joint.cpp @@ -34,8 +34,8 @@ Joint::Joint(const JointInfo& jointInfo) mPositionCorrectionTechnique(jointInfo.positionCorrectionTechnique), mIsCollisionEnabled(jointInfo.isCollisionEnabled), mIsAlreadyInIsland(false) { - assert(mBody1 != NULL); - assert(mBody2 != NULL); + assert(mBody1 != nullptr); + assert(mBody2 != nullptr); } // Destructor diff --git a/src/constraint/Joint.h b/src/constraint/Joint.h index b5ec520d..66ed1f28 100644 --- a/src/constraint/Joint.h +++ b/src/constraint/Joint.h @@ -94,7 +94,7 @@ struct JointInfo { /// Constructor JointInfo(JointType constraintType) - : body1(NULL), body2(NULL), type(constraintType), + : body1(nullptr), body2(nullptr), type(constraintType), positionCorrectionTechnique(NON_LINEAR_GAUSS_SEIDEL), isCollisionEnabled(true) {} diff --git a/src/engine/CollisionWorld.cpp b/src/engine/CollisionWorld.cpp index ddc4a7b5..68e37625 100644 --- a/src/engine/CollisionWorld.cpp +++ b/src/engine/CollisionWorld.cpp @@ -34,7 +34,7 @@ using namespace std; // Constructor CollisionWorld::CollisionWorld() : mCollisionDetection(this, mMemoryAllocator), mCurrentBodyID(0), - mEventListener(NULL) { + mEventListener(nullptr) { } @@ -69,7 +69,7 @@ CollisionBody* CollisionWorld::createCollisionBody(const Transform& transform) { CollisionBody* collisionBody = new (mMemoryAllocator.allocate(sizeof(CollisionBody))) CollisionBody(transform, *this, bodyID); - assert(collisionBody != NULL); + assert(collisionBody != nullptr); // Add the collision body to the world mBodies.insert(collisionBody); @@ -208,7 +208,7 @@ void CollisionWorld::testCollision(const CollisionBody* body, std::set shapes1; // For each shape of the body - for (const ProxyShape* shape=body->getProxyShapesList(); shape != NULL; + for (const ProxyShape* shape=body->getProxyShapesList(); shape != nullptr; shape = shape->getNext()) { shapes1.insert(shape->mBroadPhaseID); } @@ -234,13 +234,13 @@ void CollisionWorld::testCollision(const CollisionBody* body1, // Create the sets of shapes std::set shapes1; - for (const ProxyShape* shape=body1->getProxyShapesList(); shape != NULL; + for (const ProxyShape* shape=body1->getProxyShapesList(); shape != nullptr; shape = shape->getNext()) { shapes1.insert(shape->mBroadPhaseID); } std::set shapes2; - for (const ProxyShape* shape=body2->getProxyShapesList(); shape != NULL; + for (const ProxyShape* shape=body2->getProxyShapesList(); shape != nullptr; shape = shape->getNext()) { shapes2.insert(shape->mBroadPhaseID); } diff --git a/src/engine/ConstraintSolver.cpp b/src/engine/ConstraintSolver.cpp index 64a9264e..f52056e7 100644 --- a/src/engine/ConstraintSolver.cpp +++ b/src/engine/ConstraintSolver.cpp @@ -46,7 +46,7 @@ void ConstraintSolver::initializeForIsland(decimal dt, Island* island) { PROFILE("ConstraintSolver::initializeForIsland()"); - assert(island != NULL); + assert(island != nullptr); assert(island->getNbBodies() > 0); assert(island->getNbJoints() > 0); @@ -76,7 +76,7 @@ void ConstraintSolver::solveVelocityConstraints(Island* island) { PROFILE("ConstraintSolver::solveVelocityConstraints()"); - assert(island != NULL); + assert(island != nullptr); assert(island->getNbJoints() > 0); // For each joint of the island @@ -93,7 +93,7 @@ void ConstraintSolver::solvePositionConstraints(Island* island) { PROFILE("ConstraintSolver::solvePositionConstraints()"); - assert(island != NULL); + assert(island != nullptr); assert(island->getNbJoints() > 0); // For each joint of the island diff --git a/src/engine/ConstraintSolver.h b/src/engine/ConstraintSolver.h index b67e10ca..dd76c4b8 100644 --- a/src/engine/ConstraintSolver.h +++ b/src/engine/ConstraintSolver.h @@ -69,8 +69,8 @@ struct ConstraintSolverData { /// Constructor ConstraintSolverData(const std::map& refMapBodyToConstrainedVelocityIndex) - :linearVelocities(NULL), angularVelocities(NULL), - positions(NULL), orientations(NULL), + :linearVelocities(nullptr), angularVelocities(nullptr), + positions(nullptr), orientations(nullptr), mapBodyToConstrainedVelocityIndex(refMapBodyToConstrainedVelocityIndex){ } @@ -202,8 +202,8 @@ class ConstraintSolver { // Set the constrained velocities arrays inline void ConstraintSolver::setConstrainedVelocitiesArrays(Vector3* constrainedLinearVelocities, Vector3* constrainedAngularVelocities) { - assert(constrainedLinearVelocities != NULL); - assert(constrainedAngularVelocities != NULL); + assert(constrainedLinearVelocities != nullptr); + assert(constrainedAngularVelocities != nullptr); mConstraintSolverData.linearVelocities = constrainedLinearVelocities; mConstraintSolverData.angularVelocities = constrainedAngularVelocities; } @@ -211,8 +211,8 @@ inline void ConstraintSolver::setConstrainedVelocitiesArrays(Vector3* constraine // Set the constrained positions/orientations arrays inline void ConstraintSolver::setConstrainedPositionsArrays(Vector3* constrainedPositions, Quaternion* constrainedOrientations) { - assert(constrainedPositions != NULL); - assert(constrainedOrientations != NULL); + assert(constrainedPositions != nullptr); + assert(constrainedOrientations != nullptr); mConstraintSolverData.positions = constrainedPositions; mConstraintSolverData.orientations = constrainedOrientations; } diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index 076cf5e2..dcc29bc9 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -40,8 +40,8 @@ const decimal ContactSolver::SLOP= decimal(0.01); // Constructor ContactSolver::ContactSolver(const std::map& mapBodyToVelocityIndex) - :mSplitLinearVelocities(NULL), mSplitAngularVelocities(NULL), - mContactConstraints(NULL), mLinearVelocities(NULL), mAngularVelocities(NULL), + :mSplitLinearVelocities(nullptr), mSplitAngularVelocities(nullptr), + mContactConstraints(nullptr), mLinearVelocities(nullptr), mAngularVelocities(nullptr), mMapBodyToConstrainedVelocityIndex(mapBodyToVelocityIndex), mIsWarmStartingActive(true), mIsSplitImpulseActive(true), mIsSolveFrictionAtContactManifoldCenterActive(true) { @@ -58,11 +58,11 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { PROFILE("ContactSolver::initializeForIsland()"); - assert(island != NULL); + assert(island != nullptr); assert(island->getNbBodies() > 0); assert(island->getNbContactManifolds() > 0); - assert(mSplitLinearVelocities != NULL); - assert(mSplitAngularVelocities != NULL); + assert(mSplitLinearVelocities != nullptr); + assert(mSplitAngularVelocities != nullptr); // Set the current time step mTimeStep = dt; @@ -70,7 +70,7 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { mNbContactManifolds = island->getNbContactManifolds(); mContactConstraints = new ContactManifoldSolver[mNbContactManifolds]; - assert(mContactConstraints != NULL); + assert(mContactConstraints != nullptr); // For each contact manifold of the island ContactManifold** contactManifolds = island->getContactManifold(); @@ -85,8 +85,8 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { // Get the two bodies of the contact RigidBody* body1 = static_cast(externalManifold->getContactPoint(0)->getBody1()); RigidBody* body2 = static_cast(externalManifold->getContactPoint(0)->getBody2()); - assert(body1 != NULL); - assert(body2 != NULL); + assert(body1 != nullptr); + assert(body2 != nullptr); // Get the position of the two bodies const Vector3& x1 = body1->mCenterOfMassWorld; diff --git a/src/engine/ContactSolver.h b/src/engine/ContactSolver.h index aa111f42..203d140e 100644 --- a/src/engine/ContactSolver.h +++ b/src/engine/ContactSolver.h @@ -453,8 +453,8 @@ class ContactSolver { // Set the split velocities arrays inline void ContactSolver::setSplitVelocitiesArrays(Vector3* splitLinearVelocities, Vector3* splitAngularVelocities) { - assert(splitLinearVelocities != NULL); - assert(splitAngularVelocities != NULL); + assert(splitLinearVelocities != nullptr); + assert(splitAngularVelocities != nullptr); mSplitLinearVelocities = splitLinearVelocities; mSplitAngularVelocities = splitAngularVelocities; } @@ -462,8 +462,8 @@ inline void ContactSolver::setSplitVelocitiesArrays(Vector3* splitLinearVelociti // Set the constrained velocities arrays inline void ContactSolver::setConstrainedVelocitiesArrays(Vector3* constrainedLinearVelocities, Vector3* constrainedAngularVelocities) { - assert(constrainedLinearVelocities != NULL); - assert(constrainedAngularVelocities != NULL); + assert(constrainedLinearVelocities != nullptr); + assert(constrainedAngularVelocities != nullptr); mLinearVelocities = constrainedLinearVelocities; mAngularVelocities = constrainedAngularVelocities; } diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index f0725eba..b52e2378 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -45,11 +45,11 @@ DynamicsWorld::DynamicsWorld(const Vector3 &gravity) mNbVelocitySolverIterations(DEFAULT_VELOCITY_SOLVER_NB_ITERATIONS), mNbPositionSolverIterations(DEFAULT_POSITION_SOLVER_NB_ITERATIONS), mIsSleepingEnabled(SPLEEPING_ENABLED), mGravity(gravity), - mIsGravityEnabled(true), mConstrainedLinearVelocities(NULL), - mConstrainedAngularVelocities(NULL), mSplitLinearVelocities(NULL), - mSplitAngularVelocities(NULL), mConstrainedPositions(NULL), - mConstrainedOrientations(NULL), mNbIslands(0), - mNbIslandsCapacity(0), mIslands(NULL), mNbBodiesCapacity(0), + mIsGravityEnabled(true), mConstrainedLinearVelocities(nullptr), + mConstrainedAngularVelocities(nullptr), mSplitLinearVelocities(nullptr), + mSplitAngularVelocities(nullptr), mConstrainedPositions(nullptr), + mConstrainedOrientations(nullptr), mNbIslands(0), + mNbIslandsCapacity(0), mIslands(nullptr), mNbBodiesCapacity(0), mSleepLinearVelocity(DEFAULT_SLEEP_LINEAR_VELOCITY), mSleepAngularVelocity(DEFAULT_SLEEP_ANGULAR_VELOCITY), mTimeBeforeSleep(DEFAULT_TIME_BEFORE_SLEEP) { @@ -128,7 +128,7 @@ void DynamicsWorld::update(decimal timeStep) { mTimeStep = timeStep; // Notify the event listener about the beginning of an internal tick - if (mEventListener != NULL) mEventListener->beginInternalTick(); + if (mEventListener != nullptr) mEventListener->beginInternalTick(); // Reset all the contact manifolds lists of each body resetContactManifoldListsOfBodies(); @@ -157,7 +157,7 @@ void DynamicsWorld::update(decimal timeStep) { if (mIsSleepingEnabled) updateSleepingBodies(); // Notify the event listener about the end of an internal tick - if (mEventListener != NULL) mEventListener->endInternalTick(); + if (mEventListener != nullptr) mEventListener->endInternalTick(); // Reset the external force and torque applied to the bodies resetBodiesForceAndTorque(); @@ -256,12 +256,12 @@ void DynamicsWorld::initVelocityArrays() { mConstrainedAngularVelocities = new Vector3[mNbBodiesCapacity]; mConstrainedPositions = new Vector3[mNbBodiesCapacity]; mConstrainedOrientations = new Quaternion[mNbBodiesCapacity]; - assert(mSplitLinearVelocities != NULL); - assert(mSplitAngularVelocities != NULL); - assert(mConstrainedLinearVelocities != NULL); - assert(mConstrainedAngularVelocities != NULL); - assert(mConstrainedPositions != NULL); - assert(mConstrainedOrientations != NULL); + assert(mSplitLinearVelocities != nullptr); + assert(mSplitAngularVelocities != nullptr); + assert(mConstrainedLinearVelocities != nullptr); + assert(mConstrainedAngularVelocities != nullptr); + assert(mConstrainedPositions != nullptr); + assert(mConstrainedOrientations != nullptr); } // Reset the velocities arrays @@ -448,7 +448,7 @@ RigidBody* DynamicsWorld::createRigidBody(const Transform& transform) { // Create the rigid body RigidBody* rigidBody = new (mMemoryAllocator.allocate(sizeof(RigidBody))) RigidBody(transform, *this, bodyID); - assert(rigidBody != NULL); + assert(rigidBody != nullptr); // Add the rigid body to the physics world mBodies.insert(rigidBody); @@ -472,7 +472,7 @@ void DynamicsWorld::destroyRigidBody(RigidBody* rigidBody) { // Destroy all the joints in which the rigid body to be destroyed is involved JointListElement* element; - for (element = rigidBody->mJointsList; element != NULL; element = element->next) { + for (element = rigidBody->mJointsList; element != nullptr; element = element->next) { destroyJoint(element->joint); } @@ -497,7 +497,7 @@ void DynamicsWorld::destroyRigidBody(RigidBody* rigidBody) { */ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { - Joint* newJoint = NULL; + Joint* newJoint = nullptr; // Allocate memory to create the new joint switch(jointInfo.type) { @@ -542,7 +542,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { default: { assert(false); - return NULL; + return nullptr; } } @@ -569,7 +569,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { */ void DynamicsWorld::destroyJoint(Joint* joint) { - assert(joint != NULL); + assert(joint != nullptr); // If the collision between the two bodies of the constraint was disabled if (!joint->isCollisionEnabled()) { @@ -601,7 +601,7 @@ void DynamicsWorld::destroyJoint(Joint* joint) { // Add the joint to the list of joints of the two bodies involved in the joint void DynamicsWorld::addJointToBody(Joint* joint) { - assert(joint != NULL); + assert(joint != nullptr); // Add the joint at the beginning of the linked list of joints of the first body void* allocatedMemory1 = mMemoryAllocator.allocate(sizeof(JointListElement)); @@ -710,7 +710,7 @@ void DynamicsWorld::computeIslands() { // For each contact manifold in which the current body is involded ContactManifoldListElement* contactElement; - for (contactElement = bodyToVisit->mContactManifoldsList; contactElement != NULL; + for (contactElement = bodyToVisit->mContactManifoldsList; contactElement != nullptr; contactElement = contactElement->next) { ContactManifold* contactManifold = contactElement->contactManifold; @@ -740,7 +740,7 @@ void DynamicsWorld::computeIslands() { // For each joint in which the current body is involved JointListElement* jointElement; - for (jointElement = bodyToVisit->mJointsList; jointElement != NULL; + for (jointElement = bodyToVisit->mJointsList; jointElement != nullptr; jointElement = jointElement->next) { Joint* joint = jointElement->joint; @@ -916,7 +916,7 @@ void DynamicsWorld::testCollision(const CollisionBody* body, std::set shapes1; // For each shape of the body - for (const ProxyShape* shape=body->getProxyShapesList(); shape != NULL; + for (const ProxyShape* shape=body->getProxyShapesList(); shape != nullptr; shape = shape->getNext()) { shapes1.insert(shape->mBroadPhaseID); } @@ -941,13 +941,13 @@ void DynamicsWorld::testCollision(const CollisionBody* body1, // Create the sets of shapes std::set shapes1; - for (const ProxyShape* shape=body1->getProxyShapesList(); shape != NULL; + for (const ProxyShape* shape=body1->getProxyShapesList(); shape != nullptr; shape = shape->getNext()) { shapes1.insert(shape->mBroadPhaseID); } std::set shapes2; - for (const ProxyShape* shape=body2->getProxyShapesList(); shape != NULL; + for (const ProxyShape* shape=body2->getProxyShapesList(); shape != nullptr; shape = shape->getNext()) { shapes2.insert(shape->mBroadPhaseID); } diff --git a/src/engine/DynamicsWorld.h b/src/engine/DynamicsWorld.h index 11e49124..71a5336a 100644 --- a/src/engine/DynamicsWorld.h +++ b/src/engine/DynamicsWorld.h @@ -512,7 +512,7 @@ inline void DynamicsWorld::setTimeBeforeSleep(decimal timeBeforeSleep) { } // Set an event listener object to receive events callbacks. -/// If you use NULL as an argument, the events callbacks will be disabled. +/// If you use "nullptr" as an argument, the events callbacks will be disabled. /** * @param eventListener Pointer to the event listener object that will receive * event callbacks during the simulation diff --git a/src/engine/Island.cpp b/src/engine/Island.cpp index 57a7f43f..41560bde 100644 --- a/src/engine/Island.cpp +++ b/src/engine/Island.cpp @@ -31,7 +31,7 @@ using namespace reactphysics3d; // Constructor Island::Island(uint nbMaxBodies, uint nbMaxContactManifolds, uint nbMaxJoints, MemoryAllocator& memoryAllocator) - : mBodies(NULL), mContactManifolds(NULL), mJoints(NULL), mNbBodies(0), + : mBodies(nullptr), mContactManifolds(nullptr), mJoints(nullptr), mNbBodies(0), mNbContactManifolds(0), mNbJoints(0), mMemoryAllocator(memoryAllocator) { // Allocate memory for the arrays diff --git a/src/engine/Profiler.cpp b/src/engine/Profiler.cpp index f9cc8fea..9437dca0 100644 --- a/src/engine/Profiler.cpp +++ b/src/engine/Profiler.cpp @@ -31,7 +31,7 @@ using namespace reactphysics3d; // Initialization of static variables -ProfileNode Profiler::mRootNode("Root", NULL); +ProfileNode Profiler::mRootNode("Root", nullptr); ProfileNode* Profiler::mCurrentNode = &Profiler::mRootNode; long double Profiler::mProfilingStartTime = Timer::getCurrentSystemTime() * 1000.0; uint Profiler::mFrameCounter = 0; @@ -39,8 +39,8 @@ uint Profiler::mFrameCounter = 0; // Constructor ProfileNode::ProfileNode(const char* name, ProfileNode* parentNode) :mName(name), mNbTotalCalls(0), mStartingTime(0), mTotalTime(0), - mRecursionCounter(0), mParentNode(parentNode), mChildNode(NULL), - mSiblingNode(NULL) { + mRecursionCounter(0), mParentNode(parentNode), mChildNode(nullptr), + mSiblingNode(nullptr) { reset(); } @@ -56,7 +56,7 @@ ProfileNode* ProfileNode::findSubNode(const char* name) { // Try to find the node among the child nodes ProfileNode* child = mChildNode; - while (child != NULL) { + while (child != nullptr) { if (child->mName == name) { return child; } @@ -110,12 +110,12 @@ void ProfileNode::reset() { mTotalTime = 0.0; // Reset the child node - if (mChildNode != NULL) { + if (mChildNode != nullptr) { mChildNode->reset(); } // Reset the sibling node - if (mSiblingNode != NULL) { + if (mSiblingNode != nullptr) { mSiblingNode->reset(); } } @@ -123,9 +123,9 @@ void ProfileNode::reset() { // Destroy the node void ProfileNode::destroy() { delete mChildNode; - mChildNode = NULL; + mChildNode = nullptr; delete mSiblingNode; - mSiblingNode = NULL; + mSiblingNode = nullptr; } // Constructor @@ -138,12 +138,12 @@ ProfileNodeIterator::ProfileNodeIterator(ProfileNode* startingNode) // Enter a given child node void ProfileNodeIterator::enterChild(int index) { mCurrentChildNode = mCurrentParentNode->getChildNode(); - while ((mCurrentChildNode != NULL) && (index != 0)) { + while ((mCurrentChildNode != nullptr) && (index != 0)) { index--; mCurrentChildNode = mCurrentChildNode->getSiblingNode(); } - if (mCurrentChildNode != NULL) { + if (mCurrentChildNode != nullptr) { mCurrentParentNode = mCurrentChildNode; mCurrentChildNode = mCurrentParentNode->getChildNode(); } @@ -151,7 +151,7 @@ void ProfileNodeIterator::enterChild(int index) { // Enter a given parent node void ProfileNodeIterator::enterParent() { - if (mCurrentParentNode->getParentNode() != NULL) { + if (mCurrentParentNode->getParentNode() != nullptr) { mCurrentParentNode = mCurrentParentNode->getParentNode(); } mCurrentChildNode = mCurrentParentNode->getChildNode(); diff --git a/src/engine/Profiler.h b/src/engine/Profiler.h index 7a42ae1c..818d6cc8 100644 --- a/src/engine/Profiler.h +++ b/src/engine/Profiler.h @@ -269,12 +269,12 @@ class ProfileSample { // Return true if we are at the root of the profiler tree inline bool ProfileNodeIterator::isRoot() { - return (mCurrentParentNode->getParentNode() == NULL); + return (mCurrentParentNode->getParentNode() == nullptr); } // Return true if we are at the end of a branch of the profiler tree inline bool ProfileNodeIterator::isEnd() { - return (mCurrentChildNode == NULL); + return (mCurrentChildNode == nullptr); } // Return the name of the current node diff --git a/src/engine/Timer.cpp b/src/engine/Timer.cpp index 243138fc..e9a14d21 100644 --- a/src/engine/Timer.cpp +++ b/src/engine/Timer.cpp @@ -51,7 +51,7 @@ long double Timer::getCurrentSystemTime() { #else // Initialize the lastUpdateTime with the current time in seconds timeval timeValue; - gettimeofday(&timeValue, NULL); + gettimeofday(&timeValue, nullptr); return (timeValue.tv_sec + (timeValue.tv_usec / 1000000.0)); #endif } diff --git a/src/memory/MemoryAllocator.cpp b/src/memory/MemoryAllocator.cpp index 6a9c69ab..46c47e14 100644 --- a/src/memory/MemoryAllocator.cpp +++ b/src/memory/MemoryAllocator.cpp @@ -99,7 +99,7 @@ MemoryAllocator::~MemoryAllocator() { void* MemoryAllocator::allocate(size_t size) { // We cannot allocate zero bytes - if (size == 0) return NULL; + if (size == 0) return nullptr; #ifndef NDEBUG mNbTimesAllocateMethodCalled++; @@ -117,7 +117,7 @@ void* MemoryAllocator::allocate(size_t size) { assert(indexHeap >= 0 && indexHeap < NB_HEAPS); // If there still are free memory units in the corresponding heap - if (mFreeMemoryUnits[indexHeap] != NULL) { + if (mFreeMemoryUnits[indexHeap] != nullptr) { // Return a pointer to the memory unit MemoryUnit* unit = mFreeMemoryUnits[indexHeap]; @@ -142,7 +142,7 @@ void* MemoryAllocator::allocate(size_t size) { // memory units MemoryBlock* newBlock = mMemoryBlocks + mNbCurrentMemoryBlocks; newBlock->memoryUnits = (MemoryUnit*) malloc(BLOCK_SIZE); - assert(newBlock->memoryUnits != NULL); + assert(newBlock->memoryUnits != nullptr); size_t unitSize = mUnitSizes[indexHeap]; uint nbUnits = BLOCK_SIZE / unitSize; assert(nbUnits * unitSize <= BLOCK_SIZE); @@ -152,7 +152,7 @@ void* MemoryAllocator::allocate(size_t size) { unit->nextUnit = nextUnit; } MemoryUnit* lastUnit = (MemoryUnit*) ((size_t)newBlock->memoryUnits + unitSize*(nbUnits-1)); - lastUnit->nextUnit = NULL; + lastUnit->nextUnit = nullptr; // Add the new allocated block into the list of free memory units in the heap mFreeMemoryUnits[indexHeap] = newBlock->memoryUnits->nextUnit; diff --git a/test/TestSuite.cpp b/test/TestSuite.cpp index 52a7d83a..dd4f42fc 100644 --- a/test/TestSuite.cpp +++ b/test/TestSuite.cpp @@ -61,10 +61,10 @@ long TestSuite::getNbFailedTests() const { // Add a unit test in the test suite void TestSuite::addTest(Test* test) { - if (test == NULL) { - throw std::invalid_argument("Error : You cannot add a NULL test in the test suite."); + if (test == nullptr) { + throw std::invalid_argument("Error : You cannot add a nullptr test in the test suite."); } - else if (mOutputStream != NULL && test->getOutputStream() == NULL) { + else if (mOutputStream != nullptr && test->getOutputStream() == nullptr) { test->setOutputStream(mOutputStream); } @@ -80,7 +80,7 @@ void TestSuite::addTestSuite(const TestSuite& testSuite) { // Add each test of the test suite to the current one for (size_t i =0; i < testSuite.mTests.size(); i++) { - assert(testSuite.mTests[i] != NULL); + assert(testSuite.mTests[i] != nullptr); addTest(testSuite.mTests[i]); } } @@ -93,7 +93,7 @@ void TestSuite::run() { // Run all the tests for (size_t i=0; i < mTests.size(); i++) { - assert(mTests[i] != NULL); + assert(mTests[i] != nullptr); mTests[i]->run(); } } @@ -108,7 +108,7 @@ void TestSuite::reset() { // Display the tests report and return the number of failed tests long TestSuite::report() const { - if (mOutputStream != NULL) { + if (mOutputStream != nullptr) { long nbFailedTests = 0; *mOutputStream << "Test Suite \"" << mName << "\"\n"; @@ -118,7 +118,7 @@ long TestSuite::report() const { } *mOutputStream << "=" << std::endl; for (i=0; i < mTests.size(); i++) { - assert(mTests[i] != NULL); + assert(mTests[i] != nullptr); nbFailedTests += mTests[i]->report(); } for (i=0; i < 70; i++) { @@ -139,6 +139,6 @@ void TestSuite::clear() { for (size_t i=0; i Date: Sun, 15 May 2016 19:29:50 +0200 Subject: [PATCH 002/248] ProxyShape must have a virtual destructor --- src/collision/ProxyShape.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/collision/ProxyShape.h b/src/collision/ProxyShape.h index b91252de..810c15e8 100644 --- a/src/collision/ProxyShape.h +++ b/src/collision/ProxyShape.h @@ -102,7 +102,7 @@ class ProxyShape { const Transform& transform, decimal mass); /// Destructor - ~ProxyShape(); + virtual ~ProxyShape(); /// Return the collision shape const CollisionShape* getCollisionShape() const; From ae7bec43c45778da5510d79e2c01a14180d711d9 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 18 May 2016 21:39:11 +0200 Subject: [PATCH 003/248] Allow for zero mass rigid body --- src/body/RigidBody.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/src/body/RigidBody.cpp b/src/body/RigidBody.cpp index 1a54b935..b1818b26 100644 --- a/src/body/RigidBody.cpp +++ b/src/body/RigidBody.cpp @@ -213,8 +213,6 @@ ProxyShape* RigidBody::addCollisionShape(CollisionShape* collisionShape, const Transform& transform, decimal mass) { - assert(mass > decimal(0.0)); - // Create a new proxy collision shape to attach the collision shape to the body ProxyShape* proxyShape = new (mWorld.mMemoryAllocator.allocate( sizeof(ProxyShape))) ProxyShape(this, collisionShape, @@ -348,8 +346,8 @@ void RigidBody::recomputeMassInformation() { mMassInverse = decimal(1.0) / mInitMass; } else { - mInitMass = decimal(1.0); - mMassInverse = decimal(1.0); + mCenterOfMassWorld = mTransform.getPosition(); + return; } // Compute the center of mass From c3e74856a0df698ae96fad858b19fffee23fec20 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 18 May 2016 22:30:20 +0200 Subject: [PATCH 004/248] Fix assert raised in empty scene --- src/engine/ConstraintSolver.h | 4 ---- src/engine/ContactSolver.h | 4 ---- 2 files changed, 8 deletions(-) diff --git a/src/engine/ConstraintSolver.h b/src/engine/ConstraintSolver.h index b67e10ca..cd9e5292 100644 --- a/src/engine/ConstraintSolver.h +++ b/src/engine/ConstraintSolver.h @@ -202,8 +202,6 @@ class ConstraintSolver { // Set the constrained velocities arrays inline void ConstraintSolver::setConstrainedVelocitiesArrays(Vector3* constrainedLinearVelocities, Vector3* constrainedAngularVelocities) { - assert(constrainedLinearVelocities != NULL); - assert(constrainedAngularVelocities != NULL); mConstraintSolverData.linearVelocities = constrainedLinearVelocities; mConstraintSolverData.angularVelocities = constrainedAngularVelocities; } @@ -211,8 +209,6 @@ inline void ConstraintSolver::setConstrainedVelocitiesArrays(Vector3* constraine // Set the constrained positions/orientations arrays inline void ConstraintSolver::setConstrainedPositionsArrays(Vector3* constrainedPositions, Quaternion* constrainedOrientations) { - assert(constrainedPositions != NULL); - assert(constrainedOrientations != NULL); mConstraintSolverData.positions = constrainedPositions; mConstraintSolverData.orientations = constrainedOrientations; } diff --git a/src/engine/ContactSolver.h b/src/engine/ContactSolver.h index aa111f42..82b89892 100644 --- a/src/engine/ContactSolver.h +++ b/src/engine/ContactSolver.h @@ -453,8 +453,6 @@ class ContactSolver { // Set the split velocities arrays inline void ContactSolver::setSplitVelocitiesArrays(Vector3* splitLinearVelocities, Vector3* splitAngularVelocities) { - assert(splitLinearVelocities != NULL); - assert(splitAngularVelocities != NULL); mSplitLinearVelocities = splitLinearVelocities; mSplitAngularVelocities = splitAngularVelocities; } @@ -462,8 +460,6 @@ inline void ContactSolver::setSplitVelocitiesArrays(Vector3* splitLinearVelociti // Set the constrained velocities arrays inline void ContactSolver::setConstrainedVelocitiesArrays(Vector3* constrainedLinearVelocities, Vector3* constrainedAngularVelocities) { - assert(constrainedLinearVelocities != NULL); - assert(constrainedAngularVelocities != NULL); mLinearVelocities = constrainedLinearVelocities; mAngularVelocities = constrainedAngularVelocities; } From 942b63b48d15520df48420bdd7cff21eb055a40a Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 19 May 2016 22:47:19 +0200 Subject: [PATCH 005/248] Replace NULL pointer by nullptr --- src/engine/ContactSolver.cpp | 4 ++-- testbed/common/Box.cpp | 6 +++--- testbed/common/Capsule.cpp | 8 ++++---- testbed/common/ConcaveMesh.cpp | 8 ++++---- testbed/common/Cone.cpp | 8 ++++---- testbed/common/ConvexMesh.cpp | 8 ++++---- testbed/common/Cylinder.cpp | 8 ++++---- 7 files changed, 25 insertions(+), 25 deletions(-) diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index dcc29bc9..f2ee0ef2 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -906,8 +906,8 @@ void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, // Clean up the constraint solver void ContactSolver::cleanup() { - if (mContactConstraints != NULL) { + if (mContactConstraints != nullptr) { delete[] mContactConstraints; - mContactConstraints = NULL; + mContactConstraints = nullptr; } } diff --git a/testbed/common/Box.cpp b/testbed/common/Box.cpp index ff6ab12c..549b86bb 100644 --- a/testbed/common/Box.cpp +++ b/testbed/common/Box.cpp @@ -257,12 +257,12 @@ void Box::render(openglframework::Shader& shader, GLint vertexNormalLoc = shader.getAttribLocation("vertexNormal", false); glEnableVertexAttribArray(vertexPositionLoc); - glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, NULL); + glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, nullptr); mVBONormals.bind(); if (vertexNormalLoc != -1) glEnableVertexAttribArray(vertexNormalLoc); - if (vertexNormalLoc != -1) glVertexAttribPointer(vertexNormalLoc, 3, GL_FLOAT, GL_FALSE, 0, NULL); + if (vertexNormalLoc != -1) glVertexAttribPointer(vertexNormalLoc, 3, GL_FLOAT, GL_FALSE, 0, nullptr); // Draw the geometry of the box glDrawArrays(GL_TRIANGLES, 0, 36); @@ -321,7 +321,7 @@ void Box::resetTransform(const rp3d::Transform& transform) { // Reset the velocity of the rigid body rp3d::RigidBody* rigidBody = dynamic_cast(mBody); - if (rigidBody != NULL) { + if (rigidBody != nullptr) { rigidBody->setLinearVelocity(rp3d::Vector3(0, 0, 0)); rigidBody->setAngularVelocity(rp3d::Vector3(0, 0, 0)); } diff --git a/testbed/common/Capsule.cpp b/testbed/common/Capsule.cpp index a953fcfc..7b83f6b3 100644 --- a/testbed/common/Capsule.cpp +++ b/testbed/common/Capsule.cpp @@ -183,16 +183,16 @@ void Capsule::render(openglframework::Shader& shader, GLint vertexNormalLoc = shader.getAttribLocation("vertexNormal", false); glEnableVertexAttribArray(vertexPositionLoc); - glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)NULL); + glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)nullptr); mVBONormals.bind(); - if (vertexNormalLoc != -1) glVertexAttribPointer(vertexNormalLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)NULL); + if (vertexNormalLoc != -1) glVertexAttribPointer(vertexNormalLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)nullptr); if (vertexNormalLoc != -1) glEnableVertexAttribArray(vertexNormalLoc); // For each part of the mesh for (unsigned int i=0; i(mBody); - if (rigidBody != NULL) { + if (rigidBody != nullptr) { rigidBody->setLinearVelocity(rp3d::Vector3(0, 0, 0)); rigidBody->setAngularVelocity(rp3d::Vector3(0, 0, 0)); } diff --git a/testbed/common/ConcaveMesh.cpp b/testbed/common/ConcaveMesh.cpp index 26a27920..0f8d7cb1 100644 --- a/testbed/common/ConcaveMesh.cpp +++ b/testbed/common/ConcaveMesh.cpp @@ -196,16 +196,16 @@ void ConcaveMesh::render(openglframework::Shader& shader, GLint vertexNormalLoc = shader.getAttribLocation("vertexNormal", false); glEnableVertexAttribArray(vertexPositionLoc); - glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)NULL); + glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)nullptr); mVBONormals.bind(); - if (vertexNormalLoc != -1) glVertexAttribPointer(vertexNormalLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)NULL); + if (vertexNormalLoc != -1) glVertexAttribPointer(vertexNormalLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)nullptr); if (vertexNormalLoc != -1) glEnableVertexAttribArray(vertexNormalLoc); // For each part of the mesh for (unsigned int i=0; i(mBody); - if (rigidBody != NULL) { + if (rigidBody != nullptr) { rigidBody->setLinearVelocity(rp3d::Vector3(0, 0, 0)); rigidBody->setAngularVelocity(rp3d::Vector3(0, 0, 0)); } diff --git a/testbed/common/Cone.cpp b/testbed/common/Cone.cpp index ca8d9ee8..1a971922 100644 --- a/testbed/common/Cone.cpp +++ b/testbed/common/Cone.cpp @@ -180,16 +180,16 @@ void Cone::render(openglframework::Shader& shader, GLint vertexNormalLoc = shader.getAttribLocation("vertexNormal", false); glEnableVertexAttribArray(vertexPositionLoc); - glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)NULL); + glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)nullptr); mVBONormals.bind(); - if (vertexNormalLoc != -1) glVertexAttribPointer(vertexNormalLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)NULL); + if (vertexNormalLoc != -1) glVertexAttribPointer(vertexNormalLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)nullptr); if (vertexNormalLoc != -1) glEnableVertexAttribArray(vertexNormalLoc); // For each part of the mesh for (unsigned int i=0; i(mBody); - if (rigidBody != NULL) { + if (rigidBody != nullptr) { rigidBody->setLinearVelocity(rp3d::Vector3(0, 0, 0)); rigidBody->setAngularVelocity(rp3d::Vector3(0, 0, 0)); } diff --git a/testbed/common/ConvexMesh.cpp b/testbed/common/ConvexMesh.cpp index 2c6d4368..ffdbca04 100644 --- a/testbed/common/ConvexMesh.cpp +++ b/testbed/common/ConvexMesh.cpp @@ -177,16 +177,16 @@ void ConvexMesh::render(openglframework::Shader& shader, GLint vertexNormalLoc = shader.getAttribLocation("vertexNormal", false); glEnableVertexAttribArray(vertexPositionLoc); - glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)NULL); + glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)nullptr); mVBONormals.bind(); - if (vertexNormalLoc != -1) glVertexAttribPointer(vertexNormalLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)NULL); + if (vertexNormalLoc != -1) glVertexAttribPointer(vertexNormalLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)nullptr); if (vertexNormalLoc != -1) glEnableVertexAttribArray(vertexNormalLoc); // For each part of the mesh for (unsigned int i=0; i(mBody); - if (rigidBody != NULL) { + if (rigidBody != nullptr) { rigidBody->setLinearVelocity(rp3d::Vector3(0, 0, 0)); rigidBody->setAngularVelocity(rp3d::Vector3(0, 0, 0)); } diff --git a/testbed/common/Cylinder.cpp b/testbed/common/Cylinder.cpp index 188cdd57..f791317b 100644 --- a/testbed/common/Cylinder.cpp +++ b/testbed/common/Cylinder.cpp @@ -181,16 +181,16 @@ void Cylinder::render(openglframework::Shader& shader, GLint vertexNormalLoc = shader.getAttribLocation("vertexNormal", false); glEnableVertexAttribArray(vertexPositionLoc); - glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)NULL); + glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)nullptr); mVBONormals.bind(); - if (vertexNormalLoc != -1) glVertexAttribPointer(vertexNormalLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)NULL); + if (vertexNormalLoc != -1) glVertexAttribPointer(vertexNormalLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)nullptr); if (vertexNormalLoc != -1) glEnableVertexAttribArray(vertexNormalLoc); // For each part of the mesh for (unsigned int i=0; i(mBody); - if (rigidBody != NULL) { + if (rigidBody != nullptr) { rigidBody->setLinearVelocity(rp3d::Vector3(0, 0, 0)); rigidBody->setAngularVelocity(rp3d::Vector3(0, 0, 0)); } From 9fae1b4e35830dcec7cbc97a51e7a71b7309ed9e Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 20 Jun 2016 08:40:26 +0200 Subject: [PATCH 006/248] Add missing virtual destructor --- src/collision/CollisionDetection.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index 4bc4f319..7e81a25f 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -62,6 +62,9 @@ class TestCollisionBetweenShapesCallback : public NarrowPhaseCallback { } + // Destructor + virtual ~TestCollisionBetweenShapesCallback() { } + // Called by a narrow-phase collision algorithm when a new contact has been found virtual void notifyContact(OverlappingPair* overlappingPair, const ContactPointInfo& contactInfo); From fd224ebabae357f5578e435198b7ec253efd52a9 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 20 Jun 2016 08:41:22 +0200 Subject: [PATCH 007/248] Add VoronoiSimplex class for GJK algorithm --- .../narrowphase/GJK/VoronoiSimplex.cpp | 618 ++++++++++++++++++ .../narrowphase/GJK/VoronoiSimplex.h | 201 ++++++ 2 files changed, 819 insertions(+) create mode 100644 src/collision/narrowphase/GJK/VoronoiSimplex.cpp create mode 100644 src/collision/narrowphase/GJK/VoronoiSimplex.h diff --git a/src/collision/narrowphase/GJK/VoronoiSimplex.cpp b/src/collision/narrowphase/GJK/VoronoiSimplex.cpp new file mode 100644 index 00000000..cf7acd7a --- /dev/null +++ b/src/collision/narrowphase/GJK/VoronoiSimplex.cpp @@ -0,0 +1,618 @@ +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "VoronoiSimplex.h" +#include + +// We want to use the ReactPhysics3D namespace +using namespace reactphysics3d; + +decimal VoronoiSimplex::epsilon = decimal(0.0001); + +// Constructor +VoronoiSimplex::VoronoiSimplex() : mNbPoints(0), mRecomputeClosestPoint(false), mIsClosestPointValid(false) { + +} + +// Destructor +VoronoiSimplex::~VoronoiSimplex() { + +} + +// Add a new support point of (A-B) into the simplex +/// suppPointA : support point of object A in a direction -v +/// suppPointB : support point of object B in a direction v +/// point : support point of object (A-B) => point = suppPointA - suppPointB +void VoronoiSimplex::addPoint(const Vector3& point, const Vector3& suppPointA, const Vector3& suppPointB) { + assert(!isFull()); + + mPoints[mNbPoints] = point; + mSuppPointsA[mNbPoints] = suppPointA; + mSuppPointsB[mNbPoints] = suppPointB; + + mNbPoints++; + mRecomputeClosestPoint = true; +} + +// Remove a point from the simplex +void VoronoiSimplex::removePoint(int index) { + assert(mNbPoints > 0); + mNbPoints--; + mPoints[index] = mPoints[mNbPoints]; + mSuppPointsA[index] = mSuppPointsA[mNbPoints]; + mSuppPointsB[index] = mSuppPointsA[mNbPoints]; +} + +// Reduce the simplex (only keep vertices that participate to the point closest to the origin) +/// bitsUsedPoints is seen as a sequence of bits representing whether the four points of +/// the simplex are used or not to represent the current closest point to the origin. +/// - The most right bit is set to one if the first point is used +/// - The second most right bit is set to one if the second point is used +/// - The third most right bit is set to one if the third point is used +/// - The fourth most right bit is set to one if the fourth point is used +void VoronoiSimplex::reduceSimplex(int bitsUsedPoints) { + + if ((mNbPoints >= 4) && (bitsUsedPoints & 8) == 0) + removePoint(3); + + if ((mNbPoints >= 3) && (bitsUsedPoints & 4) == 0) + removePoint(2); + + if ((mNbPoints >= 2) && (bitsUsedPoints & 2) == 0) + removePoint(1); + + if ((mNbPoints >= 1) && (bitsUsedPoints & 1) == 0) + removePoint(0); +} + +// Return true if the point is in the simplex +bool VoronoiSimplex::isPointInSimplex(const Vector3& point) const { + + // For each four possible points in the simplex + for (int i=0; i= 0 && mNbPoints <= 4); + + switch(mNbPoints) { + case 0: return false; + case 1: return false; + + // Two points are independent if there distance is larger than zero + case 2: return (mPoints[1] - mPoints[0]).lengthSquare() <= epsilon; + + // Three points are independent if the triangle area is larger than zero + case 3: return (mPoints[1] - mPoints[0]).cross(mPoints[2] - mPoints[0]).lengthSquare() <= epsilon; + + // Four points are independent if the tetrahedron volume is larger than zero + case 4: return std::abs((mPoints[1] - mPoints[0]).dot((mPoints[2] - mPoints[0]).cross(mPoints[3] - mPoints[0]))) <= epsilon; + } + + return false; +} + +// Compute the closest points "pA" and "pB" of object A and B. +/// The points are computed as follows : +/// pA = sum(lambda_i * a_i) where "a_i" are the support points of object A +/// pB = sum(lambda_i * b_i) where "b_i" are the support points of object B +/// with lambda_i = deltaX_i / deltaX +void VoronoiSimplex::computeClosestPointsOfAandB(Vector3& pA, Vector3& pB) { + + // Recompute the closest point (if necessary) + recomputeClosestPoint(); + + pA = mSuppPointsA; + pB = mSuppPointsB; +} + +// Recompute the closest point if the simplex has been modified +/// This method computes the point "v" of simplex that is closest to the origin. +/// The method returns true if a closest point has been found. +bool VoronoiSimplex::recomputeClosestPoint() { + + assert(mNbPoints <= 4); + + // If we need to recompute the closest point + if (mRecomputeClosestPoint) { + + mRecomputeClosestPoint = false; + + switch(mNbPoints) { + + case 0: + + // Cannot compute closest point when the simplex is empty + mIsClosestPointValid = false; + break; + + case 1: + + { + // There is a single point in the simplex, therefore, this point is + // the one closest to the origin + mClosestPoint = mPoints[0]; + mClosestSuppPointA = mSuppPointsA[0]; + mClosestSuppPointB = mSuppPointsB[0]; + setBarycentricCoords(1, 0, 0, 0); + mIsClosestPointValid = checkClosestPointValid(); + } + break; + + case 2: + + { + int bitsUsedPoints = 0; + + // The simplex is a line AB (where A=mPoints[0] and B=mPoints[1]. + // We need to find the point of that line closest to the origin + Vector3 AP = -mPoints[0]; + Vector3 AB = mPoints[1] - mPoints[0]; + decimal APDotAB = AP.dot(AB); + decimal t; + + // If the closest point is on the side of A in the direction of B + if (APDotAB > decimal(0.0)) { + decimal lengthABSquare = AB.lengthSquare(); + + // If the closest point is on the segment AB + if (APDotAB < lengthABSquare) { + t = APDotAB / lengthABSquare; + + bitsUsedPoints = 3; // 0011 (both A and B are used) + + } + else { // If the origin is on the side of B that is not in the direction of A + // Therefore, the closest point is B + t = decimal(1.0); + + bitsUsedPoints = 2; // 0010 (only B is used) + } + } + else { // If the origin is on the side of A that is not in the direction of B + // Therefore, the closest point of the line is A + t = decimal(0.0); + + bitsUsedPoints = 1; // 0001 (only A is used) + } + + // Compute the closest point + mClosestSuppPointA = mSuppPointsA[0] + t * (mSuppPointsA[1] - mSuppPointsA[0]); + mClosestSuppPointB = mSuppPointsB[0] + t * (mSuppPointsB[1] - mSuppPointsB[0]); + mClosestPoint = mClosestSuppPointA - mClosestSuppPointB; + setBarycentricCoords(decimal(1.0) - t, t, 0, 0); + mIsClosestPointValid = checkClosestPointValid(); + + // Reduce the simplex (remove vertices that are not participating to + // the closest point + reduceSimplex(bitsUsedPoints); + } + break; + + case 3: + { + // The simplex is a triangle. We need to find the point of that + // triangle that is closest to the origin + + int bitsUsedVertices = 0; + Vector3 baryCoords; + + // Compute the point of the triangle closest to the origin + computeClosestPointOnTriangle(mPoints[0], mPoints[1], mPoints[2], bitsUsedVertices, baryCoords); + mClosestSuppPointA = baryCoords[0] * mSuppPointsA[0] + baryCoords[1] * mSuppPointsA[1] + + baryCoords[2] * mSuppPointsA[2]; + mClosestSuppPointB = baryCoords[0] * mSuppPointsB[0] + baryCoords[1] * mSuppPointsB[1] + + baryCoords[2] * mSuppPointsB[2]; + mClosestPoint = mClosestSuppPointA - mClosestSuppPointB; + + setBarycentricCoords(baryCoords.x, baryCoords.y, baryCoords.z, 0.0); + mIsClosestPointValid = checkClosestPointValid(); + + // Reduce the simplex (remove vertices that are not participating to + // the closest point + reduceSimplex(bitsUsedVertices); + } + break; + + case 4: + + { + // The simplex is a tetrahedron. We need to find the point of that + // tetrahedron that is closest to the origin + + int bitsUsedVertices = 0; + Vector2 baryCoordsAB; + Vector2 baryCoordsCD; + + // Compute the point closest to the origin on the tetrahedron + bool isOutside = computeClosestPointOnTetrahedron(mPoints[0], mPoints[1], mPoints[2], mPoints[3], + bitsUsedVertices, baryCoordsAB, baryCoordsCD); + + // If the origin is outside the tetrahedron + if (isOutside) { + + // Compute the point of the tetrahedron closest to the origin + mClosestSuppPointA = baryCoordsAB.x * mSuppPointsA[0] + baryCoordsAB.y * mSuppPointsA[1] + + baryCoordsCD.x * mSuppPointsA[2] + baryCoordsCD.y * mSuppPointsA[3]; + mClosestSuppPointB = baryCoordsAB.x * mSuppPointsB[0] + baryCoordsAB.y * mSuppPointsB[1] + + baryCoordsCD.x * mSuppPointsB[2] + baryCoordsCD.y * mSuppPointsB[3]; + mClosestPoint = mClosestSuppPointA - mClosestSuppPointB; + + setBarycentricCoords(baryCoordsAB.x, baryCoordsAB.y, baryCoordsCD.x, baryCoordsCD.y); + + // Reduce the simplex (remove vertices that are not participating to + // the closest point + reduceSimplex(bitsUsedVertices); + } + else { + + // The origin is inside the tetrahedron, therefore, the closest point + // is the origin + + setBarycentricCoords(0.0, 0.0, 0.0, 0.0); + + mClosestSuppPointA.setToZero(); + mClosestSuppPointB.setToZero(); + mClosestPoint.setToZero(); + + mIsClosestPointValid = true; + + break; + } + + mIsClosestPointValid = checkClosestPointValid(); + + } + break; + } + } + + return mIsClosestPointValid; +} + +// Compute point on a triangle that is closest to the origin +/// This implementation is based on the one in the book +/// "Real-Time Collision Detection" by Christer Ericson. +void VoronoiSimplex::computeClosestPointOnTriangle(const Vector3& a, const Vector3& b, + const Vector3& c, int& bitsUsedVertices, Vector3& baryCoordsABC) const { + + // Check if the origin is in the Voronoi region of vertex A + Vector3 ab = b - a; + Vector3 ac = c - a; + Vector3 ap = -a; + decimal d1 = ab.dot(ap); + decimal d2 = ac.dot(ap); + if (d1 <= decimal(0.0) && d2 <= decimal(0.0)) { + + // The origin is in the Voronoi region of vertex A + + // Set the barycentric coords of the closest point on the triangle + baryCoordsABC.setAllValues(1.0, 0, 0); + + bitsUsedVertices = 1; // 0001 (only A is used) + return; + } + + // Check if the origin is in the Voronoi region of vertex B + Vector3 bp = -b; + decimal d3 = ab.dot(bp); + decimal d4 = ac.dot(bp); + if (d3 >= decimal(0.0) && d4 <= d3) { + + // The origin is in the Voronoi region of vertex B + + // Set the barycentric coords of the closest point on the triangle + baryCoordsABC.setAllValues(0.0, 1.0, 0); + + bitsUsedVertices = 2; // 0010 (only B is used) + return; + } + + // Check if the origin is in the Voronoi region of edge AB + decimal vc = d1 * d4 - d3 * d2; + if (vc <= decimal(0.0) && d1 >= decimal(0.0) && d3 <= decimal(0.0)) { + + // The origin is in the Voronoi region of edge AB + // We return the projection of the origin on the edge AB + decimal v = d1 / (d1 - d3); + + // Set the barycentric coords of the closest point on the triangle + baryCoordsABC.setAllValues(decimal(1.0) - v, v, 0); + + bitsUsedVertices = 3; // 0011 (A and B are used) + return; + } + + // Check if the origin is in the Voronoi region of vertex C + Vector3 cp = -c; + decimal d5 = ab.dot(cp); + decimal d6 = ac.dot(cp); + if (d6 >= decimal(0.0) && d5 <= d6) { + + // The origin is in the Voronoi region of vertex C + + // Set the barycentric coords of the closest point on the triangle + baryCoordsABC.setAllValues(0.0, 0.0, 1.0); + + bitsUsedVertices = 4; // 0100 (only C is used) + return; + } + + // Check if the origin is in the Voronoi region of edge AC + decimal vb = d5 * d2 - d1 * d6; + if (vb <= decimal(0.0) && d2 >= decimal(0.0) && d6 <= decimal(0.0)) { + + // The origin is in the Voronoi region of edge AC + // We return the projection of the origin on the edge AC + decimal w = d2 / (d2 - d6); + + // Set the barycentric coords of the closest point on the triangle + baryCoordsABC.setAllValues(decimal(1.0) - w, 0, w); + + bitsUsedVertices = 5; // 0101 (A and C are used) + return; + } + + // Check if the origin is in the Voronoi region of edge BC + decimal va = d3 * d6 - d5 * d4; + if (va <= decimal(0.0) && (d4 - d3) >= decimal(0.0) && (d5 - d6) >= decimal(0.0)) { + + // The origin is in the Voronoi region of edge BC + // We return the projection of the origin on the edge BC + decimal w = (d4 - d3) / ((d4 - d3) + (d5 - d6)); + + // Set the barycentric coords of the closest point on the triangle + baryCoordsABC.setAllValues(0.0, decimal(1.0) - w, w); + + bitsUsedVertices = 6; // 0110 (B and C are used) + return; + } + + // The origin is in the Voronoi region of the face ABC + decimal denom = decimal(1.0) / (va + vb + vc); + decimal v = vb * denom; + decimal w = vc * denom; + + // Set the barycentric coords of the closest point on the triangle + baryCoordsABC.setAllValues(1 - v - w, v, w); + + bitsUsedVertices = 7; // 0111 (A, B and C are used) + return; +} + +// Compute point of a tetrahedron that is closest to the origin +/// This implementation is based on the one in the book +/// "Real-Time Collision Detection" by Christer Ericson. +/// This method returns true if the origin is outside the tetrahedron. +bool VoronoiSimplex::computeClosestPointOnTetrahedron(const Vector3& a, const Vector3& b, const Vector3& c, + const Vector3& d, int& bitsUsedPoints, Vector2& baryCoordsAB, + Vector2& baryCoordsCD) const { + + // Start as if the origin was inside the tetrahedron + bitsUsedPoints = 15; // 1111 (A, B, C and D are used) + baryCoordsAB.setToZero(); + baryCoordsCD.setToZero(); + + // Check if the origin is outside each tetrahedron face + int isOriginOutsideFaceABC = testOriginOutsideOfPlane(a, b, c, d); + int isOriginOutsideFaceACD = testOriginOutsideOfPlane(a, c, d, b); + int isOriginOutsideFaceADB = testOriginOutsideOfPlane(a, d, b, c); + int isOriginOutsideFaceBDC = testOriginOutsideOfPlane(b, d, c, a); + + if (isOriginOutsideFaceABC == 0 && isOriginOutsideFaceACD == 0 && + isOriginOutsideFaceADB == 0 && isOriginOutsideFaceBDC == 0) { + + // The origin is inside the tetrahedron + return true; + } + + // We know that the origin is outside the tetrahedron, we now need to find + // which of the four triangle faces is closest to it. + + decimal closestSquareDistance = DECIMAL_LARGEST; + int tempUsedVertices; + Vector3 triangleBaryCoords; + + // If the origin is outside face ABC + if (isOriginOutsideFaceABC) { + + // Compute the closest point on this triangle face + computeClosestPointOnTriangle(a, b, c, tempUsedVertices, triangleBaryCoords); + Vector3 closestPoint = triangleBaryCoords[0] * a + triangleBaryCoords[1] * b + + triangleBaryCoords[2] * c; + decimal squareDist = closestPoint.lengthSquare(); + + // If the point on that face is the closest to the origin so far + if (squareDist < closestSquareDistance) { + + // Use it as the current closest point + closestSquareDistance = squareDist; + baryCoordsAB.setAllValues(triangleBaryCoords[0], triangleBaryCoords[1]); + baryCoordsCD.setAllValues(triangleBaryCoords[2], 0.0); + bitsUsedPoints = tempUsedVertices; + } + } + + // If the origin is outside face ACD + if (isOriginOutsideFaceACD) { + + // Compute the closest point on this triangle face + computeClosestPointOnTriangle(a, c, d, tempUsedVertices, triangleBaryCoords); + Vector3 closestPoint = triangleBaryCoords[0] * a + triangleBaryCoords[1] * c + + triangleBaryCoords[2] * d; + decimal squareDist = closestPoint.lengthSquare(); + + // If the point on that face is the closest to the origin so far + if (squareDist < closestSquareDistance) { + + // Use it as the current closest point + closestSquareDistance = squareDist; + baryCoordsAB.setAllValues(triangleBaryCoords[0], 0.0); + baryCoordsCD.setAllValues(triangleBaryCoords[1], triangleBaryCoords[2]); + bitsUsedPoints = mapTriangleUsedVerticesToTetrahedron(tempUsedVertices, 0, 2, 3); + } + } + + // If the origin is outside face + if (isOriginOutsideFaceADB) { + + // Compute the closest point on this triangle face + computeClosestPointOnTriangle(a, d, b, tempUsedVertices, triangleBaryCoords); + Vector3 closestPoint = triangleBaryCoords[0] * a + triangleBaryCoords[1] * d + + triangleBaryCoords[2] * b; + decimal squareDist = closestPoint.lengthSquare(); + + // If the point on that face is the closest to the origin so far + if (squareDist < closestSquareDistance) { + + // Use it as the current closest point + closestSquareDistance = squareDist; + baryCoordsAB.setAllValues(triangleBaryCoords[0], triangleBaryCoords[2]); + baryCoordsCD.setAllValues(0.0, triangleBaryCoords[1]); + bitsUsedPoints = mapTriangleUsedVerticesToTetrahedron(tempUsedVertices, 0, 3, 1); + } + } + + // If the origin is outside face + if (isOriginOutsideFaceBDC) { + + // Compute the closest point on this triangle face + computeClosestPointOnTriangle(b, d, c, tempUsedVertices, triangleBaryCoords); + Vector3 closestPoint = triangleBaryCoords[0] * b + triangleBaryCoords[1] * d + + triangleBaryCoords[2] * c; + decimal squareDist = closestPoint.lengthSquare(); + + // If the point on that face is the closest to the origin so far + if (squareDist < closestSquareDistance) { + + // Use it as the current closest point + closestSquareDistance = squareDist; + baryCoordsAB.setAllValues(0.0, triangleBaryCoords[0]); + baryCoordsCD.setAllValues(triangleBaryCoords[2], triangleBaryCoords[1]); + bitsUsedPoints = mapTriangleUsedVerticesToTetrahedron(tempUsedVertices, 1, 3, 2); + } + } + + return true; +} + +// 0111 (1,2,3) => 0111 +// 0011 (2,1,3) => +int VoronoiSimplex::mapTriangleUsedVerticesToTetrahedron(int triangleUsedVertices, int first, int second, int third) const { + + assert(triangleUsedVertices <= 7); + int tetrahedronUsedVertices = (((1 & triangleUsedVertices) != 0) << first) | + (((2 & triangleUsedVertices) != 0) << second) | + (((4 & triangleUsedVertices) != 0) << third); + + assert(tetrahedronUsedVertices <= 14); + return tetrahedronUsedVertices; +} + +// Test if a point is outside of the plane given by the points of the triangle (a, b, c) +/// This method returns 1 if the point d and the origin are on opposite sides of +/// the triangle face (a, b, c). It returns 0 if they are on the same side. +/// This implementation is based on the one in the book +/// "Real-Time Collision Detection" by Christer Ericson. +int VoronoiSimplex::testOriginOutsideOfPlane(const Vector3& a, const Vector3& b, const Vector3& c, const Vector3& d) const { + + // Normal of (a,b,c) triangle + const Vector3 n = (b-a).cross(c-a); + + decimal signp = (-a).dot(n); + decimal signd = (d-a).dot(n); + + // This assert is raised if the tetrahedron is degenerate (all points on the same plane) + // This should never happen because after a point is added into the simplex, the user + // of this class must check that the simplex is not affinely dependent using the + // isAffinelyDependent() method + assert(signd * signd > epsilon * epsilon); + + return signp * signd < decimal(0.0); +} + +// Backup the closest point +void VoronoiSimplex::backupClosestPointInSimplex(Vector3& v) { + decimal minDistSquare = DECIMAL_LARGEST; + Bits bit; + + for (bit = mAllBits; bit != 0x0; bit--) { + if (isSubset(bit, mAllBits) && isProperSubset(bit)) { + Vector3 u = computeClosestPointForSubset(bit); + decimal distSquare = u.dot(u); + if (distSquare < minDistSquare) { + minDistSquare = distSquare; + mBitsCurrentSimplex = bit; + v = u; + } + } + } +} + +// Return the maximum squared length of a point +decimal VoronoiSimplex::getMaxLengthSquareOfAPoint() const { + + decimal maxLengthSquare = decimal(0.0); + + for (int i=0; i maxLengthSquare) { + maxLengthSquare = lengthSquare; + } + } + + // Return the maximum squared length + return maxLengthSquare; +} diff --git a/src/collision/narrowphase/GJK/VoronoiSimplex.h b/src/collision/narrowphase/GJK/VoronoiSimplex.h new file mode 100644 index 00000000..9d1ba580 --- /dev/null +++ b/src/collision/narrowphase/GJK/VoronoiSimplex.h @@ -0,0 +1,201 @@ +/******************************************************************************** +* 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_VORONOI_SIMPLEX_H +#define REACTPHYSICS3D_VORONOI_SIMPLEX_H + +// Libraries +#include "mathematics/mathematics.h" +#include + +/// ReactPhysics3D namespace +namespace reactphysics3d { + +// Type definitions +typedef unsigned int Bits; + +// Class VoronoiSimplex +/** + * This class represents a simplex which is a set of 3D points. This + * class is used in the GJK algorithm. This implementation is based in the book + * "Real-Time Collision Detection" by Christer Ericson. This simple is used to + * replace theJohnson's algorithm for computing the point of a simplex that + * is closest to the origin and also the smallest simplex needed to represent + * that closest point. + */ +class VoronoiSimplex { + + private: + + // -------------------- Attributes -------------------- // + + /// Current points + Vector3 mPoints[4]; + + /// Number of vertices in the simplex + int mNbPoints; + + /// Barycentric coordinates of the closest point using simplex vertices + decimal mBarycentricCoords[4]; + + /// pointsLengthSquare[i] = (points[i].length)^2 + decimal mPointsLengthSquare[4]; + + /// Support points of object A in local coordinates + Vector3 mSuppPointsA[4]; + + /// Support points of object B in local coordinates + Vector3 mSuppPointsB[4]; + + /// True if the closest point has to be recomputed (because the simplex has changed) + bool mRecomputeClosestPoint; + + /// Current point that is closest to the origin + Vector3 mClosestPoint; + + /// Current closest point on object A + Vector3 mClosestSuppPointA; + + /// Current closest point on object B + Vector3 mClosestSuppPointB; + + /// True if the last computed closest point is valid + bool mIsClosestPointValid; + + /// Epsilon value + static decimal epsilon; + + // -------------------- Methods -------------------- // + + /// Private copy-constructor + VoronoiSimplex(const VoronoiSimplex& simplex); + + /// Private assignment operator + VoronoiSimplex& operator=(const VoronoiSimplex& simplex); + + /// Set the barycentric coordinates of the closest point + void setBarycentricCoords(decimal a, decimal b, decimal c, decimal d); + + /// Recompute the closest point if the simplex has been modified + bool recomputeClosestPoint(); + + /// Return true if the + bool checkClosestPointValid() const; + + /// Compute point of a triangle that is closest to the origin + void computeClosestPointOnTriangle(const Vector3& a, const Vector3& b, + const Vector3& c, int& bitsUsedPoints, Vector3& baryCoordsABC) const; + + /// Compute point of a tetrahedron that is closest to the origin + bool computeClosestPointOnTetrahedron(const Vector3& a, const Vector3& b, + const Vector3& c, const Vector3& d, + int& bitsUsedPoints, Vector2& baryCoordsAB, Vector2& baryCoordsCD) const; + + /// Test if a point is outside of the plane given by the points of the triangle (a, b, c) + int testOriginOutsideOfPlane(const Vector3& a, const Vector3& b, const Vector3& c, const Vector3& d) const; + + /// Remap the used vertices bits of a triangle to the corresponding used vertices of a tetrahedron + int mapTriangleUsedVerticesToTetrahedron(int triangleUsedVertices, int first, int second, int third) const; + + public: + + // -------------------- Methods -------------------- // + + /// Constructor + VoronoiSimplex(); + + /// Destructor + ~VoronoiSimplex(); + + /// Return true if the simplex contains 4 points + bool isFull() const; + + /// Return true if the simplex is empty + bool isEmpty() const; + + /// Return the points of the simplex + int getSimplex(Vector3* mSuppPointsA, Vector3* mSuppPointsB, Vector3* mPoints) const; + + /// Return the maximum squared length of a point + decimal getMaxLengthSquareOfAPoint() const; + + /// Add a new support point of (A-B) into the simplex + void addPoint(const Vector3& point, const Vector3& suppPointA, const Vector3& suppPointB); + + /// Remove a point from the simplex + void removePoint(int index); + + /// Reduce the simplex (only keep vertices that participate to the point closest to the origin) + void reduceSimplex(int bitsUsedPoints); + + /// Return true if the point is in the simplex + bool isPointInSimplex(const Vector3& point) const; + + /// Return true if the set is affinely dependent + bool isAffinelyDependent() const; + + /// Backup the closest point + void backupClosestPointInSimplex(Vector3& point); + + /// Compute the closest points "pA" and "pB" of object A and B. + void computeClosestPointsOfAandB(Vector3& pA, Vector3& pB); + + /// Compute the closest point to the origin of the current simplex. + bool computeClosestPoint(Vector3& v); +}; + +// Return true if the simplex contains 4 points +inline bool VoronoiSimplex::isFull() const { + return mNbPoints == 4; +} + +// Return true if the simple is empty +inline bool VoronoiSimplex::isEmpty() const { + return mNbPoints == 0; +} + +// Set the barycentric coordinates of the closest point +inline void VoronoiSimplex::setBarycentricCoords(decimal a, decimal b, decimal c, decimal d) { + mBarycentricCoords[0] = a; + mBarycentricCoords[1] = b; + mBarycentricCoords[2] = c; + mBarycentricCoords[3] = d; +} + +// Compute the closest point "v" to the origin of the current simplex. +inline bool VoronoiSimplex::computeClosestPoint(Vector3& v) { + + bool isValid = recomputeClosestPoint(); + v = mClosestPoint; + return isValid; +} + +// Return true if the +inline bool VoronoiSimplex::checkClosestPointValid() const { + return mBarycentricCoords[0] >= decimal(0.0) && mBarycentricCoords[1] >= decimal(0.0) && + mBarycentricCoords[2] >= decimal(0.0) && mBarycentricCoords[3] >= decimal(0.0); +} + +#endif From ccd33c2502350af867dfb8659d2f004dd8a66e44 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 27 Jun 2016 18:50:12 +0200 Subject: [PATCH 008/248] Fix issue in VoronoiSimplex --- .../narrowphase/GJK/VoronoiSimplex.cpp | 136 ++++++++++-------- .../narrowphase/GJK/VoronoiSimplex.h | 9 +- 2 files changed, 83 insertions(+), 62 deletions(-) diff --git a/src/collision/narrowphase/GJK/VoronoiSimplex.cpp b/src/collision/narrowphase/GJK/VoronoiSimplex.cpp index cf7acd7a..a30f52ff 100644 --- a/src/collision/narrowphase/GJK/VoronoiSimplex.cpp +++ b/src/collision/narrowphase/GJK/VoronoiSimplex.cpp @@ -63,7 +63,7 @@ void VoronoiSimplex::removePoint(int index) { mNbPoints--; mPoints[index] = mPoints[mNbPoints]; mSuppPointsA[index] = mSuppPointsA[mNbPoints]; - mSuppPointsB[index] = mSuppPointsA[mNbPoints]; + mSuppPointsB[index] = mSuppPointsB[mNbPoints]; } // Reduce the simplex (only keep vertices that participate to the point closest to the origin) @@ -138,6 +138,7 @@ bool VoronoiSimplex::isAffinelyDependent() const { case 3: return (mPoints[1] - mPoints[0]).cross(mPoints[2] - mPoints[0]).lengthSquare() <= epsilon; // Four points are independent if the tetrahedron volume is larger than zero + // Test in three different ways (for more robustness) case 4: return std::abs((mPoints[1] - mPoints[0]).dot((mPoints[2] - mPoints[0]).cross(mPoints[3] - mPoints[0]))) <= epsilon; } @@ -152,10 +153,10 @@ bool VoronoiSimplex::isAffinelyDependent() const { void VoronoiSimplex::computeClosestPointsOfAandB(Vector3& pA, Vector3& pB) { // Recompute the closest point (if necessary) - recomputeClosestPoint(); + //recomputeClosestPoint(); - pA = mSuppPointsA; - pB = mSuppPointsB; + pA = mClosestSuppPointA; + pB = mClosestSuppPointB; } // Recompute the closest point if the simplex has been modified @@ -195,38 +196,11 @@ bool VoronoiSimplex::recomputeClosestPoint() { { int bitsUsedPoints = 0; + float t; // The simplex is a line AB (where A=mPoints[0] and B=mPoints[1]. // We need to find the point of that line closest to the origin - Vector3 AP = -mPoints[0]; - Vector3 AB = mPoints[1] - mPoints[0]; - decimal APDotAB = AP.dot(AB); - decimal t; - - // If the closest point is on the side of A in the direction of B - if (APDotAB > decimal(0.0)) { - decimal lengthABSquare = AB.lengthSquare(); - - // If the closest point is on the segment AB - if (APDotAB < lengthABSquare) { - t = APDotAB / lengthABSquare; - - bitsUsedPoints = 3; // 0011 (both A and B are used) - - } - else { // If the origin is on the side of B that is not in the direction of A - // Therefore, the closest point is B - t = decimal(1.0); - - bitsUsedPoints = 2; // 0010 (only B is used) - } - } - else { // If the origin is on the side of A that is not in the direction of B - // Therefore, the closest point of the line is A - t = decimal(0.0); - - bitsUsedPoints = 1; // 0001 (only A is used) - } + computeClosestPointOnSegment(mPoints[0], mPoints[1], bitsUsedPoints, t); // Compute the closest point mClosestSuppPointA = mSuppPointsA[0] + t * (mSuppPointsA[1] - mSuppPointsA[0]); @@ -275,10 +249,11 @@ bool VoronoiSimplex::recomputeClosestPoint() { int bitsUsedVertices = 0; Vector2 baryCoordsAB; Vector2 baryCoordsCD; + bool isDegenerate; // Compute the point closest to the origin on the tetrahedron bool isOutside = computeClosestPointOnTetrahedron(mPoints[0], mPoints[1], mPoints[2], mPoints[3], - bitsUsedVertices, baryCoordsAB, baryCoordsCD); + bitsUsedVertices, baryCoordsAB, baryCoordsCD, isDegenerate); // If the origin is outside the tetrahedron if (isOutside) { @@ -298,22 +273,27 @@ bool VoronoiSimplex::recomputeClosestPoint() { } else { - // The origin is inside the tetrahedron, therefore, the closest point - // is the origin + // If it is a degenerate case + if (isDegenerate) { + mIsClosestPointValid = false; + } + else { - setBarycentricCoords(0.0, 0.0, 0.0, 0.0); + // The origin is inside the tetrahedron, therefore, the closest point + // is the origin - mClosestSuppPointA.setToZero(); - mClosestSuppPointB.setToZero(); - mClosestPoint.setToZero(); + setBarycentricCoords(0.0, 0.0, 0.0, 0.0); - mIsClosestPointValid = true; + mClosestSuppPointA.setToZero(); + mClosestSuppPointB.setToZero(); + mClosestPoint.setToZero(); + mIsClosestPointValid = true; + } break; } mIsClosestPointValid = checkClosestPointValid(); - } break; } @@ -322,11 +302,45 @@ bool VoronoiSimplex::recomputeClosestPoint() { return mIsClosestPointValid; } +// Compute point of a line segment that is closest to the origin +void VoronoiSimplex::computeClosestPointOnSegment(const Vector3& a, const Vector3& b, int& bitUsedVertices, + float& t) const { + + Vector3 AP = -a; + Vector3 AB = b - a; + decimal APDotAB = AP.dot(AB); + + // If the closest point is on the side of A in the direction of B + if (APDotAB > decimal(0.0)) { + decimal lengthABSquare = AB.lengthSquare(); + + // If the closest point is on the segment AB + if (APDotAB < lengthABSquare) { + t = APDotAB / lengthABSquare; + + bitUsedVertices = 3; // 0011 (both A and B are used) + + } + else { // If the origin is on the side of B that is not in the direction of A + // Therefore, the closest point is B + t = decimal(1.0); + + bitUsedVertices = 2; // 0010 (only B is used) + } + } + else { // If the origin is on the side of A that is not in the direction of B + // Therefore, the closest point of the line is A + t = decimal(0.0); + + bitUsedVertices = 1; // 0001 (only A is used) + } +} + // Compute point on a triangle that is closest to the origin /// This implementation is based on the one in the book /// "Real-Time Collision Detection" by Christer Ericson. -void VoronoiSimplex::computeClosestPointOnTriangle(const Vector3& a, const Vector3& b, - const Vector3& c, int& bitsUsedVertices, Vector3& baryCoordsABC) const { +void VoronoiSimplex::computeClosestPointOnTriangle(const Vector3& a, const Vector3& b, const Vector3& c, + int& bitsUsedVertices, Vector3& baryCoordsABC) const { // Check if the origin is in the Voronoi region of vertex A Vector3 ab = b - a; @@ -438,7 +452,9 @@ void VoronoiSimplex::computeClosestPointOnTriangle(const Vector3& a, const Vecto /// This method returns true if the origin is outside the tetrahedron. bool VoronoiSimplex::computeClosestPointOnTetrahedron(const Vector3& a, const Vector3& b, const Vector3& c, const Vector3& d, int& bitsUsedPoints, Vector2& baryCoordsAB, - Vector2& baryCoordsCD) const { + Vector2& baryCoordsCD, bool& isDegenerate) const { + + isDegenerate = false; // Start as if the origin was inside the tetrahedron bitsUsedPoints = 15; // 1111 (A, B, C and D are used) @@ -451,6 +467,15 @@ bool VoronoiSimplex::computeClosestPointOnTetrahedron(const Vector3& a, const Ve int isOriginOutsideFaceADB = testOriginOutsideOfPlane(a, d, b, c); int isOriginOutsideFaceBDC = testOriginOutsideOfPlane(b, d, c, a); + // If we have a degenerate tetrahedron + if (isOriginOutsideFaceABC < 0 || isOriginOutsideFaceACD < 0 || + isOriginOutsideFaceADB < 0 || isOriginOutsideFaceBDC < 0) { + + // The tetrahedron is degenerate + isDegenerate = true; + return false; + } + if (isOriginOutsideFaceABC == 0 && isOriginOutsideFaceACD == 0 && isOriginOutsideFaceADB == 0 && isOriginOutsideFaceBDC == 0) { @@ -574,31 +599,20 @@ int VoronoiSimplex::testOriginOutsideOfPlane(const Vector3& a, const Vector3& b, decimal signp = (-a).dot(n); decimal signd = (d-a).dot(n); - // This assert is raised if the tetrahedron is degenerate (all points on the same plane) + // If the tetrahedron is degenerate (all points on the same plane) // This should never happen because after a point is added into the simplex, the user // of this class must check that the simplex is not affinely dependent using the // isAffinelyDependent() method - assert(signd * signd > epsilon * epsilon); + if(signd * signd < epsilon * epsilon) { + return -1; + } return signp * signd < decimal(0.0); } // Backup the closest point void VoronoiSimplex::backupClosestPointInSimplex(Vector3& v) { - decimal minDistSquare = DECIMAL_LARGEST; - Bits bit; - - for (bit = mAllBits; bit != 0x0; bit--) { - if (isSubset(bit, mAllBits) && isProperSubset(bit)) { - Vector3 u = computeClosestPointForSubset(bit); - decimal distSquare = u.dot(u); - if (distSquare < minDistSquare) { - minDistSquare = distSquare; - mBitsCurrentSimplex = bit; - v = u; - } - } - } + v = mClosestPoint; } // Return the maximum squared length of a point diff --git a/src/collision/narrowphase/GJK/VoronoiSimplex.h b/src/collision/narrowphase/GJK/VoronoiSimplex.h index 9d1ba580..7b6c6614 100644 --- a/src/collision/narrowphase/GJK/VoronoiSimplex.h +++ b/src/collision/narrowphase/GJK/VoronoiSimplex.h @@ -104,6 +104,10 @@ class VoronoiSimplex { /// Return true if the bool checkClosestPointValid() const; + /// Compute point of a line segment that is closest to the origin + void computeClosestPointOnSegment(const Vector3& a, const Vector3& b, int& bitUsedVertices, + float& t) const; + /// Compute point of a triangle that is closest to the origin void computeClosestPointOnTriangle(const Vector3& a, const Vector3& b, const Vector3& c, int& bitsUsedPoints, Vector3& baryCoordsABC) const; @@ -111,7 +115,8 @@ class VoronoiSimplex { /// Compute point of a tetrahedron that is closest to the origin bool computeClosestPointOnTetrahedron(const Vector3& a, const Vector3& b, const Vector3& c, const Vector3& d, - int& bitsUsedPoints, Vector2& baryCoordsAB, Vector2& baryCoordsCD) const; + int& bitsUsedPoints, Vector2& baryCoordsAB, Vector2& baryCoordsCD, + bool& isDegenerate) const; /// Test if a point is outside of the plane given by the points of the triangle (a, b, c) int testOriginOutsideOfPlane(const Vector3& a, const Vector3& b, const Vector3& c, const Vector3& d) const; @@ -198,4 +203,6 @@ inline bool VoronoiSimplex::checkClosestPointValid() const { mBarycentricCoords[2] >= decimal(0.0) && mBarycentricCoords[3] >= decimal(0.0); } +} + #endif From 4bad013c91faa9beff8e291280ae68c3e7441176 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 5 Jul 2016 21:34:44 +0200 Subject: [PATCH 009/248] Make GJK/EPA collision detection more robust --- src/body/CollisionBody.h | 2 +- src/collision/CollisionDetection.h | 2 +- .../narrowphase/EPA/EPAAlgorithm.cpp | 47 +++-- src/collision/narrowphase/EPA/EPAAlgorithm.h | 6 +- .../narrowphase/GJK/GJKAlgorithm.cpp | 192 +++++++----------- src/collision/narrowphase/GJK/GJKAlgorithm.h | 2 +- .../narrowphase/GJK/VoronoiSimplex.cpp | 8 +- .../narrowphase/GJK/VoronoiSimplex.h | 2 +- src/collision/shapes/BoxShape.h | 8 + src/collision/shapes/CapsuleShape.h | 8 + src/collision/shapes/CollisionShape.h | 3 + src/collision/shapes/ConcaveShape.h | 10 +- src/collision/shapes/ConeShape.h | 8 + src/collision/shapes/ConvexMeshShape.h | 8 + src/collision/shapes/CylinderShape.h | 8 + src/collision/shapes/SphereShape.h | 8 + src/collision/shapes/TriangleShape.h | 8 + 17 files changed, 187 insertions(+), 143 deletions(-) diff --git a/src/body/CollisionBody.h b/src/body/CollisionBody.h index 2c88d155..f69be6c5 100644 --- a/src/body/CollisionBody.h +++ b/src/body/CollisionBody.h @@ -303,4 +303,4 @@ inline Vector3 CollisionBody::getLocalVector(const Vector3& worldVector) const { } - #endif +#endif diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index 7e81a25f..d5c585e6 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -35,9 +35,9 @@ #include "memory/MemoryAllocator.h" #include "constraint/ContactPoint.h" #include -#include #include #include +#include /// ReactPhysics3D namespace namespace reactphysics3d { diff --git a/src/collision/narrowphase/EPA/EPAAlgorithm.cpp b/src/collision/narrowphase/EPA/EPAAlgorithm.cpp index 513ca367..6c94ed5a 100644 --- a/src/collision/narrowphase/EPA/EPAAlgorithm.cpp +++ b/src/collision/narrowphase/EPA/EPAAlgorithm.cpp @@ -81,8 +81,9 @@ int EPAAlgorithm::isOriginInTetrahedron(const Vector3& p1, const Vector3& p2, /// enlarged objects (with margin) where the original objects (without margin) /// intersect. An initial simplex that contains origin has been computed with /// GJK algorithm. The EPA Algorithm will extend this simplex polytope to find -/// the correct penetration depth -void EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simplex, +/// the correct penetration depth. This method returns true if the EPA penetration +/// depth computation has succeeded and false it has failed. +bool EPAAlgorithm::computePenetrationDepthAndContactPoints(const VoronoiSimplex& simplex, CollisionShapeInfo shape1Info, const Transform& transform1, CollisionShapeInfo shape2Info, @@ -92,6 +93,8 @@ void EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simple PROFILE("EPAAlgorithm::computePenetrationDepthAndContactPoints()"); + decimal gjkPenDepthSquare = v.lengthSquare(); + assert(shape1Info.collisionShape->isConvex()); assert(shape2Info.collisionShape->isConvex()); @@ -118,7 +121,7 @@ void EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simple transform1.getOrientation(); // Get the simplex computed previously by the GJK algorithm - unsigned int nbVertices = simplex.getSimplex(suppPointsA, suppPointsB, points); + int nbVertices = simplex.getSimplex(suppPointsA, suppPointsB, points); // Compute the tolerance decimal tolerance = MACHINE_EPSILON * simplex.getMaxLengthSquareOfAPoint(); @@ -137,7 +140,7 @@ void EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simple // Only one point in the simplex (which should be the origin). // We have a touching contact with zero penetration depth. // We drop that kind of contact. Therefore, we return false - return; + return true; case 2: { // The simplex returned by GJK is a line segment d containing the origin. @@ -204,7 +207,7 @@ void EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simple } else { // The origin is not in the initial polytope - return; + return false; } // The polytope contains now 4 vertices @@ -234,7 +237,7 @@ void EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simple if (!((face0 != NULL) && (face1 != NULL) && (face2 != NULL) && (face3 != NULL) && face0->getDistSquare() > 0.0 && face1->getDistSquare() > 0.0 && face2->getDistSquare() > 0.0 && face3->getDistSquare() > 0.0)) { - return; + return false; } // Associate the edges of neighbouring triangle faces @@ -319,14 +322,14 @@ void EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simple face3 = triangleStore.newTriangle(points, 1, 4, 2); } else { - return; + return false; } // If the constructed tetrahedron is not correct if (!((face0 != NULL) && (face1 != NULL) && (face2 != NULL) && (face3 != NULL) && face0->getDistSquare() > 0.0 && face1->getDistSquare() > 0.0 && face2->getDistSquare() > 0.0 && face3->getDistSquare() > 0.0)) { - return; + return false; } // Associate the edges of neighbouring triangle faces @@ -353,7 +356,7 @@ void EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simple // can run the EPA algorithm. if (nbTriangles == 0) { - return; + return false; } TriangleEPA* triangle = 0; @@ -368,6 +371,7 @@ void EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simple // If the candidate face in the heap is not obsolete if (!triangle->getIsObsolete()) { + // If we have reached the maximum number of support points if (nbVertices == MAX_SUPPORT_POINTS) { assert(false); @@ -388,7 +392,7 @@ void EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simple // Update the upper bound of the penetration depth decimal wDotv = points[indexNewVertex].dot(triangle->getClosestPoint()); - assert(wDotv > 0.0); + decimal wDotVSquare = wDotv * wDotv / triangle->getDistSquare(); if (wDotVSquare < upperBoundSquarePenDepth) { upperBoundSquarePenDepth = wDotVSquare; @@ -427,13 +431,22 @@ void EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simple Vector3 pBLocal = body2Tobody1.getInverse() * triangle->computeClosestPointOfObject(suppPointsB); Vector3 normal = v.getUnit(); decimal penetrationDepth = v.length(); - assert(penetrationDepth > 0.0); - if (normal.lengthSquare() < MACHINE_EPSILON) return; - - // Create the contact info object - ContactPointInfo contactInfo(shape1Info.proxyShape, shape2Info.proxyShape, shape1Info.collisionShape, - shape2Info.collisionShape, normal, penetrationDepth, pALocal, pBLocal); + // If the length of the normal vector is too small, skip this contact point + if (normal.lengthSquare() < MACHINE_EPSILON) { + return false; + } - narrowPhaseCallback->notifyContact(shape1Info.overlappingPair, contactInfo); + if (penetrationDepth * penetrationDepth > gjkPenDepthSquare && penetrationDepth > 0) { + + // Create the contact info object + ContactPointInfo contactInfo(shape1Info.proxyShape, shape2Info.proxyShape, shape1Info.collisionShape, + shape2Info.collisionShape, normal, penetrationDepth, pALocal, pBLocal); + + narrowPhaseCallback->notifyContact(shape1Info.overlappingPair, contactInfo); + + return true; + } + + return false; } diff --git a/src/collision/narrowphase/EPA/EPAAlgorithm.h b/src/collision/narrowphase/EPA/EPAAlgorithm.h index 1d4b527a..377ccc11 100644 --- a/src/collision/narrowphase/EPA/EPAAlgorithm.h +++ b/src/collision/narrowphase/EPA/EPAAlgorithm.h @@ -27,7 +27,7 @@ #define REACTPHYSICS3D_EPA_ALGORITHM_H // Libraries -#include "collision/narrowphase/GJK/Simplex.h" +#include "collision/narrowphase/GJK/VoronoiSimplex.h" #include "collision/shapes/CollisionShape.h" #include "collision/CollisionShapeInfo.h" #include "constraint/ContactPoint.h" @@ -123,13 +123,13 @@ class EPAAlgorithm { void init(MemoryAllocator* memoryAllocator); /// Compute the penetration depth with EPA algorithm. - void computePenetrationDepthAndContactPoints(const Simplex& simplex, + bool computePenetrationDepthAndContactPoints(const VoronoiSimplex& simplex, CollisionShapeInfo shape1Info, const Transform& transform1, CollisionShapeInfo shape2Info, const Transform& transform2, Vector3& v, - NarrowPhaseCallback* narrowPhaseCallback); + NarrowPhaseCallback* narrowPhaseCallback); }; // Add a triangle face in the candidate triangle heap in the EPA algorithm diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp index 49db5968..a9419bb5 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp @@ -69,6 +69,7 @@ void GJKAlgorithm::testCollision(const CollisionShapeInfo& shape1Info, Vector3 pB; // Closest point of object B decimal vDotw; decimal prevDistSquare; + bool contactFound = false; assert(shape1Info.collisionShape->isConvex()); assert(shape2Info.collisionShape->isConvex()); @@ -79,6 +80,8 @@ void GJKAlgorithm::testCollision(const CollisionShapeInfo& shape1Info, void** shape1CachedCollisionData = shape1Info.cachedCollisionData; void** shape2CachedCollisionData = shape2Info.cachedCollisionData; + bool isPolytopeShape = shape1->isPolyhedron() && shape2->isPolyhedron(); + // Get the local-space to world-space transforms const Transform transform1 = shape1Info.shapeToWorldTransform; const Transform transform2 = shape2Info.shapeToWorldTransform; @@ -98,7 +101,7 @@ void GJKAlgorithm::testCollision(const CollisionShapeInfo& shape1Info, assert(margin > 0.0); // Create a simplex set - Simplex simplex; + VoronoiSimplex simplex; // Get the previous point V (last cached separating axis) Vector3 v = mCurrentOverlappingPair->getCachedSeparatingAxis(); @@ -131,31 +134,9 @@ void GJKAlgorithm::testCollision(const CollisionShapeInfo& shape1Info, // If the objects intersect only in the margins if (simplex.isPointInSimplex(w) || distSquare - vDotw <= distSquare * REL_ERROR_SQUARE) { - // Compute the closet points of both objects (without the margins) - simplex.computeClosestPointsOfAandB(pA, pB); - - // Project those two points on the margins to have the closest points of both - // object with the margins - decimal dist = sqrt(distSquare); - assert(dist > 0.0); - pA = (pA - (shape1->getMargin() / dist) * v); - pB = body2Tobody1.getInverse() * (pB + (shape2->getMargin() / dist) * v); - - // Compute the contact info - Vector3 normal = transform1.getOrientation() * (-v.getUnit()); - decimal penetrationDepth = margin - dist; - - // Reject the contact if the penetration depth is negative (due too numerical errors) - if (penetrationDepth <= 0.0) return; - - // Create the contact info object - ContactPointInfo contactInfo(shape1Info.proxyShape, shape2Info.proxyShape, shape1Info.collisionShape, - shape2Info.collisionShape, normal, penetrationDepth, pA, pB); - - narrowPhaseCallback->notifyContact(shape1Info.overlappingPair, contactInfo); - - // There is an intersection, therefore we return - return; + // Contact point has been found + contactFound = true; + break; } // Add the new support point to the simplex @@ -164,62 +145,24 @@ void GJKAlgorithm::testCollision(const CollisionShapeInfo& shape1Info, // If the simplex is affinely dependent if (simplex.isAffinelyDependent()) { - // Compute the closet points of both objects (without the margins) - simplex.computeClosestPointsOfAandB(pA, pB); - - // Project those two points on the margins to have the closest points of both - // object with the margins - decimal dist = sqrt(distSquare); - assert(dist > 0.0); - pA = (pA - (shape1->getMargin() / dist) * v); - pB = body2Tobody1.getInverse() * (pB + (shape2->getMargin() / dist) * v); - - // Compute the contact info - Vector3 normal = transform1.getOrientation() * (-v.getUnit()); - decimal penetrationDepth = margin - dist; - - // Reject the contact if the penetration depth is negative (due too numerical errors) - if (penetrationDepth <= 0.0) return; - - // Create the contact info object - ContactPointInfo contactInfo(shape1Info.proxyShape, shape2Info.proxyShape, shape1Info.collisionShape, - shape2Info.collisionShape, normal, penetrationDepth, pA, pB); - - narrowPhaseCallback->notifyContact(shape1Info.overlappingPair, contactInfo); - - // There is an intersection, therefore we return - return; + // Contact point has been found + contactFound = true; + break; } // Compute the point of the simplex closest to the origin - // If the computation of the closest point fail + // If the computation of the closest point fails if (!simplex.computeClosestPoint(v)) { - // Compute the closet points of both objects (without the margins) - simplex.computeClosestPointsOfAandB(pA, pB); + // Contact point has been found + contactFound = true; + break; + } - // Project those two points on the margins to have the closest points of both - // object with the margins - decimal dist = sqrt(distSquare); - assert(dist > 0.0); - pA = (pA - (shape1->getMargin() / dist) * v); - pB = body2Tobody1.getInverse() * (pB + (shape2->getMargin() / dist) * v); - - // Compute the contact info - Vector3 normal = transform1.getOrientation() * (-v.getUnit()); - decimal penetrationDepth = margin - dist; - - // Reject the contact if the penetration depth is negative (due too numerical errors) - if (penetrationDepth <= 0.0) return; - - // Create the contact info object - ContactPointInfo contactInfo(shape1Info.proxyShape, shape2Info.proxyShape, shape1Info.collisionShape, - shape2Info.collisionShape, normal, penetrationDepth, pA, pB); - - narrowPhaseCallback->notifyContact(shape1Info.overlappingPair, contactInfo); - - // There is an intersection, therefore we return - return; + // Closest point is almost the origin, go to EPA algorithm + // Vector v to small to continue computing support points + if (v.lengthSquare() < MACHINE_EPSILON) { + break; } // Store and update the squared distance of the closest point @@ -228,46 +171,65 @@ void GJKAlgorithm::testCollision(const CollisionShapeInfo& shape1Info, // If the distance to the closest point doesn't improve a lot if (prevDistSquare - distSquare <= MACHINE_EPSILON * prevDistSquare) { + simplex.backupClosestPointInSimplex(v); // Get the new squared distance distSquare = v.lengthSquare(); - // Compute the closet points of both objects (without the margins) - simplex.computeClosestPointsOfAandB(pA, pB); + // Contact point has been found + contactFound = true; + break; + } - // Project those two points on the margins to have the closest points of both - // object with the margins - decimal dist = sqrt(distSquare); - assert(dist > 0.0); - pA = (pA - (shape1->getMargin() / dist) * v); - pB = body2Tobody1.getInverse() * (pB + (shape2->getMargin() / dist) * v); + } while((isPolytopeShape && !simplex.isFull()) || (!isPolytopeShape && !simplex.isFull() && + distSquare > MACHINE_EPSILON * simplex.getMaxLengthSquareOfAPoint())); - // Compute the contact info - Vector3 normal = transform1.getOrientation() * (-v.getUnit()); - decimal penetrationDepth = margin - dist; - - // Reject the contact if the penetration depth is negative (due too numerical errors) - if (penetrationDepth <= 0.0) return; - - // Create the contact info object - ContactPointInfo contactInfo(shape1Info.proxyShape, shape2Info.proxyShape, shape1Info.collisionShape, - shape2Info.collisionShape, normal, penetrationDepth, pA, pB); + bool isEPAResultValid = false; - narrowPhaseCallback->notifyContact(shape1Info.overlappingPair, contactInfo); + // If no contact has been found (penetration case) + if (!contactFound) { - // There is an intersection, therefore we return + // The objects (without margins) intersect. Therefore, we run the GJK algorithm + // again but on the enlarged objects to compute a simplex polytope that contains + // the origin. Then, we give that simplex polytope to the EPA algorithm to compute + // the correct penetration depth and contact points between the enlarged objects. + isEPAResultValid = computePenetrationDepthForEnlargedObjects(shape1Info, transform1, shape2Info, + transform2, narrowPhaseCallback, v); + } + + if ((contactFound || !isEPAResultValid) && distSquare > MACHINE_EPSILON) { + + // Compute the closet points of both objects (without the margins) + simplex.computeClosestPointsOfAandB(pA, pB); + + // Project those two points on the margins to have the closest points of both + // object with the margins + decimal dist = std::sqrt(distSquare); + assert(dist > 0.0); + pA = (pA - (shape1->getMargin() / dist) * v); + pB = body2Tobody1.getInverse() * (pB + (shape2->getMargin() / dist) * v); + + // Compute the contact info + Vector3 normal = transform1.getOrientation() * (-v.getUnit()); + decimal penetrationDepth = margin - dist; + + // If the penetration depth is negative (due too numerical errors), there is no contact + if (penetrationDepth <= 0.0) { return; } - } while(!simplex.isFull() && distSquare > MACHINE_EPSILON * - simplex.getMaxLengthSquareOfAPoint()); - // The objects (without margins) intersect. Therefore, we run the GJK algorithm - // again but on the enlarged objects to compute a simplex polytope that contains - // the origin. Then, we give that simplex polytope to the EPA algorithm to compute - // the correct penetration depth and contact points between the enlarged objects. - return computePenetrationDepthForEnlargedObjects(shape1Info, transform1, shape2Info, - transform2, narrowPhaseCallback, v); + // Do not generate a contact point with zero normal length + if (normal.lengthSquare() < MACHINE_EPSILON) { + return; + } + + // Create the contact info object + ContactPointInfo contactInfo(shape1Info.proxyShape, shape2Info.proxyShape, shape1Info.collisionShape, + shape2Info.collisionShape, normal, penetrationDepth, pA, pB); + + narrowPhaseCallback->notifyContact(shape1Info.overlappingPair, contactInfo); + } } /// This method runs the GJK algorithm on the two enlarged objects (with margin) @@ -275,7 +237,7 @@ void GJKAlgorithm::testCollision(const CollisionShapeInfo& shape1Info, /// assumed to intersect in the original objects (without margin). Therefore such /// a polytope must exist. Then, we give that polytope to the EPA algorithm to /// compute the correct penetration depth and contact points of the enlarged objects. -void GJKAlgorithm::computePenetrationDepthForEnlargedObjects(const CollisionShapeInfo& shape1Info, +bool GJKAlgorithm::computePenetrationDepthForEnlargedObjects(const CollisionShapeInfo& shape1Info, const Transform& transform1, const CollisionShapeInfo& shape2Info, const Transform& transform2, @@ -283,7 +245,7 @@ void GJKAlgorithm::computePenetrationDepthForEnlargedObjects(const CollisionShap Vector3& v) { PROFILE("GJKAlgorithm::computePenetrationDepthForEnlargedObjects()"); - Simplex simplex; + VoronoiSimplex simplex; Vector3 suppA; Vector3 suppB; Vector3 w; @@ -297,6 +259,8 @@ void GJKAlgorithm::computePenetrationDepthForEnlargedObjects(const CollisionShap const ConvexShape* shape1 = static_cast(shape1Info.collisionShape); const ConvexShape* shape2 = static_cast(shape2Info.collisionShape); + bool isPolytopeShape = shape1->isPolyhedron() && shape2->isPolyhedron(); + void** shape1CachedCollisionData = shape1Info.cachedCollisionData; void** shape2CachedCollisionData = shape2Info.cachedCollisionData; @@ -322,18 +286,18 @@ void GJKAlgorithm::computePenetrationDepthForEnlargedObjects(const CollisionShap if (vDotw > 0.0) { // No intersection, we return - return; + return false; } // Add the new support point to the simplex simplex.addPoint(w, suppA, suppB); if (simplex.isAffinelyDependent()) { - return; + return false; } if (!simplex.computeClosestPoint(v)) { - return; + return false; } // Store and update the square distance @@ -341,11 +305,11 @@ void GJKAlgorithm::computePenetrationDepthForEnlargedObjects(const CollisionShap distSquare = v.lengthSquare(); if (prevDistSquare - distSquare <= MACHINE_EPSILON * prevDistSquare) { - return; + return false; } - } while(!simplex.isFull() && distSquare > MACHINE_EPSILON * - simplex.getMaxLengthSquareOfAPoint()); + } while((!simplex.isFull() && isPolytopeShape) || (!isPolytopeShape && !simplex.isFull() && + distSquare > MACHINE_EPSILON * simplex.getMaxLengthSquareOfAPoint())); // Give the simplex computed with GJK algorithm to the EPA algorithm // which will compute the correct penetration depth and contact points @@ -372,7 +336,7 @@ bool GJKAlgorithm::testPointInside(const Vector3& localPoint, ProxyShape* proxyS const Vector3 suppB(localPoint); // Create a simplex set - Simplex simplex; + VoronoiSimplex simplex; // Initial supporting direction Vector3 v(1, 1, 1); @@ -446,7 +410,7 @@ bool GJKAlgorithm::raycast(const Ray& ray, ProxyShape* proxyShape, RaycastInfo& Vector3 w; // Create a simplex set - Simplex simplex; + VoronoiSimplex simplex; Vector3 n(decimal(0.0), decimal(0.0), decimal(0.0)); decimal lambda = decimal(0.0); diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.h b/src/collision/narrowphase/GJK/GJKAlgorithm.h index 23ebc789..8617a002 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.h +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.h @@ -75,7 +75,7 @@ class GJKAlgorithm : public NarrowPhaseAlgorithm { GJKAlgorithm& operator=(const GJKAlgorithm& algorithm); /// Compute the penetration depth for enlarged objects. - void computePenetrationDepthForEnlargedObjects(const CollisionShapeInfo& shape1Info, + bool computePenetrationDepthForEnlargedObjects(const CollisionShapeInfo& shape1Info, const Transform& transform1, const CollisionShapeInfo& shape2Info, const Transform& transform2, diff --git a/src/collision/narrowphase/GJK/VoronoiSimplex.cpp b/src/collision/narrowphase/GJK/VoronoiSimplex.cpp index a30f52ff..382ccc9b 100644 --- a/src/collision/narrowphase/GJK/VoronoiSimplex.cpp +++ b/src/collision/narrowphase/GJK/VoronoiSimplex.cpp @@ -150,10 +150,7 @@ bool VoronoiSimplex::isAffinelyDependent() const { /// pA = sum(lambda_i * a_i) where "a_i" are the support points of object A /// pB = sum(lambda_i * b_i) where "b_i" are the support points of object B /// with lambda_i = deltaX_i / deltaX -void VoronoiSimplex::computeClosestPointsOfAandB(Vector3& pA, Vector3& pB) { - - // Recompute the closest point (if necessary) - //recomputeClosestPoint(); +void VoronoiSimplex::computeClosestPointsOfAandB(Vector3& pA, Vector3& pB) const { pA = mClosestSuppPointA; pB = mClosestSuppPointB; @@ -380,6 +377,7 @@ void VoronoiSimplex::computeClosestPointOnTriangle(const Vector3& a, const Vecto // The origin is in the Voronoi region of edge AB // We return the projection of the origin on the edge AB + assert(std::abs(d1 - d3) > MACHINE_EPSILON); decimal v = d1 / (d1 - d3); // Set the barycentric coords of the closest point on the triangle @@ -410,6 +408,7 @@ void VoronoiSimplex::computeClosestPointOnTriangle(const Vector3& a, const Vecto // The origin is in the Voronoi region of edge AC // We return the projection of the origin on the edge AC + assert(std::abs(d2 - d6) > MACHINE_EPSILON); decimal w = d2 / (d2 - d6); // Set the barycentric coords of the closest point on the triangle @@ -425,6 +424,7 @@ void VoronoiSimplex::computeClosestPointOnTriangle(const Vector3& a, const Vecto // The origin is in the Voronoi region of edge BC // We return the projection of the origin on the edge BC + assert(std::abs((d4 - d3) + (d5 - d6)) > MACHINE_EPSILON); decimal w = (d4 - d3) / ((d4 - d3) + (d5 - d6)); // Set the barycentric coords of the closest point on the triangle diff --git a/src/collision/narrowphase/GJK/VoronoiSimplex.h b/src/collision/narrowphase/GJK/VoronoiSimplex.h index 7b6c6614..9cbee47e 100644 --- a/src/collision/narrowphase/GJK/VoronoiSimplex.h +++ b/src/collision/narrowphase/GJK/VoronoiSimplex.h @@ -165,7 +165,7 @@ class VoronoiSimplex { void backupClosestPointInSimplex(Vector3& point); /// Compute the closest points "pA" and "pB" of object A and B. - void computeClosestPointsOfAandB(Vector3& pA, Vector3& pB); + void computeClosestPointsOfAandB(Vector3& pA, Vector3& pB) const; /// Compute the closest point to the origin of the current simplex. bool computeClosestPoint(Vector3& v); diff --git a/src/collision/shapes/BoxShape.h b/src/collision/shapes/BoxShape.h index f581baa0..bda4bf3f 100644 --- a/src/collision/shapes/BoxShape.h +++ b/src/collision/shapes/BoxShape.h @@ -99,6 +99,9 @@ class BoxShape : public ConvexShape { /// Return the local bounds of the shape in x, y and z directions virtual void getLocalBounds(Vector3& min, Vector3& max) const; + /// Return true if the collision shape is a polyhedron + virtual bool isPolyhedron() const; + /// Return the local inertia tensor of the collision shape virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; }; @@ -134,6 +137,11 @@ inline void BoxShape::getLocalBounds(Vector3& min, Vector3& max) const { min = -max; } +// Return true if the collision shape is a polyhedron +inline bool BoxShape::isPolyhedron() const { + return true; +} + // Return the number of bytes used by the collision shape inline size_t BoxShape::getSizeInBytes() const { return sizeof(BoxShape); diff --git a/src/collision/shapes/CapsuleShape.h b/src/collision/shapes/CapsuleShape.h index 56269d04..8e77f050 100644 --- a/src/collision/shapes/CapsuleShape.h +++ b/src/collision/shapes/CapsuleShape.h @@ -101,6 +101,9 @@ class CapsuleShape : public ConvexShape { /// Return the local bounds of the shape in x, y and z directions virtual void getLocalBounds(Vector3& min, Vector3& max) const; + /// Return true if the collision shape is a polyhedron + virtual bool isPolyhedron() const; + /// Return the local inertia tensor of the collision shape virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; }; @@ -154,6 +157,11 @@ inline void CapsuleShape::getLocalBounds(Vector3& min, Vector3& max) const { min.z = min.x; } +// Return true if the collision shape is a polyhedron +inline bool CapsuleShape::isPolyhedron() const { + return false; +} + // Return a local support point in a given direction without the object margin. /// A capsule is the convex hull of two spheres S1 and S2. The support point in the direction "d" /// of the convex hull of a set of convex objects is the support point "p" in the set of all diff --git a/src/collision/shapes/CollisionShape.h b/src/collision/shapes/CollisionShape.h index cd89255d..80419c03 100644 --- a/src/collision/shapes/CollisionShape.h +++ b/src/collision/shapes/CollisionShape.h @@ -98,6 +98,9 @@ class CollisionShape { /// Return true if the collision shape is convex, false if it is concave virtual bool isConvex() const=0; + /// Return true if the collision shape is a polyhedron + virtual bool isPolyhedron() const=0; + /// Return the local bounds of the shape in x, y and z directions virtual void getLocalBounds(Vector3& min, Vector3& max) const=0; diff --git a/src/collision/shapes/ConcaveShape.h b/src/collision/shapes/ConcaveShape.h index 9c1418df..9cee92ab 100644 --- a/src/collision/shapes/ConcaveShape.h +++ b/src/collision/shapes/ConcaveShape.h @@ -101,6 +101,9 @@ class ConcaveShape : public CollisionShape { /// Return true if the collision shape is convex, false if it is concave virtual bool isConvex() const; + /// Return true if the collision shape is a polyhedron + virtual bool isPolyhedron() const; + /// Use a callback method on all triangles of the concave shape inside a given AABB virtual void testAllTriangles(TriangleCallback& callback, const AABB& localAABB) const=0; @@ -116,11 +119,16 @@ inline decimal ConcaveShape::getTriangleMargin() const { return mTriangleMargin; } -/// Return true if the collision shape is convex, false if it is concave +// Return true if the collision shape is convex, false if it is concave inline bool ConcaveShape::isConvex() const { return false; } +// Return true if the collision shape is a polyhedron +inline bool ConcaveShape::isPolyhedron() const { + return true; +} + // Return true if a point is inside the collision shape inline bool ConcaveShape::testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const { return false; diff --git a/src/collision/shapes/ConeShape.h b/src/collision/shapes/ConeShape.h index b693f386..53630817 100644 --- a/src/collision/shapes/ConeShape.h +++ b/src/collision/shapes/ConeShape.h @@ -107,6 +107,9 @@ class ConeShape : public ConvexShape { /// Return the local bounds of the shape in x, y and z directions virtual void getLocalBounds(Vector3& min, Vector3& max) const; + /// Return true if the collision shape is a polyhedron + virtual bool isPolyhedron() const; + /// Return the local inertia tensor of the collision shape virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; }; @@ -159,6 +162,11 @@ inline void ConeShape::getLocalBounds(Vector3& min, Vector3& max) const { min.z = min.x; } +// Return true if the collision shape is a polyhedron +inline bool ConeShape::isPolyhedron() const { + return false; +} + // Return the local inertia tensor of the collision shape /** * @param[out] tensor The 3x3 inertia tensor matrix of the shape in local-space diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index d23e91b0..94ec67f9 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -140,6 +140,9 @@ class ConvexMeshShape : public ConvexShape { /// Add an edge into the convex mesh by specifying the two vertex indices of the edge. void addEdge(uint v1, uint v2); + /// Return true if the collision shape is a polyhedron + virtual bool isPolyhedron() const; + /// Return true if the edges information is used to speed up the collision detection bool isEdgesInformationUsed() const; @@ -159,6 +162,11 @@ inline size_t ConvexMeshShape::getSizeInBytes() const { return sizeof(ConvexMeshShape); } +// Return true if the collision shape is a polyhedron +inline bool ConvexMeshShape::isPolyhedron() const { + return true; +} + // Return the local bounds of the shape in x, y and z directions /** * @param min The minimum bounds of the shape in local-space coordinates diff --git a/src/collision/shapes/CylinderShape.h b/src/collision/shapes/CylinderShape.h index 71e4f9ae..a732ecf6 100644 --- a/src/collision/shapes/CylinderShape.h +++ b/src/collision/shapes/CylinderShape.h @@ -98,6 +98,9 @@ class CylinderShape : public ConvexShape { /// Return the height decimal getHeight() const; + /// Return true if the collision shape is a polyhedron + virtual bool isPolyhedron() const; + /// Set the scaling vector of the collision shape virtual void setLocalScaling(const Vector3& scaling); @@ -124,6 +127,11 @@ inline decimal CylinderShape::getHeight() const { return mHalfHeight + mHalfHeight; } +// Return true if the collision shape is a polyhedron +inline bool CylinderShape::isPolyhedron() const { + return false; +} + // Set the scaling vector of the collision shape inline void CylinderShape::setLocalScaling(const Vector3& scaling) { diff --git a/src/collision/shapes/SphereShape.h b/src/collision/shapes/SphereShape.h index a1316ae0..bfbe46b5 100644 --- a/src/collision/shapes/SphereShape.h +++ b/src/collision/shapes/SphereShape.h @@ -83,6 +83,9 @@ class SphereShape : public ConvexShape { /// Return the radius of the sphere decimal getRadius() const; + /// Return true if the collision shape is a polyhedron + virtual bool isPolyhedron() const; + /// Set the scaling vector of the collision shape virtual void setLocalScaling(const Vector3& scaling); @@ -104,6 +107,11 @@ inline decimal SphereShape::getRadius() const { return mMargin; } +// Return true if the collision shape is a polyhedron +inline bool SphereShape::isPolyhedron() const { + return false; +} + // Set the scaling vector of the collision shape inline void SphereShape::setLocalScaling(const Vector3& scaling) { diff --git a/src/collision/shapes/TriangleShape.h b/src/collision/shapes/TriangleShape.h index 1b9f3681..71af0f89 100644 --- a/src/collision/shapes/TriangleShape.h +++ b/src/collision/shapes/TriangleShape.h @@ -116,6 +116,9 @@ class TriangleShape : public ConvexShape { /// Return the coordinates of a given vertex of the triangle Vector3 getVertex(int index) const; + /// Return true if the collision shape is a polyhedron + virtual bool isPolyhedron() const; + // ---------- Friendship ---------- // friend class ConcaveMeshRaycastCallback; @@ -218,6 +221,11 @@ inline Vector3 TriangleShape::getVertex(int index) const { return mPoints[index]; } +// Return true if the collision shape is a polyhedron +inline bool TriangleShape::isPolyhedron() const { + return true; +} + } #endif From da9f6ae23347c9a63628aad231970e99e93c78f4 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 5 Jul 2016 22:02:16 +0200 Subject: [PATCH 010/248] Remove Simplex class (replaced by VoronoiSimplex) --- CMakeLists.txt | 4 +- .../narrowphase/GJK/GJKAlgorithm.cpp | 1 - src/collision/narrowphase/GJK/Simplex.cpp | 394 ------------------ src/collision/narrowphase/GJK/Simplex.h | 189 --------- 4 files changed, 2 insertions(+), 586 deletions(-) delete mode 100644 src/collision/narrowphase/GJK/Simplex.cpp delete mode 100644 src/collision/narrowphase/GJK/Simplex.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 6850a981..e85693d7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -75,8 +75,8 @@ SET (REACTPHYSICS3D_SOURCES "src/collision/narrowphase/EPA/TriangleEPA.cpp" "src/collision/narrowphase/EPA/TrianglesStore.h" "src/collision/narrowphase/EPA/TrianglesStore.cpp" - "src/collision/narrowphase/GJK/Simplex.h" - "src/collision/narrowphase/GJK/Simplex.cpp" + "src/collision/narrowphase/GJK/VoronoiSimplex.h" + "src/collision/narrowphase/GJK/VoronoiSimplex.cpp" "src/collision/narrowphase/GJK/GJKAlgorithm.h" "src/collision/narrowphase/GJK/GJKAlgorithm.cpp" "src/collision/narrowphase/NarrowPhaseAlgorithm.h" diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp index a9419bb5..89c4f459 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp @@ -25,7 +25,6 @@ // Libraries #include "GJKAlgorithm.h" -#include "Simplex.h" #include "constraint/ContactPoint.h" #include "configuration.h" #include "engine/Profiler.h" diff --git a/src/collision/narrowphase/GJK/Simplex.cpp b/src/collision/narrowphase/GJK/Simplex.cpp deleted file mode 100644 index 45e72e69..00000000 --- a/src/collision/narrowphase/GJK/Simplex.cpp +++ /dev/null @@ -1,394 +0,0 @@ -/******************************************************************************** -* 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. * -* * -********************************************************************************/ - -// Libraries -#include "Simplex.h" -#include - -// We want to use the ReactPhysics3D namespace -using namespace reactphysics3d; - -// Constructor -Simplex::Simplex() : mBitsCurrentSimplex(0x0), mAllBits(0x0) { - -} - -// Destructor -Simplex::~Simplex() { - -} - -// Add a new support point of (A-B) into the simplex -/// suppPointA : support point of object A in a direction -v -/// suppPointB : support point of object B in a direction v -/// point : support point of object (A-B) => point = suppPointA - suppPointB -void Simplex::addPoint(const Vector3& point, const Vector3& suppPointA, const Vector3& suppPointB) { - assert(!isFull()); - - mLastFound = 0; - mLastFoundBit = 0x1; - - // Look for the bit corresponding to one of the four point that is not in - // the current simplex - while (overlap(mBitsCurrentSimplex, mLastFoundBit)) { - mLastFound++; - mLastFoundBit <<= 1; - } - - assert(mLastFound < 4); - - // Add the point into the simplex - mPoints[mLastFound] = point; - mPointsLengthSquare[mLastFound] = point.dot(point); - mAllBits = mBitsCurrentSimplex | mLastFoundBit; - - // Update the cached values - updateCache(); - - // Compute the cached determinant values - computeDeterminants(); - - // Add the support points of objects A and B - mSuppPointsA[mLastFound] = suppPointA; - mSuppPointsB[mLastFound] = suppPointB; -} - -// Return true if the point is in the simplex -bool Simplex::isPointInSimplex(const Vector3& point) const { - int i; - Bits bit; - - // For each four possible points in the simplex - for (i=0, bit = 0x1; i<4; i++, bit <<= 1) { - // Check if the current point is in the simplex - if (overlap(mAllBits, bit) && point == mPoints[i]) return true; - } - - return false; -} - -// Update the cached values used during the GJK algorithm -void Simplex::updateCache() { - int i; - Bits bit; - - // For each of the four possible points of the simplex - for (i=0, bit = 0x1; i<4; i++, bit <<= 1) { - // If the current points is in the simplex - if (overlap(mBitsCurrentSimplex, bit)) { - - // Compute the distance between two points in the possible simplex set - mDiffLength[i][mLastFound] = mPoints[i] - mPoints[mLastFound]; - mDiffLength[mLastFound][i] = -mDiffLength[i][mLastFound]; - - // Compute the squared length of the vector - // distances from points in the possible simplex set - mNormSquare[i][mLastFound] = mNormSquare[mLastFound][i] = - mDiffLength[i][mLastFound].dot(mDiffLength[i][mLastFound]); - } - } -} - -// Return the points of the simplex -unsigned int Simplex::getSimplex(Vector3* suppPointsA, Vector3* suppPointsB, - Vector3* points) const { - unsigned int nbVertices = 0; - int i; - Bits bit; - - // For each four point in the possible simplex - for (i=0, bit=0x1; i<4; i++, bit <<=1) { - - // If the current point is in the simplex - if (overlap(mBitsCurrentSimplex, bit)) { - - // Store the points - suppPointsA[nbVertices] = this->mSuppPointsA[nbVertices]; - suppPointsB[nbVertices] = this->mSuppPointsB[nbVertices]; - points[nbVertices] = this->mPoints[nbVertices]; - - nbVertices++; - } - } - - // Return the number of points in the simplex - return nbVertices; -} - -// Compute the cached determinant values -void Simplex::computeDeterminants() { - mDet[mLastFoundBit][mLastFound] = 1.0; - - // If the current simplex is not empty - if (!isEmpty()) { - int i; - Bits bitI; - - // For each possible four points in the simplex set - for (i=0, bitI = 0x1; i<4; i++, bitI <<= 1) { - - // If the current point is in the simplex - if (overlap(mBitsCurrentSimplex, bitI)) { - Bits bit2 = bitI | mLastFoundBit; - - mDet[bit2][i] = mDiffLength[mLastFound][i].dot(mPoints[mLastFound]); - mDet[bit2][mLastFound] = mDiffLength[i][mLastFound].dot(mPoints[i]); - - - int j; - Bits bitJ; - - for (j=0, bitJ = 0x1; j 0 for each "i" in I_x and -/// 2. delta(X U {y_j})_j <= 0 for each "j" not in I_x_ -bool Simplex::isValidSubset(Bits subset) const { - int i; - Bits bit; - - // For each four point in the possible simplex set - for (i=0, bit=0x1; i<4; i++, bit <<= 1) { - if (overlap(mAllBits, bit)) { - // If the current point is in the subset - if (overlap(subset, bit)) { - // If one delta(X)_i is smaller or equal to zero - if (mDet[subset][i] <= 0.0) { - // The subset is not valid - return false; - } - } - // If the point is not in the subset and the value delta(X U {y_j})_j - // is bigger than zero - else if (mDet[subset | bit][i] > 0.0) { - // The subset is not valid - return false; - } - } - } - - return true; -} - -// Compute the closest points "pA" and "pB" of object A and B. -/// The points are computed as follows : -/// pA = sum(lambda_i * a_i) where "a_i" are the support points of object A -/// pB = sum(lambda_i * b_i) where "b_i" are the support points of object B -/// with lambda_i = deltaX_i / deltaX -void Simplex::computeClosestPointsOfAandB(Vector3& pA, Vector3& pB) const { - decimal deltaX = 0.0; - pA.setAllValues(0.0, 0.0, 0.0); - pB.setAllValues(0.0, 0.0, 0.0); - int i; - Bits bit; - - // For each four points in the possible simplex set - for (i=0, bit=0x1; i<4; i++, bit <<= 1) { - // If the current point is part of the simplex - if (overlap(mBitsCurrentSimplex, bit)) { - deltaX += mDet[mBitsCurrentSimplex][i]; - pA += mDet[mBitsCurrentSimplex][i] * mSuppPointsA[i]; - pB += mDet[mBitsCurrentSimplex][i] * mSuppPointsB[i]; - } - } - - assert(deltaX > 0.0); - decimal factor = decimal(1.0) / deltaX; - pA *= factor; - pB *= factor; -} - -// Compute the closest point "v" to the origin of the current simplex. -/// This method executes the Jonhnson's algorithm for computing the point -/// "v" of simplex that is closest to the origin. The method returns true -/// if a closest point has been found. -bool Simplex::computeClosestPoint(Vector3& v) { - Bits subset; - - // For each possible simplex set - for (subset=mBitsCurrentSimplex; subset != 0x0; subset--) { - // If the simplex is a subset of the current simplex and is valid for the Johnson's - // algorithm test - if (isSubset(subset, mBitsCurrentSimplex) && isValidSubset(subset | mLastFoundBit)) { - mBitsCurrentSimplex = subset | mLastFoundBit; // Add the last added point to the current simplex - v = computeClosestPointForSubset(mBitsCurrentSimplex); // Compute the closest point in the simplex - return true; - } - } - - // If the simplex that contains only the last added point is valid for the Johnson's algorithm test - if (isValidSubset(mLastFoundBit)) { - mBitsCurrentSimplex = mLastFoundBit; // Set the current simplex to the set that contains only the last added point - mMaxLengthSquare = mPointsLengthSquare[mLastFound]; // Update the maximum square length - v = mPoints[mLastFound]; // The closest point of the simplex "v" is the last added point - return true; - } - - // The algorithm failed to found a point - return false; -} - -// Backup the closest point -void Simplex::backupClosestPointInSimplex(Vector3& v) { - decimal minDistSquare = DECIMAL_LARGEST; - Bits bit; - - for (bit = mAllBits; bit != 0x0; bit--) { - if (isSubset(bit, mAllBits) && isProperSubset(bit)) { - Vector3 u = computeClosestPointForSubset(bit); - decimal distSquare = u.dot(u); - if (distSquare < minDistSquare) { - minDistSquare = distSquare; - mBitsCurrentSimplex = bit; - v = u; - } - } - } -} - -// Return the closest point "v" in the convex hull of the points in the subset -// represented by the bits "subset" -Vector3 Simplex::computeClosestPointForSubset(Bits subset) { - Vector3 v(0.0, 0.0, 0.0); // Closet point v = sum(lambda_i * points[i]) - mMaxLengthSquare = 0.0; - decimal deltaX = 0.0; // deltaX = sum of all det[subset][i] - int i; - Bits bit; - - // For each four point in the possible simplex set - for (i=0, bit=0x1; i<4; i++, bit <<= 1) { - // If the current point is in the subset - if (overlap(subset, bit)) { - // deltaX = sum of all det[subset][i] - deltaX += mDet[subset][i]; - - if (mMaxLengthSquare < mPointsLengthSquare[i]) { - mMaxLengthSquare = mPointsLengthSquare[i]; - } - - // Closest point v = sum(lambda_i * points[i]) - v += mDet[subset][i] * mPoints[i]; - } - } - - assert(deltaX > 0.0); - - // Return the closet point "v" in the convex hull for the given subset - return (decimal(1.0) / deltaX) * v; -} diff --git a/src/collision/narrowphase/GJK/Simplex.h b/src/collision/narrowphase/GJK/Simplex.h deleted file mode 100644 index 72f618bf..00000000 --- a/src/collision/narrowphase/GJK/Simplex.h +++ /dev/null @@ -1,189 +0,0 @@ -/******************************************************************************** -* 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_SIMPLEX_H -#define REACTPHYSICS3D_SIMPLEX_H - -// Libraries -#include "mathematics/mathematics.h" -#include - -/// ReactPhysics3D namespace -namespace reactphysics3d { - -// Type definitions -typedef unsigned int Bits; - -// Class Simplex -/** - * This class represents a simplex which is a set of 3D points. This - * class is used in the GJK algorithm. This implementation is based on - * the implementation discussed in the book "Collision Detection in 3D - * Environments". This class implements the Johnson's algorithm for - * computing the point of a simplex that is closest to the origin and also - * the smallest simplex needed to represent that closest point. - */ -class Simplex { - - private: - - // -------------------- Attributes -------------------- // - - /// Current points - Vector3 mPoints[4]; - - /// pointsLengthSquare[i] = (points[i].length)^2 - decimal mPointsLengthSquare[4]; - - /// Maximum length of pointsLengthSquare[i] - decimal mMaxLengthSquare; - - /// Support points of object A in local coordinates - Vector3 mSuppPointsA[4]; - - /// Support points of object B in local coordinates - Vector3 mSuppPointsB[4]; - - /// diff[i][j] contains points[i] - points[j] - Vector3 mDiffLength[4][4]; - - /// Cached determinant values - decimal mDet[16][4]; - - /// norm[i][j] = (diff[i][j].length())^2 - decimal mNormSquare[4][4]; - - /// 4 bits that identify the current points of the simplex - /// For instance, 0101 means that points[1] and points[3] are in the simplex - Bits mBitsCurrentSimplex; - - /// Number between 1 and 4 that identify the last found support point - Bits mLastFound; - - /// Position of the last found support point (lastFoundBit = 0x1 << lastFound) - Bits mLastFoundBit; - - /// allBits = bitsCurrentSimplex | lastFoundBit; - Bits mAllBits; - - // -------------------- Methods -------------------- // - - /// Private copy-constructor - Simplex(const Simplex& simplex); - - /// Private assignment operator - Simplex& operator=(const Simplex& simplex); - - /// Return true if some bits of "a" overlap with bits of "b" - bool overlap(Bits a, Bits b) const; - - /// Return true if the bits of "b" is a subset of the bits of "a" - bool isSubset(Bits a, Bits b) const; - - /// Return true if the subset is a valid one for the closest point computation. - bool isValidSubset(Bits subset) const; - - /// Return true if the subset is a proper subset. - bool isProperSubset(Bits subset) const; - - /// Update the cached values used during the GJK algorithm - void updateCache(); - - /// Compute the cached determinant values - void computeDeterminants(); - - /// Return the closest point "v" in the convex hull of a subset of points - Vector3 computeClosestPointForSubset(Bits subset); - - public: - - // -------------------- Methods -------------------- // - - /// Constructor - Simplex(); - - /// Destructor - ~Simplex(); - - /// Return true if the simplex contains 4 points - bool isFull() const; - - /// Return true if the simplex is empty - bool isEmpty() const; - - /// Return the points of the simplex - unsigned int getSimplex(Vector3* mSuppPointsA, Vector3* mSuppPointsB, - Vector3* mPoints) const; - - /// Return the maximum squared length of a point - decimal getMaxLengthSquareOfAPoint() const; - - /// Add a new support point of (A-B) into the simplex. - void addPoint(const Vector3& point, const Vector3& suppPointA, const Vector3& suppPointB); - - /// Return true if the point is in the simplex - bool isPointInSimplex(const Vector3& point) const; - - /// Return true if the set is affinely dependent - bool isAffinelyDependent() const; - - /// Backup the closest point - void backupClosestPointInSimplex(Vector3& point); - - /// Compute the closest points "pA" and "pB" of object A and B. - void computeClosestPointsOfAandB(Vector3& pA, Vector3& pB) const; - - /// Compute the closest point to the origin of the current simplex. - bool computeClosestPoint(Vector3& v); -}; - -// Return true if some bits of "a" overlap with bits of "b" -inline bool Simplex::overlap(Bits a, Bits b) const { - return ((a & b) != 0x0); -} - -// Return true if the bits of "b" is a subset of the bits of "a" -inline bool Simplex::isSubset(Bits a, Bits b) const { - return ((a & b) == a); -} - -// Return true if the simplex contains 4 points -inline bool Simplex::isFull() const { - return (mBitsCurrentSimplex == 0xf); -} - -// Return true if the simple is empty -inline bool Simplex::isEmpty() const { - return (mBitsCurrentSimplex == 0x0); -} - -// Return the maximum squared length of a point -inline decimal Simplex::getMaxLengthSquareOfAPoint() const { - return mMaxLengthSquare; -} - -} - -#endif From 9cc633fc67db1e193092d462e259b22ba843b3b6 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 6 Jul 2016 06:48:19 +0200 Subject: [PATCH 011/248] Modify initial GJK support direction --- src/engine/OverlappingPair.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/engine/OverlappingPair.cpp b/src/engine/OverlappingPair.cpp index fa45817e..9c4814b5 100644 --- a/src/engine/OverlappingPair.cpp +++ b/src/engine/OverlappingPair.cpp @@ -33,7 +33,7 @@ using namespace reactphysics3d; OverlappingPair::OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, int nbMaxContactManifolds, MemoryAllocator& memoryAllocator) : mContactManifoldSet(shape1, shape2, memoryAllocator, nbMaxContactManifolds), - mCachedSeparatingAxis(1.0, 1.0, 1.0) { + mCachedSeparatingAxis(0.0, 1.0, 0.0) { } From be957ba41a2d7acafb14baf6b14278afb08ff892 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 6 Jul 2016 07:05:34 +0200 Subject: [PATCH 012/248] Replace typedefs by c++11 alias declaration --- src/collision/narrowphase/GJK/Simplex.h | 2 +- src/configuration.h | 16 ++++++++-------- src/decimal.h | 4 ++-- src/engine/OverlappingPair.h | 2 +- 4 files changed, 12 insertions(+), 12 deletions(-) diff --git a/src/collision/narrowphase/GJK/Simplex.h b/src/collision/narrowphase/GJK/Simplex.h index 72f618bf..1388a161 100644 --- a/src/collision/narrowphase/GJK/Simplex.h +++ b/src/collision/narrowphase/GJK/Simplex.h @@ -34,7 +34,7 @@ namespace reactphysics3d { // Type definitions -typedef unsigned int Bits; +using Bits = unsigned int; // Class Simplex /** diff --git a/src/configuration.h b/src/configuration.h index 134668bd..a39117cc 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -46,15 +46,15 @@ namespace reactphysics3d { // ------------------- Type definitions ------------------- // -typedef unsigned int uint; -typedef long unsigned int luint; -typedef luint bodyindex; -typedef std::pair bodyindexpair; +using uint = unsigned int; +using luint = long unsigned int; +using bodyindex = luint; +using bodyindexpair = std::pair; -typedef signed short int16; -typedef signed int int32; -typedef unsigned short uint16; -typedef unsigned int uint32; +using int16 = signed short; +using int32 = signed int; +using uint16 = unsigned short; +using uint32 = unsigned int; // ------------------- Enumerations ------------------- // diff --git a/src/decimal.h b/src/decimal.h index 41cf2881..2c95e8b9 100644 --- a/src/decimal.h +++ b/src/decimal.h @@ -30,9 +30,9 @@ namespace reactphysics3d { #if defined(IS_DOUBLE_PRECISION_ENABLED) // If we are compiling for double precision - typedef double decimal; + using decimal = double; #else // If we are compiling for single precision - typedef float decimal; + using decimal = float; #endif } diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index d230afe2..995546c5 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -35,7 +35,7 @@ namespace reactphysics3d { // Type for the overlapping pair ID -typedef std::pair overlappingpairid; +using overlappingpairid = std::pair; // Class OverlappingPair /** From f5ade0f52d2bc27c461fc19d8cc4514fc9148eb9 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Fri, 8 Jul 2016 07:25:37 +0200 Subject: [PATCH 013/248] Fix virtual constructors, use c++11 scoped enums, use c++11 delete methods instead of private constructors --- src/body/Body.h | 14 ++++----- src/body/CollisionBody.cpp | 2 +- src/body/CollisionBody.h | 16 +++++----- src/body/RigidBody.cpp | 18 +++++------ src/body/RigidBody.h | 18 +++++------ src/collision/CollisionDetection.cpp | 14 +++++---- src/collision/CollisionDetection.h | 14 ++++----- src/collision/ContactManifold.h | 12 ++++---- src/collision/ProxyShape.h | 16 +++++----- src/collision/RaycastInfo.h | 14 ++++----- src/collision/TriangleVertexArray.h | 4 +-- .../broadphase/BroadPhaseAlgorithm.h | 17 ++++++----- src/collision/broadphase/DynamicAABBTree.h | 5 ++++ .../narrowphase/ConcaveVsConvexAlgorithm.cpp | 6 ++-- .../narrowphase/ConcaveVsConvexAlgorithm.h | 3 ++ .../narrowphase/DefaultCollisionDispatch.cpp | 2 +- src/collision/narrowphase/EPA/EPAAlgorithm.h | 12 ++++---- src/collision/narrowphase/EPA/TriangleEPA.h | 14 ++++----- .../narrowphase/EPA/TrianglesStore.h | 16 +++++----- src/collision/narrowphase/GJK/GJKAlgorithm.h | 12 ++++---- src/collision/narrowphase/GJK/Simplex.h | 12 ++++---- .../narrowphase/NarrowPhaseAlgorithm.h | 16 +++++----- .../narrowphase/SphereVsSphereAlgorithm.h | 14 ++++----- src/collision/shapes/BoxShape.cpp | 2 +- src/collision/shapes/BoxShape.h | 12 ++++---- src/collision/shapes/CapsuleShape.cpp | 2 +- src/collision/shapes/CapsuleShape.h | 12 ++++---- src/collision/shapes/CollisionShape.h | 16 +++++----- src/collision/shapes/ConcaveMeshShape.cpp | 20 ++++++------- src/collision/shapes/ConcaveMeshShape.h | 14 ++++----- src/collision/shapes/ConcaveShape.cpp | 2 +- src/collision/shapes/ConcaveShape.h | 15 ++++++---- src/collision/shapes/ConeShape.cpp | 2 +- src/collision/shapes/ConeShape.h | 12 ++++---- src/collision/shapes/ConvexMeshShape.cpp | 14 ++++----- src/collision/shapes/ConvexMeshShape.h | 12 ++++---- src/collision/shapes/ConvexShape.h | 12 ++++---- src/collision/shapes/CylinderShape.cpp | 2 +- src/collision/shapes/CylinderShape.h | 12 ++++---- src/collision/shapes/HeightFieldShape.cpp | 2 +- src/collision/shapes/HeightFieldShape.h | 22 +++++++------- src/collision/shapes/SphereShape.cpp | 2 +- src/collision/shapes/SphereShape.h | 12 ++++---- src/collision/shapes/TriangleShape.cpp | 20 ++++++------- src/collision/shapes/TriangleShape.h | 14 ++++----- src/configuration.h | 4 +-- src/constraint/BallAndSocketJoint.cpp | 8 ++--- src/constraint/BallAndSocketJoint.h | 14 ++++----- src/constraint/ContactPoint.h | 14 ++++----- src/constraint/FixedJoint.cpp | 14 ++++----- src/constraint/FixedJoint.h | 14 ++++----- src/constraint/HingeJoint.cpp | 18 +++++------ src/constraint/HingeJoint.h | 18 +++++------ src/constraint/Joint.h | 18 +++++------ src/constraint/SliderJoint.cpp | 18 +++++------ src/constraint/SliderJoint.h | 18 +++++------ src/engine/CollisionWorld.h | 12 ++++---- src/engine/ContactSolver.cpp | 4 +-- src/engine/DynamicsWorld.cpp | 16 +++++----- src/engine/DynamicsWorld.h | 16 +++++----- src/engine/EventListener.h | 2 +- src/engine/Impulse.h | 8 ++--- src/engine/Island.h | 14 ++++----- src/engine/OverlappingPair.h | 14 ++++----- src/engine/Timer.h | 16 +++++----- test/tests/collision/TestRaycast.h | 30 +++++++++---------- testbed/common/ConcaveMesh.cpp | 8 ++--- testbed/common/ConvexMesh.cpp | 8 ++--- testbed/common/HeightField.cpp | 4 +-- .../collisionshapes/CollisionShapesScene.cpp | 2 +- .../scenes/concavemesh/ConcaveMeshScene.cpp | 2 +- testbed/scenes/cubes/CubesScene.cpp | 2 +- .../scenes/heightfield/HeightFieldScene.cpp | 2 +- testbed/scenes/joints/JointsScene.cpp | 6 ++-- 74 files changed, 412 insertions(+), 416 deletions(-) diff --git a/src/body/Body.h b/src/body/Body.h index 4d1f9bf4..c5f011fb 100644 --- a/src/body/Body.h +++ b/src/body/Body.h @@ -75,14 +75,6 @@ class Body { /// Pointer that can be used to attach user data to the body void* mUserData; - // -------------------- Methods -------------------- // - - /// Private copy-constructor - Body(const Body& body); - - /// Private assignment operator - Body& operator=(const Body& body); - public : // -------------------- Methods -------------------- // @@ -90,6 +82,12 @@ class Body { /// Constructor Body(bodyindex id); + /// Deleted copy-constructor + Body(const Body& body) = delete; + + /// Deleted assignment operator + Body& operator=(const Body& body) = delete; + /// Destructor virtual ~Body(); diff --git a/src/body/CollisionBody.cpp b/src/body/CollisionBody.cpp index 83052131..daa4a71e 100644 --- a/src/body/CollisionBody.cpp +++ b/src/body/CollisionBody.cpp @@ -38,7 +38,7 @@ using namespace reactphysics3d; * @param id ID of the body */ CollisionBody::CollisionBody(const Transform& transform, CollisionWorld& world, bodyindex id) - : Body(id), mType(DYNAMIC), mTransform(transform), mProxyCollisionShapes(nullptr), + : Body(id), mType(BodyType::DYNAMIC), mTransform(transform), mProxyCollisionShapes(nullptr), mNbCollisionShapes(0), mContactManifoldsList(nullptr), mWorld(world) { } diff --git a/src/body/CollisionBody.h b/src/body/CollisionBody.h index 2c88d155..c5658b58 100644 --- a/src/body/CollisionBody.h +++ b/src/body/CollisionBody.h @@ -54,7 +54,7 @@ class CollisionWorld; /// DYNAMIC : A dynamic body has non-zero mass, non-zero velocity determined by forces and its /// position is determined by the physics engine. A dynamic body can collide with other /// dynamic, static or kinematic bodies. -enum BodyType {STATIC, KINEMATIC, DYNAMIC}; +enum class BodyType {STATIC, KINEMATIC, DYNAMIC}; // Class CollisionBody /** @@ -87,12 +87,6 @@ class CollisionBody : public Body { // -------------------- Methods -------------------- // - /// Private copy-constructor - CollisionBody(const CollisionBody& body); - - /// Private assignment operator - CollisionBody& operator=(const CollisionBody& body); - /// Reset the contact manifold lists void resetContactManifoldsList(); @@ -122,6 +116,12 @@ class CollisionBody : public Body { /// Destructor virtual ~CollisionBody(); + /// Deleted copy-constructor + CollisionBody(const CollisionBody& body) = delete; + + /// Deleted assignment operator + CollisionBody& operator=(const CollisionBody& body) = delete; + /// Return the type of the body BodyType getType() const; @@ -208,7 +208,7 @@ inline BodyType CollisionBody::getType() const { inline void CollisionBody::setType(BodyType type) { mType = type; - if (mType == STATIC) { + if (mType == BodyType::STATIC) { // Update the broad-phase state of the body updateBroadPhaseState(); diff --git a/src/body/RigidBody.cpp b/src/body/RigidBody.cpp index ff7fc8dd..a34df2bd 100644 --- a/src/body/RigidBody.cpp +++ b/src/body/RigidBody.cpp @@ -76,7 +76,7 @@ void RigidBody::setType(BodyType type) { recomputeMassInformation(); // If it is a static body - if (mType == STATIC) { + if (mType == BodyType::STATIC) { // Reset the velocity to zero mLinearVelocity.setToZero(); @@ -84,7 +84,7 @@ void RigidBody::setType(BodyType type) { } // If it is a static or a kinematic body - if (mType == STATIC || mType == KINEMATIC) { + if (mType == BodyType::STATIC || mType == BodyType::KINEMATIC) { // Reset the inverse mass and inverse inertia tensor to zero mMassInverse = decimal(0.0); @@ -119,7 +119,7 @@ void RigidBody::setType(BodyType type) { */ void RigidBody::setInertiaTensorLocal(const Matrix3x3& inertiaTensorLocal) { - if (mType != DYNAMIC) return; + if (mType != BodyType::DYNAMIC) return; mInertiaTensorLocal = inertiaTensorLocal; @@ -134,7 +134,7 @@ void RigidBody::setInertiaTensorLocal(const Matrix3x3& inertiaTensorLocal) { */ void RigidBody::setCenterOfMassLocal(const Vector3& centerOfMassLocal) { - if (mType != DYNAMIC) return; + if (mType != BodyType::DYNAMIC) return; const Vector3 oldCenterOfMass = mCenterOfMassWorld; mCenterOfMassLocal = centerOfMassLocal; @@ -152,7 +152,7 @@ void RigidBody::setCenterOfMassLocal(const Vector3& centerOfMassLocal) { */ void RigidBody::setMass(decimal mass) { - if (mType != DYNAMIC) return; + if (mType != BodyType::DYNAMIC) return; mInitMass = mass; @@ -267,7 +267,7 @@ void RigidBody::removeCollisionShape(const ProxyShape* proxyShape) { void RigidBody::setLinearVelocity(const Vector3& linearVelocity) { // If it is a static body, we do nothing - if (mType == STATIC) return; + if (mType == BodyType::STATIC) return; // Update the linear velocity of the current body state mLinearVelocity = linearVelocity; @@ -285,7 +285,7 @@ void RigidBody::setLinearVelocity(const Vector3& linearVelocity) { void RigidBody::setAngularVelocity(const Vector3& angularVelocity) { // If it is a static body, we do nothing - if (mType == STATIC) return; + if (mType == BodyType::STATIC) return; // Set the angular velocity mAngularVelocity = angularVelocity; @@ -329,12 +329,12 @@ void RigidBody::recomputeMassInformation() { mCenterOfMassLocal.setToZero(); // If it is STATIC or KINEMATIC body - if (mType == STATIC || mType == KINEMATIC) { + if (mType == BodyType::STATIC || mType == BodyType::KINEMATIC) { mCenterOfMassWorld = mTransform.getPosition(); return; } - assert(mType == DYNAMIC); + assert(mType == BodyType::DYNAMIC); // Compute the total mass of the body for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) { diff --git a/src/body/RigidBody.h b/src/body/RigidBody.h index fd1c18b7..b3c96c52 100644 --- a/src/body/RigidBody.h +++ b/src/body/RigidBody.h @@ -103,12 +103,6 @@ class RigidBody : public CollisionBody { // -------------------- Methods -------------------- // - /// Private copy-constructor - RigidBody(const RigidBody& body); - - /// Private assignment operator - RigidBody& operator=(const RigidBody& body); - /// Remove a joint from the joints list void removeJointFromJointsList(MemoryAllocator& memoryAllocator, const Joint* joint); @@ -128,6 +122,12 @@ class RigidBody : public CollisionBody { /// Destructor virtual ~RigidBody(); + /// Deleted copy-constructor + RigidBody(const RigidBody& body) = delete; + + /// Deleted assignment operator + RigidBody& operator=(const RigidBody& body) = delete; + /// Set the type of the body (static, kinematic or dynamic) void setType(BodyType type); @@ -407,7 +407,7 @@ inline void RigidBody::setIsSleeping(bool isSleeping) { inline void RigidBody::applyForceToCenterOfMass(const Vector3& force) { // If it is not a dynamic body, we do nothing - if (mType != DYNAMIC) return; + if (mType != BodyType::DYNAMIC) return; // Awake the body if it was sleeping if (mIsSleeping) { @@ -432,7 +432,7 @@ inline void RigidBody::applyForceToCenterOfMass(const Vector3& force) { inline void RigidBody::applyForce(const Vector3& force, const Vector3& point) { // If it is not a dynamic body, we do nothing - if (mType != DYNAMIC) return; + if (mType != BodyType::DYNAMIC) return; // Awake the body if it was sleeping if (mIsSleeping) { @@ -455,7 +455,7 @@ inline void RigidBody::applyForce(const Vector3& force, const Vector3& point) { inline void RigidBody::applyTorque(const Vector3& torque) { // If it is not a dynamic body, we do nothing - if (mType != DYNAMIC) return; + if (mType != BodyType::DYNAMIC) return; // Awake the body if it was sleeping if (mIsSleeping) { diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 5e895c7f..ed721343 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -209,8 +209,8 @@ void CollisionDetection::computeNarrowPhase() { pair->update(); // Check that at least one body is awake and not static - bool isBody1Active = !body1->isSleeping() && body1->getType() != STATIC; - bool isBody2Active = !body2->isSleeping() && body2->getType() != STATIC; + bool isBody1Active = !body1->isSleeping() && body1->getType() != BodyType::STATIC; + bool isBody2Active = !body2->isSleeping() && body2->getType() != BodyType::STATIC; if (!isBody1Active && !isBody2Active) continue; // Check if the bodies are in the set of bodies that cannot collide between each other @@ -220,7 +220,9 @@ void CollisionDetection::computeNarrowPhase() { // Select the narrow phase algorithm to use according to the two collision shapes const CollisionShapeType shape1Type = shape1->getCollisionShape()->getType(); const CollisionShapeType shape2Type = shape2->getCollisionShape()->getType(); - NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Type][shape2Type]; + const int shape1Index = static_cast(shape1Type); + const int shape2Index = static_cast(shape2Type); + NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Index][shape2Index]; // If there is no collision algorithm between those two kinds of shapes if (narrowPhaseAlgorithm == nullptr) continue; @@ -312,7 +314,7 @@ void CollisionDetection::computeNarrowPhaseBetweenShapes(CollisionCallback* call pair->update(); // Check if the two bodies are allowed to collide, otherwise, we do not test for collision - if (body1->getType() != DYNAMIC && body2->getType() != DYNAMIC) continue; + if (body1->getType() != BodyType::DYNAMIC && body2->getType() != BodyType::DYNAMIC) continue; bodyindexpair bodiesIndex = OverlappingPair::computeBodiesIndexPair(body1, body2); if (mNoCollisionPairs.count(bodiesIndex) > 0) continue; @@ -322,7 +324,9 @@ void CollisionDetection::computeNarrowPhaseBetweenShapes(CollisionCallback* call // Select the narrow phase algorithm to use according to the two collision shapes const CollisionShapeType shape1Type = shape1->getCollisionShape()->getType(); const CollisionShapeType shape2Type = shape2->getCollisionShape()->getType(); - NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Type][shape2Type]; + const int shape1Index = static_cast(shape1Type); + const int shape2Index = static_cast(shape2Type); + NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Index][shape2Index]; // If there is no collision algorithm between those two kinds of shapes if (narrowPhaseAlgorithm == nullptr) continue; diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index 4bc4f319..e02b129f 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -116,12 +116,6 @@ class CollisionDetection : public NarrowPhaseCallback { // -------------------- Methods -------------------- // - /// Private copy-constructor - CollisionDetection(const CollisionDetection& collisionDetection); - - /// Private assignment operator - CollisionDetection& operator=(const CollisionDetection& collisionDetection); - /// Compute the broad-phase collision detection void computeBroadPhase(); @@ -151,6 +145,12 @@ class CollisionDetection : public NarrowPhaseCallback { /// Destructor ~CollisionDetection(); + /// Deleted copy-constructor + CollisionDetection(const CollisionDetection& collisionDetection) = delete; + + /// Deleted assignment operator + CollisionDetection& operator=(const CollisionDetection& collisionDetection) = delete; + /// Set the collision dispatch configuration void setCollisionDispatch(CollisionDispatch* collisionDispatch); @@ -234,7 +234,7 @@ class CollisionDetection : public NarrowPhaseCallback { // Return the Narrow-phase collision detection algorithm to use between two types of shapes inline NarrowPhaseAlgorithm* CollisionDetection::getCollisionAlgorithm(CollisionShapeType shape1Type, CollisionShapeType shape2Type) const { - return mCollisionMatrix[shape1Type][shape2Type]; + return mCollisionMatrix[static_cast(shape1Type)][static_cast(shape2Type)]; } // Set the collision dispatch configuration diff --git a/src/collision/ContactManifold.h b/src/collision/ContactManifold.h index e34bb449..eb7716df 100644 --- a/src/collision/ContactManifold.h +++ b/src/collision/ContactManifold.h @@ -130,12 +130,6 @@ class ContactManifold { // -------------------- Methods -------------------- // - /// Private copy-constructor - ContactManifold(const ContactManifold& contactManifold); - - /// Private assignment operator - ContactManifold& operator=(const ContactManifold& contactManifold); - /// Return the index of maximum area int getMaxArea(decimal area0, decimal area1, decimal area2, decimal area3) const; @@ -162,6 +156,12 @@ class ContactManifold { /// Destructor ~ContactManifold(); + /// Deleted copy-constructor + ContactManifold(const ContactManifold& contactManifold) = delete; + + /// Deleted assignment operator + ContactManifold& operator=(const ContactManifold& contactManifold) = delete; + /// Return a pointer to the first proxy shape of the contact ProxyShape* getShape1() const; diff --git a/src/collision/ProxyShape.h b/src/collision/ProxyShape.h index b91252de..d7c81621 100644 --- a/src/collision/ProxyShape.h +++ b/src/collision/ProxyShape.h @@ -85,14 +85,6 @@ class ProxyShape { /// proxy shape will collide with every collision categories by default. unsigned short mCollideWithMaskBits; - // -------------------- Methods -------------------- // - - /// Private copy-constructor - ProxyShape(const ProxyShape& proxyShape); - - /// Private assignment operator - ProxyShape& operator=(const ProxyShape& proxyShape); - public: // -------------------- Methods -------------------- // @@ -102,7 +94,13 @@ class ProxyShape { const Transform& transform, decimal mass); /// Destructor - ~ProxyShape(); + virtual ~ProxyShape(); + + /// Deleted copy-constructor + ProxyShape(const ProxyShape& proxyShape) = delete; + + /// Deleted assignment operator + ProxyShape& operator=(const ProxyShape& proxyShape) = delete; /// Return the collision shape const CollisionShape* getCollisionShape() const; diff --git a/src/collision/RaycastInfo.h b/src/collision/RaycastInfo.h index 753353f3..d693f02c 100644 --- a/src/collision/RaycastInfo.h +++ b/src/collision/RaycastInfo.h @@ -46,14 +46,6 @@ struct RaycastInfo { private: - // -------------------- Methods -------------------- // - - /// Private copy constructor - RaycastInfo(const RaycastInfo& raycastInfo); - - /// Private assignment operator - RaycastInfo& operator=(const RaycastInfo& raycastInfo); - public: // -------------------- Attributes -------------------- // @@ -91,6 +83,12 @@ struct RaycastInfo { ~RaycastInfo() { } + + /// Deleted copy constructor + RaycastInfo(const RaycastInfo& raycastInfo) = delete; + + /// Deleted assignment operator + RaycastInfo& operator=(const RaycastInfo& raycastInfo) = delete; }; // Class RaycastCallback diff --git a/src/collision/TriangleVertexArray.h b/src/collision/TriangleVertexArray.h index 3cf45723..f4403092 100644 --- a/src/collision/TriangleVertexArray.h +++ b/src/collision/TriangleVertexArray.h @@ -46,10 +46,10 @@ class TriangleVertexArray { public: /// Data type for the vertices in the array - enum VertexDataType {VERTEX_FLOAT_TYPE, VERTEX_DOUBLE_TYPE}; + enum class VertexDataType {VERTEX_FLOAT_TYPE, VERTEX_DOUBLE_TYPE}; /// Data type for the indices in the array - enum IndexDataType {INDEX_INTEGER_TYPE, INDEX_SHORT_TYPE}; + enum class IndexDataType {INDEX_INTEGER_TYPE, INDEX_SHORT_TYPE}; protected: diff --git a/src/collision/broadphase/BroadPhaseAlgorithm.h b/src/collision/broadphase/BroadPhaseAlgorithm.h index 7f48f8fd..413a3d47 100644 --- a/src/collision/broadphase/BroadPhaseAlgorithm.h +++ b/src/collision/broadphase/BroadPhaseAlgorithm.h @@ -109,6 +109,9 @@ class BroadPhaseRaycastCallback : public DynamicAABBTreeRaycastCallback { } + // Destructor + virtual ~BroadPhaseRaycastCallback() {} + // Called for a broad-phase shape that has to be tested for raycast virtual decimal raycastBroadPhaseShape(int32 nodeId, const Ray& ray); @@ -159,14 +162,6 @@ class BroadPhaseAlgorithm { /// Reference to the collision detection object CollisionDetection& mCollisionDetection; - - // -------------------- Methods -------------------- // - - /// Private copy-constructor - BroadPhaseAlgorithm(const BroadPhaseAlgorithm& algorithm); - - /// Private assignment operator - BroadPhaseAlgorithm& operator=(const BroadPhaseAlgorithm& algorithm); public : @@ -177,6 +172,12 @@ class BroadPhaseAlgorithm { /// Destructor ~BroadPhaseAlgorithm(); + + /// Deleted copy-constructor + BroadPhaseAlgorithm(const BroadPhaseAlgorithm& algorithm) = delete; + + /// Deleted assignment operator + BroadPhaseAlgorithm& operator=(const BroadPhaseAlgorithm& algorithm) = delete; /// Add a proxy collision shape into the broad-phase collision detection void addProxyCollisionShape(ProxyShape* proxyShape, const AABB& aabb); diff --git a/src/collision/broadphase/DynamicAABBTree.h b/src/collision/broadphase/DynamicAABBTree.h index e8232e96..67999d0a 100644 --- a/src/collision/broadphase/DynamicAABBTree.h +++ b/src/collision/broadphase/DynamicAABBTree.h @@ -101,6 +101,9 @@ class DynamicAABBTreeOverlapCallback { // Called when a overlapping node has been found during the call to // DynamicAABBTree:reportAllShapesOverlappingWithAABB() virtual void notifyOverlappingNode(int nodeId)=0; + + // Destructor + virtual ~DynamicAABBTreeOverlapCallback() {} }; // Class DynamicAABBTreeRaycastCallback @@ -115,6 +118,8 @@ class DynamicAABBTreeRaycastCallback { // Called when the AABB of a leaf node is hit by a ray virtual decimal raycastBroadPhaseShape(int32 nodeId, const Ray& ray)=0; + virtual ~DynamicAABBTreeRaycastCallback() {} + }; // Class DynamicAABBTree diff --git a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp index 96c67531..ab07c629 100644 --- a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp +++ b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp @@ -263,8 +263,8 @@ void SmoothCollisionNarrowPhaseCallback::notifyContact(OverlappingPair* overlapp bool isFirstShapeTriangle; // If the collision shape 1 is the triangle - if (contactInfo.collisionShape1->getType() == TRIANGLE) { - assert(contactInfo.collisionShape2->getType() != TRIANGLE); + if (contactInfo.collisionShape1->getType() == CollisionShapeType::TRIANGLE) { + assert(contactInfo.collisionShape2->getType() != CollisionShapeType::TRIANGLE); const TriangleShape* triangleShape = static_cast(contactInfo.collisionShape1); triangleVertices[0] = triangleShape->getVertex(0); @@ -274,7 +274,7 @@ void SmoothCollisionNarrowPhaseCallback::notifyContact(OverlappingPair* overlapp isFirstShapeTriangle = true; } else { // If the collision shape 2 is the triangle - assert(contactInfo.collisionShape2->getType() == TRIANGLE); + assert(contactInfo.collisionShape2->getType() == CollisionShapeType::TRIANGLE); const TriangleShape* triangleShape = static_cast(contactInfo.collisionShape2); triangleVertices[0] = triangleShape->getVertex(0); diff --git a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h index e44b71c2..4fe2aec0 100644 --- a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h +++ b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h @@ -72,6 +72,9 @@ class ConvexVsTriangleCallback : public TriangleCallback { public: + /// Destructor + virtual ~ConvexVsTriangleCallback() {} + /// Set the collision detection pointer void setCollisionDetection(CollisionDetection* collisionDetection) { mCollisionDetection = collisionDetection; diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.cpp b/src/collision/narrowphase/DefaultCollisionDispatch.cpp index 0b0df8d7..bc48c001 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.cpp +++ b/src/collision/narrowphase/DefaultCollisionDispatch.cpp @@ -57,7 +57,7 @@ NarrowPhaseAlgorithm* DefaultCollisionDispatch::selectAlgorithm(int type1, int t CollisionShapeType shape2Type = static_cast(type2); // Sphere vs Sphere algorithm - if (shape1Type == SPHERE && shape2Type == SPHERE) { + if (shape1Type == CollisionShapeType::SPHERE && shape2Type == CollisionShapeType::SPHERE) { return &mSphereVsSphereAlgorithm; } // Concave vs Convex algorithm diff --git a/src/collision/narrowphase/EPA/EPAAlgorithm.h b/src/collision/narrowphase/EPA/EPAAlgorithm.h index 1d4b527a..3461f466 100644 --- a/src/collision/narrowphase/EPA/EPAAlgorithm.h +++ b/src/collision/narrowphase/EPA/EPAAlgorithm.h @@ -95,12 +95,6 @@ class EPAAlgorithm { // -------------------- Methods -------------------- // - /// Private copy-constructor - EPAAlgorithm(const EPAAlgorithm& algorithm); - - /// Private assignment operator - EPAAlgorithm& operator=(const EPAAlgorithm& algorithm); - /// Add a triangle face in the candidate triangle heap void addFaceCandidate(TriangleEPA* triangle, TriangleEPA** heap, uint& nbTriangles, decimal upperBoundSquarePenDepth); @@ -119,6 +113,12 @@ class EPAAlgorithm { /// Destructor ~EPAAlgorithm(); + /// Deleted copy-constructor + EPAAlgorithm(const EPAAlgorithm& algorithm) = delete; + + /// Deleted assignment operator + EPAAlgorithm& operator=(const EPAAlgorithm& algorithm) = delete; + /// Initalize the algorithm void init(MemoryAllocator* memoryAllocator); diff --git a/src/collision/narrowphase/EPA/TriangleEPA.h b/src/collision/narrowphase/EPA/TriangleEPA.h index e2a8ce26..4cb40f38 100644 --- a/src/collision/narrowphase/EPA/TriangleEPA.h +++ b/src/collision/narrowphase/EPA/TriangleEPA.h @@ -74,14 +74,6 @@ class TriangleEPA { /// Square distance of the point closest point v to the origin decimal mDistSquare; - // -------------------- Methods -------------------- // - - /// Private copy-constructor - TriangleEPA(const TriangleEPA& triangle); - - /// Private assignment operator - TriangleEPA& operator=(const TriangleEPA& triangle); - public: // -------------------- Methods -------------------- // @@ -95,6 +87,12 @@ class TriangleEPA { /// Destructor ~TriangleEPA(); + /// Deleted copy-constructor + TriangleEPA(const TriangleEPA& triangle) = delete; + + /// Deleted assignment operator + TriangleEPA& operator=(const TriangleEPA& triangle) = delete; + /// Return an adjacent edge of the triangle EdgeEPA& getAdjacentEdge(int index); diff --git a/src/collision/narrowphase/EPA/TrianglesStore.h b/src/collision/narrowphase/EPA/TrianglesStore.h index 82f6b6a9..840fdcbc 100644 --- a/src/collision/narrowphase/EPA/TrianglesStore.h +++ b/src/collision/narrowphase/EPA/TrianglesStore.h @@ -52,15 +52,7 @@ class TrianglesStore { TriangleEPA mTriangles[MAX_TRIANGLES]; /// Number of triangles - int mNbTriangles; - - // -------------------- Methods -------------------- // - - /// Private copy-constructor - TrianglesStore(const TrianglesStore& triangleStore); - - /// Private assignment operator - TrianglesStore& operator=(const TrianglesStore& triangleStore); + int mNbTriangles; public: @@ -72,6 +64,12 @@ class TrianglesStore { /// Destructor ~TrianglesStore(); + /// Deleted copy-constructor + TrianglesStore(const TrianglesStore& triangleStore) = delete; + + /// Deleted assignment operator + TrianglesStore& operator=(const TrianglesStore& triangleStore) = delete; + /// Clear all the storage void clear(); diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.h b/src/collision/narrowphase/GJK/GJKAlgorithm.h index 23ebc789..96cdbf8a 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.h +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.h @@ -68,12 +68,6 @@ class GJKAlgorithm : public NarrowPhaseAlgorithm { // -------------------- Methods -------------------- // - /// Private copy-constructor - GJKAlgorithm(const GJKAlgorithm& algorithm); - - /// Private assignment operator - GJKAlgorithm& operator=(const GJKAlgorithm& algorithm); - /// Compute the penetration depth for enlarged objects. void computePenetrationDepthForEnlargedObjects(const CollisionShapeInfo& shape1Info, const Transform& transform1, @@ -92,6 +86,12 @@ class GJKAlgorithm : public NarrowPhaseAlgorithm { /// Destructor ~GJKAlgorithm(); + /// Deleted copy-constructor + GJKAlgorithm(const GJKAlgorithm& algorithm) = delete; + + /// Deleted assignment operator + GJKAlgorithm& operator=(const GJKAlgorithm& algorithm) = delete; + /// Initalize the algorithm virtual void init(CollisionDetection* collisionDetection, MemoryAllocator* memoryAllocator); diff --git a/src/collision/narrowphase/GJK/Simplex.h b/src/collision/narrowphase/GJK/Simplex.h index 1388a161..f55213fb 100644 --- a/src/collision/narrowphase/GJK/Simplex.h +++ b/src/collision/narrowphase/GJK/Simplex.h @@ -90,12 +90,6 @@ class Simplex { // -------------------- Methods -------------------- // - /// Private copy-constructor - Simplex(const Simplex& simplex); - - /// Private assignment operator - Simplex& operator=(const Simplex& simplex); - /// Return true if some bits of "a" overlap with bits of "b" bool overlap(Bits a, Bits b) const; @@ -127,6 +121,12 @@ class Simplex { /// Destructor ~Simplex(); + /// Deleted copy-constructor + Simplex(const Simplex& simplex) = delete; + + /// Deleted assignment operator + Simplex& operator=(const Simplex& simplex) = delete; + /// Return true if the simplex contains 4 points bool isFull() const; diff --git a/src/collision/narrowphase/NarrowPhaseAlgorithm.h b/src/collision/narrowphase/NarrowPhaseAlgorithm.h index e8efaaa6..b765dbf3 100644 --- a/src/collision/narrowphase/NarrowPhaseAlgorithm.h +++ b/src/collision/narrowphase/NarrowPhaseAlgorithm.h @@ -47,6 +47,8 @@ class NarrowPhaseCallback { public: + virtual ~NarrowPhaseCallback() {} + /// Called by a narrow-phase collision algorithm when a new contact has been found virtual void notifyContact(OverlappingPair* overlappingPair, const ContactPointInfo& contactInfo)=0; @@ -73,14 +75,6 @@ class NarrowPhaseAlgorithm { /// Overlapping pair of the bodies currently tested for collision OverlappingPair* mCurrentOverlappingPair; - - // -------------------- Methods -------------------- // - - /// Private copy-constructor - NarrowPhaseAlgorithm(const NarrowPhaseAlgorithm& algorithm); - - /// Private assignment operator - NarrowPhaseAlgorithm& operator=(const NarrowPhaseAlgorithm& algorithm); public : @@ -92,6 +86,12 @@ class NarrowPhaseAlgorithm { /// Destructor virtual ~NarrowPhaseAlgorithm(); + /// Deleted copy-constructor + NarrowPhaseAlgorithm(const NarrowPhaseAlgorithm& algorithm) = delete; + + /// Deleted assignment operator + NarrowPhaseAlgorithm& operator=(const NarrowPhaseAlgorithm& algorithm) = delete; + /// Initalize the algorithm virtual void init(CollisionDetection* collisionDetection, MemoryAllocator* memoryAllocator); diff --git a/src/collision/narrowphase/SphereVsSphereAlgorithm.h b/src/collision/narrowphase/SphereVsSphereAlgorithm.h index 0c73d57a..44190a22 100644 --- a/src/collision/narrowphase/SphereVsSphereAlgorithm.h +++ b/src/collision/narrowphase/SphereVsSphereAlgorithm.h @@ -44,14 +44,6 @@ class SphereVsSphereAlgorithm : public NarrowPhaseAlgorithm { protected : - // -------------------- Methods -------------------- // - - /// Private copy-constructor - SphereVsSphereAlgorithm(const SphereVsSphereAlgorithm& algorithm); - - /// Private assignment operator - SphereVsSphereAlgorithm& operator=(const SphereVsSphereAlgorithm& algorithm); - public : // -------------------- Methods -------------------- // @@ -62,6 +54,12 @@ class SphereVsSphereAlgorithm : public NarrowPhaseAlgorithm { /// Destructor virtual ~SphereVsSphereAlgorithm(); + /// Deleted copy-constructor + SphereVsSphereAlgorithm(const SphereVsSphereAlgorithm& algorithm) = delete; + + /// Deleted assignment operator + SphereVsSphereAlgorithm& operator=(const SphereVsSphereAlgorithm& algorithm) = delete; + /// Compute a contact info if the two bounding volume collide virtual void testCollision(const CollisionShapeInfo& shape1Info, const CollisionShapeInfo& shape2Info, diff --git a/src/collision/shapes/BoxShape.cpp b/src/collision/shapes/BoxShape.cpp index fe1f5693..764918c7 100644 --- a/src/collision/shapes/BoxShape.cpp +++ b/src/collision/shapes/BoxShape.cpp @@ -38,7 +38,7 @@ using namespace reactphysics3d; * @param margin The collision margin (in meters) around the collision shape */ BoxShape::BoxShape(const Vector3& extent, decimal margin) - : ConvexShape(BOX, margin), mExtent(extent - Vector3(margin, margin, margin)) { + : ConvexShape(CollisionShapeType::BOX, margin), mExtent(extent - Vector3(margin, margin, margin)) { assert(extent.x > decimal(0.0) && extent.x > margin); assert(extent.y > decimal(0.0) && extent.y > margin); assert(extent.z > decimal(0.0) && extent.z > margin); diff --git a/src/collision/shapes/BoxShape.h b/src/collision/shapes/BoxShape.h index f581baa0..bfe702fb 100644 --- a/src/collision/shapes/BoxShape.h +++ b/src/collision/shapes/BoxShape.h @@ -61,12 +61,6 @@ class BoxShape : public ConvexShape { // -------------------- Methods -------------------- // - /// Private copy-constructor - BoxShape(const BoxShape& shape); - - /// Private assignment operator - BoxShape& operator=(const BoxShape& shape); - /// Return a local support point in a given direction without the object margin virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, void** cachedCollisionData) const; @@ -90,6 +84,12 @@ class BoxShape : public ConvexShape { /// Destructor virtual ~BoxShape(); + /// Deleted copy-constructor + BoxShape(const BoxShape& shape) = delete; + + /// Deleted assignment operator + BoxShape& operator=(const BoxShape& shape) = delete; + /// Return the extents of the box Vector3 getExtent() const; diff --git a/src/collision/shapes/CapsuleShape.cpp b/src/collision/shapes/CapsuleShape.cpp index 110fbd30..a8b231f5 100644 --- a/src/collision/shapes/CapsuleShape.cpp +++ b/src/collision/shapes/CapsuleShape.cpp @@ -37,7 +37,7 @@ using namespace reactphysics3d; * @param height The height of the capsule (in meters) */ CapsuleShape::CapsuleShape(decimal radius, decimal height) - : ConvexShape(CAPSULE, radius), mHalfHeight(height * decimal(0.5)) { + : ConvexShape(CollisionShapeType::CAPSULE, radius), mHalfHeight(height * decimal(0.5)) { assert(radius > decimal(0.0)); assert(height > decimal(0.0)); } diff --git a/src/collision/shapes/CapsuleShape.h b/src/collision/shapes/CapsuleShape.h index 56269d04..b4d4755b 100644 --- a/src/collision/shapes/CapsuleShape.h +++ b/src/collision/shapes/CapsuleShape.h @@ -55,12 +55,6 @@ class CapsuleShape : public ConvexShape { // -------------------- Methods -------------------- // - /// Private copy-constructor - CapsuleShape(const CapsuleShape& shape); - - /// Private assignment operator - CapsuleShape& operator=(const CapsuleShape& shape); - /// Return a local support point in a given direction without the object margin virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, void** cachedCollisionData) const; @@ -89,6 +83,12 @@ class CapsuleShape : public ConvexShape { /// Destructor virtual ~CapsuleShape(); + /// Deleted copy-constructor + CapsuleShape(const CapsuleShape& shape) = delete; + + /// Deleted assignment operator + CapsuleShape& operator=(const CapsuleShape& shape) = delete; + /// Return the radius of the capsule decimal getRadius() const; diff --git a/src/collision/shapes/CollisionShape.h b/src/collision/shapes/CollisionShape.h index cd89255d..2c50dac9 100644 --- a/src/collision/shapes/CollisionShape.h +++ b/src/collision/shapes/CollisionShape.h @@ -40,7 +40,7 @@ namespace reactphysics3d { /// Type of the collision shape -enum CollisionShapeType {TRIANGLE, BOX, SPHERE, CONE, CYLINDER, +enum class CollisionShapeType {TRIANGLE, BOX, SPHERE, CONE, CYLINDER, CAPSULE, CONVEX_MESH, CONCAVE_MESH, HEIGHTFIELD}; const int NB_COLLISION_SHAPE_TYPES = 9; @@ -67,12 +67,6 @@ class CollisionShape { // -------------------- Methods -------------------- // - /// Private copy-constructor - CollisionShape(const CollisionShape& shape); - - /// Private assignment operator - CollisionShape& operator=(const CollisionShape& shape); - /// Return true if a point is inside the collision shape virtual bool testPointInside(const Vector3& worldPoint, ProxyShape* proxyShape) const=0; @@ -92,6 +86,12 @@ class CollisionShape { /// Destructor virtual ~CollisionShape(); + /// Deleted copy-constructor + CollisionShape(const CollisionShape& shape) = delete; + + /// Deleted assignment operator + CollisionShape& operator=(const CollisionShape& shape) = delete; + /// Return the type of the collision shapes CollisionShapeType getType() const; @@ -136,7 +136,7 @@ inline CollisionShapeType CollisionShape::getType() const { // Return true if the collision shape type is a convex shape inline bool CollisionShape::isConvex(CollisionShapeType shapeType) { - return shapeType != CONCAVE_MESH && shapeType != HEIGHTFIELD; + return shapeType != CollisionShapeType::CONCAVE_MESH && shapeType != CollisionShapeType::HEIGHTFIELD; } // Return the scaling vector of the collision shape diff --git a/src/collision/shapes/ConcaveMeshShape.cpp b/src/collision/shapes/ConcaveMeshShape.cpp index 317a1c65..dfec3ba2 100644 --- a/src/collision/shapes/ConcaveMeshShape.cpp +++ b/src/collision/shapes/ConcaveMeshShape.cpp @@ -30,9 +30,9 @@ using namespace reactphysics3d; // Constructor ConcaveMeshShape::ConcaveMeshShape(TriangleMesh* triangleMesh) - : ConcaveShape(CONCAVE_MESH) { + : ConcaveShape(CollisionShapeType::CONCAVE_MESH) { mTriangleMesh = triangleMesh; - mRaycastTestType = FRONT; + mRaycastTestType = TriangleRaycastSide::FRONT; // Insert all the triangles into the dynamic AABB tree initBVHTree(); @@ -72,10 +72,10 @@ void ConcaveMeshShape::initBVHTree() { // Get the index of the current vertex in the triangle int vertexIndex = 0; - if (indexType == TriangleVertexArray::INDEX_INTEGER_TYPE) { + if (indexType == TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE) { vertexIndex = ((uint*)vertexIndexPointer)[k]; } - else if (indexType == TriangleVertexArray::INDEX_SHORT_TYPE) { + else if (indexType == TriangleVertexArray::IndexDataType::INDEX_SHORT_TYPE) { vertexIndex = ((unsigned short*)vertexIndexPointer)[k]; } else { @@ -83,13 +83,13 @@ void ConcaveMeshShape::initBVHTree() { } // Get the vertices components of the triangle - if (vertexType == TriangleVertexArray::VERTEX_FLOAT_TYPE) { + if (vertexType == TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE) { const float* vertices = (float*)(verticesStart + vertexIndex * vertexStride); trianglePoints[k][0] = decimal(vertices[0]) * mScaling.x; trianglePoints[k][1] = decimal(vertices[1]) * mScaling.y; trianglePoints[k][2] = decimal(vertices[2]) * mScaling.z; } - else if (vertexType == TriangleVertexArray::VERTEX_DOUBLE_TYPE) { + else if (vertexType == TriangleVertexArray::VertexDataType::VERTEX_DOUBLE_TYPE) { const double* vertices = (double*)(verticesStart + vertexIndex * vertexStride); trianglePoints[k][0] = decimal(vertices[0]) * mScaling.x; trianglePoints[k][1] = decimal(vertices[1]) * mScaling.y; @@ -132,10 +132,10 @@ void ConcaveMeshShape::getTriangleVerticesWithIndexPointer(int32 subPart, int32 // Get the index of the current vertex in the triangle int vertexIndex = 0; - if (indexType == TriangleVertexArray::INDEX_INTEGER_TYPE) { + if (indexType == TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE) { vertexIndex = ((uint*)vertexIndexPointer)[k]; } - else if (indexType == TriangleVertexArray::INDEX_SHORT_TYPE) { + else if (indexType == TriangleVertexArray::IndexDataType::INDEX_SHORT_TYPE) { vertexIndex = ((unsigned short*)vertexIndexPointer)[k]; } else { @@ -143,13 +143,13 @@ void ConcaveMeshShape::getTriangleVerticesWithIndexPointer(int32 subPart, int32 } // Get the vertices components of the triangle - if (vertexType == TriangleVertexArray::VERTEX_FLOAT_TYPE) { + if (vertexType == TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE) { const float* vertices = (float*)(verticesStart + vertexIndex * vertexStride); outTriangleVertices[k][0] = decimal(vertices[0]) * mScaling.x; outTriangleVertices[k][1] = decimal(vertices[1]) * mScaling.y; outTriangleVertices[k][2] = decimal(vertices[2]) * mScaling.z; } - else if (vertexType == TriangleVertexArray::VERTEX_DOUBLE_TYPE) { + else if (vertexType == TriangleVertexArray::VertexDataType::VERTEX_DOUBLE_TYPE) { const double* vertices = (double*)(verticesStart + vertexIndex * vertexStride); outTriangleVertices[k][0] = decimal(vertices[0]) * mScaling.x; outTriangleVertices[k][1] = decimal(vertices[1]) * mScaling.y; diff --git a/src/collision/shapes/ConcaveMeshShape.h b/src/collision/shapes/ConcaveMeshShape.h index 015c8159..f440f4b2 100644 --- a/src/collision/shapes/ConcaveMeshShape.h +++ b/src/collision/shapes/ConcaveMeshShape.h @@ -120,12 +120,6 @@ class ConcaveMeshShape : public ConcaveShape { // -------------------- Methods -------------------- // - /// Private copy-constructor - ConcaveMeshShape(const ConcaveMeshShape& shape); - - /// Private assignment operator - ConcaveMeshShape& operator=(const ConcaveMeshShape& shape); - /// Raycast method with feedback information virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const; @@ -146,7 +140,13 @@ class ConcaveMeshShape : public ConcaveShape { ConcaveMeshShape(TriangleMesh* triangleMesh); /// Destructor - ~ConcaveMeshShape(); + virtual ~ConcaveMeshShape(); + + /// Deleted copy-constructor + ConcaveMeshShape(const ConcaveMeshShape& shape) = delete; + + /// Deleted assignment operator + ConcaveMeshShape& operator=(const ConcaveMeshShape& shape) = delete; /// Return the local bounds of the shape in x, y and z directions. virtual void getLocalBounds(Vector3& min, Vector3& max) const; diff --git a/src/collision/shapes/ConcaveShape.cpp b/src/collision/shapes/ConcaveShape.cpp index 65a0c8b4..017a277a 100644 --- a/src/collision/shapes/ConcaveShape.cpp +++ b/src/collision/shapes/ConcaveShape.cpp @@ -33,7 +33,7 @@ using namespace reactphysics3d; // Constructor ConcaveShape::ConcaveShape(CollisionShapeType type) : CollisionShape(type), mIsSmoothMeshCollisionEnabled(false), - mTriangleMargin(0), mRaycastTestType(FRONT) { + mTriangleMargin(0), mRaycastTestType(TriangleRaycastSide::FRONT) { } diff --git a/src/collision/shapes/ConcaveShape.h b/src/collision/shapes/ConcaveShape.h index 9c1418df..1476e4b0 100644 --- a/src/collision/shapes/ConcaveShape.h +++ b/src/collision/shapes/ConcaveShape.h @@ -42,6 +42,9 @@ class TriangleCallback { public: + /// Destructor + virtual ~TriangleCallback() {} + /// Report a triangle virtual void testTriangle(const Vector3* trianglePoints)=0; @@ -70,12 +73,6 @@ class ConcaveShape : public CollisionShape { // -------------------- Methods -------------------- // - /// Private copy-constructor - ConcaveShape(const ConcaveShape& shape); - - /// Private assignment operator - ConcaveShape& operator=(const ConcaveShape& shape); - /// Return true if a point is inside the collision shape virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const; @@ -89,6 +86,12 @@ class ConcaveShape : public CollisionShape { /// Destructor virtual ~ConcaveShape(); + /// Deleted copy-constructor + ConcaveShape(const ConcaveShape& shape) = delete; + + /// Deleted assignment operator + ConcaveShape& operator=(const ConcaveShape& shape) = delete; + /// Return the triangle margin decimal getTriangleMargin() const; diff --git a/src/collision/shapes/ConeShape.cpp b/src/collision/shapes/ConeShape.cpp index cc956c73..fc166895 100644 --- a/src/collision/shapes/ConeShape.cpp +++ b/src/collision/shapes/ConeShape.cpp @@ -38,7 +38,7 @@ using namespace reactphysics3d; * @param margin Collision margin (in meters) around the collision shape */ ConeShape::ConeShape(decimal radius, decimal height, decimal margin) - : ConvexShape(CONE, margin), mRadius(radius), mHalfHeight(height * decimal(0.5)) { + : ConvexShape(CollisionShapeType::CONE, margin), mRadius(radius), mHalfHeight(height * decimal(0.5)) { assert(mRadius > decimal(0.0)); assert(mHalfHeight > decimal(0.0)); diff --git a/src/collision/shapes/ConeShape.h b/src/collision/shapes/ConeShape.h index b693f386..d9499823 100644 --- a/src/collision/shapes/ConeShape.h +++ b/src/collision/shapes/ConeShape.h @@ -66,12 +66,6 @@ class ConeShape : public ConvexShape { // -------------------- Methods -------------------- // - /// Private copy-constructor - ConeShape(const ConeShape& shape); - - /// Private assignment operator - ConeShape& operator=(const ConeShape& shape); - /// Return a local support point in a given direction without the object margin virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, void** cachedCollisionData) const; @@ -95,6 +89,12 @@ class ConeShape : public ConvexShape { /// Destructor virtual ~ConeShape(); + /// Deleted copy-constructor + ConeShape(const ConeShape& shape) = delete; + + /// Deleted assignment operator + ConeShape& operator=(const ConeShape& shape) = delete; + /// Return the radius decimal getRadius() const; diff --git a/src/collision/shapes/ConvexMeshShape.cpp b/src/collision/shapes/ConvexMeshShape.cpp index 5d0b651c..aedab6d1 100644 --- a/src/collision/shapes/ConvexMeshShape.cpp +++ b/src/collision/shapes/ConvexMeshShape.cpp @@ -39,7 +39,7 @@ using namespace reactphysics3d; * @param margin Collision margin (in meters) around the collision shape */ ConvexMeshShape::ConvexMeshShape(const decimal* arrayVertices, uint nbVertices, int stride, decimal margin) - : ConvexShape(CONVEX_MESH, margin), mNbVertices(nbVertices), mMinBounds(0, 0, 0), + : ConvexShape(CollisionShapeType::CONVEX_MESH, margin), mNbVertices(nbVertices), mMinBounds(0, 0, 0), mMaxBounds(0, 0, 0), mIsEdgesInformationUsed(false) { assert(nbVertices > 0); assert(stride > 0); @@ -65,7 +65,7 @@ ConvexMeshShape::ConvexMeshShape(const decimal* arrayVertices, uint nbVertices, * @param margin Collision margin (in meters) around the collision shape */ ConvexMeshShape::ConvexMeshShape(TriangleVertexArray* triangleVertexArray, bool isEdgesInformationUsed, decimal margin) - : ConvexShape(CONVEX_MESH, margin), mMinBounds(0, 0, 0), + : ConvexShape(CollisionShapeType::CONVEX_MESH, margin), mMinBounds(0, 0, 0), mMaxBounds(0, 0, 0), mIsEdgesInformationUsed(isEdgesInformationUsed) { TriangleVertexArray::VertexDataType vertexType = triangleVertexArray->getVertexDataType(); @@ -79,14 +79,14 @@ ConvexMeshShape::ConvexMeshShape(TriangleVertexArray* triangleVertexArray, bool for (uint v = 0; v < triangleVertexArray->getNbVertices(); v++) { // Get the vertices components of the triangle - if (vertexType == TriangleVertexArray::VERTEX_FLOAT_TYPE) { + if (vertexType == TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE) { const float* vertices = (float*)(verticesStart + v * vertexStride); Vector3 vertex(vertices[0], vertices[1], vertices[2] ); vertex = vertex * mScaling; mVertices.push_back(vertex); } - else if (vertexType == TriangleVertexArray::VERTEX_DOUBLE_TYPE) { + else if (vertexType == TriangleVertexArray::VertexDataType::VERTEX_DOUBLE_TYPE) { const double* vertices = (double*)(verticesStart + v * vertexStride); Vector3 vertex(vertices[0], vertices[1], vertices[2] ); @@ -109,10 +109,10 @@ ConvexMeshShape::ConvexMeshShape(TriangleVertexArray* triangleVertexArray, bool for (int k=0; k < 3; k++) { // Get the index of the current vertex in the triangle - if (indexType == TriangleVertexArray::INDEX_INTEGER_TYPE) { + if (indexType == TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE) { vertexIndex[k] = ((uint*)vertexIndexPointer)[k]; } - else if (indexType == TriangleVertexArray::INDEX_SHORT_TYPE) { + else if (indexType == TriangleVertexArray::IndexDataType::INDEX_SHORT_TYPE) { vertexIndex[k] = ((unsigned short*)vertexIndexPointer)[k]; } else { @@ -135,7 +135,7 @@ ConvexMeshShape::ConvexMeshShape(TriangleVertexArray* triangleVertexArray, bool /// If you use this constructor, you will need to set the vertices manually one by one using /// the addVertex() method. ConvexMeshShape::ConvexMeshShape(decimal margin) - : ConvexShape(CONVEX_MESH, margin), mNbVertices(0), mMinBounds(0, 0, 0), + : ConvexShape(CollisionShapeType::CONVEX_MESH, margin), mNbVertices(0), mMinBounds(0, 0, 0), mMaxBounds(0, 0, 0), mIsEdgesInformationUsed(false) { } diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index d23e91b0..cd309f9a 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -85,12 +85,6 @@ class ConvexMeshShape : public ConvexShape { // -------------------- Methods -------------------- // - /// Private copy-constructor - ConvexMeshShape(const ConvexMeshShape& shape); - - /// Private assignment operator - ConvexMeshShape& operator=(const ConvexMeshShape& shape); - /// Recompute the bounds of the mesh void recalculateBounds(); @@ -128,6 +122,12 @@ class ConvexMeshShape : public ConvexShape { /// Destructor virtual ~ConvexMeshShape(); + /// Deleted copy-constructor + ConvexMeshShape(const ConvexMeshShape& shape) = delete; + + /// Deleted assignment operator + ConvexMeshShape& operator=(const ConvexMeshShape& shape) = delete; + /// Return the local bounds of the shape in x, y and z directions virtual void getLocalBounds(Vector3& min, Vector3& max) const; diff --git a/src/collision/shapes/ConvexShape.h b/src/collision/shapes/ConvexShape.h index a3cd3131..93a11b81 100644 --- a/src/collision/shapes/ConvexShape.h +++ b/src/collision/shapes/ConvexShape.h @@ -48,12 +48,6 @@ class ConvexShape : public CollisionShape { // -------------------- Methods -------------------- // - /// Private copy-constructor - ConvexShape(const ConvexShape& shape); - - /// Private assignment operator - ConvexShape& operator=(const ConvexShape& shape); - // Return a local support point in a given direction with the object margin Vector3 getLocalSupportPointWithMargin(const Vector3& direction, void** cachedCollisionData) const; @@ -75,6 +69,12 @@ class ConvexShape : public CollisionShape { /// Destructor virtual ~ConvexShape(); + /// Deleted copy-constructor + ConvexShape(const ConvexShape& shape) = delete; + + /// Deleted assignment operator + ConvexShape& operator=(const ConvexShape& shape) = delete; + /// Return the current object margin decimal getMargin() const; diff --git a/src/collision/shapes/CylinderShape.cpp b/src/collision/shapes/CylinderShape.cpp index fd3da01c..c65047e8 100644 --- a/src/collision/shapes/CylinderShape.cpp +++ b/src/collision/shapes/CylinderShape.cpp @@ -37,7 +37,7 @@ using namespace reactphysics3d; * @param margin Collision margin (in meters) around the collision shape */ CylinderShape::CylinderShape(decimal radius, decimal height, decimal margin) - : ConvexShape(CYLINDER, margin), mRadius(radius), + : ConvexShape(CollisionShapeType::CYLINDER, margin), mRadius(radius), mHalfHeight(height/decimal(2.0)) { assert(radius > decimal(0.0)); assert(height > decimal(0.0)); diff --git a/src/collision/shapes/CylinderShape.h b/src/collision/shapes/CylinderShape.h index 71e4f9ae..819a1154 100644 --- a/src/collision/shapes/CylinderShape.h +++ b/src/collision/shapes/CylinderShape.h @@ -63,12 +63,6 @@ class CylinderShape : public ConvexShape { // -------------------- Methods -------------------- // - /// Private copy-constructor - CylinderShape(const CylinderShape& shape); - - /// Private assignment operator - CylinderShape& operator=(const CylinderShape& shape); - /// Return a local support point in a given direction without the object margin virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, void** cachedCollisionData) const; @@ -92,6 +86,12 @@ class CylinderShape : public ConvexShape { /// Destructor virtual ~CylinderShape(); + /// Deleted copy-constructor + CylinderShape(const CylinderShape& shape) = delete; + + /// Deleted assignment operator + CylinderShape& operator=(const CylinderShape& shape) = delete; + /// Return the radius decimal getRadius() const; diff --git a/src/collision/shapes/HeightFieldShape.cpp b/src/collision/shapes/HeightFieldShape.cpp index 88224e2d..720619e8 100644 --- a/src/collision/shapes/HeightFieldShape.cpp +++ b/src/collision/shapes/HeightFieldShape.cpp @@ -42,7 +42,7 @@ using namespace reactphysics3d; HeightFieldShape::HeightFieldShape(int nbGridColumns, int nbGridRows, decimal minHeight, decimal maxHeight, const void* heightFieldData, HeightDataType dataType, int upAxis, decimal integerHeightScale) - : ConcaveShape(HEIGHTFIELD), mNbColumns(nbGridColumns), mNbRows(nbGridRows), + : ConcaveShape(CollisionShapeType::HEIGHTFIELD), mNbColumns(nbGridColumns), mNbRows(nbGridRows), mWidth(nbGridColumns - 1), mLength(nbGridRows - 1), mMinHeight(minHeight), mMaxHeight(maxHeight), mUpAxis(upAxis), mIntegerHeightScale(integerHeightScale), mHeightDataType(dataType) { diff --git a/src/collision/shapes/HeightFieldShape.h b/src/collision/shapes/HeightFieldShape.h index 49adff48..ae7b4c62 100644 --- a/src/collision/shapes/HeightFieldShape.h +++ b/src/collision/shapes/HeightFieldShape.h @@ -84,7 +84,7 @@ class HeightFieldShape : public ConcaveShape { public: /// Data type for the height data of the height field - enum HeightDataType {HEIGHT_FLOAT_TYPE, HEIGHT_DOUBLE_TYPE, HEIGHT_INT_TYPE}; + enum class HeightDataType {HEIGHT_FLOAT_TYPE, HEIGHT_DOUBLE_TYPE, HEIGHT_INT_TYPE}; protected: @@ -125,12 +125,6 @@ class HeightFieldShape : public ConcaveShape { // -------------------- Methods -------------------- // - /// Private copy-constructor - HeightFieldShape(const HeightFieldShape& shape); - - /// Private assignment operator - HeightFieldShape& operator=(const HeightFieldShape& shape); - /// Raycast method with feedback information virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const; @@ -165,7 +159,13 @@ class HeightFieldShape : public ConcaveShape { int upAxis = 1, decimal integerHeightScale = 1.0f); /// Destructor - ~HeightFieldShape(); + virtual ~HeightFieldShape(); + + /// Deleted copy-constructor + HeightFieldShape(const HeightFieldShape& shape) = delete; + + /// Deleted assignment operator + HeightFieldShape& operator=(const HeightFieldShape& shape) = delete; /// Return the number of rows in the height field int getNbRows() const; @@ -223,9 +223,9 @@ inline void HeightFieldShape::setLocalScaling(const Vector3& scaling) { inline decimal HeightFieldShape::getHeightAt(int x, int y) const { switch(mHeightDataType) { - case HEIGHT_FLOAT_TYPE : return ((float*)mHeightFieldData)[y * mNbColumns + x]; - case HEIGHT_DOUBLE_TYPE : return ((double*)mHeightFieldData)[y * mNbColumns + x]; - case HEIGHT_INT_TYPE : return ((int*)mHeightFieldData)[y * mNbColumns + x] * mIntegerHeightScale; + case HeightDataType::HEIGHT_FLOAT_TYPE : return ((float*)mHeightFieldData)[y * mNbColumns + x]; + case HeightDataType::HEIGHT_DOUBLE_TYPE : return ((double*)mHeightFieldData)[y * mNbColumns + x]; + case HeightDataType::HEIGHT_INT_TYPE : return ((int*)mHeightFieldData)[y * mNbColumns + x] * mIntegerHeightScale; default: assert(false); return 0; } } diff --git a/src/collision/shapes/SphereShape.cpp b/src/collision/shapes/SphereShape.cpp index 549a6359..50c2e94d 100644 --- a/src/collision/shapes/SphereShape.cpp +++ b/src/collision/shapes/SphereShape.cpp @@ -35,7 +35,7 @@ using namespace reactphysics3d; /** * @param radius Radius of the sphere (in meters) */ -SphereShape::SphereShape(decimal radius) : ConvexShape(SPHERE, radius) { +SphereShape::SphereShape(decimal radius) : ConvexShape(CollisionShapeType::SPHERE, radius) { assert(radius > decimal(0.0)); } diff --git a/src/collision/shapes/SphereShape.h b/src/collision/shapes/SphereShape.h index a1316ae0..c8157952 100644 --- a/src/collision/shapes/SphereShape.h +++ b/src/collision/shapes/SphereShape.h @@ -51,12 +51,6 @@ class SphereShape : public ConvexShape { // -------------------- Methods -------------------- // - /// Private copy-constructor - SphereShape(const SphereShape& shape); - - /// Private assignment operator - SphereShape& operator=(const SphereShape& shape); - /// Return a local support point in a given direction without the object margin virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, void** cachedCollisionData) const; @@ -80,6 +74,12 @@ class SphereShape : public ConvexShape { /// Destructor virtual ~SphereShape(); + /// Deleted copy-constructor + SphereShape(const SphereShape& shape) = delete; + + /// Deleted assignment operator + SphereShape& operator=(const SphereShape& shape) = delete; + /// Return the radius of the sphere decimal getRadius() const; diff --git a/src/collision/shapes/TriangleShape.cpp b/src/collision/shapes/TriangleShape.cpp index 24bd3fda..065b7526 100644 --- a/src/collision/shapes/TriangleShape.cpp +++ b/src/collision/shapes/TriangleShape.cpp @@ -40,11 +40,11 @@ using namespace reactphysics3d; * @param margin The collision margin (in meters) around the collision shape */ TriangleShape::TriangleShape(const Vector3& point1, const Vector3& point2, const Vector3& point3, decimal margin) - : ConvexShape(TRIANGLE, margin) { + : ConvexShape(CollisionShapeType::TRIANGLE, margin) { mPoints[0] = point1; mPoints[1] = point2; mPoints[2] = point3; - mRaycastTestType = FRONT; + mRaycastTestType = TriangleRaycastSide::FRONT; } // Destructor @@ -68,32 +68,32 @@ bool TriangleShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape // product for this test. const Vector3 m = pq.cross(pc); decimal u = pb.dot(m); - if (mRaycastTestType == FRONT) { + if (mRaycastTestType == TriangleRaycastSide::FRONT) { if (u < decimal(0.0)) return false; } - else if (mRaycastTestType == BACK) { + else if (mRaycastTestType == TriangleRaycastSide::BACK) { if (u > decimal(0.0)) return false; } decimal v = -pa.dot(m); - if (mRaycastTestType == FRONT) { + if (mRaycastTestType == TriangleRaycastSide::FRONT) { if (v < decimal(0.0)) return false; } - else if (mRaycastTestType == BACK) { + else if (mRaycastTestType == TriangleRaycastSide::BACK) { if (v > decimal(0.0)) return false; } - else if (mRaycastTestType == FRONT_AND_BACK) { + else if (mRaycastTestType == TriangleRaycastSide::FRONT_AND_BACK) { if (!sameSign(u, v)) return false; } decimal w = pa.dot(pq.cross(pb)); - if (mRaycastTestType == FRONT) { + if (mRaycastTestType == TriangleRaycastSide::FRONT) { if (w < decimal(0.0)) return false; } - else if (mRaycastTestType == BACK) { + else if (mRaycastTestType == TriangleRaycastSide::BACK) { if (w > decimal(0.0)) return false; } - else if (mRaycastTestType == FRONT_AND_BACK) { + else if (mRaycastTestType == TriangleRaycastSide::FRONT_AND_BACK) { if (!sameSign(u, w)) return false; } diff --git a/src/collision/shapes/TriangleShape.h b/src/collision/shapes/TriangleShape.h index 1b9f3681..02757b88 100644 --- a/src/collision/shapes/TriangleShape.h +++ b/src/collision/shapes/TriangleShape.h @@ -34,7 +34,7 @@ namespace reactphysics3d { /// Raycast test side for the triangle -enum TriangleRaycastSide { +enum class TriangleRaycastSide { /// Raycast against front triangle FRONT, @@ -65,12 +65,6 @@ class TriangleShape : public ConvexShape { // -------------------- Methods -------------------- // - /// Private copy-constructor - TriangleShape(const TriangleShape& shape); - - /// Private assignment operator - TriangleShape& operator=(const TriangleShape& shape); - /// Return a local support point in a given direction without the object margin virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, void** cachedCollisionData) const; @@ -95,6 +89,12 @@ class TriangleShape : public ConvexShape { /// Destructor virtual ~TriangleShape(); + /// Deleted copy-constructor + TriangleShape(const TriangleShape& shape) = delete; + + /// Deleted assignment operator + TriangleShape& operator=(const TriangleShape& shape) = delete; + /// Return the local bounds of the shape in x, y and z directions. virtual void getLocalBounds(Vector3& min, Vector3& max) const; diff --git a/src/configuration.h b/src/configuration.h index a39117cc..731071fd 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -61,7 +61,7 @@ using uint32 = unsigned int; /// Position correction technique used in the constraint solver (for joints). /// BAUMGARTE_JOINTS : Faster but can be innacurate in some situations. /// NON_LINEAR_GAUSS_SEIDEL : Slower but more precise. This is the option used by default. -enum JointsPositionCorrectionTechnique {BAUMGARTE_JOINTS, NON_LINEAR_GAUSS_SEIDEL}; +enum class JointsPositionCorrectionTechnique {BAUMGARTE_JOINTS, NON_LINEAR_GAUSS_SEIDEL}; /// Position correction technique used in the contact solver (for contacts) /// BAUMGARTE_CONTACTS : Faster but can be innacurate and can lead to unexpected bounciness @@ -69,7 +69,7 @@ enum JointsPositionCorrectionTechnique {BAUMGARTE_JOINTS, NON_LINEAR_GAUSS_SEIDE /// the bodies momentum). /// SPLIT_IMPULSES : A bit slower but the error correction factor is not added to the /// bodies momentum. This is the option used by default. -enum ContactsPositionCorrectionTechnique {BAUMGARTE_CONTACTS, SPLIT_IMPULSES}; +enum class ContactsPositionCorrectionTechnique {BAUMGARTE_CONTACTS, SPLIT_IMPULSES}; // ------------------- Constants ------------------- // diff --git a/src/constraint/BallAndSocketJoint.cpp b/src/constraint/BallAndSocketJoint.cpp index 275b5643..8883d3e7 100644 --- a/src/constraint/BallAndSocketJoint.cpp +++ b/src/constraint/BallAndSocketJoint.cpp @@ -81,13 +81,13 @@ void BallAndSocketJoint::initBeforeSolve(const ConstraintSolverData& constraintS // Compute the inverse mass matrix K^-1 mInverseMassMatrix.setToZero(); - if (mBody1->getType() == DYNAMIC || mBody2->getType() == DYNAMIC) { + if (mBody1->getType() == BodyType::DYNAMIC || mBody2->getType() == BodyType::DYNAMIC) { mInverseMassMatrix = massMatrix.getInverse(); } // Compute the bias "b" of the constraint mBiasVector.setToZero(); - if (mPositionCorrectionTechnique == BAUMGARTE_JOINTS) { + if (mPositionCorrectionTechnique == JointsPositionCorrectionTechnique::BAUMGARTE_JOINTS) { decimal biasFactor = (BETA / constraintSolverData.timeStep); mBiasVector = biasFactor * (x2 + mR2World - x1 - mR1World); } @@ -162,7 +162,7 @@ void BallAndSocketJoint::solvePositionConstraint(const ConstraintSolverData& con // If the error position correction technique is not the non-linear-gauss-seidel, we do // do not execute this method - if (mPositionCorrectionTechnique != NON_LINEAR_GAUSS_SEIDEL) return; + if (mPositionCorrectionTechnique != JointsPositionCorrectionTechnique::NON_LINEAR_GAUSS_SEIDEL) return; // Get the bodies center of mass and orientations Vector3& x1 = constraintSolverData.positions[mIndexBody1]; @@ -194,7 +194,7 @@ void BallAndSocketJoint::solvePositionConstraint(const ConstraintSolverData& con skewSymmetricMatrixU1 * mI1 * skewSymmetricMatrixU1.getTranspose() + skewSymmetricMatrixU2 * mI2 * skewSymmetricMatrixU2.getTranspose(); mInverseMassMatrix.setToZero(); - if (mBody1->getType() == DYNAMIC || mBody2->getType() == DYNAMIC) { + if (mBody1->getType() == BodyType::DYNAMIC || mBody2->getType() == BodyType::DYNAMIC) { mInverseMassMatrix = massMatrix.getInverse(); } diff --git a/src/constraint/BallAndSocketJoint.h b/src/constraint/BallAndSocketJoint.h index f4671e87..bc37b63e 100644 --- a/src/constraint/BallAndSocketJoint.h +++ b/src/constraint/BallAndSocketJoint.h @@ -55,7 +55,7 @@ struct BallAndSocketJointInfo : public JointInfo { */ BallAndSocketJointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2, const Vector3& initAnchorPointWorldSpace) - : JointInfo(rigidBody1, rigidBody2, BALLSOCKETJOINT), + : JointInfo(rigidBody1, rigidBody2, JointType::BALLSOCKETJOINT), anchorPointWorldSpace(initAnchorPointWorldSpace) {} }; @@ -105,12 +105,6 @@ class BallAndSocketJoint : public Joint { // -------------------- Methods -------------------- // - /// Private copy-constructor - BallAndSocketJoint(const BallAndSocketJoint& constraint); - - /// Private assignment operator - BallAndSocketJoint& operator=(const BallAndSocketJoint& constraint); - /// Return the number of bytes used by the joint virtual size_t getSizeInBytes() const; @@ -135,6 +129,12 @@ class BallAndSocketJoint : public Joint { /// Destructor virtual ~BallAndSocketJoint(); + + /// Deleted copy-constructor + BallAndSocketJoint(const BallAndSocketJoint& constraint) = delete; + + /// Deleted assignment operator + BallAndSocketJoint& operator=(const BallAndSocketJoint& constraint) = delete; }; // Return the number of bytes used by the joint diff --git a/src/constraint/ContactPoint.h b/src/constraint/ContactPoint.h index 9b172e6c..b7fef547 100644 --- a/src/constraint/ContactPoint.h +++ b/src/constraint/ContactPoint.h @@ -142,14 +142,6 @@ class ContactPoint { /// Cached rolling resistance impulse Vector3 mRollingResistanceImpulse; - - // -------------------- Methods -------------------- // - - /// Private copy-constructor - ContactPoint(const ContactPoint& contact); - - /// Private assignment operator - ContactPoint& operator=(const ContactPoint& contact); public : @@ -161,6 +153,12 @@ class ContactPoint { /// Destructor ~ContactPoint(); + /// Deleted copy-constructor + ContactPoint(const ContactPoint& contact) = delete; + + /// Deleted assignment operator + ContactPoint& operator=(const ContactPoint& contact) = delete; + /// Return the reference to the body 1 CollisionBody* getBody1() const; diff --git a/src/constraint/FixedJoint.cpp b/src/constraint/FixedJoint.cpp index 57c8d8c6..f17d0b9e 100644 --- a/src/constraint/FixedJoint.cpp +++ b/src/constraint/FixedJoint.cpp @@ -89,27 +89,27 @@ void FixedJoint::initBeforeSolve(const ConstraintSolverData& constraintSolverDat // Compute the inverse mass matrix K^-1 for the 3 translation constraints mInverseMassMatrixTranslation.setToZero(); - if (mBody1->getType() == DYNAMIC || mBody2->getType() == DYNAMIC) { + if (mBody1->getType() == BodyType::DYNAMIC || mBody2->getType() == BodyType::DYNAMIC) { mInverseMassMatrixTranslation = massMatrix.getInverse(); } // Compute the bias "b" of the constraint for the 3 translation constraints decimal biasFactor = (BETA / constraintSolverData.timeStep); mBiasTranslation.setToZero(); - if (mPositionCorrectionTechnique == BAUMGARTE_JOINTS) { + if (mPositionCorrectionTechnique == JointsPositionCorrectionTechnique::BAUMGARTE_JOINTS) { mBiasTranslation = biasFactor * (x2 + mR2World - x1 - mR1World); } // Compute the inverse of the mass matrix K=JM^-1J^t for the 3 rotation // contraints (3x3 matrix) mInverseMassMatrixRotation = mI1 + mI2; - if (mBody1->getType() == DYNAMIC || mBody2->getType() == DYNAMIC) { + if (mBody1->getType() == BodyType::DYNAMIC || mBody2->getType() == BodyType::DYNAMIC) { mInverseMassMatrixRotation = mInverseMassMatrixRotation.getInverse(); } // Compute the bias "b" for the 3 rotation constraints mBiasRotation.setToZero(); - if (mPositionCorrectionTechnique == BAUMGARTE_JOINTS) { + if (mPositionCorrectionTechnique == JointsPositionCorrectionTechnique::BAUMGARTE_JOINTS) { Quaternion currentOrientationDifference = orientationBody2 * orientationBody1.getInverse(); currentOrientationDifference.normalize(); const Quaternion qError = currentOrientationDifference * mInitOrientationDifferenceInv; @@ -222,7 +222,7 @@ void FixedJoint::solvePositionConstraint(const ConstraintSolverData& constraintS // If the error position correction technique is not the non-linear-gauss-seidel, we do // do not execute this method - if (mPositionCorrectionTechnique != NON_LINEAR_GAUSS_SEIDEL) return; + if (mPositionCorrectionTechnique != JointsPositionCorrectionTechnique::NON_LINEAR_GAUSS_SEIDEL) return; // Get the bodies positions and orientations Vector3& x1 = constraintSolverData.positions[mIndexBody1]; @@ -256,7 +256,7 @@ void FixedJoint::solvePositionConstraint(const ConstraintSolverData& constraintS skewSymmetricMatrixU1 * mI1 * skewSymmetricMatrixU1.getTranspose() + skewSymmetricMatrixU2 * mI2 * skewSymmetricMatrixU2.getTranspose(); mInverseMassMatrixTranslation.setToZero(); - if (mBody1->getType() == DYNAMIC || mBody2->getType() == DYNAMIC) { + if (mBody1->getType() == BodyType::DYNAMIC || mBody2->getType() == BodyType::DYNAMIC) { mInverseMassMatrixTranslation = massMatrix.getInverse(); } @@ -296,7 +296,7 @@ void FixedJoint::solvePositionConstraint(const ConstraintSolverData& constraintS // Compute the inverse of the mass matrix K=JM^-1J^t for the 3 rotation // contraints (3x3 matrix) mInverseMassMatrixRotation = mI1 + mI2; - if (mBody1->getType() == DYNAMIC || mBody2->getType() == DYNAMIC) { + if (mBody1->getType() == BodyType::DYNAMIC || mBody2->getType() == BodyType::DYNAMIC) { mInverseMassMatrixRotation = mInverseMassMatrixRotation.getInverse(); } diff --git a/src/constraint/FixedJoint.h b/src/constraint/FixedJoint.h index aa9f2798..974f1b79 100644 --- a/src/constraint/FixedJoint.h +++ b/src/constraint/FixedJoint.h @@ -55,7 +55,7 @@ struct FixedJointInfo : public JointInfo { */ FixedJointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2, const Vector3& initAnchorPointWorldSpace) - : JointInfo(rigidBody1, rigidBody2, FIXEDJOINT), + : JointInfo(rigidBody1, rigidBody2, JointType::FIXEDJOINT), anchorPointWorldSpace(initAnchorPointWorldSpace){} }; @@ -116,12 +116,6 @@ class FixedJoint : public Joint { // -------------------- Methods -------------------- // - /// Private copy-constructor - FixedJoint(const FixedJoint& constraint); - - /// Private assignment operator - FixedJoint& operator=(const FixedJoint& constraint); - /// Return the number of bytes used by the joint virtual size_t getSizeInBytes() const; @@ -146,6 +140,12 @@ class FixedJoint : public Joint { /// Destructor virtual ~FixedJoint(); + + /// Deleted copy-constructor + FixedJoint(const FixedJoint& constraint) = delete; + + /// Deleted assignment operator + FixedJoint& operator=(const FixedJoint& constraint) = delete; }; // Return the number of bytes used by the joint diff --git a/src/constraint/HingeJoint.cpp b/src/constraint/HingeJoint.cpp index e64cbde8..01563de4 100644 --- a/src/constraint/HingeJoint.cpp +++ b/src/constraint/HingeJoint.cpp @@ -129,14 +129,14 @@ void HingeJoint::initBeforeSolve(const ConstraintSolverData& constraintSolverDat skewSymmetricMatrixU1 * mI1 * skewSymmetricMatrixU1.getTranspose() + skewSymmetricMatrixU2 * mI2 * skewSymmetricMatrixU2.getTranspose(); mInverseMassMatrixTranslation.setToZero(); - if (mBody1->getType() == DYNAMIC || mBody2->getType() == DYNAMIC) { + if (mBody1->getType() == BodyType::DYNAMIC || mBody2->getType() == BodyType::DYNAMIC) { mInverseMassMatrixTranslation = massMatrix.getInverse(); } // Compute the bias "b" of the translation constraints mBTranslation.setToZero(); decimal biasFactor = (BETA / constraintSolverData.timeStep); - if (mPositionCorrectionTechnique == BAUMGARTE_JOINTS) { + if (mPositionCorrectionTechnique == JointsPositionCorrectionTechnique::BAUMGARTE_JOINTS) { mBTranslation = biasFactor * (x2 + mR2World - x1 - mR1World); } @@ -155,13 +155,13 @@ void HingeJoint::initBeforeSolve(const ConstraintSolverData& constraintSolverDat mC2CrossA1.dot(I2C2CrossA1); const Matrix2x2 matrixKRotation(el11, el12, el21, el22); mInverseMassMatrixRotation.setToZero(); - if (mBody1->getType() == DYNAMIC || mBody2->getType() == DYNAMIC) { + if (mBody1->getType() == BodyType::DYNAMIC || mBody2->getType() == BodyType::DYNAMIC) { mInverseMassMatrixRotation = matrixKRotation.getInverse(); } // Compute the bias "b" of the rotation constraints mBRotation.setToZero(); - if (mPositionCorrectionTechnique == BAUMGARTE_JOINTS) { + if (mPositionCorrectionTechnique == JointsPositionCorrectionTechnique::BAUMGARTE_JOINTS) { mBRotation = biasFactor * Vector2(mA1.dot(b2), mA1.dot(c2)); } @@ -188,13 +188,13 @@ void HingeJoint::initBeforeSolve(const ConstraintSolverData& constraintSolverDat // Compute the bias "b" of the lower limit constraint mBLowerLimit = 0.0; - if (mPositionCorrectionTechnique == BAUMGARTE_JOINTS) { + if (mPositionCorrectionTechnique == JointsPositionCorrectionTechnique::BAUMGARTE_JOINTS) { mBLowerLimit = biasFactor * lowerLimitError; } // Compute the bias "b" of the upper limit constraint mBUpperLimit = 0.0; - if (mPositionCorrectionTechnique == BAUMGARTE_JOINTS) { + if (mPositionCorrectionTechnique == JointsPositionCorrectionTechnique::BAUMGARTE_JOINTS) { mBUpperLimit = biasFactor * upperLimitError; } } @@ -408,7 +408,7 @@ void HingeJoint::solvePositionConstraint(const ConstraintSolverData& constraintS // If the error position correction technique is not the non-linear-gauss-seidel, we do // do not execute this method - if (mPositionCorrectionTechnique != NON_LINEAR_GAUSS_SEIDEL) return; + if (mPositionCorrectionTechnique != JointsPositionCorrectionTechnique::NON_LINEAR_GAUSS_SEIDEL) return; // Get the bodies positions and orientations Vector3& x1 = constraintSolverData.positions[mIndexBody1]; @@ -461,7 +461,7 @@ void HingeJoint::solvePositionConstraint(const ConstraintSolverData& constraintS skewSymmetricMatrixU1 * mI1 * skewSymmetricMatrixU1.getTranspose() + skewSymmetricMatrixU2 * mI2 * skewSymmetricMatrixU2.getTranspose(); mInverseMassMatrixTranslation.setToZero(); - if (mBody1->getType() == DYNAMIC || mBody2->getType() == DYNAMIC) { + if (mBody1->getType() == BodyType::DYNAMIC || mBody2->getType() == BodyType::DYNAMIC) { mInverseMassMatrixTranslation = massMatrix.getInverse(); } @@ -513,7 +513,7 @@ void HingeJoint::solvePositionConstraint(const ConstraintSolverData& constraintS mC2CrossA1.dot(I2C2CrossA1); const Matrix2x2 matrixKRotation(el11, el12, el21, el22); mInverseMassMatrixRotation.setToZero(); - if (mBody1->getType() == DYNAMIC || mBody2->getType() == DYNAMIC) { + if (mBody1->getType() == BodyType::DYNAMIC || mBody2->getType() == BodyType::DYNAMIC) { mInverseMassMatrixRotation = matrixKRotation.getInverse(); } diff --git a/src/constraint/HingeJoint.h b/src/constraint/HingeJoint.h index 662c7e5c..bebd19c8 100644 --- a/src/constraint/HingeJoint.h +++ b/src/constraint/HingeJoint.h @@ -82,7 +82,7 @@ struct HingeJointInfo : public JointInfo { HingeJointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2, const Vector3& initAnchorPointWorldSpace, const Vector3& initRotationAxisWorld) - : JointInfo(rigidBody1, rigidBody2, HINGEJOINT), + : JointInfo(rigidBody1, rigidBody2, JointType::HINGEJOINT), anchorPointWorldSpace(initAnchorPointWorldSpace), rotationAxisWorld(initRotationAxisWorld), isLimitEnabled(false), isMotorEnabled(false), minAngleLimit(-1), maxAngleLimit(1), @@ -101,7 +101,7 @@ struct HingeJointInfo : public JointInfo { const Vector3& initAnchorPointWorldSpace, const Vector3& initRotationAxisWorld, decimal initMinAngleLimit, decimal initMaxAngleLimit) - : JointInfo(rigidBody1, rigidBody2, HINGEJOINT), + : JointInfo(rigidBody1, rigidBody2, JointType::HINGEJOINT), anchorPointWorldSpace(initAnchorPointWorldSpace), rotationAxisWorld(initRotationAxisWorld), isLimitEnabled(true), isMotorEnabled(false), minAngleLimit(initMinAngleLimit), @@ -124,7 +124,7 @@ struct HingeJointInfo : public JointInfo { const Vector3& initRotationAxisWorld, decimal initMinAngleLimit, decimal initMaxAngleLimit, decimal initMotorSpeed, decimal initMaxMotorTorque) - : JointInfo(rigidBody1, rigidBody2, HINGEJOINT), + : JointInfo(rigidBody1, rigidBody2, JointType::HINGEJOINT), anchorPointWorldSpace(initAnchorPointWorldSpace), rotationAxisWorld(initRotationAxisWorld), isLimitEnabled(true), isMotorEnabled(false), minAngleLimit(initMinAngleLimit), @@ -250,12 +250,6 @@ class HingeJoint : public Joint { // -------------------- Methods -------------------- // - /// Private copy-constructor - HingeJoint(const HingeJoint& constraint); - - /// Private assignment operator - HingeJoint& operator=(const HingeJoint& constraint); - /// Reset the limits void resetLimits(); @@ -298,6 +292,12 @@ class HingeJoint : public Joint { /// Destructor virtual ~HingeJoint(); + /// Deleted copy-constructor + HingeJoint(const HingeJoint& constraint) = delete; + + /// Deleted assignment operator + HingeJoint& operator=(const HingeJoint& constraint) = delete; + /// Return true if the limits or the joint are enabled bool isLimitEnabled() const; diff --git a/src/constraint/Joint.h b/src/constraint/Joint.h index 66ed1f28..eb73f87f 100644 --- a/src/constraint/Joint.h +++ b/src/constraint/Joint.h @@ -35,7 +35,7 @@ namespace reactphysics3d { /// Enumeration for the type of a constraint -enum JointType {BALLSOCKETJOINT, SLIDERJOINT, HINGEJOINT, FIXEDJOINT}; +enum class JointType {BALLSOCKETJOINT, SLIDERJOINT, HINGEJOINT, FIXEDJOINT}; // Class declarations struct ConstraintSolverData; @@ -95,13 +95,13 @@ struct JointInfo { /// Constructor JointInfo(JointType constraintType) : body1(nullptr), body2(nullptr), type(constraintType), - positionCorrectionTechnique(NON_LINEAR_GAUSS_SEIDEL), + positionCorrectionTechnique(JointsPositionCorrectionTechnique::NON_LINEAR_GAUSS_SEIDEL), isCollisionEnabled(true) {} /// Constructor JointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2, JointType constraintType) : body1(rigidBody1), body2(rigidBody2), type(constraintType), - positionCorrectionTechnique(NON_LINEAR_GAUSS_SEIDEL), + positionCorrectionTechnique(JointsPositionCorrectionTechnique::NON_LINEAR_GAUSS_SEIDEL), isCollisionEnabled(true) { } @@ -146,12 +146,6 @@ class Joint { // -------------------- Methods -------------------- // - /// Private copy-constructor - Joint(const Joint& constraint); - - /// Private assignment operator - Joint& operator=(const Joint& constraint); - /// Return true if the joint has already been added into an island bool isAlreadyInIsland() const; @@ -180,6 +174,12 @@ class Joint { /// Destructor virtual ~Joint(); + /// Deleted copy-constructor + Joint(const Joint& constraint) = delete; + + /// Deleted assignment operator + Joint& operator=(const Joint& constraint) = delete; + /// Return the reference to the body 1 RigidBody* getBody1() const; diff --git a/src/constraint/SliderJoint.cpp b/src/constraint/SliderJoint.cpp index 99a5c834..a1904174 100644 --- a/src/constraint/SliderJoint.cpp +++ b/src/constraint/SliderJoint.cpp @@ -139,14 +139,14 @@ void SliderJoint::initBeforeSolve(const ConstraintSolverData& constraintSolverDa mR2CrossN2.dot(I2R2CrossN2); Matrix2x2 matrixKTranslation(el11, el12, el21, el22); mInverseMassMatrixTranslationConstraint.setToZero(); - if (mBody1->getType() == DYNAMIC || mBody2->getType() == DYNAMIC) { + if (mBody1->getType() == BodyType::DYNAMIC || mBody2->getType() == BodyType::DYNAMIC) { mInverseMassMatrixTranslationConstraint = matrixKTranslation.getInverse(); } // Compute the bias "b" of the translation constraint mBTranslation.setToZero(); decimal biasFactor = (BETA / constraintSolverData.timeStep); - if (mPositionCorrectionTechnique == BAUMGARTE_JOINTS) { + if (mPositionCorrectionTechnique == JointsPositionCorrectionTechnique::BAUMGARTE_JOINTS) { mBTranslation.x = u.dot(mN1); mBTranslation.y = u.dot(mN2); mBTranslation *= biasFactor; @@ -155,13 +155,13 @@ void SliderJoint::initBeforeSolve(const ConstraintSolverData& constraintSolverDa // Compute the inverse of the mass matrix K=JM^-1J^t for the 3 rotation // contraints (3x3 matrix) mInverseMassMatrixRotationConstraint = mI1 + mI2; - if (mBody1->getType() == DYNAMIC || mBody2->getType() == DYNAMIC) { + if (mBody1->getType() == BodyType::DYNAMIC || mBody2->getType() == BodyType::DYNAMIC) { mInverseMassMatrixRotationConstraint = mInverseMassMatrixRotationConstraint.getInverse(); } // Compute the bias "b" of the rotation constraint mBRotation.setToZero(); - if (mPositionCorrectionTechnique == BAUMGARTE_JOINTS) { + if (mPositionCorrectionTechnique == JointsPositionCorrectionTechnique::BAUMGARTE_JOINTS) { Quaternion currentOrientationDifference = orientationBody2 * orientationBody1.getInverse(); currentOrientationDifference.normalize(); const Quaternion qError = currentOrientationDifference * mInitOrientationDifferenceInv; @@ -180,13 +180,13 @@ void SliderJoint::initBeforeSolve(const ConstraintSolverData& constraintSolverDa // Compute the bias "b" of the lower limit constraint mBLowerLimit = 0.0; - if (mPositionCorrectionTechnique == BAUMGARTE_JOINTS) { + if (mPositionCorrectionTechnique == JointsPositionCorrectionTechnique::BAUMGARTE_JOINTS) { mBLowerLimit = biasFactor * lowerLimitError; } // Compute the bias "b" of the upper limit constraint mBUpperLimit = 0.0; - if (mPositionCorrectionTechnique == BAUMGARTE_JOINTS) { + if (mPositionCorrectionTechnique == JointsPositionCorrectionTechnique::BAUMGARTE_JOINTS) { mBUpperLimit = biasFactor * upperLimitError; } } @@ -433,7 +433,7 @@ void SliderJoint::solvePositionConstraint(const ConstraintSolverData& constraint // If the error position correction technique is not the non-linear-gauss-seidel, we do // do not execute this method - if (mPositionCorrectionTechnique != NON_LINEAR_GAUSS_SEIDEL) return; + if (mPositionCorrectionTechnique != JointsPositionCorrectionTechnique::NON_LINEAR_GAUSS_SEIDEL) return; // Get the bodies positions and orientations Vector3& x1 = constraintSolverData.positions[mIndexBody1]; @@ -497,7 +497,7 @@ void SliderJoint::solvePositionConstraint(const ConstraintSolverData& constraint mR2CrossN2.dot(I2R2CrossN2); Matrix2x2 matrixKTranslation(el11, el12, el21, el22); mInverseMassMatrixTranslationConstraint.setToZero(); - if (mBody1->getType() == DYNAMIC || mBody2->getType() == DYNAMIC) { + if (mBody1->getType() == BodyType::DYNAMIC || mBody2->getType() == BodyType::DYNAMIC) { mInverseMassMatrixTranslationConstraint = matrixKTranslation.getInverse(); } @@ -540,7 +540,7 @@ void SliderJoint::solvePositionConstraint(const ConstraintSolverData& constraint // Compute the inverse of the mass matrix K=JM^-1J^t for the 3 rotation // contraints (3x3 matrix) mInverseMassMatrixRotationConstraint = mI1 + mI2; - if (mBody1->getType() == DYNAMIC || mBody2->getType() == DYNAMIC) { + if (mBody1->getType() == BodyType::DYNAMIC || mBody2->getType() == BodyType::DYNAMIC) { mInverseMassMatrixRotationConstraint = mInverseMassMatrixRotationConstraint.getInverse(); } diff --git a/src/constraint/SliderJoint.h b/src/constraint/SliderJoint.h index c40526d4..a4f359da 100644 --- a/src/constraint/SliderJoint.h +++ b/src/constraint/SliderJoint.h @@ -77,7 +77,7 @@ struct SliderJointInfo : public JointInfo { SliderJointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2, const Vector3& initAnchorPointWorldSpace, const Vector3& initSliderAxisWorldSpace) - : JointInfo(rigidBody1, rigidBody2, SLIDERJOINT), + : JointInfo(rigidBody1, rigidBody2, JointType::SLIDERJOINT), anchorPointWorldSpace(initAnchorPointWorldSpace), sliderAxisWorldSpace(initSliderAxisWorldSpace), isLimitEnabled(false), isMotorEnabled(false), minTranslationLimit(-1.0), @@ -96,7 +96,7 @@ struct SliderJointInfo : public JointInfo { const Vector3& initAnchorPointWorldSpace, const Vector3& initSliderAxisWorldSpace, decimal initMinTranslationLimit, decimal initMaxTranslationLimit) - : JointInfo(rigidBody1, rigidBody2, SLIDERJOINT), + : JointInfo(rigidBody1, rigidBody2, JointType::SLIDERJOINT), anchorPointWorldSpace(initAnchorPointWorldSpace), sliderAxisWorldSpace(initSliderAxisWorldSpace), isLimitEnabled(true), isMotorEnabled(false), @@ -120,7 +120,7 @@ struct SliderJointInfo : public JointInfo { const Vector3& initSliderAxisWorldSpace, decimal initMinTranslationLimit, decimal initMaxTranslationLimit, decimal initMotorSpeed, decimal initMaxMotorForce) - : JointInfo(rigidBody1, rigidBody2, SLIDERJOINT), + : JointInfo(rigidBody1, rigidBody2, JointType::SLIDERJOINT), anchorPointWorldSpace(initAnchorPointWorldSpace), sliderAxisWorldSpace(initSliderAxisWorldSpace), isLimitEnabled(true), isMotorEnabled(true), @@ -262,12 +262,6 @@ class SliderJoint : public Joint { // -------------------- Methods -------------------- // - /// Private copy-constructor - SliderJoint(const SliderJoint& constraint); - - /// Private assignment operator - SliderJoint& operator=(const SliderJoint& constraint); - /// Reset the limits void resetLimits(); @@ -296,6 +290,12 @@ class SliderJoint : public Joint { /// Destructor virtual ~SliderJoint(); + /// Deleted copy-constructor + SliderJoint(const SliderJoint& constraint) = delete; + + /// Deleted assignment operator + SliderJoint& operator=(const SliderJoint& constraint) = delete; + /// Return true if the limits or the joint are enabled bool isLimitEnabled() const; diff --git a/src/engine/CollisionWorld.h b/src/engine/CollisionWorld.h index 91560935..77189e89 100644 --- a/src/engine/CollisionWorld.h +++ b/src/engine/CollisionWorld.h @@ -80,12 +80,6 @@ class CollisionWorld { // -------------------- Methods -------------------- // - /// Private copy-constructor - CollisionWorld(const CollisionWorld& world); - - /// Private assignment operator - CollisionWorld& operator=(const CollisionWorld& world); - /// Return the next available body ID bodyindex computeNextAvailableBodyID(); @@ -102,6 +96,12 @@ class CollisionWorld { /// Destructor virtual ~CollisionWorld(); + /// Deleted copy-constructor + CollisionWorld(const CollisionWorld& world) = delete; + + /// Deleted assignment operator + CollisionWorld& operator=(const CollisionWorld& world) = delete; + /// Return an iterator to the beginning of the bodies of the physics world std::set::iterator getBodiesBeginIterator(); diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index f2ee0ef2..c3a0d0ef 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -105,8 +105,8 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { internalManifold.frictionCoefficient = computeMixedFrictionCoefficient(body1, body2); internalManifold.rollingResistanceFactor = computeMixedRollingResistance(body1, body2); internalManifold.externalContactManifold = externalManifold; - internalManifold.isBody1DynamicType = body1->getType() == DYNAMIC; - internalManifold.isBody2DynamicType = body2->getType() == DYNAMIC; + internalManifold.isBody1DynamicType = body1->getType() == BodyType::DYNAMIC; + internalManifold.isBody2DynamicType = body2->getType() == BodyType::DYNAMIC; // If we solve the friction constraints at the center of the contact manifold if (mIsSolveFrictionAtContactManifoldCenterActive) { diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index b52e2378..2f601edd 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -503,7 +503,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { switch(jointInfo.type) { // Ball-and-Socket joint - case BALLSOCKETJOINT: + case JointType::BALLSOCKETJOINT: { void* allocatedMemory = mMemoryAllocator.allocate(sizeof(BallAndSocketJoint)); const BallAndSocketJointInfo& info = static_cast( @@ -513,7 +513,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { } // Slider joint - case SLIDERJOINT: + case JointType::SLIDERJOINT: { void* allocatedMemory = mMemoryAllocator.allocate(sizeof(SliderJoint)); const SliderJointInfo& info = static_cast(jointInfo); @@ -522,7 +522,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { } // Hinge joint - case HINGEJOINT: + case JointType::HINGEJOINT: { void* allocatedMemory = mMemoryAllocator.allocate(sizeof(HingeJoint)); const HingeJointInfo& info = static_cast(jointInfo); @@ -531,7 +531,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { } // Fixed joint - case FIXEDJOINT: + case JointType::FIXEDJOINT: { void* allocatedMemory = mMemoryAllocator.allocate(sizeof(FixedJoint)); const FixedJointInfo& info = static_cast(jointInfo); @@ -673,7 +673,7 @@ void DynamicsWorld::computeIslands() { if (body->mIsAlreadyInIsland) continue; // If the body is static, we go to the next body - if (body->getType() == STATIC) continue; + if (body->getType() == BodyType::STATIC) continue; // If the body is sleeping or inactive, we go to the next body if (body->isSleeping() || !body->isActive()) continue; @@ -706,7 +706,7 @@ void DynamicsWorld::computeIslands() { // If the current body is static, we do not want to perform the DFS // search across that body - if (bodyToVisit->getType() == STATIC) continue; + if (bodyToVisit->getType() == BodyType::STATIC) continue; // For each contact manifold in which the current body is involded ContactManifoldListElement* contactElement; @@ -771,7 +771,7 @@ void DynamicsWorld::computeIslands() { // can also be included in the other islands for (uint i=0; i < mIslands[mNbIslands]->mNbBodies; i++) { - if (mIslands[mNbIslands]->mBodies[i]->getType() == STATIC) { + if (mIslands[mNbIslands]->mBodies[i]->getType() == BodyType::STATIC) { mIslands[mNbIslands]->mBodies[i]->mIsAlreadyInIsland = false; } } @@ -803,7 +803,7 @@ void DynamicsWorld::updateSleepingBodies() { for (uint b=0; b < mIslands[i]->getNbBodies(); b++) { // Skip static bodies - if (bodies[b]->getType() == STATIC) continue; + if (bodies[b]->getType() == BodyType::STATIC) continue; // If the body is velocity is large enough to stay awake if (bodies[b]->getLinearVelocity().lengthSquare() > sleepLinearVelocitySquare || diff --git a/src/engine/DynamicsWorld.h b/src/engine/DynamicsWorld.h index 71a5336a..a9bfc9d8 100644 --- a/src/engine/DynamicsWorld.h +++ b/src/engine/DynamicsWorld.h @@ -127,12 +127,6 @@ class DynamicsWorld : public CollisionWorld { // -------------------- Methods -------------------- // - /// Private copy-constructor - DynamicsWorld(const DynamicsWorld& world); - - /// Private assignment operator - DynamicsWorld& operator=(const DynamicsWorld& world); - /// Integrate the positions and orientations of rigid bodies. void integrateRigidBodiesPositions(); @@ -186,6 +180,12 @@ class DynamicsWorld : public CollisionWorld { /// Destructor virtual ~DynamicsWorld(); + /// Deleted copy-constructor + DynamicsWorld(const DynamicsWorld& world) = delete; + + /// Deleted assignment operator + DynamicsWorld& operator=(const DynamicsWorld& world) = delete; + /// Update the physics simulation void update(decimal timeStep); @@ -348,7 +348,7 @@ inline void DynamicsWorld::setNbIterationsPositionSolver(uint nbIterations) { */ inline void DynamicsWorld::setContactsPositionCorrectionTechnique( ContactsPositionCorrectionTechnique technique) { - if (technique == BAUMGARTE_CONTACTS) { + if (technique == ContactsPositionCorrectionTechnique::BAUMGARTE_CONTACTS) { mContactSolver.setIsSplitImpulseActive(false); } else { @@ -362,7 +362,7 @@ inline void DynamicsWorld::setContactsPositionCorrectionTechnique( */ inline void DynamicsWorld::setJointsPositionCorrectionTechnique( JointsPositionCorrectionTechnique technique) { - if (technique == BAUMGARTE_JOINTS) { + if (technique == JointsPositionCorrectionTechnique::BAUMGARTE_JOINTS) { mConstraintSolver.setIsNonLinearGaussSeidelPositionCorrectionActive(false); } else { diff --git a/src/engine/EventListener.h b/src/engine/EventListener.h index 4df79259..a2e9d868 100644 --- a/src/engine/EventListener.h +++ b/src/engine/EventListener.h @@ -53,7 +53,7 @@ class EventListener { /** * @param contact Information about the contact */ - virtual void beginContact(const ContactPointInfo& contact) {}; + virtual void beginContact(const ContactPointInfo& contact) {} /// Called when a new contact point is found between two bodies /** diff --git a/src/engine/Impulse.h b/src/engine/Impulse.h index 8c2bef33..89e36429 100644 --- a/src/engine/Impulse.h +++ b/src/engine/Impulse.h @@ -41,9 +41,6 @@ struct Impulse { // -------------------- Methods -------------------- // - /// Private assignment operator - Impulse& operator=(const Impulse& impulse); - public: // -------------------- Attributes -------------------- // @@ -78,8 +75,11 @@ struct Impulse { angularImpulseBody1(impulse.angularImpulseBody1), linearImpulseBody2(impulse.linearImpulseBody2), angularImpulseBody2(impulse.angularImpulseBody2) { -; + } + + /// Deleted assignment operator + Impulse& operator=(const Impulse& impulse) = delete; }; } diff --git a/src/engine/Island.h b/src/engine/Island.h index 6be38d5e..1b086939 100644 --- a/src/engine/Island.h +++ b/src/engine/Island.h @@ -75,14 +75,6 @@ class Island { /// Number of bytes allocated for the joints array size_t mNbAllocatedBytesJoints; - // -------------------- Methods -------------------- // - - /// Private assignment operator - Island& operator=(const Island& island); - - /// Private copy-constructor - Island(const Island& island); - public: // -------------------- Methods -------------------- // @@ -94,6 +86,12 @@ class Island { /// Destructor ~Island(); + /// Deleted assignment operator + Island& operator=(const Island& island) = delete; + + /// Deleted copy-constructor + Island(const Island& island) = delete; + /// Add a body into the island void addBody(RigidBody* body); diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index 995546c5..e40814ca 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -56,14 +56,6 @@ class OverlappingPair { /// Cached previous separating axis Vector3 mCachedSeparatingAxis; - - // -------------------- Methods -------------------- // - - /// Private copy-constructor - OverlappingPair(const OverlappingPair& pair); - - /// Private assignment operator - OverlappingPair& operator=(const OverlappingPair& pair); public: @@ -75,6 +67,12 @@ class OverlappingPair { /// Destructor ~OverlappingPair(); + + /// Deleted copy-constructor + OverlappingPair(const OverlappingPair& pair) = delete; + + /// Deleted assignment operator + OverlappingPair& operator=(const OverlappingPair& pair) = delete; /// Return the pointer to first proxy collision shape ProxyShape* getShape1() const; diff --git a/src/engine/Timer.h b/src/engine/Timer.h index ec673b67..9c59d033 100644 --- a/src/engine/Timer.h +++ b/src/engine/Timer.h @@ -71,14 +71,6 @@ class Timer { /// True if the timer is running bool mIsRunning; - // -------------------- Methods -------------------- // - - /// Private copy-constructor - Timer(const Timer& timer); - - /// Private assignment operator - Timer& operator=(const Timer& timer); - public : // -------------------- Methods -------------------- // @@ -87,7 +79,13 @@ class Timer { Timer(double timeStep); /// Destructor - virtual ~Timer(); + ~Timer(); + + /// Deleted copy-constructor + Timer(const Timer& timer) = delete; + + /// Deleted assignment operator + Timer& operator=(const Timer& timer) = delete; /// Return the timestep of the physics engine double getTimeStep() const; diff --git a/test/tests/collision/TestRaycast.h b/test/tests/collision/TestRaycast.h index 89b38110..09e3ebd8 100644 --- a/test/tests/collision/TestRaycast.h +++ b/test/tests/collision/TestRaycast.h @@ -288,13 +288,13 @@ class TestRaycast : public Test { mConcaveMeshIndices.push_back(1); mConcaveMeshIndices.push_back(4); mConcaveMeshIndices.push_back(5); mConcaveMeshIndices.push_back(5); mConcaveMeshIndices.push_back(7); mConcaveMeshIndices.push_back(6); mConcaveMeshIndices.push_back(4); mConcaveMeshIndices.push_back(7); mConcaveMeshIndices.push_back(5); - TriangleVertexArray::VertexDataType vertexType = sizeof(decimal) == 4 ? TriangleVertexArray::VERTEX_FLOAT_TYPE : - TriangleVertexArray::VERTEX_DOUBLE_TYPE; + TriangleVertexArray::VertexDataType vertexType = sizeof(decimal) == 4 ? TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE : + TriangleVertexArray::VertexDataType::VERTEX_DOUBLE_TYPE; mConcaveMeshVertexArray = new TriangleVertexArray(8, &(mConcaveMeshVertices[0]), sizeof(Vector3), 12, &(mConcaveMeshIndices[0]), sizeof(uint), vertexType, - TriangleVertexArray::INDEX_INTEGER_TYPE); + TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE); // Add the triangle vertex array of the subpart to the triangle mesh @@ -305,7 +305,7 @@ class TestRaycast : public Test { // Heightfield shape (plane height field at height=4) for (int i=0; i<100; i++) mHeightFieldData[i] = 4; - mHeightFieldShape = new HeightFieldShape(10, 10, 0, 4, mHeightFieldData, HeightFieldShape::HEIGHT_FLOAT_TYPE); + mHeightFieldShape = new HeightFieldShape(10, 10, 0, 4, mHeightFieldData, HeightFieldShape::HeightDataType::HEIGHT_FLOAT_TYPE); mHeightFieldProxyShape = mHeightFieldBody->addCollisionShape(mHeightFieldShape, mShapeTransform); // Assign proxy shapes to the different categories @@ -1032,7 +1032,7 @@ class TestRaycast : public Test { // CollisionWorld::raycast() mCallback.reset(); - mTriangleShape->setRaycastTestType(FRONT); + mTriangleShape->setRaycastTestType(TriangleRaycastSide::FRONT); mWorld->raycast(ray, &mCallback); test(mCallback.isHit); test(mCallback.raycastInfo.body == mTriangleBody); @@ -1046,7 +1046,7 @@ class TestRaycast : public Test { test(approxEqual(mCallback.raycastInfo.worldNormal.z, hitNormal.z, epsilon)); mCallback.reset(); - mTriangleShape->setRaycastTestType(BACK); + mTriangleShape->setRaycastTestType(TriangleRaycastSide::BACK); mWorld->raycast(rayBackward, &mCallback); test(mCallback.isHit); test(mCallback.raycastInfo.body == mTriangleBody); @@ -1060,7 +1060,7 @@ class TestRaycast : public Test { test(approxEqual(mCallback.raycastInfo.worldNormal.z, -hitNormal.z, epsilon)); mCallback.reset(); - mTriangleShape->setRaycastTestType(FRONT_AND_BACK); + mTriangleShape->setRaycastTestType(TriangleRaycastSide::FRONT_AND_BACK); mWorld->raycast(ray, &mCallback); test(mCallback.isHit); test(mCallback.raycastInfo.body == mTriangleBody); @@ -1074,7 +1074,7 @@ class TestRaycast : public Test { test(approxEqual(mCallback.raycastInfo.worldNormal.z, hitNormal.z, epsilon)); mCallback.reset(); - mTriangleShape->setRaycastTestType(FRONT_AND_BACK); + mTriangleShape->setRaycastTestType(TriangleRaycastSide::FRONT_AND_BACK); mWorld->raycast(rayBackward, &mCallback); test(mCallback.isHit); test(mCallback.raycastInfo.body == mTriangleBody); @@ -1087,7 +1087,7 @@ class TestRaycast : public Test { test(approxEqual(mCallback.raycastInfo.worldNormal.y, -hitNormal.y, epsilon)); test(approxEqual(mCallback.raycastInfo.worldNormal.z, -hitNormal.z, epsilon)); - mTriangleShape->setRaycastTestType(FRONT); + mTriangleShape->setRaycastTestType(TriangleRaycastSide::FRONT); // Correct category filter mask mCallback.reset(); @@ -1157,7 +1157,7 @@ class TestRaycast : public Test { test(!mCallback.isHit); // Test backward ray against front triangles (not hit should occur) - mTriangleShape->setRaycastTestType(FRONT); + mTriangleShape->setRaycastTestType(TriangleRaycastSide::FRONT); test(!mTriangleBody->raycast(ray4Back, raycastInfo3)); test(!mTriangleProxyShape->raycast(ray4Back, raycastInfo3)); @@ -1178,7 +1178,7 @@ class TestRaycast : public Test { test(!mCallback.isHit); // Test front ray against back triangles (not hit should occur) - mTriangleShape->setRaycastTestType(BACK); + mTriangleShape->setRaycastTestType(TriangleRaycastSide::BACK); test(!mTriangleBody->raycast(ray4, raycastInfo3)); test(!mTriangleProxyShape->raycast(ray4, raycastInfo3)); @@ -1201,7 +1201,7 @@ class TestRaycast : public Test { // ----- Test raycast hits ----- // // Test front ray against front triangles - mTriangleShape->setRaycastTestType(FRONT); + mTriangleShape->setRaycastTestType(TriangleRaycastSide::FRONT); test(mTriangleBody->raycast(ray4, raycastInfo3)); test(mTriangleProxyShape->raycast(ray4, raycastInfo3)); @@ -1229,7 +1229,7 @@ class TestRaycast : public Test { mWorld->raycast(Ray(ray6.point1, ray6.point2, decimal(0.8)), &mCallback); // Test back ray against back triangles - mTriangleShape->setRaycastTestType(BACK); + mTriangleShape->setRaycastTestType(TriangleRaycastSide::BACK); test(mTriangleBody->raycast(ray4Back, raycastInfo3)); test(mTriangleProxyShape->raycast(ray4Back, raycastInfo3)); @@ -1257,7 +1257,7 @@ class TestRaycast : public Test { mWorld->raycast(Ray(ray6Back.point1, ray6Back.point2, decimal(0.8)), &mCallback); // Test front ray against front-back triangles - mTriangleShape->setRaycastTestType(FRONT_AND_BACK); + mTriangleShape->setRaycastTestType(TriangleRaycastSide::FRONT_AND_BACK); test(mTriangleBody->raycast(ray4, raycastInfo3)); test(mTriangleProxyShape->raycast(ray4, raycastInfo3)); @@ -1285,7 +1285,7 @@ class TestRaycast : public Test { mWorld->raycast(Ray(ray6.point1, ray6.point2, decimal(0.8)), &mCallback); // Test back ray against front-back triangles - mTriangleShape->setRaycastTestType(FRONT_AND_BACK); + mTriangleShape->setRaycastTestType(TriangleRaycastSide::FRONT_AND_BACK); test(mTriangleBody->raycast(ray4Back, raycastInfo3)); test(mTriangleProxyShape->raycast(ray4Back, raycastInfo3)); diff --git a/testbed/common/ConcaveMesh.cpp b/testbed/common/ConcaveMesh.cpp index 0f8d7cb1..68f7a56e 100644 --- a/testbed/common/ConcaveMesh.cpp +++ b/testbed/common/ConcaveMesh.cpp @@ -53,8 +53,8 @@ ConcaveMesh::ConcaveMesh(const openglframework::Vector3 &position, rp3d::TriangleVertexArray* vertexArray = new rp3d::TriangleVertexArray(getNbVertices(), &(mVertices[0]), sizeof(openglframework::Vector3), getNbFaces(i), &(mIndices[i][0]), sizeof(int), - rp3d::TriangleVertexArray::VERTEX_FLOAT_TYPE, - rp3d::TriangleVertexArray::INDEX_INTEGER_TYPE); + rp3d::TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE, + rp3d::TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE); // Add the triangle vertex array of the subpart to the triangle mesh mPhysicsTriangleMesh.addSubpart(vertexArray); @@ -110,8 +110,8 @@ ConcaveMesh::ConcaveMesh(const openglframework::Vector3 &position, float mass, rp3d::TriangleVertexArray* vertexArray = new rp3d::TriangleVertexArray(getNbVertices(), &(mVertices[0]), sizeof(openglframework::Vector3), getNbFaces(i), &(mIndices[i][0]), sizeof(int), - rp3d::TriangleVertexArray::VERTEX_FLOAT_TYPE, - rp3d::TriangleVertexArray::INDEX_INTEGER_TYPE); + rp3d::TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE, + rp3d::TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE); // Add the triangle vertex array of the subpart to the triangle mesh mPhysicsTriangleMesh.addSubpart(vertexArray); diff --git a/testbed/common/ConvexMesh.cpp b/testbed/common/ConvexMesh.cpp index ffdbca04..1ded48a2 100644 --- a/testbed/common/ConvexMesh.cpp +++ b/testbed/common/ConvexMesh.cpp @@ -51,8 +51,8 @@ ConvexMesh::ConvexMesh(const openglframework::Vector3 &position, mPhysicsTriangleVertexArray = new rp3d::TriangleVertexArray(getNbVertices(), &(mVertices[0]), sizeof(openglframework::Vector3), getNbFaces(0), &(mIndices[0][0]), sizeof(int), - rp3d::TriangleVertexArray::VERTEX_FLOAT_TYPE, - rp3d::TriangleVertexArray::INDEX_INTEGER_TYPE); + rp3d::TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE, + rp3d::TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE); // Create the collision shape for the rigid body (convex mesh shape) and // do not forget to delete it at the end @@ -101,8 +101,8 @@ ConvexMesh::ConvexMesh(const openglframework::Vector3 &position, float mass, mPhysicsTriangleVertexArray = new rp3d::TriangleVertexArray(getNbVertices(), &(mVertices[0]), sizeof(openglframework::Vector3), getNbFaces(0), &(mIndices[0][0]), sizeof(int), - rp3d::TriangleVertexArray::VERTEX_FLOAT_TYPE, - rp3d::TriangleVertexArray::INDEX_INTEGER_TYPE); + rp3d::TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE, + rp3d::TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE); // Create the collision shape for the rigid body (convex mesh shape) and do // not forget to delete it at the end diff --git a/testbed/common/HeightField.cpp b/testbed/common/HeightField.cpp index e230c365..f65123ee 100644 --- a/testbed/common/HeightField.cpp +++ b/testbed/common/HeightField.cpp @@ -49,7 +49,7 @@ HeightField::HeightField(const openglframework::Vector3 &position, // Create the collision shape for the rigid body (convex mesh shape) and // do not forget to delete it at the end mHeightFieldShape = new rp3d::HeightFieldShape(NB_POINTS_WIDTH, NB_POINTS_LENGTH, mMinHeight, mMaxHeight, - mHeightData, rp3d::HeightFieldShape::HEIGHT_FLOAT_TYPE); + mHeightData, rp3d::HeightFieldShape::HeightDataType::HEIGHT_FLOAT_TYPE); // Initial position and orientation of the rigid body rp3d::Vector3 initPosition(position.x, position.y, position.z); @@ -92,7 +92,7 @@ HeightField::HeightField(const openglframework::Vector3 &position, float mass, // Create the collision shape for the rigid body (convex mesh shape) and // do not forget to delete it at the end mHeightFieldShape = new rp3d::HeightFieldShape(NB_POINTS_WIDTH, NB_POINTS_LENGTH, mMinHeight, mMaxHeight, - mHeightData, rp3d::HeightFieldShape::HEIGHT_FLOAT_TYPE); + mHeightData, rp3d::HeightFieldShape::HeightDataType::HEIGHT_FLOAT_TYPE); // Initial position and orientation of the rigid body rp3d::Vector3 initPosition(position.x, position.y, position.z); diff --git a/testbed/scenes/collisionshapes/CollisionShapesScene.cpp b/testbed/scenes/collisionshapes/CollisionShapesScene.cpp index bcf7c836..b1778398 100644 --- a/testbed/scenes/collisionshapes/CollisionShapesScene.cpp +++ b/testbed/scenes/collisionshapes/CollisionShapesScene.cpp @@ -245,7 +245,7 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name) mFloor->setSleepingColor(mGreyColorDemo); // The floor must be a static rigid body - mFloor->getRigidBody()->setType(rp3d::STATIC); + mFloor->getRigidBody()->setType(rp3d::BodyType::STATIC); // Change the material properties of the rigid body rp3d::Material& material = mFloor->getRigidBody()->getMaterial(); diff --git a/testbed/scenes/concavemesh/ConcaveMeshScene.cpp b/testbed/scenes/concavemesh/ConcaveMeshScene.cpp index d8309cde..c8396712 100644 --- a/testbed/scenes/concavemesh/ConcaveMeshScene.cpp +++ b/testbed/scenes/concavemesh/ConcaveMeshScene.cpp @@ -83,7 +83,7 @@ ConcaveMeshScene::ConcaveMeshScene(const std::string& name) mConcaveMesh = new ConcaveMesh(position, mass, mDynamicsWorld, meshFolderPath + "city.obj"); // Set the mesh as beeing static - mConcaveMesh->getRigidBody()->setType(rp3d::STATIC); + mConcaveMesh->getRigidBody()->setType(rp3d::BodyType::STATIC); // Set the box color mConcaveMesh->setColor(mGreyColorDemo); diff --git a/testbed/scenes/cubes/CubesScene.cpp b/testbed/scenes/cubes/CubesScene.cpp index 2de04857..e0a04cee 100644 --- a/testbed/scenes/cubes/CubesScene.cpp +++ b/testbed/scenes/cubes/CubesScene.cpp @@ -82,7 +82,7 @@ CubesScene::CubesScene(const std::string& name) mFloor->setSleepingColor(mGreyColorDemo); // The floor must be a static rigid body - mFloor->getRigidBody()->setType(rp3d::STATIC); + mFloor->getRigidBody()->setType(rp3d::BodyType::STATIC); // Change the material properties of the floor rigid body rp3d::Material& material = mFloor->getRigidBody()->getMaterial(); diff --git a/testbed/scenes/heightfield/HeightFieldScene.cpp b/testbed/scenes/heightfield/HeightFieldScene.cpp index ab168b13..fd72c9bb 100644 --- a/testbed/scenes/heightfield/HeightFieldScene.cpp +++ b/testbed/scenes/heightfield/HeightFieldScene.cpp @@ -78,7 +78,7 @@ HeightFieldScene::HeightFieldScene(const std::string& name) : SceneDemo(name, SC mHeightField = new HeightField(position, mass, mDynamicsWorld); // Set the mesh as beeing static - mHeightField->getRigidBody()->setType(rp3d::STATIC); + mHeightField->getRigidBody()->setType(rp3d::BodyType::STATIC); // Set the color mHeightField->setColor(mGreyColorDemo); diff --git a/testbed/scenes/joints/JointsScene.cpp b/testbed/scenes/joints/JointsScene.cpp index ae006573..4b96096c 100644 --- a/testbed/scenes/joints/JointsScene.cpp +++ b/testbed/scenes/joints/JointsScene.cpp @@ -274,7 +274,7 @@ void JointsScene::createBallAndSocketJoints() { // The fist box cannot move (static body) if (i == 0) { - mBallAndSocketJointChainBoxes[i]->getRigidBody()->setType(rp3d::STATIC); + mBallAndSocketJointChainBoxes[i]->getRigidBody()->setType(rp3d::BodyType::STATIC); } // Add some angular velocity damping @@ -322,7 +322,7 @@ void JointsScene::createSliderJoint() { mSliderJointBottomBox->setSleepingColor(mRedColorDemo); // The fist box cannot move - mSliderJointBottomBox->getRigidBody()->setType(rp3d::STATIC); + mSliderJointBottomBox->getRigidBody()->setType(rp3d::BodyType::STATIC); // Change the material properties of the rigid body rp3d::Material& material1 = mSliderJointBottomBox->getRigidBody()->getMaterial(); @@ -476,7 +476,7 @@ void JointsScene::createFloor() { mFloor->setSleepingColor(mGreyColorDemo); // The floor must be a static rigid body - mFloor->getRigidBody()->setType(rp3d::STATIC); + mFloor->getRigidBody()->setType(rp3d::BodyType::STATIC); // Change the material properties of the rigid body rp3d::Material& material = mFloor->getRigidBody()->getMaterial(); From 16478722dea6ca18629c5a89a4afb012e81a681c Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 11 Jul 2016 08:33:24 +0200 Subject: [PATCH 014/248] Use override keyword to mark virtual overriden methods --- src/body/CollisionBody.h | 4 ++-- src/body/RigidBody.h | 10 +++++----- src/collision/CollisionDetection.h | 4 ++-- .../broadphase/BroadPhaseAlgorithm.h | 6 +++--- .../narrowphase/ConcaveVsConvexAlgorithm.h | 10 +++++----- .../narrowphase/DefaultCollisionDispatch.h | 6 +++--- src/collision/narrowphase/GJK/GJKAlgorithm.h | 4 ++-- .../narrowphase/SphereVsSphereAlgorithm.h | 4 ++-- src/collision/shapes/BoxShape.h | 16 +++++++-------- src/collision/shapes/CapsuleShape.h | 16 +++++++-------- src/collision/shapes/ConcaveMeshShape.h | 16 +++++++-------- src/collision/shapes/ConcaveShape.h | 6 +++--- src/collision/shapes/ConeShape.h | 16 +++++++-------- src/collision/shapes/ConvexMeshShape.h | 16 +++++++-------- src/collision/shapes/ConvexShape.h | 4 ++-- src/collision/shapes/CylinderShape.h | 16 +++++++-------- src/collision/shapes/HeightFieldShape.h | 16 +++++++-------- src/collision/shapes/SphereShape.h | 18 ++++++++--------- src/collision/shapes/TriangleShape.h | 18 ++++++++--------- src/constraint/BallAndSocketJoint.h | 12 +++++------ src/constraint/FixedJoint.h | 12 +++++------ src/constraint/HingeJoint.h | 12 +++++------ src/constraint/SliderJoint.h | 12 +++++------ src/engine/DynamicsWorld.h | 12 +++++------ src/mathematics/Matrix3x3.h | 2 +- test/tests/collision/TestCollisionWorld.h | 2 +- test/tests/collision/TestDynamicAABBTree.h | 4 ++-- test/tests/collision/TestRaycast.h | 2 +- testbed/common/Box.h | 2 +- testbed/common/Capsule.h | 2 +- testbed/common/ConcaveMesh.h | 2 +- testbed/common/Cone.h | 2 +- testbed/common/ConvexMesh.h | 2 +- testbed/common/Cylinder.h | 2 +- testbed/common/Dumbbell.h | 2 +- testbed/common/HeightField.h | 2 +- testbed/common/Sphere.h | 2 +- .../collisionshapes/CollisionShapesScene.h | 12 +++++------ testbed/scenes/concavemesh/ConcaveMeshScene.h | 12 +++++------ testbed/scenes/cubes/CubesScene.h | 12 +++++------ testbed/scenes/heightfield/HeightFieldScene.h | 12 +++++------ testbed/scenes/joints/JointsScene.h | 12 +++++------ testbed/scenes/raycast/RaycastScene.h | 20 +++++++++---------- testbed/src/SceneDemo.h | 10 +++++----- testbed/src/TestbedApplication.h | 14 ++++++------- testbed/src/Timer.h | 2 +- 46 files changed, 200 insertions(+), 200 deletions(-) diff --git a/src/body/CollisionBody.h b/src/body/CollisionBody.h index c5658b58..33b0d489 100644 --- a/src/body/CollisionBody.h +++ b/src/body/CollisionBody.h @@ -114,7 +114,7 @@ class CollisionBody : public Body { CollisionBody(const Transform& transform, CollisionWorld& world, bodyindex id); /// Destructor - virtual ~CollisionBody(); + virtual ~CollisionBody() override; /// Deleted copy-constructor CollisionBody(const CollisionBody& body) = delete; @@ -129,7 +129,7 @@ class CollisionBody : public Body { void setType(BodyType type); /// Set whether or not the body is active - virtual void setIsActive(bool isActive); + virtual void setIsActive(bool isActive) override; /// Return the current position and orientation const Transform& getTransform() const; diff --git a/src/body/RigidBody.h b/src/body/RigidBody.h index b3c96c52..8fb36d0e 100644 --- a/src/body/RigidBody.h +++ b/src/body/RigidBody.h @@ -110,7 +110,7 @@ class RigidBody : public CollisionBody { void updateTransformWithCenterOfMass(); /// Update the broad-phase state for this body (because it has moved for instance) - virtual void updateBroadPhaseState() const; + virtual void updateBroadPhaseState() const override; public : @@ -120,7 +120,7 @@ class RigidBody : public CollisionBody { RigidBody(const Transform& transform, CollisionWorld& world, bodyindex id); /// Destructor - virtual ~RigidBody(); + virtual ~RigidBody() override; /// Deleted copy-constructor RigidBody(const RigidBody& body) = delete; @@ -132,7 +132,7 @@ class RigidBody : public CollisionBody { void setType(BodyType type); /// Set the current position and orientation - virtual void setTransform(const Transform& transform); + virtual void setTransform(const Transform& transform) override; /// Return the mass of the body decimal getMass() const; @@ -150,7 +150,7 @@ class RigidBody : public CollisionBody { void setAngularVelocity(const Vector3& angularVelocity); /// Set the variable to know whether or not the body is sleeping - virtual void setIsSleeping(bool isSleeping); + virtual void setIsSleeping(bool isSleeping) override; /// Return the local inertia tensor of the body (in body coordinates) const Matrix3x3& getInertiaTensorLocal() const; @@ -215,7 +215,7 @@ class RigidBody : public CollisionBody { decimal mass); /// Remove a collision shape from the body - virtual void removeCollisionShape(const ProxyShape* proxyShape); + virtual void removeCollisionShape(const ProxyShape* proxyShape) override; /// Recompute the center of mass, total mass and inertia tensor of the body using all /// the collision shapes attached to the body. diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index e02b129f..04d44f34 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -64,7 +64,7 @@ class TestCollisionBetweenShapesCallback : public NarrowPhaseCallback { // Called by a narrow-phase collision algorithm when a new contact has been found virtual void notifyContact(OverlappingPair* overlappingPair, - const ContactPointInfo& contactInfo); + const ContactPointInfo& contactInfo) override; }; // Class CollisionDetection @@ -220,7 +220,7 @@ class CollisionDetection : public NarrowPhaseCallback { MemoryAllocator& getWorldMemoryAllocator(); /// Called by a narrow-phase collision algorithm when a new contact has been found - virtual void notifyContact(OverlappingPair* overlappingPair, const ContactPointInfo& contactInfo); + virtual void notifyContact(OverlappingPair* overlappingPair, const ContactPointInfo& contactInfo) override; /// Create a new contact void createContact(OverlappingPair* overlappingPair, const ContactPointInfo& contactInfo); diff --git a/src/collision/broadphase/BroadPhaseAlgorithm.h b/src/collision/broadphase/BroadPhaseAlgorithm.h index 413a3d47..c4ea2c51 100644 --- a/src/collision/broadphase/BroadPhaseAlgorithm.h +++ b/src/collision/broadphase/BroadPhaseAlgorithm.h @@ -80,7 +80,7 @@ class AABBOverlapCallback : public DynamicAABBTreeOverlapCallback { // Called when a overlapping node has been found during the call to // DynamicAABBTree:reportAllShapesOverlappingWithAABB() - virtual void notifyOverlappingNode(int nodeId); + virtual void notifyOverlappingNode(int nodeId) override; }; @@ -110,10 +110,10 @@ class BroadPhaseRaycastCallback : public DynamicAABBTreeRaycastCallback { } // Destructor - virtual ~BroadPhaseRaycastCallback() {} + virtual ~BroadPhaseRaycastCallback() override {} // Called for a broad-phase shape that has to be tested for raycast - virtual decimal raycastBroadPhaseShape(int32 nodeId, const Ray& ray); + virtual decimal raycastBroadPhaseShape(int32 nodeId, const Ray& ray) override; }; diff --git a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h index 4fe2aec0..c8ba0fce 100644 --- a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h +++ b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h @@ -73,7 +73,7 @@ class ConvexVsTriangleCallback : public TriangleCallback { public: /// Destructor - virtual ~ConvexVsTriangleCallback() {} + virtual ~ConvexVsTriangleCallback() override {} /// Set the collision detection pointer void setCollisionDetection(CollisionDetection* collisionDetection) { @@ -107,7 +107,7 @@ class ConvexVsTriangleCallback : public TriangleCallback { } /// Test collision between a triangle and the convex mesh shape - virtual void testTriangle(const Vector3* trianglePoints); + virtual void testTriangle(const Vector3* trianglePoints) override; }; // Class SmoothMeshContactInfo @@ -172,7 +172,7 @@ class SmoothCollisionNarrowPhaseCallback : public NarrowPhaseCallback { /// Called by a narrow-phase collision algorithm when a new contact has been found virtual void notifyContact(OverlappingPair* overlappingPair, - const ContactPointInfo& contactInfo); + const ContactPointInfo& contactInfo) override; }; @@ -218,12 +218,12 @@ class ConcaveVsConvexAlgorithm : public NarrowPhaseAlgorithm { ConcaveVsConvexAlgorithm(); /// Destructor - virtual ~ConcaveVsConvexAlgorithm(); + virtual ~ConcaveVsConvexAlgorithm() override; /// Compute a contact info if the two bounding volume collide virtual void testCollision(const CollisionShapeInfo& shape1Info, const CollisionShapeInfo& shape2Info, - NarrowPhaseCallback* narrowPhaseCallback); + NarrowPhaseCallback* narrowPhaseCallback) override; }; // Add a triangle vertex into the set of processed triangles diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.h b/src/collision/narrowphase/DefaultCollisionDispatch.h index 6a3fb167..28f114f9 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.h +++ b/src/collision/narrowphase/DefaultCollisionDispatch.h @@ -59,15 +59,15 @@ class DefaultCollisionDispatch : public CollisionDispatch { DefaultCollisionDispatch(); /// Destructor - virtual ~DefaultCollisionDispatch(); + virtual ~DefaultCollisionDispatch() override; /// Initialize the collision dispatch configuration virtual void init(CollisionDetection* collisionDetection, - MemoryAllocator* memoryAllocator); + MemoryAllocator* memoryAllocator) override; /// Select and return the narrow-phase collision detection algorithm to /// use between two types of collision shapes. - virtual NarrowPhaseAlgorithm* selectAlgorithm(int type1, int type2); + virtual NarrowPhaseAlgorithm* selectAlgorithm(int type1, int type2) override; }; } diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.h b/src/collision/narrowphase/GJK/GJKAlgorithm.h index 96cdbf8a..209000ab 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.h +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.h @@ -94,12 +94,12 @@ class GJKAlgorithm : public NarrowPhaseAlgorithm { /// Initalize the algorithm virtual void init(CollisionDetection* collisionDetection, - MemoryAllocator* memoryAllocator); + MemoryAllocator* memoryAllocator) override; /// Compute a contact info if the two bounding volumes collide. virtual void testCollision(const CollisionShapeInfo& shape1Info, const CollisionShapeInfo& shape2Info, - NarrowPhaseCallback* narrowPhaseCallback); + NarrowPhaseCallback* narrowPhaseCallback) override; /// Use the GJK Algorithm to find if a point is inside a convex collision shape bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape); diff --git a/src/collision/narrowphase/SphereVsSphereAlgorithm.h b/src/collision/narrowphase/SphereVsSphereAlgorithm.h index 44190a22..9875d814 100644 --- a/src/collision/narrowphase/SphereVsSphereAlgorithm.h +++ b/src/collision/narrowphase/SphereVsSphereAlgorithm.h @@ -52,7 +52,7 @@ class SphereVsSphereAlgorithm : public NarrowPhaseAlgorithm { SphereVsSphereAlgorithm(); /// Destructor - virtual ~SphereVsSphereAlgorithm(); + virtual ~SphereVsSphereAlgorithm() override; /// Deleted copy-constructor SphereVsSphereAlgorithm(const SphereVsSphereAlgorithm& algorithm) = delete; @@ -63,7 +63,7 @@ class SphereVsSphereAlgorithm : public NarrowPhaseAlgorithm { /// Compute a contact info if the two bounding volume collide virtual void testCollision(const CollisionShapeInfo& shape1Info, const CollisionShapeInfo& shape2Info, - NarrowPhaseCallback* narrowPhaseCallback); + NarrowPhaseCallback* narrowPhaseCallback) override; }; } diff --git a/src/collision/shapes/BoxShape.h b/src/collision/shapes/BoxShape.h index bfe702fb..972012a8 100644 --- a/src/collision/shapes/BoxShape.h +++ b/src/collision/shapes/BoxShape.h @@ -63,16 +63,16 @@ class BoxShape : public ConvexShape { /// Return a local support point in a given direction without the object margin virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const; + void** cachedCollisionData) const override; /// Return true if a point is inside the collision shape - virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const; + 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; + virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const override; /// Return the number of bytes used by the collision shape - virtual size_t getSizeInBytes() const; + virtual size_t getSizeInBytes() const override; public : @@ -82,7 +82,7 @@ class BoxShape : public ConvexShape { BoxShape(const Vector3& extent, decimal margin = OBJECT_MARGIN); /// Destructor - virtual ~BoxShape(); + virtual ~BoxShape() override; /// Deleted copy-constructor BoxShape(const BoxShape& shape) = delete; @@ -94,13 +94,13 @@ class BoxShape : public ConvexShape { Vector3 getExtent() const; /// Set the scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling); + virtual void setLocalScaling(const Vector3& scaling) override; /// Return the local bounds of the shape in x, y and z directions - virtual void getLocalBounds(Vector3& min, Vector3& max) const; + virtual void getLocalBounds(Vector3& min, Vector3& max) const override; /// Return the local inertia tensor of the collision shape - virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; + virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; }; // Return the extents of the box diff --git a/src/collision/shapes/CapsuleShape.h b/src/collision/shapes/CapsuleShape.h index b4d4755b..fae76ce0 100644 --- a/src/collision/shapes/CapsuleShape.h +++ b/src/collision/shapes/CapsuleShape.h @@ -57,13 +57,13 @@ class CapsuleShape : public ConvexShape { /// Return a local support point in a given direction without the object margin virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const; + void** cachedCollisionData) const override; /// Return true if a point is inside the collision shape - virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const; + 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; + virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) 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, @@ -71,7 +71,7 @@ class CapsuleShape : public ConvexShape { Vector3& hitLocalPoint, decimal& hitFraction) const; /// Return the number of bytes used by the collision shape - virtual size_t getSizeInBytes() const; + virtual size_t getSizeInBytes() const override; public : @@ -81,7 +81,7 @@ class CapsuleShape : public ConvexShape { CapsuleShape(decimal radius, decimal height); /// Destructor - virtual ~CapsuleShape(); + virtual ~CapsuleShape() override; /// Deleted copy-constructor CapsuleShape(const CapsuleShape& shape) = delete; @@ -96,13 +96,13 @@ class CapsuleShape : public ConvexShape { decimal getHeight() const; /// Set the scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling); + virtual void setLocalScaling(const Vector3& scaling) override; /// Return the local bounds of the shape in x, y and z directions - virtual void getLocalBounds(Vector3& min, Vector3& max) const; + virtual void getLocalBounds(Vector3& min, Vector3& max) const override; /// Return the local inertia tensor of the collision shape - virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; + virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; }; // Get the radius of the capsule diff --git a/src/collision/shapes/ConcaveMeshShape.h b/src/collision/shapes/ConcaveMeshShape.h index f440f4b2..2af6ed9f 100644 --- a/src/collision/shapes/ConcaveMeshShape.h +++ b/src/collision/shapes/ConcaveMeshShape.h @@ -61,7 +61,7 @@ class ConvexTriangleAABBOverlapCallback : public DynamicAABBTreeOverlapCallback // Called when a overlapping node has been found during the call to // DynamicAABBTree:reportAllShapesOverlappingWithAABB() - virtual void notifyOverlappingNode(int nodeId); + virtual void notifyOverlappingNode(int nodeId) override; }; @@ -89,7 +89,7 @@ class ConcaveMeshRaycastCallback : public DynamicAABBTreeRaycastCallback { } /// Collect all the AABB nodes that are hit by the ray in the Dynamic AABB Tree - virtual decimal raycastBroadPhaseShape(int32 nodeId, const Ray& ray); + virtual decimal raycastBroadPhaseShape(int32 nodeId, const Ray& ray) override; /// Raycast all collision shapes that have been collected void raycastTriangles(); @@ -121,10 +121,10 @@ class ConcaveMeshShape : public ConcaveShape { // -------------------- Methods -------------------- // /// Raycast method with feedback information - virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const; + virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const override; /// Return the number of bytes used by the collision shape - virtual size_t getSizeInBytes() const; + virtual size_t getSizeInBytes() const override; /// Insert all the triangles into the dynamic AABB tree void initBVHTree(); @@ -149,16 +149,16 @@ class ConcaveMeshShape : public ConcaveShape { ConcaveMeshShape& operator=(const ConcaveMeshShape& shape) = delete; /// Return the local bounds of the shape in x, y and z directions. - virtual void getLocalBounds(Vector3& min, Vector3& max) const; + virtual void getLocalBounds(Vector3& min, Vector3& max) const override; /// Set the local scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling); + virtual void setLocalScaling(const Vector3& scaling) override; /// Return the local inertia tensor of the collision shape - virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; + virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; /// Use a callback method on all triangles of the concave shape inside a given AABB - virtual void testAllTriangles(TriangleCallback& callback, const AABB& localAABB) const; + virtual void testAllTriangles(TriangleCallback& callback, const AABB& localAABB) const override; // ---------- Friendship ----------- // diff --git a/src/collision/shapes/ConcaveShape.h b/src/collision/shapes/ConcaveShape.h index 1476e4b0..14bebf4d 100644 --- a/src/collision/shapes/ConcaveShape.h +++ b/src/collision/shapes/ConcaveShape.h @@ -74,7 +74,7 @@ class ConcaveShape : public CollisionShape { // -------------------- Methods -------------------- // /// Return true if a point is inside the collision shape - virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const; + virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const override; public : @@ -84,7 +84,7 @@ class ConcaveShape : public CollisionShape { ConcaveShape(CollisionShapeType type); /// Destructor - virtual ~ConcaveShape(); + virtual ~ConcaveShape() override; /// Deleted copy-constructor ConcaveShape(const ConcaveShape& shape) = delete; @@ -102,7 +102,7 @@ class ConcaveShape : public CollisionShape { void setRaycastTestType(TriangleRaycastSide testType); /// Return true if the collision shape is convex, false if it is concave - virtual bool isConvex() const; + virtual bool isConvex() const override; /// Use a callback method on all triangles of the concave shape inside a given AABB virtual void testAllTriangles(TriangleCallback& callback, const AABB& localAABB) const=0; diff --git a/src/collision/shapes/ConeShape.h b/src/collision/shapes/ConeShape.h index d9499823..e0ff722a 100644 --- a/src/collision/shapes/ConeShape.h +++ b/src/collision/shapes/ConeShape.h @@ -68,16 +68,16 @@ class ConeShape : public ConvexShape { /// Return a local support point in a given direction without the object margin virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const; + void** cachedCollisionData) const override; /// Return true if a point is inside the collision shape - virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const; + 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; + virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const override; /// Return the number of bytes used by the collision shape - virtual size_t getSizeInBytes() const; + virtual size_t getSizeInBytes() const override; public : @@ -87,7 +87,7 @@ class ConeShape : public ConvexShape { ConeShape(decimal mRadius, decimal height, decimal margin = OBJECT_MARGIN); /// Destructor - virtual ~ConeShape(); + virtual ~ConeShape() override; /// Deleted copy-constructor ConeShape(const ConeShape& shape) = delete; @@ -102,13 +102,13 @@ class ConeShape : public ConvexShape { decimal getHeight() const; /// Set the scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling); + virtual void setLocalScaling(const Vector3& scaling) override; /// Return the local bounds of the shape in x, y and z directions - virtual void getLocalBounds(Vector3& min, Vector3& max) const; + virtual void getLocalBounds(Vector3& min, Vector3& max) const override; /// Return the local inertia tensor of the collision shape - virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; + virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; }; // Return the radius diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index cd309f9a..449762a5 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -89,20 +89,20 @@ class ConvexMeshShape : public ConvexShape { void recalculateBounds(); /// Set the scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling); + virtual void setLocalScaling(const Vector3& scaling) override; /// Return a local support point in a given direction without the object margin. virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const; + void** cachedCollisionData) const override; /// Return true if a point is inside the collision shape - virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const; + 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; + virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const override; /// Return the number of bytes used by the collision shape - virtual size_t getSizeInBytes() const; + virtual size_t getSizeInBytes() const override; public : @@ -120,7 +120,7 @@ class ConvexMeshShape : public ConvexShape { ConvexMeshShape(decimal margin = OBJECT_MARGIN); /// Destructor - virtual ~ConvexMeshShape(); + virtual ~ConvexMeshShape() override; /// Deleted copy-constructor ConvexMeshShape(const ConvexMeshShape& shape) = delete; @@ -129,10 +129,10 @@ class ConvexMeshShape : public ConvexShape { ConvexMeshShape& operator=(const ConvexMeshShape& shape) = delete; /// Return the local bounds of the shape in x, y and z directions - virtual void getLocalBounds(Vector3& min, Vector3& max) const; + virtual void getLocalBounds(Vector3& min, Vector3& max) const override; /// Return the local inertia tensor of the collision shape. - virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; + virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; /// Add a vertex into the convex mesh void addVertex(const Vector3& vertex); diff --git a/src/collision/shapes/ConvexShape.h b/src/collision/shapes/ConvexShape.h index 93a11b81..f70a88e1 100644 --- a/src/collision/shapes/ConvexShape.h +++ b/src/collision/shapes/ConvexShape.h @@ -67,7 +67,7 @@ class ConvexShape : public CollisionShape { ConvexShape(CollisionShapeType type, decimal margin); /// Destructor - virtual ~ConvexShape(); + virtual ~ConvexShape() override; /// Deleted copy-constructor ConvexShape(const ConvexShape& shape) = delete; @@ -79,7 +79,7 @@ class ConvexShape : public CollisionShape { decimal getMargin() const; /// Return true if the collision shape is convex, false if it is concave - virtual bool isConvex() const; + virtual bool isConvex() const override; // -------------------- Friendship -------------------- // diff --git a/src/collision/shapes/CylinderShape.h b/src/collision/shapes/CylinderShape.h index 819a1154..4ac7d811 100644 --- a/src/collision/shapes/CylinderShape.h +++ b/src/collision/shapes/CylinderShape.h @@ -65,16 +65,16 @@ class CylinderShape : public ConvexShape { /// Return a local support point in a given direction without the object margin virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const; + void** cachedCollisionData) const override; /// Return true if a point is inside the collision shape - virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const; + 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; + virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const override ; /// Return the number of bytes used by the collision shape - virtual size_t getSizeInBytes() const; + virtual size_t getSizeInBytes() const override; public : @@ -84,7 +84,7 @@ class CylinderShape : public ConvexShape { CylinderShape(decimal radius, decimal height, decimal margin = OBJECT_MARGIN); /// Destructor - virtual ~CylinderShape(); + virtual ~CylinderShape() override; /// Deleted copy-constructor CylinderShape(const CylinderShape& shape) = delete; @@ -99,13 +99,13 @@ class CylinderShape : public ConvexShape { decimal getHeight() const; /// Set the scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling); + virtual void setLocalScaling(const Vector3& scaling) override; /// Return the local bounds of the shape in x, y and z directions - virtual void getLocalBounds(Vector3& min, Vector3& max) const; + virtual void getLocalBounds(Vector3& min, Vector3& max) const override; /// Return the local inertia tensor of the collision shape - virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; + virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; }; // Return the radius diff --git a/src/collision/shapes/HeightFieldShape.h b/src/collision/shapes/HeightFieldShape.h index ae7b4c62..be6819e5 100644 --- a/src/collision/shapes/HeightFieldShape.h +++ b/src/collision/shapes/HeightFieldShape.h @@ -64,7 +64,7 @@ class TriangleOverlapCallback : public TriangleCallback { bool getIsHit() const {return mIsHit;} /// Raycast test between a ray and a triangle of the heightfield - virtual void testTriangle(const Vector3* trianglePoints); + virtual void testTriangle(const Vector3* trianglePoints) override; }; @@ -126,10 +126,10 @@ class HeightFieldShape : public ConcaveShape { // -------------------- Methods -------------------- // /// Raycast method with feedback information - virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const; + virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const override; /// Return the number of bytes used by the collision shape - virtual size_t getSizeInBytes() const; + virtual size_t getSizeInBytes() const override; /// Insert all the triangles into the dynamic AABB tree void initBVHTree(); @@ -159,7 +159,7 @@ class HeightFieldShape : public ConcaveShape { int upAxis = 1, decimal integerHeightScale = 1.0f); /// Destructor - virtual ~HeightFieldShape(); + virtual ~HeightFieldShape() override; /// Deleted copy-constructor HeightFieldShape(const HeightFieldShape& shape) = delete; @@ -177,16 +177,16 @@ class HeightFieldShape : public ConcaveShape { HeightDataType getHeightDataType() const; /// Return the local bounds of the shape in x, y and z directions. - virtual void getLocalBounds(Vector3& min, Vector3& max) const; + virtual void getLocalBounds(Vector3& min, Vector3& max) const override; /// Set the local scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling); + virtual void setLocalScaling(const Vector3& scaling) override; /// Return the local inertia tensor of the collision shape - virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; + virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; /// Use a callback method on all triangles of the concave shape inside a given AABB - virtual void testAllTriangles(TriangleCallback& callback, const AABB& localAABB) const; + virtual void testAllTriangles(TriangleCallback& callback, const AABB& localAABB) const override; // ---------- Friendship ----------- // diff --git a/src/collision/shapes/SphereShape.h b/src/collision/shapes/SphereShape.h index c8157952..dc6a6cea 100644 --- a/src/collision/shapes/SphereShape.h +++ b/src/collision/shapes/SphereShape.h @@ -53,16 +53,16 @@ class SphereShape : public ConvexShape { /// Return a local support point in a given direction without the object margin virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const; + void** cachedCollisionData) const override; /// Return true if a point is inside the collision shape - virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const; + 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; + virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const override; /// Return the number of bytes used by the collision shape - virtual size_t getSizeInBytes() const; + virtual size_t getSizeInBytes() const override; public : @@ -72,7 +72,7 @@ class SphereShape : public ConvexShape { SphereShape(decimal radius); /// Destructor - virtual ~SphereShape(); + virtual ~SphereShape() override; /// Deleted copy-constructor SphereShape(const SphereShape& shape) = delete; @@ -84,16 +84,16 @@ class SphereShape : public ConvexShape { decimal getRadius() const; /// Set the scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling); + virtual void setLocalScaling(const Vector3& scaling) override; /// Return the local bounds of the shape in x, y and z directions. - virtual void getLocalBounds(Vector3& min, Vector3& max) const; + virtual void getLocalBounds(Vector3& min, Vector3& max) const override; /// Return the local inertia tensor of the collision shape - virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; + virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; /// Update the AABB of a body using its collision shape - virtual void computeAABB(AABB& aabb, const Transform& transform) const; + virtual void computeAABB(AABB& aabb, const Transform& transform) const override; }; // Get the radius of the sphere diff --git a/src/collision/shapes/TriangleShape.h b/src/collision/shapes/TriangleShape.h index 02757b88..699a42fc 100644 --- a/src/collision/shapes/TriangleShape.h +++ b/src/collision/shapes/TriangleShape.h @@ -67,16 +67,16 @@ class TriangleShape : public ConvexShape { /// Return a local support point in a given direction without the object margin virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const; + void** cachedCollisionData) const override; /// Return true if a point is inside the collision shape - virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const; + 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; + virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const override; /// Return the number of bytes used by the collision shape - virtual size_t getSizeInBytes() const; + virtual size_t getSizeInBytes() const override; public: @@ -87,7 +87,7 @@ class TriangleShape : public ConvexShape { decimal margin = OBJECT_MARGIN); /// Destructor - virtual ~TriangleShape(); + virtual ~TriangleShape() override; /// Deleted copy-constructor TriangleShape(const TriangleShape& shape) = delete; @@ -96,16 +96,16 @@ class TriangleShape : public ConvexShape { TriangleShape& operator=(const TriangleShape& shape) = delete; /// Return the local bounds of the shape in x, y and z directions. - virtual void getLocalBounds(Vector3& min, Vector3& max) const; + virtual void getLocalBounds(Vector3& min, Vector3& max) const override; /// Set the local scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling); + virtual void setLocalScaling(const Vector3& scaling) override; /// Return the local inertia tensor of the collision shape - virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; + virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; /// Update the AABB of a body using its collision shape - virtual void computeAABB(AABB& aabb, const Transform& transform) const; + virtual void computeAABB(AABB& aabb, const Transform& transform) const override; /// Return the raycast test type (front, back, front-back) TriangleRaycastSide getRaycastTestType() const; diff --git a/src/constraint/BallAndSocketJoint.h b/src/constraint/BallAndSocketJoint.h index bc37b63e..4244823c 100644 --- a/src/constraint/BallAndSocketJoint.h +++ b/src/constraint/BallAndSocketJoint.h @@ -106,19 +106,19 @@ class BallAndSocketJoint : public Joint { // -------------------- Methods -------------------- // /// Return the number of bytes used by the joint - virtual size_t getSizeInBytes() const; + virtual size_t getSizeInBytes() const override; /// Initialize before solving the constraint - virtual void initBeforeSolve(const ConstraintSolverData& constraintSolverData); + virtual void initBeforeSolve(const ConstraintSolverData& constraintSolverData) override; /// Warm start the constraint (apply the previous impulse at the beginning of the step) - virtual void warmstart(const ConstraintSolverData& constraintSolverData); + virtual void warmstart(const ConstraintSolverData& constraintSolverData) override; /// Solve the velocity constraint - virtual void solveVelocityConstraint(const ConstraintSolverData& constraintSolverData); + virtual void solveVelocityConstraint(const ConstraintSolverData& constraintSolverData) override; /// Solve the position constraint (for position error correction) - virtual void solvePositionConstraint(const ConstraintSolverData& constraintSolverData); + virtual void solvePositionConstraint(const ConstraintSolverData& constraintSolverData) override; public : @@ -128,7 +128,7 @@ class BallAndSocketJoint : public Joint { BallAndSocketJoint(const BallAndSocketJointInfo& jointInfo); /// Destructor - virtual ~BallAndSocketJoint(); + virtual ~BallAndSocketJoint() override; /// Deleted copy-constructor BallAndSocketJoint(const BallAndSocketJoint& constraint) = delete; diff --git a/src/constraint/FixedJoint.h b/src/constraint/FixedJoint.h index 974f1b79..54c9624c 100644 --- a/src/constraint/FixedJoint.h +++ b/src/constraint/FixedJoint.h @@ -117,19 +117,19 @@ class FixedJoint : public Joint { // -------------------- Methods -------------------- // /// Return the number of bytes used by the joint - virtual size_t getSizeInBytes() const; + virtual size_t getSizeInBytes() const override; /// Initialize before solving the constraint - virtual void initBeforeSolve(const ConstraintSolverData& constraintSolverData); + virtual void initBeforeSolve(const ConstraintSolverData& constraintSolverData) override; /// Warm start the constraint (apply the previous impulse at the beginning of the step) - virtual void warmstart(const ConstraintSolverData& constraintSolverData); + virtual void warmstart(const ConstraintSolverData& constraintSolverData) override; /// Solve the velocity constraint - virtual void solveVelocityConstraint(const ConstraintSolverData& constraintSolverData); + virtual void solveVelocityConstraint(const ConstraintSolverData& constraintSolverData) override; /// Solve the position constraint (for position error correction) - virtual void solvePositionConstraint(const ConstraintSolverData& constraintSolverData); + virtual void solvePositionConstraint(const ConstraintSolverData& constraintSolverData) override; public : @@ -139,7 +139,7 @@ class FixedJoint : public Joint { FixedJoint(const FixedJointInfo& jointInfo); /// Destructor - virtual ~FixedJoint(); + virtual ~FixedJoint() override; /// Deleted copy-constructor FixedJoint(const FixedJoint& constraint) = delete; diff --git a/src/constraint/HingeJoint.h b/src/constraint/HingeJoint.h index bebd19c8..21960697 100644 --- a/src/constraint/HingeJoint.h +++ b/src/constraint/HingeJoint.h @@ -268,19 +268,19 @@ class HingeJoint : public Joint { const Quaternion& orientationBody2); /// Return the number of bytes used by the joint - virtual size_t getSizeInBytes() const; + virtual size_t getSizeInBytes() const override; /// Initialize before solving the constraint - virtual void initBeforeSolve(const ConstraintSolverData& constraintSolverData); + virtual void initBeforeSolve(const ConstraintSolverData& constraintSolverData) override; /// Warm start the constraint (apply the previous impulse at the beginning of the step) - virtual void warmstart(const ConstraintSolverData& constraintSolverData); + virtual void warmstart(const ConstraintSolverData& constraintSolverData) override; /// Solve the velocity constraint - virtual void solveVelocityConstraint(const ConstraintSolverData& constraintSolverData); + virtual void solveVelocityConstraint(const ConstraintSolverData& constraintSolverData) override; /// Solve the position constraint (for position error correction) - virtual void solvePositionConstraint(const ConstraintSolverData& constraintSolverData); + virtual void solvePositionConstraint(const ConstraintSolverData& constraintSolverData) override; public : @@ -290,7 +290,7 @@ class HingeJoint : public Joint { HingeJoint(const HingeJointInfo& jointInfo); /// Destructor - virtual ~HingeJoint(); + virtual ~HingeJoint() override; /// Deleted copy-constructor HingeJoint(const HingeJoint& constraint) = delete; diff --git a/src/constraint/SliderJoint.h b/src/constraint/SliderJoint.h index a4f359da..859cbe28 100644 --- a/src/constraint/SliderJoint.h +++ b/src/constraint/SliderJoint.h @@ -266,19 +266,19 @@ class SliderJoint : public Joint { void resetLimits(); /// Return the number of bytes used by the joint - virtual size_t getSizeInBytes() const; + virtual size_t getSizeInBytes() const override; /// Initialize before solving the constraint - virtual void initBeforeSolve(const ConstraintSolverData& constraintSolverData); + virtual void initBeforeSolve(const ConstraintSolverData& constraintSolverData) override; /// Warm start the constraint (apply the previous impulse at the beginning of the step) - virtual void warmstart(const ConstraintSolverData& constraintSolverData); + virtual void warmstart(const ConstraintSolverData& constraintSolverData) override; /// Solve the velocity constraint - virtual void solveVelocityConstraint(const ConstraintSolverData& constraintSolverData); + virtual void solveVelocityConstraint(const ConstraintSolverData& constraintSolverData) override; /// Solve the position constraint (for position error correction) - virtual void solvePositionConstraint(const ConstraintSolverData& constraintSolverData); + virtual void solvePositionConstraint(const ConstraintSolverData& constraintSolverData) override; public : @@ -288,7 +288,7 @@ class SliderJoint : public Joint { SliderJoint(const SliderJointInfo& jointInfo); /// Destructor - virtual ~SliderJoint(); + virtual ~SliderJoint() override; /// Deleted copy-constructor SliderJoint(const SliderJoint& constraint) = delete; diff --git a/src/engine/DynamicsWorld.h b/src/engine/DynamicsWorld.h index a9bfc9d8..7dc715c9 100644 --- a/src/engine/DynamicsWorld.h +++ b/src/engine/DynamicsWorld.h @@ -178,7 +178,7 @@ class DynamicsWorld : public CollisionWorld { DynamicsWorld(const Vector3& mGravity); /// Destructor - virtual ~DynamicsWorld(); + virtual ~DynamicsWorld() override; /// Deleted copy-constructor DynamicsWorld(const DynamicsWorld& world) = delete; @@ -277,25 +277,25 @@ class DynamicsWorld : public CollisionWorld { /// Test and report collisions between a given shape and all the others /// shapes of the world virtual void testCollision(const ProxyShape* shape, - CollisionCallback* callback); + CollisionCallback* callback) override; /// Test and report collisions between two given shapes virtual void testCollision(const ProxyShape* shape1, const ProxyShape* shape2, - CollisionCallback* callback); + CollisionCallback* callback) override; /// Test and report collisions between a body and all /// the others bodies of the world virtual void testCollision(const CollisionBody* body, - CollisionCallback* callback); + CollisionCallback* callback) override; /// Test and report collisions between two bodies virtual void testCollision(const CollisionBody* body1, const CollisionBody* body2, - CollisionCallback* callback); + CollisionCallback* callback) override; /// Test and report collisions between all shapes of the world - virtual void testCollision(CollisionCallback* callback); + virtual void testCollision(CollisionCallback* callback) override; /// Return the list of all contacts of the world std::vector getContactsList() const; diff --git a/src/mathematics/Matrix3x3.h b/src/mathematics/Matrix3x3.h index d06957cf..50d9dbd0 100644 --- a/src/mathematics/Matrix3x3.h +++ b/src/mathematics/Matrix3x3.h @@ -63,7 +63,7 @@ class Matrix3x3 { decimal c1, decimal c2, decimal c3); /// Destructor - virtual ~Matrix3x3(); + ~Matrix3x3(); /// Copy-constructor Matrix3x3(const Matrix3x3& matrix); diff --git a/test/tests/collision/TestCollisionWorld.h b/test/tests/collision/TestCollisionWorld.h index a1efcb9a..d778bcd5 100644 --- a/test/tests/collision/TestCollisionWorld.h +++ b/test/tests/collision/TestCollisionWorld.h @@ -70,7 +70,7 @@ class WorldCollisionCallback : public CollisionCallback } // This method will be called for contact - virtual void notifyContact(const ContactPointInfo& contactPointInfo) { + virtual void notifyContact(const ContactPointInfo& contactPointInfo) override { if (isContactBetweenBodies(boxBody, sphere1Body, contactPointInfo)) { boxCollideWithSphere1 = true; diff --git a/test/tests/collision/TestDynamicAABBTree.h b/test/tests/collision/TestDynamicAABBTree.h index dfc84b82..cb407738 100644 --- a/test/tests/collision/TestDynamicAABBTree.h +++ b/test/tests/collision/TestDynamicAABBTree.h @@ -42,7 +42,7 @@ class OverlapCallback : public DynamicAABBTreeOverlapCallback { // Called when a overlapping node has been found during the call to // DynamicAABBTree:reportAllShapesOverlappingWithAABB() - virtual void notifyOverlappingNode(int nodeId) { + virtual void notifyOverlappingNode(int nodeId) override { mOverlapNodes.push_back(nodeId); } @@ -62,7 +62,7 @@ class DynamicTreeRaycastCallback : public DynamicAABBTreeRaycastCallback { std::vector mHitNodes; // Called when the AABB of a leaf node is hit by a ray - virtual decimal raycastBroadPhaseShape(int32 nodeId, const Ray& ray) { + virtual decimal raycastBroadPhaseShape(int32 nodeId, const Ray& ray) override { mHitNodes.push_back(nodeId); return 1.0; } diff --git a/test/tests/collision/TestRaycast.h b/test/tests/collision/TestRaycast.h index 09e3ebd8..7295a8d9 100644 --- a/test/tests/collision/TestRaycast.h +++ b/test/tests/collision/TestRaycast.h @@ -63,7 +63,7 @@ class WorldRaycastCallback : public RaycastCallback { shapeToTest = nullptr; } - virtual decimal notifyRaycastHit(const RaycastInfo& info) { + virtual decimal notifyRaycastHit(const RaycastInfo& info) override { if (shapeToTest->getBody()->getID() == info.body->getID()) { raycastInfo.body = info.body; diff --git a/testbed/common/Box.h b/testbed/common/Box.h index 44682c1c..56f8daf5 100644 --- a/testbed/common/Box.h +++ b/testbed/common/Box.h @@ -92,7 +92,7 @@ class Box : public openglframework::Object3D, public PhysicsObject { void resetTransform(const rp3d::Transform& transform); /// Update the transform matrix of the object - virtual void updateTransform(float interpolationFactor); + virtual void updateTransform(float interpolationFactor) override; /// Set the scaling of the object void setScaling(const openglframework::Vector3& scaling); diff --git a/testbed/common/Capsule.h b/testbed/common/Capsule.h index eaae3482..ee380914 100644 --- a/testbed/common/Capsule.h +++ b/testbed/common/Capsule.h @@ -101,7 +101,7 @@ class Capsule : public openglframework::Mesh, public PhysicsObject { void resetTransform(const rp3d::Transform& transform); /// Update the transform matrix of the object - virtual void updateTransform(float interpolationFactor); + virtual void updateTransform(float interpolationFactor) override; /// Set the scaling of the object void setScaling(const openglframework::Vector3& scaling); diff --git a/testbed/common/ConcaveMesh.h b/testbed/common/ConcaveMesh.h index 354a1a3b..087c030c 100644 --- a/testbed/common/ConcaveMesh.h +++ b/testbed/common/ConcaveMesh.h @@ -94,7 +94,7 @@ class ConcaveMesh : public openglframework::Mesh, public PhysicsObject { void resetTransform(const rp3d::Transform& transform); /// Update the transform matrix of the object - virtual void updateTransform(float interpolationFactor); + virtual void updateTransform(float interpolationFactor) override; /// Set the scaling of the object void setScaling(const openglframework::Vector3& scaling); diff --git a/testbed/common/Cone.h b/testbed/common/Cone.h index 4ce19c8d..e886c66b 100644 --- a/testbed/common/Cone.h +++ b/testbed/common/Cone.h @@ -100,7 +100,7 @@ class Cone : public openglframework::Mesh, public PhysicsObject { void resetTransform(const rp3d::Transform& transform); /// Update the transform matrix of the object - virtual void updateTransform(float interpolationFactor); + virtual void updateTransform(float interpolationFactor) override; /// Set the scaling of the object void setScaling(const openglframework::Vector3& scaling); diff --git a/testbed/common/ConvexMesh.h b/testbed/common/ConvexMesh.h index 50b4fb4a..842d187f 100644 --- a/testbed/common/ConvexMesh.h +++ b/testbed/common/ConvexMesh.h @@ -93,7 +93,7 @@ class ConvexMesh : public openglframework::Mesh, public PhysicsObject { void resetTransform(const rp3d::Transform& transform); /// Update the transform matrix of the object - virtual void updateTransform(float interpolationFactor); + virtual void updateTransform(float interpolationFactor) override; /// Set the scaling of the object void setScaling(const openglframework::Vector3& scaling); diff --git a/testbed/common/Cylinder.h b/testbed/common/Cylinder.h index eeea6d5f..2e75084c 100644 --- a/testbed/common/Cylinder.h +++ b/testbed/common/Cylinder.h @@ -100,7 +100,7 @@ class Cylinder : public openglframework::Mesh, public PhysicsObject { void resetTransform(const rp3d::Transform& transform); /// Update the transform matrix of the object - virtual void updateTransform(float interpolationFactor); + virtual void updateTransform(float interpolationFactor) override; /// Set the scaling of the object void setScaling(const openglframework::Vector3& scaling); diff --git a/testbed/common/Dumbbell.h b/testbed/common/Dumbbell.h index 6b68c1aa..7982819d 100644 --- a/testbed/common/Dumbbell.h +++ b/testbed/common/Dumbbell.h @@ -101,7 +101,7 @@ class Dumbbell : public openglframework::Mesh, public PhysicsObject { void resetTransform(const rp3d::Transform& transform); /// Update the transform matrix of the object - virtual void updateTransform(float interpolationFactor); + virtual void updateTransform(float interpolationFactor) override; /// Set the scaling of the object void setScaling(const openglframework::Vector3& scaling); diff --git a/testbed/common/HeightField.h b/testbed/common/HeightField.h index 0b2665f9..bf1cb148 100644 --- a/testbed/common/HeightField.h +++ b/testbed/common/HeightField.h @@ -107,7 +107,7 @@ class HeightField : public openglframework::Mesh, public PhysicsObject { void resetTransform(const rp3d::Transform& transform); /// Update the transform matrix of the object - virtual void updateTransform(float interpolationFactor); + virtual void updateTransform(float interpolationFactor) override; /// Set the scaling of the object void setScaling(const openglframework::Vector3& scaling); diff --git a/testbed/common/Sphere.h b/testbed/common/Sphere.h index f51d4074..70270026 100644 --- a/testbed/common/Sphere.h +++ b/testbed/common/Sphere.h @@ -97,7 +97,7 @@ class Sphere : public openglframework::Mesh, public PhysicsObject { void resetTransform(const rp3d::Transform& transform); /// Update the transform matrix of the object - virtual void updateTransform(float interpolationFactor); + virtual void updateTransform(float interpolationFactor) override; /// Set the scaling of the object void setScaling(const openglframework::Vector3& scaling); diff --git a/testbed/scenes/collisionshapes/CollisionShapesScene.h b/testbed/scenes/collisionshapes/CollisionShapesScene.h index 9a61f93e..93d14051 100644 --- a/testbed/scenes/collisionshapes/CollisionShapesScene.h +++ b/testbed/scenes/collisionshapes/CollisionShapesScene.h @@ -106,24 +106,24 @@ class CollisionShapesScene : public SceneDemo { CollisionShapesScene(const std::string& name); /// Destructor - virtual ~CollisionShapesScene(); + virtual ~CollisionShapesScene() override; /// Update the physics world (take a simulation step) /// Can be called several times per frame - virtual void updatePhysics(); + virtual void updatePhysics() override; /// Take a step for the simulation - virtual void update(); + virtual void update() override; /// Render the scene in a single pass virtual void renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix); + const openglframework::Matrix4& worldToCameraMatrix) override; /// Reset the scene - virtual void reset(); + virtual void reset() override; /// Return all the contact points of the scene - virtual std::vector getContactPoints() const; + virtual std::vector getContactPoints() const override; }; // Return all the contact points of the scene diff --git a/testbed/scenes/concavemesh/ConcaveMeshScene.h b/testbed/scenes/concavemesh/ConcaveMeshScene.h index 9871526d..5943fe6c 100644 --- a/testbed/scenes/concavemesh/ConcaveMeshScene.h +++ b/testbed/scenes/concavemesh/ConcaveMeshScene.h @@ -66,24 +66,24 @@ class ConcaveMeshScene : public SceneDemo { ConcaveMeshScene(const std::string& name); /// Destructor - virtual ~ConcaveMeshScene(); + virtual ~ConcaveMeshScene() override; /// Update the physics world (take a simulation step) /// Can be called several times per frame - virtual void updatePhysics(); + virtual void updatePhysics() override; /// Update the scene (take a simulation step) - virtual void update(); + virtual void update() override; /// Render the scene in a single pass virtual void renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix); + const openglframework::Matrix4& worldToCameraMatrix) override; /// Reset the scene - virtual void reset(); + virtual void reset() override; /// Return all the contact points of the scene - virtual std::vector getContactPoints() const; + virtual std::vector getContactPoints() const override; }; // Return all the contact points of the scene diff --git a/testbed/scenes/cubes/CubesScene.h b/testbed/scenes/cubes/CubesScene.h index fcc6fb25..a07c74d2 100644 --- a/testbed/scenes/cubes/CubesScene.h +++ b/testbed/scenes/cubes/CubesScene.h @@ -66,24 +66,24 @@ class CubesScene : public SceneDemo { CubesScene(const std::string& name); /// Destructor - virtual ~CubesScene(); + virtual ~CubesScene() override; /// Update the physics world (take a simulation step) /// Can be called several times per frame - virtual void updatePhysics(); + virtual void updatePhysics() override; /// Update the scene (take a simulation step) - virtual void update(); + virtual void update() override; /// Render the scene in a single pass virtual void renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix); + const openglframework::Matrix4& worldToCameraMatrix) override; /// Reset the scene - virtual void reset(); + virtual void reset() override; /// Return all the contact points of the scene - virtual std::vector getContactPoints() const; + virtual std::vector getContactPoints() const override; }; // Return all the contact points of the scene diff --git a/testbed/scenes/heightfield/HeightFieldScene.h b/testbed/scenes/heightfield/HeightFieldScene.h index 36749ef6..7eb9527d 100644 --- a/testbed/scenes/heightfield/HeightFieldScene.h +++ b/testbed/scenes/heightfield/HeightFieldScene.h @@ -63,24 +63,24 @@ class HeightFieldScene : public SceneDemo { HeightFieldScene(const std::string& name); /// Destructor - virtual ~HeightFieldScene(); + virtual ~HeightFieldScene() override; /// Update the physics world (take a simulation step) /// Can be called several times per frame - virtual void updatePhysics(); + virtual void updatePhysics() override; /// Update the scene (take a simulation step) - virtual void update(); + virtual void update() override; /// Render the scene in a single pass virtual void renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix); + const openglframework::Matrix4& worldToCameraMatrix) override ; /// Reset the scene - virtual void reset(); + virtual void reset() override ; /// Return all the contact points of the scene - virtual std::vector getContactPoints() const; + virtual std::vector getContactPoints() const override ; }; // Return all the contact points of the scene diff --git a/testbed/scenes/joints/JointsScene.h b/testbed/scenes/joints/JointsScene.h index 4a573957..a9474393 100644 --- a/testbed/scenes/joints/JointsScene.h +++ b/testbed/scenes/joints/JointsScene.h @@ -120,24 +120,24 @@ class JointsScene : public SceneDemo { JointsScene(const std::string& name); /// Destructor - virtual ~JointsScene(); + virtual ~JointsScene() override ; /// Update the physics world (take a simulation step) /// Can be called several times per frame - virtual void updatePhysics(); + virtual void updatePhysics() override; /// Take a step for the simulation - virtual void update(); + virtual void update() override; /// Render the scene in a single pass virtual void renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix); + const openglframework::Matrix4& worldToCameraMatrix) override; /// Reset the scene - virtual void reset(); + virtual void reset() override; /// Return all the contact points of the scene - virtual std::vector getContactPoints() const; + virtual std::vector getContactPoints() const override; }; // Return all the contact points of the scene diff --git a/testbed/scenes/raycast/RaycastScene.h b/testbed/scenes/raycast/RaycastScene.h index 583d2d36..56ebb565 100644 --- a/testbed/scenes/raycast/RaycastScene.h +++ b/testbed/scenes/raycast/RaycastScene.h @@ -83,7 +83,7 @@ class RaycastManager : public rp3d::RaycastCallback { } - virtual rp3d::decimal notifyRaycastHit(const rp3d::RaycastInfo& raycastInfo) { + virtual rp3d::decimal notifyRaycastHit(const rp3d::RaycastInfo& raycastInfo) override { rp3d::Vector3 hitPos = raycastInfo.worldPoint; openglframework::Vector3 position(hitPos.x, hitPos.y, hitPos.z); mHitPoints.push_back(ContactPoint(position)); @@ -176,21 +176,21 @@ class RaycastScene : public SceneDemo { RaycastScene(const std::string& name); /// Destructor - virtual ~RaycastScene(); + virtual ~RaycastScene() override; /// Update the physics world (take a simulation step) /// Can be called several times per frame - virtual void updatePhysics(); + virtual void updatePhysics() override; /// Take a step for the simulation - virtual void update(); + virtual void update() override; /// Render the scene in a single pass virtual void renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix); + const openglframework::Matrix4& worldToCameraMatrix) override; /// Reset the scene - virtual void reset(); + virtual void reset() override; /// Change the body to raycast void changeBody(); @@ -199,16 +199,16 @@ class RaycastScene : public SceneDemo { void showHideNormals(); /// Called when a keyboard event occurs - virtual bool keyboardEvent(int key, int scancode, int action, int mods); + virtual bool keyboardEvent(int key, int scancode, int action, int mods) override; /// Enabled/Disable the shadow mapping - void virtual setIsShadowMappingEnabled(bool isShadowMappingEnabled); + virtual void setIsShadowMappingEnabled(bool isShadowMappingEnabled) override; /// Display/Hide the contact points - void virtual setIsContactPointsDisplayed(bool display); + virtual void setIsContactPointsDisplayed(bool display) override; /// Return all the contact points of the scene - virtual std::vector getContactPoints() const; + virtual std::vector getContactPoints() const override; }; // Display or not the surface normals at hit points diff --git a/testbed/src/SceneDemo.h b/testbed/src/SceneDemo.h index e6e12e45..c64c8a9b 100644 --- a/testbed/src/SceneDemo.h +++ b/testbed/src/SceneDemo.h @@ -120,20 +120,20 @@ class SceneDemo : public Scene { SceneDemo(const std::string& name, float sceneRadius, bool isShadowMappingEnabled = true); /// Destructor - virtual ~SceneDemo(); + virtual ~SceneDemo() override; /// Update the scene - virtual void update(); + virtual void update() override; /// Render the scene (possibly in multiple passes for shadow mapping) - virtual void render(); + virtual void render() override; /// Render the scene in a single pass virtual void renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix)=0; + const openglframework::Matrix4& worldToCameraMatrix)=0 ; /// Enabled/Disable the shadow mapping - void virtual setIsShadowMappingEnabled(bool isShadowMappingEnabled); + virtual void setIsShadowMappingEnabled(bool isShadowMappingEnabled) override; /// Return all the contact points of the scene std::vector computeContactPointsOfWorld(const rp3d::DynamicsWorld* world) const; diff --git a/testbed/src/TestbedApplication.h b/testbed/src/TestbedApplication.h index d9554e42..dcff0598 100644 --- a/testbed/src/TestbedApplication.h +++ b/testbed/src/TestbedApplication.h @@ -173,25 +173,25 @@ class TestbedApplication : public Screen { TestbedApplication(bool isFullscreen); /// Destructor - virtual ~TestbedApplication(); + virtual ~TestbedApplication() override; /// Render the content of the application - virtual void drawContents(); + virtual void drawContents() override; /// Window resize event handler - virtual bool resizeEvent(const Vector2i& size); + virtual bool resizeEvent(const Vector2i& size) override; /// Default keyboard event handler - virtual bool keyboardEvent(int key, int scancode, int action, int modifiers); + virtual bool keyboardEvent(int key, int scancode, int action, int modifiers) override; /// Handle a mouse button event (default implementation: propagate to children) - virtual bool mouseButtonEvent(const Vector2i &p, int button, bool down, int modifiers); + virtual bool mouseButtonEvent(const Vector2i &p, int button, bool down, int modifiers) override; /// Handle a mouse motion event (default implementation: propagate to children) - virtual bool mouseMotionEvent(const Vector2i &p, const Vector2i &rel, int button, int modifiers); + virtual bool mouseMotionEvent(const Vector2i &p, const Vector2i &rel, int button, int modifiers) override; /// Handle a mouse scroll event (default implementation: propagate to children) - virtual bool scrollEvent(const Vector2i &p, const Vector2f &rel); + virtual bool scrollEvent(const Vector2i &p, const Vector2f &rel) override; /// Initialize the application void init(); diff --git a/testbed/src/Timer.h b/testbed/src/Timer.h index bc1d17e6..cddc7ca5 100644 --- a/testbed/src/Timer.h +++ b/testbed/src/Timer.h @@ -80,7 +80,7 @@ class Timer { Timer(); /// Destructor - virtual ~Timer(); + ~Timer(); /// Return the current time of the physics engine long double getPhysicsTime() const; From cfede8f1797d95b0e0fe4b43a2a45192915ee028 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 11 Jul 2016 08:59:39 +0200 Subject: [PATCH 015/248] Use constexpr for compile time constants --- src/collision/broadphase/DynamicAABBTree.cpp | 2 +- src/collision/narrowphase/EPA/EPAAlgorithm.h | 4 +-- src/collision/narrowphase/EPA/EdgeEPA.cpp | 1 - .../narrowphase/EPA/TrianglesStore.h | 2 +- src/collision/narrowphase/GJK/GJKAlgorithm.h | 6 ++-- src/collision/shapes/CylinderShape.cpp | 2 +- src/configuration.h | 36 +++++++++---------- src/constraint/BallAndSocketJoint.cpp | 2 +- src/constraint/FixedJoint.cpp | 2 +- src/constraint/HingeJoint.cpp | 2 +- src/constraint/SliderJoint.cpp | 2 +- src/engine/ContactSolver.cpp | 6 ++-- 12 files changed, 33 insertions(+), 34 deletions(-) diff --git a/src/collision/broadphase/DynamicAABBTree.cpp b/src/collision/broadphase/DynamicAABBTree.cpp index 7efd86ac..de494f69 100644 --- a/src/collision/broadphase/DynamicAABBTree.cpp +++ b/src/collision/broadphase/DynamicAABBTree.cpp @@ -32,7 +32,7 @@ using namespace reactphysics3d; // Initialization of static variables -const int TreeNode::NULL_TREE_NODE = -1; +constexpr int TreeNode::NULL_TREE_NODE = -1; // Constructor DynamicAABBTree::DynamicAABBTree(decimal extraAABBGap) : mExtraAABBGap(extraAABBGap) { diff --git a/src/collision/narrowphase/EPA/EPAAlgorithm.h b/src/collision/narrowphase/EPA/EPAAlgorithm.h index 3461f466..81e35bf5 100644 --- a/src/collision/narrowphase/EPA/EPAAlgorithm.h +++ b/src/collision/narrowphase/EPA/EPAAlgorithm.h @@ -43,10 +43,10 @@ namespace reactphysics3d { // ---------- Constants ---------- // /// Maximum number of support points of the polytope -const unsigned int MAX_SUPPORT_POINTS = 100; +constexpr unsigned int MAX_SUPPORT_POINTS = 100; /// Maximum number of facets of the polytope -const unsigned int MAX_FACETS = 200; +constexpr unsigned int MAX_FACETS = 200; // Class TriangleComparison diff --git a/src/collision/narrowphase/EPA/EdgeEPA.cpp b/src/collision/narrowphase/EPA/EdgeEPA.cpp index 098602da..842f445d 100644 --- a/src/collision/narrowphase/EPA/EdgeEPA.cpp +++ b/src/collision/narrowphase/EPA/EdgeEPA.cpp @@ -32,7 +32,6 @@ // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; - // Constructor EdgeEPA::EdgeEPA() { diff --git a/src/collision/narrowphase/EPA/TrianglesStore.h b/src/collision/narrowphase/EPA/TrianglesStore.h index 840fdcbc..5cd7edee 100644 --- a/src/collision/narrowphase/EPA/TrianglesStore.h +++ b/src/collision/narrowphase/EPA/TrianglesStore.h @@ -36,7 +36,7 @@ namespace reactphysics3d { // Constants -const unsigned int MAX_TRIANGLES = 200; // Maximum number of triangles +constexpr unsigned int MAX_TRIANGLES = 200; // Maximum number of triangles // Class TriangleStore /** diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.h b/src/collision/narrowphase/GJK/GJKAlgorithm.h index 209000ab..c89178bc 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.h +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.h @@ -37,9 +37,9 @@ namespace reactphysics3d { // Constants -const decimal REL_ERROR = decimal(1.0e-3); -const decimal REL_ERROR_SQUARE = REL_ERROR * REL_ERROR; -const int MAX_ITERATIONS_GJK_RAYCAST = 32; +constexpr decimal REL_ERROR = decimal(1.0e-3); +constexpr decimal REL_ERROR_SQUARE = REL_ERROR * REL_ERROR; +constexpr int MAX_ITERATIONS_GJK_RAYCAST = 32; // Class GJKAlgorithm /** diff --git a/src/collision/shapes/CylinderShape.cpp b/src/collision/shapes/CylinderShape.cpp index c65047e8..5485bb37 100644 --- a/src/collision/shapes/CylinderShape.cpp +++ b/src/collision/shapes/CylinderShape.cpp @@ -55,7 +55,7 @@ Vector3 CylinderShape::getLocalSupportPointWithoutMargin(const Vector3& directio Vector3 supportPoint(0.0, 0.0, 0.0); decimal uDotv = direction.y; Vector3 w(direction.x, 0.0, direction.z); - decimal lengthW = sqrt(direction.x * direction.x + direction.z * direction.z); + decimal lengthW = std::sqrt(direction.x * direction.x + direction.z * direction.z); if (lengthW > MACHINE_EPSILON) { if (uDotv < 0.0) supportPoint.y = -mHalfHeight; diff --git a/src/configuration.h b/src/configuration.h index 731071fd..4364c548 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -83,66 +83,66 @@ const decimal DECIMAL_LARGEST = std::numeric_limits::max(); const decimal MACHINE_EPSILON = std::numeric_limits::epsilon(); /// Pi constant -const decimal PI = decimal(3.14159265); +constexpr decimal PI = decimal(3.14159265); /// 2*Pi constant -const decimal PI_TIMES_2 = decimal(6.28318530); +constexpr decimal PI_TIMES_2 = decimal(6.28318530); /// Default friction coefficient for a rigid body -const decimal DEFAULT_FRICTION_COEFFICIENT = decimal(0.3); +constexpr decimal DEFAULT_FRICTION_COEFFICIENT = decimal(0.3); /// Default bounciness factor for a rigid body -const decimal DEFAULT_BOUNCINESS = decimal(0.5); +constexpr decimal DEFAULT_BOUNCINESS = decimal(0.5); /// Default rolling resistance -const decimal DEFAULT_ROLLING_RESISTANCE = decimal(0.0); +constexpr decimal DEFAULT_ROLLING_RESISTANCE = decimal(0.0); /// True if the spleeping technique is enabled -const bool SPLEEPING_ENABLED = true; +constexpr bool SPLEEPING_ENABLED = true; /// Object margin for collision detection in meters (for the GJK-EPA Algorithm) -const decimal OBJECT_MARGIN = decimal(0.04); +constexpr decimal OBJECT_MARGIN = decimal(0.04); /// Distance threshold for two contact points for a valid persistent contact (in meters) -const decimal PERSISTENT_CONTACT_DIST_THRESHOLD = decimal(0.03); +constexpr decimal PERSISTENT_CONTACT_DIST_THRESHOLD = decimal(0.03); /// Velocity threshold for contact velocity restitution -const decimal RESTITUTION_VELOCITY_THRESHOLD = decimal(1.0); +constexpr decimal RESTITUTION_VELOCITY_THRESHOLD = decimal(1.0); /// Number of iterations when solving the velocity constraints of the Sequential Impulse technique -const uint DEFAULT_VELOCITY_SOLVER_NB_ITERATIONS = 10; +constexpr uint DEFAULT_VELOCITY_SOLVER_NB_ITERATIONS = 10; /// Number of iterations when solving the position constraints of the Sequential Impulse technique -const uint DEFAULT_POSITION_SOLVER_NB_ITERATIONS = 5; +constexpr uint DEFAULT_POSITION_SOLVER_NB_ITERATIONS = 5; /// Time (in seconds) that a body must stay still to be considered sleeping -const float DEFAULT_TIME_BEFORE_SLEEP = 1.0f; +constexpr float DEFAULT_TIME_BEFORE_SLEEP = 1.0f; /// A body with a linear velocity smaller than the sleep linear velocity (in m/s) /// might enter sleeping mode. -const decimal DEFAULT_SLEEP_LINEAR_VELOCITY = decimal(0.02); +constexpr decimal DEFAULT_SLEEP_LINEAR_VELOCITY = decimal(0.02); /// A body with angular velocity smaller than the sleep angular velocity (in rad/s) /// might enter sleeping mode -const decimal DEFAULT_SLEEP_ANGULAR_VELOCITY = decimal(3.0 * (PI / 180.0)); +constexpr decimal DEFAULT_SLEEP_ANGULAR_VELOCITY = decimal(3.0 * (PI / 180.0)); /// In the broad-phase collision detection (dynamic AABB tree), the AABBs are /// inflated with a constant gap to allow the collision shape to move a little bit /// without triggering a large modification of the tree which can be costly -const decimal DYNAMIC_TREE_AABB_GAP = decimal(0.1); +constexpr decimal DYNAMIC_TREE_AABB_GAP = decimal(0.1); /// In the broad-phase collision detection (dynamic AABB tree), the AABBs are /// also inflated in direction of the linear motion of the body by mutliplying the /// followin constant with the linear velocity and the elapsed time between two frames. -const decimal DYNAMIC_TREE_AABB_LIN_GAP_MULTIPLIER = decimal(1.7); +constexpr decimal DYNAMIC_TREE_AABB_LIN_GAP_MULTIPLIER = decimal(1.7); /// Maximum number of contact manifolds in an overlapping pair that involves two /// convex collision shapes. -const int NB_MAX_CONTACT_MANIFOLDS_CONVEX_SHAPE = 1; +constexpr int NB_MAX_CONTACT_MANIFOLDS_CONVEX_SHAPE = 1; /// Maximum number of contact manifolds in an overlapping pair that involves at /// least one concave collision shape. -const int NB_MAX_CONTACT_MANIFOLDS_CONCAVE_SHAPE = 3; +constexpr int NB_MAX_CONTACT_MANIFOLDS_CONCAVE_SHAPE = 3; } diff --git a/src/constraint/BallAndSocketJoint.cpp b/src/constraint/BallAndSocketJoint.cpp index 8883d3e7..448499de 100644 --- a/src/constraint/BallAndSocketJoint.cpp +++ b/src/constraint/BallAndSocketJoint.cpp @@ -30,7 +30,7 @@ using namespace reactphysics3d; // Static variables definition -const decimal BallAndSocketJoint::BETA = decimal(0.2); +constexpr decimal BallAndSocketJoint::BETA = decimal(0.2); // Constructor BallAndSocketJoint::BallAndSocketJoint(const BallAndSocketJointInfo& jointInfo) diff --git a/src/constraint/FixedJoint.cpp b/src/constraint/FixedJoint.cpp index f17d0b9e..687043e8 100644 --- a/src/constraint/FixedJoint.cpp +++ b/src/constraint/FixedJoint.cpp @@ -30,7 +30,7 @@ using namespace reactphysics3d; // Static variables definition -const decimal FixedJoint::BETA = decimal(0.2); +constexpr decimal FixedJoint::BETA = decimal(0.2); // Constructor FixedJoint::FixedJoint(const FixedJointInfo& jointInfo) diff --git a/src/constraint/HingeJoint.cpp b/src/constraint/HingeJoint.cpp index 01563de4..021ee495 100644 --- a/src/constraint/HingeJoint.cpp +++ b/src/constraint/HingeJoint.cpp @@ -31,7 +31,7 @@ using namespace reactphysics3d; // Static variables definition -const decimal HingeJoint::BETA = decimal(0.2); +constexpr decimal HingeJoint::BETA = decimal(0.2); // Constructor HingeJoint::HingeJoint(const HingeJointInfo& jointInfo) diff --git a/src/constraint/SliderJoint.cpp b/src/constraint/SliderJoint.cpp index a1904174..365a9ad4 100644 --- a/src/constraint/SliderJoint.cpp +++ b/src/constraint/SliderJoint.cpp @@ -29,7 +29,7 @@ using namespace reactphysics3d; // Static variables definition -const decimal SliderJoint::BETA = decimal(0.2); +constexpr decimal SliderJoint::BETA = decimal(0.2); // Constructor SliderJoint::SliderJoint(const SliderJointInfo& jointInfo) diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index c3a0d0ef..faf58825 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -34,9 +34,9 @@ using namespace reactphysics3d; using namespace std; // Constants initialization -const decimal ContactSolver::BETA = decimal(0.2); -const decimal ContactSolver::BETA_SPLIT_IMPULSE = decimal(0.2); -const decimal ContactSolver::SLOP= decimal(0.01); +constexpr decimal ContactSolver::BETA = decimal(0.2); +constexpr decimal ContactSolver::BETA_SPLIT_IMPULSE = decimal(0.2); +constexpr decimal ContactSolver::SLOP= decimal(0.01); // Constructor ContactSolver::ContactSolver(const std::map& mapBodyToVelocityIndex) From 2932403ff4e2302a6c2446409409bbcce6fcdc75 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 19 Jul 2016 06:52:18 +0200 Subject: [PATCH 016/248] Use default keyword for default constructors/destructors --- src/body/Body.cpp | 5 ----- src/body/Body.h | 2 +- src/collision/CollisionDetection.cpp | 5 ----- src/collision/CollisionDetection.h | 2 +- src/collision/RaycastInfo.h | 4 +--- src/collision/TriangleMesh.cpp | 10 ---------- src/collision/TriangleMesh.h | 4 ++-- src/collision/TriangleVertexArray.cpp | 5 ----- src/collision/TriangleVertexArray.h | 2 +- src/collision/broadphase/BroadPhaseAlgorithm.h | 2 +- src/collision/broadphase/DynamicAABBTree.h | 4 ++-- src/collision/narrowphase/CollisionDispatch.h | 4 ++-- .../narrowphase/ConcaveVsConvexAlgorithm.cpp | 10 ---------- .../narrowphase/ConcaveVsConvexAlgorithm.h | 18 +++++++++--------- .../narrowphase/DefaultCollisionDispatch.cpp | 10 ---------- .../narrowphase/DefaultCollisionDispatch.h | 4 ++-- src/collision/narrowphase/EPA/EPAAlgorithm.cpp | 10 ---------- src/collision/narrowphase/EPA/EPAAlgorithm.h | 4 ++-- src/collision/narrowphase/EPA/EdgeEPA.cpp | 10 ---------- src/collision/narrowphase/EPA/EdgeEPA.h | 4 ++-- src/collision/narrowphase/EPA/TriangleEPA.cpp | 10 ---------- src/collision/narrowphase/EPA/TriangleEPA.h | 4 ++-- .../narrowphase/EPA/TrianglesStore.cpp | 5 ----- src/collision/narrowphase/EPA/TrianglesStore.h | 2 +- src/collision/narrowphase/GJK/GJKAlgorithm.cpp | 5 ----- src/collision/narrowphase/GJK/GJKAlgorithm.h | 2 +- .../narrowphase/NarrowPhaseAlgorithm.cpp | 5 ----- .../narrowphase/NarrowPhaseAlgorithm.h | 4 ++-- .../narrowphase/SphereVsSphereAlgorithm.cpp | 12 +----------- .../narrowphase/SphereVsSphereAlgorithm.h | 4 ++-- src/collision/shapes/AABB.cpp | 10 ---------- src/collision/shapes/AABB.h | 4 ++-- src/collision/shapes/BoxShape.cpp | 5 ----- src/collision/shapes/BoxShape.h | 2 +- src/collision/shapes/CapsuleShape.cpp | 5 ----- src/collision/shapes/CapsuleShape.h | 2 +- src/collision/shapes/CollisionShape.cpp | 5 ----- src/collision/shapes/CollisionShape.h | 2 +- src/collision/shapes/ConcaveMeshShape.cpp | 5 ----- src/collision/shapes/ConcaveMeshShape.h | 2 +- src/collision/shapes/ConcaveShape.cpp | 5 ----- src/collision/shapes/ConcaveShape.h | 4 ++-- src/collision/shapes/ConeShape.cpp | 5 ----- src/collision/shapes/ConeShape.h | 2 +- src/collision/shapes/ConvexMeshShape.cpp | 5 ----- src/collision/shapes/ConvexMeshShape.h | 2 +- src/collision/shapes/ConvexShape.cpp | 5 ----- src/collision/shapes/ConvexShape.h | 5 +---- src/collision/shapes/CylinderShape.cpp | 5 ----- src/collision/shapes/CylinderShape.h | 2 +- src/collision/shapes/HeightFieldShape.cpp | 5 ----- src/collision/shapes/HeightFieldShape.h | 2 +- src/collision/shapes/SphereShape.cpp | 5 ----- src/collision/shapes/SphereShape.h | 5 +---- src/collision/shapes/TriangleShape.cpp | 5 ----- src/collision/shapes/TriangleShape.h | 2 +- src/constraint/BallAndSocketJoint.cpp | 5 ----- src/constraint/BallAndSocketJoint.h | 2 +- src/constraint/ContactPoint.cpp | 5 ----- src/constraint/ContactPoint.h | 2 +- src/constraint/FixedJoint.cpp | 5 ----- src/constraint/FixedJoint.h | 2 +- src/constraint/HingeJoint.cpp | 5 ----- src/constraint/HingeJoint.h | 2 +- src/constraint/Joint.cpp | 5 ----- src/constraint/Joint.h | 4 ++-- src/constraint/SliderJoint.cpp | 5 ----- src/constraint/SliderJoint.h | 2 +- src/engine/ConstraintSolver.cpp | 5 ----- src/engine/ConstraintSolver.h | 2 +- src/engine/ContactSolver.cpp | 5 ----- src/engine/ContactSolver.h | 2 +- src/engine/EventListener.h | 4 ++-- src/engine/Material.cpp | 5 ----- src/engine/Material.h | 2 +- src/engine/OverlappingPair.cpp | 7 +------ src/engine/OverlappingPair.h | 2 +- src/engine/Timer.cpp | 5 ----- src/engine/Timer.h | 2 +- src/mathematics/Matrix2x2.cpp | 5 ----- src/mathematics/Matrix2x2.h | 2 +- src/mathematics/Matrix3x3.cpp | 5 ----- src/mathematics/Matrix3x3.h | 2 +- src/mathematics/Quaternion.cpp | 5 ----- src/mathematics/Quaternion.h | 2 +- src/mathematics/Ray.h | 4 +--- src/mathematics/Transform.cpp | 5 ----- src/mathematics/Transform.h | 2 +- src/mathematics/Vector2.cpp | 5 ----- src/mathematics/Vector2.h | 2 +- src/mathematics/Vector3.cpp | 5 ----- src/mathematics/Vector3.h | 2 +- 92 files changed, 72 insertions(+), 337 deletions(-) diff --git a/src/body/Body.cpp b/src/body/Body.cpp index b143321e..0f02a55b 100644 --- a/src/body/Body.cpp +++ b/src/body/Body.cpp @@ -39,8 +39,3 @@ Body::Body(bodyindex id) mIsSleeping(false), mSleepTime(0), mUserData(nullptr) { } - -// Destructor -Body::~Body() { - -} diff --git a/src/body/Body.h b/src/body/Body.h index c5f011fb..b1b18325 100644 --- a/src/body/Body.h +++ b/src/body/Body.h @@ -89,7 +89,7 @@ class Body { Body& operator=(const Body& body) = delete; /// Destructor - virtual ~Body(); + virtual ~Body() = default; /// Return the ID of the body bodyindex getID() const; diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index ed721343..7d9f6fb2 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -53,11 +53,6 @@ CollisionDetection::CollisionDetection(CollisionWorld* world, MemoryAllocator& m fillInCollisionMatrix(); } -// Destructor -CollisionDetection::~CollisionDetection() { - -} - // Compute the collision detection void CollisionDetection::computeCollisionDetection() { diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index 04d44f34..2a95b2f5 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -143,7 +143,7 @@ class CollisionDetection : public NarrowPhaseCallback { CollisionDetection(CollisionWorld* world, MemoryAllocator& memoryAllocator); /// Destructor - ~CollisionDetection(); + ~CollisionDetection() = default; /// Deleted copy-constructor CollisionDetection(const CollisionDetection& collisionDetection) = delete; diff --git a/src/collision/RaycastInfo.h b/src/collision/RaycastInfo.h index d693f02c..06510e04 100644 --- a/src/collision/RaycastInfo.h +++ b/src/collision/RaycastInfo.h @@ -80,9 +80,7 @@ struct RaycastInfo { } /// Destructor - ~RaycastInfo() { - - } + ~RaycastInfo() = default; /// Deleted copy constructor RaycastInfo(const RaycastInfo& raycastInfo) = delete; diff --git a/src/collision/TriangleMesh.cpp b/src/collision/TriangleMesh.cpp index 5439b3f3..3fdc48c5 100644 --- a/src/collision/TriangleMesh.cpp +++ b/src/collision/TriangleMesh.cpp @@ -27,13 +27,3 @@ #include "TriangleMesh.h" using namespace reactphysics3d; - -// Constructor -TriangleMesh::TriangleMesh() { - -} - -// Destructor -TriangleMesh::~TriangleMesh() { - -} diff --git a/src/collision/TriangleMesh.h b/src/collision/TriangleMesh.h index 52dabbe7..936824e9 100644 --- a/src/collision/TriangleMesh.h +++ b/src/collision/TriangleMesh.h @@ -51,10 +51,10 @@ class TriangleMesh { public: /// Constructor - TriangleMesh(); + TriangleMesh() = default; /// Destructor - ~TriangleMesh(); + ~TriangleMesh() = default; /// Add a subpart of the mesh void addSubpart(TriangleVertexArray* triangleVertexArray); diff --git a/src/collision/TriangleVertexArray.cpp b/src/collision/TriangleVertexArray.cpp index f1808a3c..883b0ab7 100644 --- a/src/collision/TriangleVertexArray.cpp +++ b/src/collision/TriangleVertexArray.cpp @@ -54,8 +54,3 @@ TriangleVertexArray::TriangleVertexArray(uint nbVertices, void* verticesStart, i mVertexDataType = vertexDataType; mIndexDataType = indexDataType; } - -// Destructor -TriangleVertexArray::~TriangleVertexArray() { - -} diff --git a/src/collision/TriangleVertexArray.h b/src/collision/TriangleVertexArray.h index f4403092..8e434919 100644 --- a/src/collision/TriangleVertexArray.h +++ b/src/collision/TriangleVertexArray.h @@ -87,7 +87,7 @@ class TriangleVertexArray { VertexDataType vertexDataType, IndexDataType indexDataType); /// Destructor - ~TriangleVertexArray(); + ~TriangleVertexArray() = default; /// Return the vertex data type VertexDataType getVertexDataType() const; diff --git a/src/collision/broadphase/BroadPhaseAlgorithm.h b/src/collision/broadphase/BroadPhaseAlgorithm.h index c4ea2c51..45c8acfb 100644 --- a/src/collision/broadphase/BroadPhaseAlgorithm.h +++ b/src/collision/broadphase/BroadPhaseAlgorithm.h @@ -110,7 +110,7 @@ class BroadPhaseRaycastCallback : public DynamicAABBTreeRaycastCallback { } // Destructor - virtual ~BroadPhaseRaycastCallback() override {} + virtual ~BroadPhaseRaycastCallback() override = default; // Called for a broad-phase shape that has to be tested for raycast virtual decimal raycastBroadPhaseShape(int32 nodeId, const Ray& ray) override; diff --git a/src/collision/broadphase/DynamicAABBTree.h b/src/collision/broadphase/DynamicAABBTree.h index 67999d0a..8025e4f9 100644 --- a/src/collision/broadphase/DynamicAABBTree.h +++ b/src/collision/broadphase/DynamicAABBTree.h @@ -103,7 +103,7 @@ class DynamicAABBTreeOverlapCallback { virtual void notifyOverlappingNode(int nodeId)=0; // Destructor - virtual ~DynamicAABBTreeOverlapCallback() {} + virtual ~DynamicAABBTreeOverlapCallback() = default; }; // Class DynamicAABBTreeRaycastCallback @@ -118,7 +118,7 @@ class DynamicAABBTreeRaycastCallback { // Called when the AABB of a leaf node is hit by a ray virtual decimal raycastBroadPhaseShape(int32 nodeId, const Ray& ray)=0; - virtual ~DynamicAABBTreeRaycastCallback() {} + virtual ~DynamicAABBTreeRaycastCallback() = default; }; diff --git a/src/collision/narrowphase/CollisionDispatch.h b/src/collision/narrowphase/CollisionDispatch.h index 29b6426b..8fa24f87 100644 --- a/src/collision/narrowphase/CollisionDispatch.h +++ b/src/collision/narrowphase/CollisionDispatch.h @@ -44,10 +44,10 @@ class CollisionDispatch { public: /// Constructor - CollisionDispatch() {} + CollisionDispatch() = default; /// Destructor - virtual ~CollisionDispatch() {} + virtual ~CollisionDispatch() = default; /// Initialize the collision dispatch configuration virtual void init(CollisionDetection* collisionDetection, diff --git a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp index ab07c629..1e3c86c6 100644 --- a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp +++ b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp @@ -33,16 +33,6 @@ using namespace reactphysics3d; -// Constructor -ConcaveVsConvexAlgorithm::ConcaveVsConvexAlgorithm() { - -} - -// Destructor -ConcaveVsConvexAlgorithm::~ConcaveVsConvexAlgorithm() { - -} - // Return true and compute a contact info if the two bounding volumes collide void ConcaveVsConvexAlgorithm::testCollision(const CollisionShapeInfo& shape1Info, const CollisionShapeInfo& shape2Info, diff --git a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h index c8ba0fce..bcd4ef8f 100644 --- a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h +++ b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h @@ -73,7 +73,7 @@ class ConvexVsTriangleCallback : public TriangleCallback { public: /// Destructor - virtual ~ConvexVsTriangleCallback() override {} + virtual ~ConvexVsTriangleCallback() override = default; /// Set the collision detection pointer void setCollisionDetection(CollisionDetection* collisionDetection) { @@ -191,12 +191,6 @@ class ConcaveVsConvexAlgorithm : public NarrowPhaseAlgorithm { // -------------------- Methods -------------------- // - /// Private copy-constructor - ConcaveVsConvexAlgorithm(const ConcaveVsConvexAlgorithm& algorithm); - - /// Private assignment operator - ConcaveVsConvexAlgorithm& operator=(const ConcaveVsConvexAlgorithm& algorithm); - /// Process the concave triangle mesh collision using the smooth mesh collision algorithm void processSmoothMeshCollision(OverlappingPair* overlappingPair, std::vector contactPoints, @@ -215,10 +209,16 @@ class ConcaveVsConvexAlgorithm : public NarrowPhaseAlgorithm { // -------------------- Methods -------------------- // /// Constructor - ConcaveVsConvexAlgorithm(); + ConcaveVsConvexAlgorithm() = default; /// Destructor - virtual ~ConcaveVsConvexAlgorithm() override; + virtual ~ConcaveVsConvexAlgorithm() override = default; + + /// Private copy-constructor + ConcaveVsConvexAlgorithm(const ConcaveVsConvexAlgorithm& algorithm) = delete; + + /// Private assignment operator + ConcaveVsConvexAlgorithm& operator=(const ConcaveVsConvexAlgorithm& algorithm) = delete; /// Compute a contact info if the two bounding volume collide virtual void testCollision(const CollisionShapeInfo& shape1Info, diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.cpp b/src/collision/narrowphase/DefaultCollisionDispatch.cpp index bc48c001..109b5de3 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.cpp +++ b/src/collision/narrowphase/DefaultCollisionDispatch.cpp @@ -29,16 +29,6 @@ using namespace reactphysics3d; -// Constructor -DefaultCollisionDispatch::DefaultCollisionDispatch() { - -} - -// Destructor -DefaultCollisionDispatch::~DefaultCollisionDispatch() { - -} - /// Initialize the collision dispatch configuration void DefaultCollisionDispatch::init(CollisionDetection* collisionDetection, MemoryAllocator* memoryAllocator) { diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.h b/src/collision/narrowphase/DefaultCollisionDispatch.h index 28f114f9..9bf15b11 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.h +++ b/src/collision/narrowphase/DefaultCollisionDispatch.h @@ -56,10 +56,10 @@ class DefaultCollisionDispatch : public CollisionDispatch { public: /// Constructor - DefaultCollisionDispatch(); + DefaultCollisionDispatch() = default; /// Destructor - virtual ~DefaultCollisionDispatch() override; + virtual ~DefaultCollisionDispatch() override = default; /// Initialize the collision dispatch configuration virtual void init(CollisionDetection* collisionDetection, diff --git a/src/collision/narrowphase/EPA/EPAAlgorithm.cpp b/src/collision/narrowphase/EPA/EPAAlgorithm.cpp index 03647182..68fdce35 100644 --- a/src/collision/narrowphase/EPA/EPAAlgorithm.cpp +++ b/src/collision/narrowphase/EPA/EPAAlgorithm.cpp @@ -32,16 +32,6 @@ // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; -// Constructor -EPAAlgorithm::EPAAlgorithm() { - -} - -// Destructor -EPAAlgorithm::~EPAAlgorithm() { - -} - // Decide if the origin is in the tetrahedron. /// Return 0 if the origin is in the tetrahedron and return the number (1,2,3 or 4) of /// the vertex that is wrong if the origin is not in the tetrahedron diff --git a/src/collision/narrowphase/EPA/EPAAlgorithm.h b/src/collision/narrowphase/EPA/EPAAlgorithm.h index 81e35bf5..d9dca0e6 100644 --- a/src/collision/narrowphase/EPA/EPAAlgorithm.h +++ b/src/collision/narrowphase/EPA/EPAAlgorithm.h @@ -108,10 +108,10 @@ class EPAAlgorithm { // -------------------- Methods -------------------- // /// Constructor - EPAAlgorithm(); + EPAAlgorithm() = default; /// Destructor - ~EPAAlgorithm(); + ~EPAAlgorithm() = default; /// Deleted copy-constructor EPAAlgorithm(const EPAAlgorithm& algorithm) = delete; diff --git a/src/collision/narrowphase/EPA/EdgeEPA.cpp b/src/collision/narrowphase/EPA/EdgeEPA.cpp index 842f445d..dcbf61fd 100644 --- a/src/collision/narrowphase/EPA/EdgeEPA.cpp +++ b/src/collision/narrowphase/EPA/EdgeEPA.cpp @@ -32,11 +32,6 @@ // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; -// Constructor -EdgeEPA::EdgeEPA() { - -} - // Constructor EdgeEPA::EdgeEPA(TriangleEPA* ownerTriangle, int index) : mOwnerTriangle(ownerTriangle), mIndex(index) { @@ -49,11 +44,6 @@ EdgeEPA::EdgeEPA(const EdgeEPA& edge) { mIndex = edge.mIndex; } -// Destructor -EdgeEPA::~EdgeEPA() { - -} - // Return the index of the source vertex of the edge (vertex starting the edge) uint EdgeEPA::getSourceVertexIndex() const { return (*mOwnerTriangle)[mIndex]; diff --git a/src/collision/narrowphase/EPA/EdgeEPA.h b/src/collision/narrowphase/EPA/EdgeEPA.h index ca580919..ba3dcfee 100644 --- a/src/collision/narrowphase/EPA/EdgeEPA.h +++ b/src/collision/narrowphase/EPA/EdgeEPA.h @@ -59,7 +59,7 @@ class EdgeEPA { // -------------------- Methods -------------------- // /// Constructor - EdgeEPA(); + EdgeEPA() = default; /// Constructor EdgeEPA(TriangleEPA* ownerTriangle, int index); @@ -68,7 +68,7 @@ class EdgeEPA { EdgeEPA(const EdgeEPA& edge); /// Destructor - ~EdgeEPA(); + ~EdgeEPA() = default; /// Return the pointer to the owner triangle TriangleEPA* getOwnerTriangle() const; diff --git a/src/collision/narrowphase/EPA/TriangleEPA.cpp b/src/collision/narrowphase/EPA/TriangleEPA.cpp index c4a279a2..c322059f 100644 --- a/src/collision/narrowphase/EPA/TriangleEPA.cpp +++ b/src/collision/narrowphase/EPA/TriangleEPA.cpp @@ -32,11 +32,6 @@ // We use the ReactPhysics3D namespace using namespace reactphysics3d; -// Constructor -TriangleEPA::TriangleEPA() { - -} - // Constructor TriangleEPA::TriangleEPA(uint indexVertex1, uint indexVertex2, uint indexVertex3) : mIsObsolete(false) { @@ -45,11 +40,6 @@ TriangleEPA::TriangleEPA(uint indexVertex1, uint indexVertex2, uint indexVertex3 mIndicesVertices[2] = indexVertex3; } -// Destructor -TriangleEPA::~TriangleEPA() { - -} - // Compute the point v closest to the origin of this triangle bool TriangleEPA::computeClosestPoint(const Vector3* vertices) { const Vector3& p0 = vertices[mIndicesVertices[0]]; diff --git a/src/collision/narrowphase/EPA/TriangleEPA.h b/src/collision/narrowphase/EPA/TriangleEPA.h index 4cb40f38..865c69d4 100644 --- a/src/collision/narrowphase/EPA/TriangleEPA.h +++ b/src/collision/narrowphase/EPA/TriangleEPA.h @@ -79,13 +79,13 @@ class TriangleEPA { // -------------------- Methods -------------------- // /// Constructor - TriangleEPA(); + TriangleEPA() = default; /// Constructor TriangleEPA(uint v1, uint v2, uint v3); /// Destructor - ~TriangleEPA(); + ~TriangleEPA() = default; /// Deleted copy-constructor TriangleEPA(const TriangleEPA& triangle) = delete; diff --git a/src/collision/narrowphase/EPA/TrianglesStore.cpp b/src/collision/narrowphase/EPA/TrianglesStore.cpp index ebc214fb..93fb95a6 100644 --- a/src/collision/narrowphase/EPA/TrianglesStore.cpp +++ b/src/collision/narrowphase/EPA/TrianglesStore.cpp @@ -33,8 +33,3 @@ using namespace reactphysics3d; TrianglesStore::TrianglesStore() : mNbTriangles(0) { } - -// Destructor -TrianglesStore::~TrianglesStore() { - -} diff --git a/src/collision/narrowphase/EPA/TrianglesStore.h b/src/collision/narrowphase/EPA/TrianglesStore.h index 5cd7edee..d21ccd35 100644 --- a/src/collision/narrowphase/EPA/TrianglesStore.h +++ b/src/collision/narrowphase/EPA/TrianglesStore.h @@ -62,7 +62,7 @@ class TrianglesStore { TrianglesStore(); /// Destructor - ~TrianglesStore(); + ~TrianglesStore() = default; /// Deleted copy-constructor TrianglesStore(const TrianglesStore& triangleStore) = delete; diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp index 49db5968..55468066 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp @@ -42,11 +42,6 @@ GJKAlgorithm::GJKAlgorithm() : NarrowPhaseAlgorithm() { } -// Destructor -GJKAlgorithm::~GJKAlgorithm() { - -} - // Compute a contact info if the two collision shapes collide. /// This method implements the Hybrid Technique for computing the penetration depth by /// running the GJK algorithm on original objects (without margin). If the shapes intersect diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.h b/src/collision/narrowphase/GJK/GJKAlgorithm.h index c89178bc..ced8d9e7 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.h +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.h @@ -84,7 +84,7 @@ class GJKAlgorithm : public NarrowPhaseAlgorithm { GJKAlgorithm(); /// Destructor - ~GJKAlgorithm(); + ~GJKAlgorithm() = default; /// Deleted copy-constructor GJKAlgorithm(const GJKAlgorithm& algorithm) = delete; diff --git a/src/collision/narrowphase/NarrowPhaseAlgorithm.cpp b/src/collision/narrowphase/NarrowPhaseAlgorithm.cpp index 970905da..0fbbe5fe 100644 --- a/src/collision/narrowphase/NarrowPhaseAlgorithm.cpp +++ b/src/collision/narrowphase/NarrowPhaseAlgorithm.cpp @@ -35,11 +35,6 @@ NarrowPhaseAlgorithm::NarrowPhaseAlgorithm() } -// Destructor -NarrowPhaseAlgorithm::~NarrowPhaseAlgorithm() { - -} - // Initalize the algorithm void NarrowPhaseAlgorithm::init(CollisionDetection* collisionDetection, MemoryAllocator* memoryAllocator) { mCollisionDetection = collisionDetection; diff --git a/src/collision/narrowphase/NarrowPhaseAlgorithm.h b/src/collision/narrowphase/NarrowPhaseAlgorithm.h index b765dbf3..30b216f0 100644 --- a/src/collision/narrowphase/NarrowPhaseAlgorithm.h +++ b/src/collision/narrowphase/NarrowPhaseAlgorithm.h @@ -47,7 +47,7 @@ class NarrowPhaseCallback { public: - virtual ~NarrowPhaseCallback() {} + virtual ~NarrowPhaseCallback() = default; /// Called by a narrow-phase collision algorithm when a new contact has been found virtual void notifyContact(OverlappingPair* overlappingPair, @@ -84,7 +84,7 @@ class NarrowPhaseAlgorithm { NarrowPhaseAlgorithm(); /// Destructor - virtual ~NarrowPhaseAlgorithm(); + virtual ~NarrowPhaseAlgorithm() = default; /// Deleted copy-constructor NarrowPhaseAlgorithm(const NarrowPhaseAlgorithm& algorithm) = delete; diff --git a/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp b/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp index 89e2987e..9d2c4baa 100644 --- a/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp @@ -28,17 +28,7 @@ #include "collision/shapes/SphereShape.h" // We want to use the ReactPhysics3D namespace -using namespace reactphysics3d; - -// Constructor -SphereVsSphereAlgorithm::SphereVsSphereAlgorithm() : NarrowPhaseAlgorithm() { - -} - -// Destructor -SphereVsSphereAlgorithm::~SphereVsSphereAlgorithm() { - -} +using namespace reactphysics3d; void SphereVsSphereAlgorithm::testCollision(const CollisionShapeInfo& shape1Info, const CollisionShapeInfo& shape2Info, diff --git a/src/collision/narrowphase/SphereVsSphereAlgorithm.h b/src/collision/narrowphase/SphereVsSphereAlgorithm.h index 9875d814..525c55d5 100644 --- a/src/collision/narrowphase/SphereVsSphereAlgorithm.h +++ b/src/collision/narrowphase/SphereVsSphereAlgorithm.h @@ -49,10 +49,10 @@ class SphereVsSphereAlgorithm : public NarrowPhaseAlgorithm { // -------------------- Methods -------------------- // /// Constructor - SphereVsSphereAlgorithm(); + SphereVsSphereAlgorithm() = default; /// Destructor - virtual ~SphereVsSphereAlgorithm() override; + virtual ~SphereVsSphereAlgorithm() override = default; /// Deleted copy-constructor SphereVsSphereAlgorithm(const SphereVsSphereAlgorithm& algorithm) = delete; diff --git a/src/collision/shapes/AABB.cpp b/src/collision/shapes/AABB.cpp index 0e18eebd..6c43aeb6 100644 --- a/src/collision/shapes/AABB.cpp +++ b/src/collision/shapes/AABB.cpp @@ -31,11 +31,6 @@ using namespace reactphysics3d; using namespace std; -// Constructor -AABB::AABB() { - -} - // Constructor AABB::AABB(const Vector3& minCoordinates, const Vector3& maxCoordinates) :mMinCoordinates(minCoordinates), mMaxCoordinates(maxCoordinates) { @@ -48,11 +43,6 @@ AABB::AABB(const AABB& aabb) } -// Destructor -AABB::~AABB() { - -} - // Merge the AABB in parameter with the current one void AABB::mergeWithAABB(const AABB& aabb) { mMinCoordinates.x = std::min(mMinCoordinates.x, aabb.mMinCoordinates.x); diff --git a/src/collision/shapes/AABB.h b/src/collision/shapes/AABB.h index 364dfc83..8683db55 100644 --- a/src/collision/shapes/AABB.h +++ b/src/collision/shapes/AABB.h @@ -56,7 +56,7 @@ class AABB { // -------------------- Methods -------------------- // /// Constructor - AABB(); + AABB() = default; /// Constructor AABB(const Vector3& minCoordinates, const Vector3& maxCoordinates); @@ -65,7 +65,7 @@ class AABB { AABB(const AABB& aabb); /// Destructor - ~AABB(); + ~AABB() = default; /// Return the center point Vector3 getCenter() const; diff --git a/src/collision/shapes/BoxShape.cpp b/src/collision/shapes/BoxShape.cpp index 764918c7..ce3197e3 100644 --- a/src/collision/shapes/BoxShape.cpp +++ b/src/collision/shapes/BoxShape.cpp @@ -44,11 +44,6 @@ BoxShape::BoxShape(const Vector3& extent, decimal margin) assert(extent.z > decimal(0.0) && extent.z > margin); } -// Destructor -BoxShape::~BoxShape() { - -} - // Return the local inertia tensor of the collision shape /** * @param[out] tensor The 3x3 inertia tensor matrix of the shape in local-space diff --git a/src/collision/shapes/BoxShape.h b/src/collision/shapes/BoxShape.h index 972012a8..0ba0942a 100644 --- a/src/collision/shapes/BoxShape.h +++ b/src/collision/shapes/BoxShape.h @@ -82,7 +82,7 @@ class BoxShape : public ConvexShape { BoxShape(const Vector3& extent, decimal margin = OBJECT_MARGIN); /// Destructor - virtual ~BoxShape() override; + virtual ~BoxShape() override = default; /// Deleted copy-constructor BoxShape(const BoxShape& shape) = delete; diff --git a/src/collision/shapes/CapsuleShape.cpp b/src/collision/shapes/CapsuleShape.cpp index a8b231f5..f9f442ce 100644 --- a/src/collision/shapes/CapsuleShape.cpp +++ b/src/collision/shapes/CapsuleShape.cpp @@ -42,11 +42,6 @@ CapsuleShape::CapsuleShape(decimal radius, decimal height) assert(height > decimal(0.0)); } -// Destructor -CapsuleShape::~CapsuleShape() { - -} - // Return the local inertia tensor of the capsule /** * @param[out] tensor The 3x3 inertia tensor matrix of the shape in local-space diff --git a/src/collision/shapes/CapsuleShape.h b/src/collision/shapes/CapsuleShape.h index fae76ce0..19122111 100644 --- a/src/collision/shapes/CapsuleShape.h +++ b/src/collision/shapes/CapsuleShape.h @@ -81,7 +81,7 @@ class CapsuleShape : public ConvexShape { CapsuleShape(decimal radius, decimal height); /// Destructor - virtual ~CapsuleShape() override; + virtual ~CapsuleShape() override = default; /// Deleted copy-constructor CapsuleShape(const CapsuleShape& shape) = delete; diff --git a/src/collision/shapes/CollisionShape.cpp b/src/collision/shapes/CollisionShape.cpp index b71c9467..301c97d2 100644 --- a/src/collision/shapes/CollisionShape.cpp +++ b/src/collision/shapes/CollisionShape.cpp @@ -36,11 +36,6 @@ CollisionShape::CollisionShape(CollisionShapeType type) : mType(type), mScaling( } -// Destructor -CollisionShape::~CollisionShape() { - -} - // Compute the world-space AABB of the collision shape given a transform /** * @param[out] aabb The axis-aligned bounding box (AABB) of the collision shape diff --git a/src/collision/shapes/CollisionShape.h b/src/collision/shapes/CollisionShape.h index 2c50dac9..cd261717 100644 --- a/src/collision/shapes/CollisionShape.h +++ b/src/collision/shapes/CollisionShape.h @@ -84,7 +84,7 @@ class CollisionShape { CollisionShape(CollisionShapeType type); /// Destructor - virtual ~CollisionShape(); + virtual ~CollisionShape() = default; /// Deleted copy-constructor CollisionShape(const CollisionShape& shape) = delete; diff --git a/src/collision/shapes/ConcaveMeshShape.cpp b/src/collision/shapes/ConcaveMeshShape.cpp index dfec3ba2..a0bd1094 100644 --- a/src/collision/shapes/ConcaveMeshShape.cpp +++ b/src/collision/shapes/ConcaveMeshShape.cpp @@ -38,11 +38,6 @@ ConcaveMeshShape::ConcaveMeshShape(TriangleMesh* triangleMesh) initBVHTree(); } -// Destructor -ConcaveMeshShape::~ConcaveMeshShape() { - -} - // Insert all the triangles into the dynamic AABB tree void ConcaveMeshShape::initBVHTree() { diff --git a/src/collision/shapes/ConcaveMeshShape.h b/src/collision/shapes/ConcaveMeshShape.h index 2af6ed9f..83e5103a 100644 --- a/src/collision/shapes/ConcaveMeshShape.h +++ b/src/collision/shapes/ConcaveMeshShape.h @@ -140,7 +140,7 @@ class ConcaveMeshShape : public ConcaveShape { ConcaveMeshShape(TriangleMesh* triangleMesh); /// Destructor - virtual ~ConcaveMeshShape(); + virtual ~ConcaveMeshShape() = default; /// Deleted copy-constructor ConcaveMeshShape(const ConcaveMeshShape& shape) = delete; diff --git a/src/collision/shapes/ConcaveShape.cpp b/src/collision/shapes/ConcaveShape.cpp index 017a277a..3f691468 100644 --- a/src/collision/shapes/ConcaveShape.cpp +++ b/src/collision/shapes/ConcaveShape.cpp @@ -36,8 +36,3 @@ ConcaveShape::ConcaveShape(CollisionShapeType type) mTriangleMargin(0), mRaycastTestType(TriangleRaycastSide::FRONT) { } - -// Destructor -ConcaveShape::~ConcaveShape() { - -} diff --git a/src/collision/shapes/ConcaveShape.h b/src/collision/shapes/ConcaveShape.h index 14bebf4d..92d20b33 100644 --- a/src/collision/shapes/ConcaveShape.h +++ b/src/collision/shapes/ConcaveShape.h @@ -43,7 +43,7 @@ class TriangleCallback { public: /// Destructor - virtual ~TriangleCallback() {} + virtual ~TriangleCallback() = default; /// Report a triangle virtual void testTriangle(const Vector3* trianglePoints)=0; @@ -84,7 +84,7 @@ class ConcaveShape : public CollisionShape { ConcaveShape(CollisionShapeType type); /// Destructor - virtual ~ConcaveShape() override; + virtual ~ConcaveShape() override = default; /// Deleted copy-constructor ConcaveShape(const ConcaveShape& shape) = delete; diff --git a/src/collision/shapes/ConeShape.cpp b/src/collision/shapes/ConeShape.cpp index fc166895..4a1ece33 100644 --- a/src/collision/shapes/ConeShape.cpp +++ b/src/collision/shapes/ConeShape.cpp @@ -46,11 +46,6 @@ ConeShape::ConeShape(decimal radius, decimal height, decimal margin) mSinTheta = mRadius / (sqrt(mRadius * mRadius + height * height)); } -// Destructor -ConeShape::~ConeShape() { - -} - // Return a local support point in a given direction without the object margin Vector3 ConeShape::getLocalSupportPointWithoutMargin(const Vector3& direction, void** cachedCollisionData) const { diff --git a/src/collision/shapes/ConeShape.h b/src/collision/shapes/ConeShape.h index e0ff722a..33d7c861 100644 --- a/src/collision/shapes/ConeShape.h +++ b/src/collision/shapes/ConeShape.h @@ -87,7 +87,7 @@ class ConeShape : public ConvexShape { ConeShape(decimal mRadius, decimal height, decimal margin = OBJECT_MARGIN); /// Destructor - virtual ~ConeShape() override; + virtual ~ConeShape() override = default; /// Deleted copy-constructor ConeShape(const ConeShape& shape) = delete; diff --git a/src/collision/shapes/ConvexMeshShape.cpp b/src/collision/shapes/ConvexMeshShape.cpp index aedab6d1..cc880a25 100644 --- a/src/collision/shapes/ConvexMeshShape.cpp +++ b/src/collision/shapes/ConvexMeshShape.cpp @@ -140,11 +140,6 @@ ConvexMeshShape::ConvexMeshShape(decimal margin) } -// Destructor -ConvexMeshShape::~ConvexMeshShape() { - -} - // Return a local support point in a given direction without the object margin. /// If the edges information is not used for collision detection, this method will go through /// the whole vertices list and pick up the vertex with the largest dot product in the support diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index 449762a5..cbc5c692 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -120,7 +120,7 @@ class ConvexMeshShape : public ConvexShape { ConvexMeshShape(decimal margin = OBJECT_MARGIN); /// Destructor - virtual ~ConvexMeshShape() override; + virtual ~ConvexMeshShape() override = default; /// Deleted copy-constructor ConvexMeshShape(const ConvexMeshShape& shape) = delete; diff --git a/src/collision/shapes/ConvexShape.cpp b/src/collision/shapes/ConvexShape.cpp index 2faa877f..f077cdcb 100644 --- a/src/collision/shapes/ConvexShape.cpp +++ b/src/collision/shapes/ConvexShape.cpp @@ -36,11 +36,6 @@ ConvexShape::ConvexShape(CollisionShapeType type, decimal margin) } -// Destructor -ConvexShape::~ConvexShape() { - -} - // Return a local support point in a given direction with the object margin Vector3 ConvexShape::getLocalSupportPointWithMargin(const Vector3& direction, void** cachedCollisionData) const { diff --git a/src/collision/shapes/ConvexShape.h b/src/collision/shapes/ConvexShape.h index f70a88e1..4b12cae4 100644 --- a/src/collision/shapes/ConvexShape.h +++ b/src/collision/shapes/ConvexShape.h @@ -56,9 +56,6 @@ class ConvexShape : public CollisionShape { virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, void** cachedCollisionData) const=0; - /// Return true if a point is inside the collision shape - virtual bool testPointInside(const Vector3& worldPoint, ProxyShape* proxyShape) const=0; - public : // -------------------- Methods -------------------- // @@ -67,7 +64,7 @@ class ConvexShape : public CollisionShape { ConvexShape(CollisionShapeType type, decimal margin); /// Destructor - virtual ~ConvexShape() override; + virtual ~ConvexShape() override = default; /// Deleted copy-constructor ConvexShape(const ConvexShape& shape) = delete; diff --git a/src/collision/shapes/CylinderShape.cpp b/src/collision/shapes/CylinderShape.cpp index 5485bb37..8cb405f1 100644 --- a/src/collision/shapes/CylinderShape.cpp +++ b/src/collision/shapes/CylinderShape.cpp @@ -43,11 +43,6 @@ CylinderShape::CylinderShape(decimal radius, decimal height, decimal margin) assert(height > decimal(0.0)); } -// Destructor -CylinderShape::~CylinderShape() { - -} - // Return a local support point in a given direction without the object margin Vector3 CylinderShape::getLocalSupportPointWithoutMargin(const Vector3& direction, void** cachedCollisionData) const { diff --git a/src/collision/shapes/CylinderShape.h b/src/collision/shapes/CylinderShape.h index 4ac7d811..2718d2ff 100644 --- a/src/collision/shapes/CylinderShape.h +++ b/src/collision/shapes/CylinderShape.h @@ -84,7 +84,7 @@ class CylinderShape : public ConvexShape { CylinderShape(decimal radius, decimal height, decimal margin = OBJECT_MARGIN); /// Destructor - virtual ~CylinderShape() override; + virtual ~CylinderShape() override = default; /// Deleted copy-constructor CylinderShape(const CylinderShape& shape) = delete; diff --git a/src/collision/shapes/HeightFieldShape.cpp b/src/collision/shapes/HeightFieldShape.cpp index 720619e8..02ef852f 100644 --- a/src/collision/shapes/HeightFieldShape.cpp +++ b/src/collision/shapes/HeightFieldShape.cpp @@ -74,11 +74,6 @@ HeightFieldShape::HeightFieldShape(int nbGridColumns, int nbGridRows, decimal mi } } -// Destructor -HeightFieldShape::~HeightFieldShape() { - -} - // Return the local bounds of the shape in x, y and z directions. // This method is used to compute the AABB of the box /** diff --git a/src/collision/shapes/HeightFieldShape.h b/src/collision/shapes/HeightFieldShape.h index be6819e5..6f2b8459 100644 --- a/src/collision/shapes/HeightFieldShape.h +++ b/src/collision/shapes/HeightFieldShape.h @@ -159,7 +159,7 @@ class HeightFieldShape : public ConcaveShape { int upAxis = 1, decimal integerHeightScale = 1.0f); /// Destructor - virtual ~HeightFieldShape() override; + virtual ~HeightFieldShape() override = default; /// Deleted copy-constructor HeightFieldShape(const HeightFieldShape& shape) = delete; diff --git a/src/collision/shapes/SphereShape.cpp b/src/collision/shapes/SphereShape.cpp index 50c2e94d..73fe49aa 100644 --- a/src/collision/shapes/SphereShape.cpp +++ b/src/collision/shapes/SphereShape.cpp @@ -39,11 +39,6 @@ SphereShape::SphereShape(decimal radius) : ConvexShape(CollisionShapeType::SPHER assert(radius > decimal(0.0)); } -// Destructor -SphereShape::~SphereShape() { - -} - // Raycast method with feedback information bool SphereShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const { diff --git a/src/collision/shapes/SphereShape.h b/src/collision/shapes/SphereShape.h index dc6a6cea..36b3a1f7 100644 --- a/src/collision/shapes/SphereShape.h +++ b/src/collision/shapes/SphereShape.h @@ -46,9 +46,6 @@ class SphereShape : public ConvexShape { protected : - // -------------------- Attributes -------------------- // - - // -------------------- Methods -------------------- // /// Return a local support point in a given direction without the object margin @@ -72,7 +69,7 @@ class SphereShape : public ConvexShape { SphereShape(decimal radius); /// Destructor - virtual ~SphereShape() override; + virtual ~SphereShape() override = default; /// Deleted copy-constructor SphereShape(const SphereShape& shape) = delete; diff --git a/src/collision/shapes/TriangleShape.cpp b/src/collision/shapes/TriangleShape.cpp index 065b7526..4767435b 100644 --- a/src/collision/shapes/TriangleShape.cpp +++ b/src/collision/shapes/TriangleShape.cpp @@ -47,11 +47,6 @@ TriangleShape::TriangleShape(const Vector3& point1, const Vector3& point2, const mRaycastTestType = TriangleRaycastSide::FRONT; } -// Destructor -TriangleShape::~TriangleShape() { - -} - // Raycast method with feedback information /// This method use the line vs triangle raycasting technique described in /// Real-time Collision Detection by Christer Ericson. diff --git a/src/collision/shapes/TriangleShape.h b/src/collision/shapes/TriangleShape.h index 699a42fc..5faae51b 100644 --- a/src/collision/shapes/TriangleShape.h +++ b/src/collision/shapes/TriangleShape.h @@ -87,7 +87,7 @@ class TriangleShape : public ConvexShape { decimal margin = OBJECT_MARGIN); /// Destructor - virtual ~TriangleShape() override; + virtual ~TriangleShape() override = default; /// Deleted copy-constructor TriangleShape(const TriangleShape& shape) = delete; diff --git a/src/constraint/BallAndSocketJoint.cpp b/src/constraint/BallAndSocketJoint.cpp index 448499de..497a45dc 100644 --- a/src/constraint/BallAndSocketJoint.cpp +++ b/src/constraint/BallAndSocketJoint.cpp @@ -41,11 +41,6 @@ BallAndSocketJoint::BallAndSocketJoint(const BallAndSocketJointInfo& jointInfo) mLocalAnchorPointBody2 = mBody2->getTransform().getInverse() * jointInfo.anchorPointWorldSpace; } -// Destructor -BallAndSocketJoint::~BallAndSocketJoint() { - -} - // Initialize before solving the constraint void BallAndSocketJoint::initBeforeSolve(const ConstraintSolverData& constraintSolverData) { diff --git a/src/constraint/BallAndSocketJoint.h b/src/constraint/BallAndSocketJoint.h index 4244823c..c8836a23 100644 --- a/src/constraint/BallAndSocketJoint.h +++ b/src/constraint/BallAndSocketJoint.h @@ -128,7 +128,7 @@ class BallAndSocketJoint : public Joint { BallAndSocketJoint(const BallAndSocketJointInfo& jointInfo); /// Destructor - virtual ~BallAndSocketJoint() override; + virtual ~BallAndSocketJoint() override = default; /// Deleted copy-constructor BallAndSocketJoint(const BallAndSocketJoint& constraint) = delete; diff --git a/src/constraint/ContactPoint.cpp b/src/constraint/ContactPoint.cpp index ccc7e960..3be8476a 100644 --- a/src/constraint/ContactPoint.cpp +++ b/src/constraint/ContactPoint.cpp @@ -51,8 +51,3 @@ ContactPoint::ContactPoint(const ContactPointInfo& contactInfo) assert(mPenetrationDepth > 0.0); } - -// Destructor -ContactPoint::~ContactPoint() { - -} diff --git a/src/constraint/ContactPoint.h b/src/constraint/ContactPoint.h index b7fef547..d2e8f189 100644 --- a/src/constraint/ContactPoint.h +++ b/src/constraint/ContactPoint.h @@ -151,7 +151,7 @@ class ContactPoint { ContactPoint(const ContactPointInfo& contactInfo); /// Destructor - ~ContactPoint(); + ~ContactPoint() = default; /// Deleted copy-constructor ContactPoint(const ContactPoint& contact) = delete; diff --git a/src/constraint/FixedJoint.cpp b/src/constraint/FixedJoint.cpp index 687043e8..9ed31f01 100644 --- a/src/constraint/FixedJoint.cpp +++ b/src/constraint/FixedJoint.cpp @@ -49,11 +49,6 @@ FixedJoint::FixedJoint(const FixedJointInfo& jointInfo) mInitOrientationDifferenceInv.inverse(); } -// Destructor -FixedJoint::~FixedJoint() { - -} - // Initialize before solving the constraint void FixedJoint::initBeforeSolve(const ConstraintSolverData& constraintSolverData) { diff --git a/src/constraint/FixedJoint.h b/src/constraint/FixedJoint.h index 54c9624c..e08b31cc 100644 --- a/src/constraint/FixedJoint.h +++ b/src/constraint/FixedJoint.h @@ -139,7 +139,7 @@ class FixedJoint : public Joint { FixedJoint(const FixedJointInfo& jointInfo); /// Destructor - virtual ~FixedJoint() override; + virtual ~FixedJoint() override = default; /// Deleted copy-constructor FixedJoint(const FixedJoint& constraint) = delete; diff --git a/src/constraint/HingeJoint.cpp b/src/constraint/HingeJoint.cpp index 021ee495..4b152caa 100644 --- a/src/constraint/HingeJoint.cpp +++ b/src/constraint/HingeJoint.cpp @@ -64,11 +64,6 @@ HingeJoint::HingeJoint(const HingeJointInfo& jointInfo) mInitOrientationDifferenceInv.inverse(); } -// Destructor -HingeJoint::~HingeJoint() { - -} - // Initialize before solving the constraint void HingeJoint::initBeforeSolve(const ConstraintSolverData& constraintSolverData) { diff --git a/src/constraint/HingeJoint.h b/src/constraint/HingeJoint.h index 21960697..c553755d 100644 --- a/src/constraint/HingeJoint.h +++ b/src/constraint/HingeJoint.h @@ -290,7 +290,7 @@ class HingeJoint : public Joint { HingeJoint(const HingeJointInfo& jointInfo); /// Destructor - virtual ~HingeJoint() override; + virtual ~HingeJoint() override = default; /// Deleted copy-constructor HingeJoint(const HingeJoint& constraint) = delete; diff --git a/src/constraint/Joint.cpp b/src/constraint/Joint.cpp index 5c6a98f7..2c0695ab 100644 --- a/src/constraint/Joint.cpp +++ b/src/constraint/Joint.cpp @@ -37,8 +37,3 @@ Joint::Joint(const JointInfo& jointInfo) assert(mBody1 != nullptr); assert(mBody2 != nullptr); } - -// Destructor -Joint::~Joint() { - -} diff --git a/src/constraint/Joint.h b/src/constraint/Joint.h index eb73f87f..ead08a53 100644 --- a/src/constraint/Joint.h +++ b/src/constraint/Joint.h @@ -106,7 +106,7 @@ struct JointInfo { } /// Destructor - virtual ~JointInfo() {} + virtual ~JointInfo() = default; }; @@ -172,7 +172,7 @@ class Joint { Joint(const JointInfo& jointInfo); /// Destructor - virtual ~Joint(); + virtual ~Joint() = default; /// Deleted copy-constructor Joint(const Joint& constraint) = delete; diff --git a/src/constraint/SliderJoint.cpp b/src/constraint/SliderJoint.cpp index 365a9ad4..efe7cbff 100644 --- a/src/constraint/SliderJoint.cpp +++ b/src/constraint/SliderJoint.cpp @@ -63,11 +63,6 @@ SliderJoint::SliderJoint(const SliderJointInfo& jointInfo) mSliderAxisBody1.normalize(); } -// Destructor -SliderJoint::~SliderJoint() { - -} - // Initialize before solving the constraint void SliderJoint::initBeforeSolve(const ConstraintSolverData& constraintSolverData) { diff --git a/src/constraint/SliderJoint.h b/src/constraint/SliderJoint.h index 859cbe28..e01a9ab4 100644 --- a/src/constraint/SliderJoint.h +++ b/src/constraint/SliderJoint.h @@ -288,7 +288,7 @@ class SliderJoint : public Joint { SliderJoint(const SliderJointInfo& jointInfo); /// Destructor - virtual ~SliderJoint() override; + virtual ~SliderJoint() override = default; /// Deleted copy-constructor SliderJoint(const SliderJoint& constraint) = delete; diff --git a/src/engine/ConstraintSolver.cpp b/src/engine/ConstraintSolver.cpp index f52056e7..547aea6e 100644 --- a/src/engine/ConstraintSolver.cpp +++ b/src/engine/ConstraintSolver.cpp @@ -36,11 +36,6 @@ ConstraintSolver::ConstraintSolver(const std::map& mapBodyToVe } -// Destructor -ConstraintSolver::~ConstraintSolver() { - -} - // Initialize the constraint solver for a given island void ConstraintSolver::initializeForIsland(decimal dt, Island* island) { diff --git a/src/engine/ConstraintSolver.h b/src/engine/ConstraintSolver.h index dd76c4b8..ea16a844 100644 --- a/src/engine/ConstraintSolver.h +++ b/src/engine/ConstraintSolver.h @@ -173,7 +173,7 @@ class ConstraintSolver { ConstraintSolver(const std::map& mapBodyToVelocityIndex); /// Destructor - ~ConstraintSolver(); + ~ConstraintSolver() = default; /// Initialize the constraint solver for a given island void initializeForIsland(decimal dt, Island* island); diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index faf58825..a11cc2e9 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -48,11 +48,6 @@ ContactSolver::ContactSolver(const std::map& mapBodyToVelocity } -// Destructor -ContactSolver::~ContactSolver() { - -} - // Initialize the constraint solver for a given island void ContactSolver::initializeForIsland(decimal dt, Island* island) { diff --git a/src/engine/ContactSolver.h b/src/engine/ContactSolver.h index 203d140e..5b944c2f 100644 --- a/src/engine/ContactSolver.h +++ b/src/engine/ContactSolver.h @@ -413,7 +413,7 @@ class ContactSolver { ContactSolver(const std::map& mapBodyToVelocityIndex); /// Destructor - virtual ~ContactSolver(); + ~ContactSolver() = default; /// Initialize the constraint solver for a given island void initializeForIsland(decimal dt, Island* island); diff --git a/src/engine/EventListener.h b/src/engine/EventListener.h index a2e9d868..562e8ac7 100644 --- a/src/engine/EventListener.h +++ b/src/engine/EventListener.h @@ -44,10 +44,10 @@ class EventListener { public : /// Constructor - EventListener() {} + EventListener() = default; /// Destructor - virtual ~EventListener() {} + virtual ~EventListener() = default; /// Called when a new contact point is found between two bodies that were separated before /** diff --git a/src/engine/Material.cpp b/src/engine/Material.cpp index 4dc99647..f0484c96 100644 --- a/src/engine/Material.cpp +++ b/src/engine/Material.cpp @@ -42,8 +42,3 @@ Material::Material(const Material& material) mRollingResistance(material.mRollingResistance), mBounciness(material.mBounciness) { } - -// Destructor -Material::~Material() { - -} diff --git a/src/engine/Material.h b/src/engine/Material.h index c820cb93..ca5fd532 100644 --- a/src/engine/Material.h +++ b/src/engine/Material.h @@ -64,7 +64,7 @@ class Material { Material(const Material& material); /// Destructor - ~Material(); + ~Material() = default; /// Return the bounciness decimal getBounciness() const; diff --git a/src/engine/OverlappingPair.cpp b/src/engine/OverlappingPair.cpp index fa45817e..979ecc52 100644 --- a/src/engine/OverlappingPair.cpp +++ b/src/engine/OverlappingPair.cpp @@ -35,9 +35,4 @@ OverlappingPair::OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, : mContactManifoldSet(shape1, shape2, memoryAllocator, nbMaxContactManifolds), mCachedSeparatingAxis(1.0, 1.0, 1.0) { -} - -// Destructor -OverlappingPair::~OverlappingPair() { - -} +} diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index e40814ca..7995b0d2 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -66,7 +66,7 @@ class OverlappingPair { int nbMaxContactManifolds, MemoryAllocator& memoryAllocator); /// Destructor - ~OverlappingPair(); + ~OverlappingPair() = default; /// Deleted copy-constructor OverlappingPair(const OverlappingPair& pair) = delete; diff --git a/src/engine/Timer.cpp b/src/engine/Timer.cpp index e9a14d21..7d50dd79 100644 --- a/src/engine/Timer.cpp +++ b/src/engine/Timer.cpp @@ -34,11 +34,6 @@ Timer::Timer(double timeStep) : mTimeStep(timeStep), mIsRunning(false) { assert(timeStep > 0.0); } -// Destructor -Timer::~Timer() { - -} - // Return the current time of the system in seconds long double Timer::getCurrentSystemTime() { diff --git a/src/engine/Timer.h b/src/engine/Timer.h index 9c59d033..83fc0b0a 100644 --- a/src/engine/Timer.h +++ b/src/engine/Timer.h @@ -79,7 +79,7 @@ class Timer { Timer(double timeStep); /// Destructor - ~Timer(); + ~Timer() = default; /// Deleted copy-constructor Timer(const Timer& timer) = delete; diff --git a/src/mathematics/Matrix2x2.cpp b/src/mathematics/Matrix2x2.cpp index 30fdc1a8..c501c1db 100644 --- a/src/mathematics/Matrix2x2.cpp +++ b/src/mathematics/Matrix2x2.cpp @@ -47,11 +47,6 @@ Matrix2x2::Matrix2x2(decimal a1, decimal a2, decimal b1, decimal b2) { setAllValues(a1, a2, b1, b2); } -// Destructor -Matrix2x2::~Matrix2x2() { - -} - // Copy-constructor Matrix2x2::Matrix2x2(const Matrix2x2& matrix) { setAllValues(matrix.mRows[0][0], matrix.mRows[0][1], diff --git a/src/mathematics/Matrix2x2.h b/src/mathematics/Matrix2x2.h index 9e9a6e4d..ee31b07a 100644 --- a/src/mathematics/Matrix2x2.h +++ b/src/mathematics/Matrix2x2.h @@ -60,7 +60,7 @@ class Matrix2x2 { Matrix2x2(decimal a1, decimal a2, decimal b1, decimal b2); /// Destructor - ~Matrix2x2(); + ~Matrix2x2() = default; /// Copy-constructor Matrix2x2(const Matrix2x2& matrix); diff --git a/src/mathematics/Matrix3x3.cpp b/src/mathematics/Matrix3x3.cpp index 3cd03509..a5491ed4 100644 --- a/src/mathematics/Matrix3x3.cpp +++ b/src/mathematics/Matrix3x3.cpp @@ -49,11 +49,6 @@ Matrix3x3::Matrix3x3(decimal a1, decimal a2, decimal a3, setAllValues(a1, a2, a3, b1, b2, b3, c1, c2, c3); } -// Destructor -Matrix3x3::~Matrix3x3() { - -} - // Copy-constructor Matrix3x3::Matrix3x3(const Matrix3x3& matrix) { setAllValues(matrix.mRows[0][0], matrix.mRows[0][1], matrix.mRows[0][2], diff --git a/src/mathematics/Matrix3x3.h b/src/mathematics/Matrix3x3.h index 50d9dbd0..dfa23085 100644 --- a/src/mathematics/Matrix3x3.h +++ b/src/mathematics/Matrix3x3.h @@ -63,7 +63,7 @@ class Matrix3x3 { decimal c1, decimal c2, decimal c3); /// Destructor - ~Matrix3x3(); + ~Matrix3x3() = default; /// Copy-constructor Matrix3x3(const Matrix3x3& matrix); diff --git a/src/mathematics/Quaternion.cpp b/src/mathematics/Quaternion.cpp index 3236a1b7..0b2587f5 100644 --- a/src/mathematics/Quaternion.cpp +++ b/src/mathematics/Quaternion.cpp @@ -128,11 +128,6 @@ Quaternion::Quaternion(const Matrix3x3& matrix) { } } -// Destructor -Quaternion::~Quaternion() { - -} - // Compute the rotation angle (in radians) and the rotation axis /// This method is used to get the rotation angle (in radian) and the unit /// rotation axis of an orientation quaternion. diff --git a/src/mathematics/Quaternion.h b/src/mathematics/Quaternion.h index c1bb584d..360cf229 100644 --- a/src/mathematics/Quaternion.h +++ b/src/mathematics/Quaternion.h @@ -82,7 +82,7 @@ struct Quaternion { Quaternion(const Matrix3x3& matrix); /// Destructor - ~Quaternion(); + ~Quaternion() = default; /// Set all the values void setAllValues(decimal newX, decimal newY, decimal newZ, decimal newW); diff --git a/src/mathematics/Ray.h b/src/mathematics/Ray.h index 10f182b0..938e8960 100644 --- a/src/mathematics/Ray.h +++ b/src/mathematics/Ray.h @@ -67,9 +67,7 @@ struct Ray { } /// Destructor - ~Ray() { - - } + ~Ray() = default; /// Overloaded assignment operator Ray& operator=(const Ray& ray) { diff --git a/src/mathematics/Transform.cpp b/src/mathematics/Transform.cpp index 4a77d84c..4bc91253 100644 --- a/src/mathematics/Transform.cpp +++ b/src/mathematics/Transform.cpp @@ -51,8 +51,3 @@ Transform::Transform(const Transform& transform) : mPosition(transform.mPosition), mOrientation(transform.mOrientation) { } - -// Destructor -Transform::~Transform() { - -} diff --git a/src/mathematics/Transform.h b/src/mathematics/Transform.h index 35d1862c..a93734cd 100644 --- a/src/mathematics/Transform.h +++ b/src/mathematics/Transform.h @@ -65,7 +65,7 @@ class Transform { Transform(const Vector3& position, const Quaternion& orientation); /// Destructor - ~Transform(); + ~Transform() = default; /// Copy-constructor Transform(const Transform& transform); diff --git a/src/mathematics/Vector2.cpp b/src/mathematics/Vector2.cpp index 55926bfd..2f225636 100644 --- a/src/mathematics/Vector2.cpp +++ b/src/mathematics/Vector2.cpp @@ -45,11 +45,6 @@ Vector2::Vector2(const Vector2& vector) : x(vector.x), y(vector.y) { } -// Destructor -Vector2::~Vector2() { - -} - // Return the corresponding unit vector Vector2 Vector2::getUnit() const { decimal lengthVector = length(); diff --git a/src/mathematics/Vector2.h b/src/mathematics/Vector2.h index 6e30363b..4b0e32f1 100644 --- a/src/mathematics/Vector2.h +++ b/src/mathematics/Vector2.h @@ -64,7 +64,7 @@ struct Vector2 { Vector2(const Vector2& vector); /// Destructor - ~Vector2(); + ~Vector2() = default; /// Set all the values of the vector void setAllValues(decimal newX, decimal newY); diff --git a/src/mathematics/Vector3.cpp b/src/mathematics/Vector3.cpp index f356705a..ed29a37f 100644 --- a/src/mathematics/Vector3.cpp +++ b/src/mathematics/Vector3.cpp @@ -46,11 +46,6 @@ Vector3::Vector3(const Vector3& vector) : x(vector.x), y(vector.y), z(vector.z) } -// Destructor -Vector3::~Vector3() { - -} - // Return the corresponding unit vector Vector3 Vector3::getUnit() const { decimal lengthVector = length(); diff --git a/src/mathematics/Vector3.h b/src/mathematics/Vector3.h index 0936f4ef..4f30391d 100644 --- a/src/mathematics/Vector3.h +++ b/src/mathematics/Vector3.h @@ -67,7 +67,7 @@ struct Vector3 { Vector3(const Vector3& vector); /// Destructor - ~Vector3(); + ~Vector3() = default; /// Set all the values of the vector void setAllValues(decimal newX, decimal newY, decimal newZ); From 4e70174da725e0e207620619cee52aa2ff80652b Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 20 Jul 2016 07:18:17 +0200 Subject: [PATCH 017/248] Use default nb solver iterations in demo scenes --- testbed/scenes/collisionshapes/CollisionShapesScene.cpp | 3 --- testbed/scenes/concavemesh/ConcaveMeshScene.cpp | 3 --- testbed/scenes/cubes/CubesScene.cpp | 3 --- testbed/scenes/heightfield/HeightFieldScene.cpp | 3 --- testbed/scenes/joints/JointsScene.cpp | 3 --- 5 files changed, 15 deletions(-) diff --git a/testbed/scenes/collisionshapes/CollisionShapesScene.cpp b/testbed/scenes/collisionshapes/CollisionShapesScene.cpp index bcf7c836..e18feea9 100644 --- a/testbed/scenes/collisionshapes/CollisionShapesScene.cpp +++ b/testbed/scenes/collisionshapes/CollisionShapesScene.cpp @@ -48,9 +48,6 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name) // Create the dynamics world for the physics simulation mDynamicsWorld = new rp3d::DynamicsWorld(gravity); - // Set the number of iterations of the constraint solver - mDynamicsWorld->setNbIterationsVelocitySolver(15); - float radius = 3.0f; for (int i=0; isetNbIterationsVelocitySolver(15); - // ---------- Create the boxes ----------- // for (int i=0; isetNbIterationsVelocitySolver(15); - float radius = 2.0f; // Create all the cubes of the scene diff --git a/testbed/scenes/heightfield/HeightFieldScene.cpp b/testbed/scenes/heightfield/HeightFieldScene.cpp index ab168b13..8779fa9c 100644 --- a/testbed/scenes/heightfield/HeightFieldScene.cpp +++ b/testbed/scenes/heightfield/HeightFieldScene.cpp @@ -45,9 +45,6 @@ HeightFieldScene::HeightFieldScene(const std::string& name) : SceneDemo(name, SC // Create the dynamics world for the physics simulation mDynamicsWorld = new rp3d::DynamicsWorld(gravity); - // Set the number of iterations of the constraint solver - mDynamicsWorld->setNbIterationsVelocitySolver(15); - // ---------- Create the boxes ----------- // // For each box diff --git a/testbed/scenes/joints/JointsScene.cpp b/testbed/scenes/joints/JointsScene.cpp index ae006573..9927613f 100644 --- a/testbed/scenes/joints/JointsScene.cpp +++ b/testbed/scenes/joints/JointsScene.cpp @@ -47,9 +47,6 @@ JointsScene::JointsScene(const std::string& name) // Create the dynamics world for the physics simulation mDynamicsWorld = new rp3d::DynamicsWorld(gravity); - // Set the number of iterations of the constraint solver - mDynamicsWorld->setNbIterationsVelocitySolver(15); - // Create the Ball-and-Socket joint createBallAndSocketJoints(); From 8a69dc89fa9a830e72a56c8ff836af49f7e23ef6 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 21 Aug 2016 12:34:27 +0200 Subject: [PATCH 018/248] Add missing override keyword --- src/collision/shapes/BoxShape.h | 2 +- src/collision/shapes/CapsuleShape.h | 2 +- src/collision/shapes/ConcaveShape.h | 2 +- src/collision/shapes/ConeShape.h | 2 +- src/collision/shapes/ConvexMeshShape.h | 2 +- src/collision/shapes/CylinderShape.h | 2 +- src/collision/shapes/SphereShape.h | 2 +- src/collision/shapes/TriangleShape.h | 2 +- 8 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/collision/shapes/BoxShape.h b/src/collision/shapes/BoxShape.h index 2d0fef75..776356ba 100644 --- a/src/collision/shapes/BoxShape.h +++ b/src/collision/shapes/BoxShape.h @@ -100,7 +100,7 @@ class BoxShape : public ConvexShape { virtual void getLocalBounds(Vector3& min, Vector3& max) const override; /// Return true if the collision shape is a polyhedron - virtual bool isPolyhedron() const; + virtual bool isPolyhedron() const override; /// Return the local inertia tensor of the collision shape virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; diff --git a/src/collision/shapes/CapsuleShape.h b/src/collision/shapes/CapsuleShape.h index 542fb12f..9c0a4545 100644 --- a/src/collision/shapes/CapsuleShape.h +++ b/src/collision/shapes/CapsuleShape.h @@ -102,7 +102,7 @@ class CapsuleShape : public ConvexShape { virtual void getLocalBounds(Vector3& min, Vector3& max) const override; /// Return true if the collision shape is a polyhedron - virtual bool isPolyhedron() const; + virtual bool isPolyhedron() const override; /// Return the local inertia tensor of the collision shape virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; diff --git a/src/collision/shapes/ConcaveShape.h b/src/collision/shapes/ConcaveShape.h index 4af49338..c5657b2b 100644 --- a/src/collision/shapes/ConcaveShape.h +++ b/src/collision/shapes/ConcaveShape.h @@ -105,7 +105,7 @@ class ConcaveShape : public CollisionShape { virtual bool isConvex() const override; /// Return true if the collision shape is a polyhedron - virtual bool isPolyhedron() const; + virtual bool isPolyhedron() const override; /// Use a callback method on all triangles of the concave shape inside a given AABB virtual void testAllTriangles(TriangleCallback& callback, const AABB& localAABB) const=0; diff --git a/src/collision/shapes/ConeShape.h b/src/collision/shapes/ConeShape.h index 65ddb35e..16102163 100644 --- a/src/collision/shapes/ConeShape.h +++ b/src/collision/shapes/ConeShape.h @@ -108,7 +108,7 @@ class ConeShape : public ConvexShape { virtual void getLocalBounds(Vector3& min, Vector3& max) const override; /// Return true if the collision shape is a polyhedron - virtual bool isPolyhedron() const; + virtual bool isPolyhedron() const override; /// Return the local inertia tensor of the collision shape virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index aeb1edbe..66b624aa 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -141,7 +141,7 @@ class ConvexMeshShape : public ConvexShape { void addEdge(uint v1, uint v2); /// Return true if the collision shape is a polyhedron - virtual bool isPolyhedron() const; + virtual bool isPolyhedron() const override; /// Return true if the edges information is used to speed up the collision detection bool isEdgesInformationUsed() const; diff --git a/src/collision/shapes/CylinderShape.h b/src/collision/shapes/CylinderShape.h index b58c454d..e0744a80 100644 --- a/src/collision/shapes/CylinderShape.h +++ b/src/collision/shapes/CylinderShape.h @@ -99,7 +99,7 @@ class CylinderShape : public ConvexShape { decimal getHeight() const; /// Return true if the collision shape is a polyhedron - virtual bool isPolyhedron() const; + virtual bool isPolyhedron() const override; /// Set the scaling vector of the collision shape virtual void setLocalScaling(const Vector3& scaling) override; diff --git a/src/collision/shapes/SphereShape.h b/src/collision/shapes/SphereShape.h index 58f20e6f..fe55a7a8 100644 --- a/src/collision/shapes/SphereShape.h +++ b/src/collision/shapes/SphereShape.h @@ -81,7 +81,7 @@ class SphereShape : public ConvexShape { decimal getRadius() const; /// Return true if the collision shape is a polyhedron - virtual bool isPolyhedron() const; + virtual bool isPolyhedron() const override; /// Set the scaling vector of the collision shape virtual void setLocalScaling(const Vector3& scaling) override; diff --git a/src/collision/shapes/TriangleShape.h b/src/collision/shapes/TriangleShape.h index d1c82f70..29732f8f 100644 --- a/src/collision/shapes/TriangleShape.h +++ b/src/collision/shapes/TriangleShape.h @@ -117,7 +117,7 @@ class TriangleShape : public ConvexShape { Vector3 getVertex(int index) const; /// Return true if the collision shape is a polyhedron - virtual bool isPolyhedron() const; + virtual bool isPolyhedron() const override; // ---------- Friendship ---------- // From 0a7eeaeb48014357a7e84974769f258288d984ed Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 21 Aug 2016 19:32:14 +0200 Subject: [PATCH 019/248] Fix compilation error on gcc --- src/collision/broadphase/DynamicAABBTree.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/collision/broadphase/DynamicAABBTree.cpp b/src/collision/broadphase/DynamicAABBTree.cpp index de494f69..7efd86ac 100644 --- a/src/collision/broadphase/DynamicAABBTree.cpp +++ b/src/collision/broadphase/DynamicAABBTree.cpp @@ -32,7 +32,7 @@ using namespace reactphysics3d; // Initialization of static variables -constexpr int TreeNode::NULL_TREE_NODE = -1; +const int TreeNode::NULL_TREE_NODE = -1; // Constructor DynamicAABBTree::DynamicAABBTree(decimal extraAABBGap) : mExtraAABBGap(extraAABBGap) { From 6f8d9586c7ba78cc17b57ffb49f4618984235006 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 21 Aug 2016 20:25:50 +0200 Subject: [PATCH 020/248] Fix compilation error on gcc --- src/constraint/BallAndSocketJoint.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/constraint/BallAndSocketJoint.cpp b/src/constraint/BallAndSocketJoint.cpp index 497a45dc..7a5fce1b 100644 --- a/src/constraint/BallAndSocketJoint.cpp +++ b/src/constraint/BallAndSocketJoint.cpp @@ -30,7 +30,7 @@ using namespace reactphysics3d; // Static variables definition -constexpr decimal BallAndSocketJoint::BETA = decimal(0.2); +const decimal BallAndSocketJoint::BETA = decimal(0.2); // Constructor BallAndSocketJoint::BallAndSocketJoint(const BallAndSocketJointInfo& jointInfo) From 123cd93f387b7a0ea813e29c293e0ad81f1f8540 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 21 Aug 2016 20:37:58 +0200 Subject: [PATCH 021/248] Fix compilation error on gcc --- src/constraint/FixedJoint.cpp | 2 +- src/constraint/HingeJoint.cpp | 2 +- src/constraint/SliderJoint.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/constraint/FixedJoint.cpp b/src/constraint/FixedJoint.cpp index 9ed31f01..8f0b105c 100644 --- a/src/constraint/FixedJoint.cpp +++ b/src/constraint/FixedJoint.cpp @@ -30,7 +30,7 @@ using namespace reactphysics3d; // Static variables definition -constexpr decimal FixedJoint::BETA = decimal(0.2); +const decimal FixedJoint::BETA = decimal(0.2); // Constructor FixedJoint::FixedJoint(const FixedJointInfo& jointInfo) diff --git a/src/constraint/HingeJoint.cpp b/src/constraint/HingeJoint.cpp index 4b152caa..1634bf27 100644 --- a/src/constraint/HingeJoint.cpp +++ b/src/constraint/HingeJoint.cpp @@ -31,7 +31,7 @@ using namespace reactphysics3d; // Static variables definition -constexpr decimal HingeJoint::BETA = decimal(0.2); +const decimal HingeJoint::BETA = decimal(0.2); // Constructor HingeJoint::HingeJoint(const HingeJointInfo& jointInfo) diff --git a/src/constraint/SliderJoint.cpp b/src/constraint/SliderJoint.cpp index efe7cbff..919d91c0 100644 --- a/src/constraint/SliderJoint.cpp +++ b/src/constraint/SliderJoint.cpp @@ -29,7 +29,7 @@ using namespace reactphysics3d; // Static variables definition -constexpr decimal SliderJoint::BETA = decimal(0.2); +const decimal SliderJoint::BETA = decimal(0.2); // Constructor SliderJoint::SliderJoint(const SliderJointInfo& jointInfo) From 2f195c61066c71dc45c5570709b0e78a61888fa0 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 21 Aug 2016 20:44:29 +0200 Subject: [PATCH 022/248] Fix compilation error on gcc --- src/engine/ContactSolver.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index a11cc2e9..331e8045 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -34,9 +34,9 @@ using namespace reactphysics3d; using namespace std; // Constants initialization -constexpr decimal ContactSolver::BETA = decimal(0.2); -constexpr decimal ContactSolver::BETA_SPLIT_IMPULSE = decimal(0.2); -constexpr decimal ContactSolver::SLOP= decimal(0.01); +const decimal ContactSolver::BETA = decimal(0.2); +const decimal ContactSolver::BETA_SPLIT_IMPULSE = decimal(0.2); +const decimal ContactSolver::SLOP= decimal(0.01); // Constructor ContactSolver::ContactSolver(const std::map& mapBodyToVelocityIndex) From e069a25f08bfee44b84ed88ab0b7b65dd7e0b4b7 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sat, 10 Sep 2016 11:18:52 +0200 Subject: [PATCH 023/248] Start refactoring the contact solver --- src/engine/ContactSolver.cpp | 1308 ++++++++++++++++++++++------------ src/engine/ContactSolver.h | 317 ++++++-- src/engine/DynamicsWorld.cpp | 10 +- src/mathematics/Vector3.cpp | 8 +- 4 files changed, 1114 insertions(+), 529 deletions(-) diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index 331e8045..22359b10 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -38,12 +38,15 @@ const decimal ContactSolver::BETA = decimal(0.2); const decimal ContactSolver::BETA_SPLIT_IMPULSE = decimal(0.2); const decimal ContactSolver::SLOP= decimal(0.01); +// TODO : Enable warmstarting again + // Constructor ContactSolver::ContactSolver(const std::map& mapBodyToVelocityIndex) :mSplitLinearVelocities(nullptr), mSplitAngularVelocities(nullptr), - mContactConstraints(nullptr), mLinearVelocities(nullptr), mAngularVelocities(nullptr), + mContactConstraints(nullptr), mPenetrationConstraints(nullptr), + mFrictionConstraints(nullptr), mLinearVelocities(nullptr), mAngularVelocities(nullptr), mMapBodyToConstrainedVelocityIndex(mapBodyToVelocityIndex), - mIsWarmStartingActive(true), mIsSplitImpulseActive(true), + mIsWarmStartingActive(false), mIsSplitImpulseActive(true), mIsSolveFrictionAtContactManifoldCenterActive(true) { } @@ -64,9 +67,21 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { mNbContactManifolds = island->getNbContactManifolds(); + mNbFrictionConstraints = 0; + mNbPenetrationConstraints = 0; + + // TODO : Try to do faster allocation here mContactConstraints = new ContactManifoldSolver[mNbContactManifolds]; assert(mContactConstraints != nullptr); + // TODO : Count exactly the number of constraints to allocate here (do not reallocate each frame) + mPenetrationConstraints = new PenetrationConstraint[mNbContactManifolds * 4]; + assert(mPenetrationConstraints != nullptr); + + // TODO : Do not reallocate each frame) + mFrictionConstraints = new FrictionConstraint[mNbContactManifolds]; + assert(mFrictionConstraints != nullptr); + // For each contact manifold of the island ContactManifold** contactManifolds = island->getContactManifold(); for (uint i=0; isecond; + uint indexBody2 = mMapBodyToConstrainedVelocityIndex.find(body2)->second; + + mFrictionConstraints[mNbFrictionConstraints].indexBody1 = indexBody1; + mFrictionConstraints[mNbFrictionConstraints].indexBody2 = indexBody2; + // Get the position of the two bodies const Vector3& x1 = body1->mCenterOfMassWorld; const Vector3& x2 = body2->mCenterOfMassWorld; + // Get the velocities of the bodies + const Vector3& v1 = mLinearVelocities[indexBody1]; + const Vector3& w1 = mAngularVelocities[indexBody1]; + const Vector3& v2 = mLinearVelocities[indexBody2]; + const Vector3& w2 = mAngularVelocities[indexBody2]; + + // Get the inertia tensors of both bodies + Matrix3x3 I1 = body1->getInertiaTensorInverseWorld(); + Matrix3x3 I2 = body2->getInertiaTensorInverseWorld(); + + mFrictionConstraints[mNbFrictionConstraints].inverseInertiaTensorBody1 = I1; + mFrictionConstraints[mNbFrictionConstraints].inverseInertiaTensorBody2 = I2; + // Initialize the internal contact manifold structure using the external // contact manifold - internalManifold.indexBody1 = mMapBodyToConstrainedVelocityIndex.find(body1)->second; - internalManifold.indexBody2 = mMapBodyToConstrainedVelocityIndex.find(body2)->second; - internalManifold.inverseInertiaTensorBody1 = body1->getInertiaTensorInverseWorld(); - internalManifold.inverseInertiaTensorBody2 = body2->getInertiaTensorInverseWorld(); - internalManifold.massInverseBody1 = body1->mMassInverse; - internalManifold.massInverseBody2 = body2->mMassInverse; - internalManifold.nbContacts = externalManifold->getNbContactPoints(); - internalManifold.restitutionFactor = computeMixedRestitutionFactor(body1, body2); - internalManifold.frictionCoefficient = computeMixedFrictionCoefficient(body1, body2); - internalManifold.rollingResistanceFactor = computeMixedRollingResistance(body1, body2); + mFrictionConstraints[mNbFrictionConstraints].massInverseBody1 = body1->mMassInverse; + mFrictionConstraints[mNbFrictionConstraints].massInverseBody2 = body2->mMassInverse; + //internalManifold.nbContacts = externalManifold->getNbContactPoints(); + decimal restitutionFactor = computeMixedRestitutionFactor(body1, body2); + mFrictionConstraints[mNbFrictionConstraints].frictionCoefficient = computeMixedFrictionCoefficient(body1, body2); + mFrictionConstraints[mNbFrictionConstraints].rollingResistanceFactor = computeMixedRollingResistance(body1, body2); internalManifold.externalContactManifold = externalManifold; - internalManifold.isBody1DynamicType = body1->getType() == BodyType::DYNAMIC; - internalManifold.isBody2DynamicType = body2->getType() == BodyType::DYNAMIC; + //internalManifold.isBody1DynamicType = body1->getType() == BodyType::DYNAMIC; + //internalManifold.isBody2DynamicType = body2->getType() == BodyType::DYNAMIC; + + bool isBody1DynamicType = body1->getType() == BodyType::DYNAMIC; + bool isBody2DynamicType = body2->getType() == BodyType::DYNAMIC; // If we solve the friction constraints at the center of the contact manifold - if (mIsSolveFrictionAtContactManifoldCenterActive) { - internalManifold.frictionPointBody1 = Vector3::zero(); - internalManifold.frictionPointBody2 = Vector3::zero(); + //if (mIsSolveFrictionAtContactManifoldCenterActive) { + mFrictionConstraints[mNbFrictionConstraints].frictionPointBody1 = Vector3::zero(); + mFrictionConstraints[mNbFrictionConstraints].frictionPointBody2 = Vector3::zero(); + mFrictionConstraints[mNbFrictionConstraints].normal = Vector3::zero(); + //} + + // Compute the inverse K matrix for the rolling resistance constraint + mFrictionConstraints[mNbFrictionConstraints].inverseRollingResistance.setToZero(); + if (mFrictionConstraints[mNbFrictionConstraints].rollingResistanceFactor > 0 && (isBody1DynamicType || isBody2DynamicType)) { + mFrictionConstraints[mNbFrictionConstraints].inverseRollingResistance = I1 + I2; + mFrictionConstraints[mNbFrictionConstraints].inverseRollingResistance = mFrictionConstraints[mNbFrictionConstraints].inverseRollingResistance.getInverse(); } + int nbContacts = 0; + // For each contact point of the contact manifold for (uint c=0; cgetNbContactPoints(); c++) { - ContactPointSolver& contactPoint = internalManifold.contacts[c]; - // Get a contact point ContactPoint* externalContact = externalManifold->getContactPoint(c); + mPenetrationConstraints[mNbPenetrationConstraints].indexBody1 = indexBody1; + mPenetrationConstraints[mNbPenetrationConstraints].indexBody2 = indexBody2; + mPenetrationConstraints[mNbPenetrationConstraints].inverseInertiaTensorBody1 = I1; + mPenetrationConstraints[mNbPenetrationConstraints].inverseInertiaTensorBody2 = I2; + mPenetrationConstraints[mNbPenetrationConstraints].massInverseBody1 = body1->mMassInverse; + mPenetrationConstraints[mNbPenetrationConstraints].massInverseBody2 = body2->mMassInverse; + mPenetrationConstraints[mNbPenetrationConstraints].restitutionFactor = restitutionFactor; + mPenetrationConstraints[mNbPenetrationConstraints].indexFrictionConstraint = mNbFrictionConstraints; + // Get the contact point on the two bodies Vector3 p1 = externalContact->getWorldPointOnBody1(); Vector3 p2 = externalContact->getWorldPointOnBody2(); - contactPoint.externalContact = externalContact; - contactPoint.normal = externalContact->getNormal(); - contactPoint.r1 = p1 - x1; - contactPoint.r2 = p2 - x2; - contactPoint.penetrationDepth = externalContact->getPenetrationDepth(); - contactPoint.isRestingContact = externalContact->getIsRestingContact(); + mPenetrationConstraints[mNbPenetrationConstraints].r1 = p1 - x1; + mPenetrationConstraints[mNbPenetrationConstraints].r2 = p2 - x2; + + //mPenetrationConstraints[penConstIndex].externalContact = externalContact; + mPenetrationConstraints[mNbPenetrationConstraints].normal = externalContact->getNormal(); + mPenetrationConstraints[mNbPenetrationConstraints].penetrationDepth = externalContact->getPenetrationDepth(); + //mPenetrationConstraints[penConstIndex].isRestingContact = externalContact->getIsRestingContact(); externalContact->setIsRestingContact(true); - contactPoint.oldFrictionVector1 = externalContact->getFrictionVector1(); - contactPoint.oldFrictionVector2 = externalContact->getFrictionVector2(); - contactPoint.penetrationImpulse = 0.0; - contactPoint.friction1Impulse = 0.0; - contactPoint.friction2Impulse = 0.0; - contactPoint.rollingResistanceImpulse = Vector3::zero(); + //mPenetrationConstraints[penConstIndex].oldFrictionVector1 = externalContact->getFrictionVector1(); + //mPenetrationConstraints[penConstIndex].oldFrictionVector2 = externalContact->getFrictionVector2(); + mPenetrationConstraints[mNbPenetrationConstraints].penetrationImpulse = 0.0; + //mPenetrationConstraints[penConstIndex].friction1Impulse = 0.0; + //mPenetrationConstraints[penConstIndex].friction2Impulse = 0.0; + //mPenetrationConstraints[penConstIndex].rollingResistanceImpulse = Vector3::zero(); // If we solve the friction constraints at the center of the contact manifold - if (mIsSolveFrictionAtContactManifoldCenterActive) { - internalManifold.frictionPointBody1 += p1; - internalManifold.frictionPointBody2 += p2; - } - } - - // If we solve the friction constraints at the center of the contact manifold - if (mIsSolveFrictionAtContactManifoldCenterActive) { - - internalManifold.frictionPointBody1 /=static_cast(internalManifold.nbContacts); - internalManifold.frictionPointBody2 /=static_cast(internalManifold.nbContacts); - internalManifold.r1Friction = internalManifold.frictionPointBody1 - x1; - internalManifold.r2Friction = internalManifold.frictionPointBody2 - x2; - internalManifold.oldFrictionVector1 = externalManifold->getFrictionVector1(); - internalManifold.oldFrictionVector2 = externalManifold->getFrictionVector2(); - - // If warm starting is active - if (mIsWarmStartingActive) { - - // Initialize the accumulated impulses with the previous step accumulated impulses - internalManifold.friction1Impulse = externalManifold->getFrictionImpulse1(); - internalManifold.friction2Impulse = externalManifold->getFrictionImpulse2(); - internalManifold.frictionTwistImpulse = externalManifold->getFrictionTwistImpulse(); - } - else { - - // Initialize the accumulated impulses to zero - internalManifold.friction1Impulse = 0.0; - internalManifold.friction2Impulse = 0.0; - internalManifold.frictionTwistImpulse = 0.0; - internalManifold.rollingResistanceImpulse = Vector3(0, 0, 0); - } - } - } - - // Fill-in all the matrices needed to solve the LCP problem - initializeContactConstraints(); -} - -// Initialize the contact constraints before solving the system -void ContactSolver::initializeContactConstraints() { - - // For each contact constraint - for (uint c=0; c 0.0 ? contactPoint.inversePenetrationMass = decimal(1.0) / + decimal massPenetration = mPenetrationConstraints[mNbPenetrationConstraints].massInverseBody1 + mPenetrationConstraints[mNbPenetrationConstraints].massInverseBody2 + + ((mPenetrationConstraints[mNbPenetrationConstraints].inverseInertiaTensorBody1 * mPenetrationConstraints[mNbPenetrationConstraints].r1CrossN ).cross(mPenetrationConstraints[mNbPenetrationConstraints].r1)).dot(mPenetrationConstraints[mNbPenetrationConstraints].normal) + + ((mPenetrationConstraints[mNbPenetrationConstraints].inverseInertiaTensorBody2 * mPenetrationConstraints[mNbPenetrationConstraints].r2CrossN ).cross(mPenetrationConstraints[mNbPenetrationConstraints].r2)).dot(mPenetrationConstraints[mNbPenetrationConstraints].normal); + massPenetration > decimal(0.0) ? mPenetrationConstraints[mNbPenetrationConstraints].inversePenetrationMass = decimal(1.0) / massPenetration : decimal(0.0); - // If we do not solve the friction constraints at the center of the contact manifold - if (!mIsSolveFrictionAtContactManifoldCenterActive) { - - // Compute the friction vectors - computeFrictionVectors(deltaV, contactPoint); - - contactPoint.r1CrossT1 = contactPoint.r1.cross(contactPoint.frictionVector1); - contactPoint.r1CrossT2 = contactPoint.r1.cross(contactPoint.frictionVector2); - contactPoint.r2CrossT1 = contactPoint.r2.cross(contactPoint.frictionVector1); - contactPoint.r2CrossT2 = contactPoint.r2.cross(contactPoint.frictionVector2); - - // Compute the inverse mass matrix K for the friction - // constraints at each contact point - decimal friction1Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + - ((I1 * contactPoint.r1CrossT1).cross(contactPoint.r1)).dot( - contactPoint.frictionVector1) + - ((I2 * contactPoint.r2CrossT1).cross(contactPoint.r2)).dot( - contactPoint.frictionVector1); - decimal friction2Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + - ((I1 * contactPoint.r1CrossT2).cross(contactPoint.r1)).dot( - contactPoint.frictionVector2) + - ((I2 * contactPoint.r2CrossT2).cross(contactPoint.r2)).dot( - contactPoint.frictionVector2); - friction1Mass > 0.0 ? contactPoint.inverseFriction1Mass = decimal(1.0) / - friction1Mass : - decimal(0.0); - friction2Mass > 0.0 ? contactPoint.inverseFriction2Mass = decimal(1.0) / - friction2Mass : - decimal(0.0); - } - // Compute the restitution velocity bias "b". We compute this here instead // of inside the solve() method because we need to use the velocity difference // at the beginning of the contact. Note that if it is a resting contact (normal // velocity bellow a given threshold), we do not add a restitution velocity bias - contactPoint.restitutionBias = 0.0; - decimal deltaVDotN = deltaV.dot(contactPoint.normal); + mPenetrationConstraints[mNbPenetrationConstraints].restitutionBias = 0.0; + decimal deltaVDotN = deltaV.dot(mPenetrationConstraints[mNbPenetrationConstraints].normal); if (deltaVDotN < -RESTITUTION_VELOCITY_THRESHOLD) { - contactPoint.restitutionBias = manifold.restitutionFactor * deltaVDotN; + mPenetrationConstraints[mNbPenetrationConstraints].restitutionBias = mPenetrationConstraints[mNbPenetrationConstraints].restitutionFactor * deltaVDotN; } // If the warm starting of the contact solver is active if (mIsWarmStartingActive) { // Get the cached accumulated impulses from the previous step - contactPoint.penetrationImpulse = externalContact->getPenetrationImpulse(); - contactPoint.friction1Impulse = externalContact->getFrictionImpulse1(); - contactPoint.friction2Impulse = externalContact->getFrictionImpulse2(); - contactPoint.rollingResistanceImpulse = externalContact->getRollingResistanceImpulse(); + mPenetrationConstraints[mNbPenetrationConstraints].penetrationImpulse = externalContact->getPenetrationImpulse(); } // Initialize the split impulses to zero - contactPoint.penetrationSplitImpulse = 0.0; + mPenetrationConstraints[mNbPenetrationConstraints].penetrationSplitImpulse = 0.0; // If we solve the friction constraints at the center of the contact manifold - if (mIsSolveFrictionAtContactManifoldCenterActive) { - manifold.normal += contactPoint.normal; - } - } + //if (mIsSolveFrictionAtContactManifoldCenterActive) { + mFrictionConstraints[mNbFrictionConstraints].normal += mPenetrationConstraints[mNbPenetrationConstraints].normal; + //} - // Compute the inverse K matrix for the rolling resistance constraint - manifold.inverseRollingResistance.setToZero(); - if (manifold.rollingResistanceFactor > 0 && (manifold.isBody1DynamicType || manifold.isBody2DynamicType)) { - manifold.inverseRollingResistance = manifold.inverseInertiaTensorBody1 + manifold.inverseInertiaTensorBody2; - manifold.inverseRollingResistance = manifold.inverseRollingResistance.getInverse(); + mNbPenetrationConstraints++; + nbContacts++; } // If we solve the friction constraints at the center of the contact manifold - if (mIsSolveFrictionAtContactManifoldCenterActive) { + //if (mIsSolveFrictionAtContactManifoldCenterActive) { - manifold.normal.normalize(); + //mFrictionConstraints[mNbFrictionConstraints].normal = Vector3::zero(); + mFrictionConstraints[mNbFrictionConstraints].frictionPointBody1 /= nbContacts; + mFrictionConstraints[mNbFrictionConstraints].frictionPointBody2 /= nbContacts; + mFrictionConstraints[mNbFrictionConstraints].r1Friction = mFrictionConstraints[mNbFrictionConstraints].frictionPointBody1 - x1; + mFrictionConstraints[mNbFrictionConstraints].r2Friction = mFrictionConstraints[mNbFrictionConstraints].frictionPointBody2 - x2; + mFrictionConstraints[mNbFrictionConstraints].oldFrictionVector1 = externalManifold->getFrictionVector1(); + mFrictionConstraints[mNbFrictionConstraints].oldFrictionVector2 = externalManifold->getFrictionVector2(); - Vector3 deltaVFrictionPoint = v2 + w2.cross(manifold.r2Friction) - - v1 - w1.cross(manifold.r1Friction); + // If warm starting is active + if (mIsWarmStartingActive) { + + // Initialize the accumulated impulses with the previous step accumulated impulses + mFrictionConstraints[mNbFrictionConstraints].friction1Impulse = externalManifold->getFrictionImpulse1(); + mFrictionConstraints[mNbFrictionConstraints].friction2Impulse = externalManifold->getFrictionImpulse2(); + mFrictionConstraints[mNbFrictionConstraints].frictionTwistImpulse = externalManifold->getFrictionTwistImpulse(); + } + else { + + // Initialize the accumulated impulses to zero + mFrictionConstraints[mNbFrictionConstraints].friction1Impulse = 0.0; + mFrictionConstraints[mNbFrictionConstraints].friction2Impulse = 0.0; + mFrictionConstraints[mNbFrictionConstraints].frictionTwistImpulse = 0.0; + mFrictionConstraints[mNbFrictionConstraints].rollingResistanceImpulse = Vector3(0, 0, 0); + } + + mFrictionConstraints[mNbFrictionConstraints].normal.normalize(); + + Vector3 deltaVFrictionPoint = v2 + w2.cross(mFrictionConstraints[mNbFrictionConstraints].r2Friction) - + v1 - w1.cross(mFrictionConstraints[mNbFrictionConstraints].r1Friction); // Compute the friction vectors - computeFrictionVectors(deltaVFrictionPoint, manifold); + computeFrictionVectors(deltaVFrictionPoint, mFrictionConstraints[mNbFrictionConstraints]); - // Compute the inverse mass matrix K for the friction constraints at the center of - // the contact manifold - manifold.r1CrossT1 = manifold.r1Friction.cross(manifold.frictionVector1); - manifold.r1CrossT2 = manifold.r1Friction.cross(manifold.frictionVector2); - manifold.r2CrossT1 = manifold.r2Friction.cross(manifold.frictionVector1); - manifold.r2CrossT2 = manifold.r2Friction.cross(manifold.frictionVector2); - decimal friction1Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + - ((I1 * manifold.r1CrossT1).cross(manifold.r1Friction)).dot( - manifold.frictionVector1) + - ((I2 * manifold.r2CrossT1).cross(manifold.r2Friction)).dot( - manifold.frictionVector1); - decimal friction2Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + - ((I1 * manifold.r1CrossT2).cross(manifold.r1Friction)).dot( - manifold.frictionVector2) + - ((I2 * manifold.r2CrossT2).cross(manifold.r2Friction)).dot( - manifold.frictionVector2); - decimal frictionTwistMass = manifold.normal.dot(manifold.inverseInertiaTensorBody1 * - manifold.normal) + - manifold.normal.dot(manifold.inverseInertiaTensorBody2 * - manifold.normal); - friction1Mass > 0.0 ? manifold.inverseFriction1Mass = decimal(1.0)/friction1Mass + // Compute the inverse mass matrix K for the friction constraints at the center of the contact manifold + mFrictionConstraints[mNbFrictionConstraints].r1CrossT1 = mFrictionConstraints[mNbFrictionConstraints].r1Friction.cross(mFrictionConstraints[mNbFrictionConstraints].frictionVector1); + mFrictionConstraints[mNbFrictionConstraints].r1CrossT2 = mFrictionConstraints[mNbFrictionConstraints].r1Friction.cross(mFrictionConstraints[mNbFrictionConstraints].frictionVector2); + mFrictionConstraints[mNbFrictionConstraints].r2CrossT1 = mFrictionConstraints[mNbFrictionConstraints].r2Friction.cross(mFrictionConstraints[mNbFrictionConstraints].frictionVector1); + mFrictionConstraints[mNbFrictionConstraints].r2CrossT2 = mFrictionConstraints[mNbFrictionConstraints].r2Friction.cross(mFrictionConstraints[mNbFrictionConstraints].frictionVector2); + decimal friction1Mass = mFrictionConstraints[mNbFrictionConstraints].massInverseBody1 + mFrictionConstraints[mNbFrictionConstraints].massInverseBody2 + + ((I1 * mFrictionConstraints[mNbFrictionConstraints].r1CrossT1).cross(mFrictionConstraints[mNbFrictionConstraints].r1Friction)).dot( + mFrictionConstraints[mNbFrictionConstraints].frictionVector1) + + ((I2 * mFrictionConstraints[mNbFrictionConstraints].r2CrossT1).cross(mFrictionConstraints[mNbFrictionConstraints].r2Friction)).dot( + mFrictionConstraints[mNbFrictionConstraints].frictionVector1); + decimal friction2Mass = mFrictionConstraints[mNbFrictionConstraints].massInverseBody1 + mFrictionConstraints[mNbFrictionConstraints].massInverseBody2 + + ((I1 * mFrictionConstraints[mNbFrictionConstraints].r1CrossT2).cross(mFrictionConstraints[mNbFrictionConstraints].r1Friction)).dot( + mFrictionConstraints[mNbFrictionConstraints].frictionVector2) + + ((I2 * mFrictionConstraints[mNbFrictionConstraints].r2CrossT2).cross(mFrictionConstraints[mNbFrictionConstraints].r2Friction)).dot( + mFrictionConstraints[mNbFrictionConstraints].frictionVector2); + decimal frictionTwistMass = mFrictionConstraints[mNbFrictionConstraints].normal.dot(mFrictionConstraints[mNbFrictionConstraints].inverseInertiaTensorBody1 * + mFrictionConstraints[mNbFrictionConstraints].normal) + + mFrictionConstraints[mNbFrictionConstraints].normal.dot(mFrictionConstraints[mNbFrictionConstraints].inverseInertiaTensorBody2 * + mFrictionConstraints[mNbFrictionConstraints].normal); + friction1Mass > decimal(0.0) ? mFrictionConstraints[mNbFrictionConstraints].inverseFriction1Mass = decimal(1.0)/friction1Mass : decimal(0.0); - friction2Mass > 0.0 ? manifold.inverseFriction2Mass = decimal(1.0)/friction2Mass + friction2Mass > decimal(0.0) ? mFrictionConstraints[mNbFrictionConstraints].inverseFriction2Mass = decimal(1.0)/friction2Mass : decimal(0.0); - frictionTwistMass > 0.0 ? manifold.inverseTwistFrictionMass = decimal(1.0) / + frictionTwistMass > decimal(0.0) ? mFrictionConstraints[mNbFrictionConstraints].inverseTwistFrictionMass = decimal(1.0) / frictionTwistMass : decimal(0.0); - } + //} + + mNbFrictionConstraints++; } + + // Fill-in all the matrices needed to solve the LCP problem + //initializeContactConstraints(); +} + +// TODO : Delete this method +// Initialize the contact constraints before solving the system +void ContactSolver::initializeContactConstraints() { + + PROFILE("ContactSolver::initializeContactConstraints()"); + + // For each contact constraint + //for (uint c=0; c 0.0 ? contactPoint.inversePenetrationMass = decimal(1.0) / +// massPenetration : +// decimal(0.0); + + // If we do not solve the friction constraints at the center of the contact manifold +// if (!mIsSolveFrictionAtContactManifoldCenterActive) { + +// // Compute the friction vectors +// computeFrictionVectors(deltaV, contactPoint); + +// contactPoint.r1CrossT1 = contactPoint.r1.cross(contactPoint.frictionVector1); +// contactPoint.r1CrossT2 = contactPoint.r1.cross(contactPoint.frictionVector2); +// contactPoint.r2CrossT1 = contactPoint.r2.cross(contactPoint.frictionVector1); +// contactPoint.r2CrossT2 = contactPoint.r2.cross(contactPoint.frictionVector2); + +// // Compute the inverse mass matrix K for the friction +// // constraints at each contact point +// decimal friction1Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + +// ((I1 * contactPoint.r1CrossT1).cross(contactPoint.r1)).dot( +// contactPoint.frictionVector1) + +// ((I2 * contactPoint.r2CrossT1).cross(contactPoint.r2)).dot( +// contactPoint.frictionVector1); +// decimal friction2Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + +// ((I1 * contactPoint.r1CrossT2).cross(contactPoint.r1)).dot( +// contactPoint.frictionVector2) + +// ((I2 * contactPoint.r2CrossT2).cross(contactPoint.r2)).dot( +// contactPoint.frictionVector2); +// friction1Mass > 0.0 ? contactPoint.inverseFriction1Mass = decimal(1.0) / +// friction1Mass : +// decimal(0.0); +// friction2Mass > 0.0 ? contactPoint.inverseFriction2Mass = decimal(1.0) / +// friction2Mass : +// decimal(0.0); +// } + + // Compute the restitution velocity bias "b". We compute this here instead + // of inside the solve() method because we need to use the velocity difference + // at the beginning of the contact. Note that if it is a resting contact (normal + // velocity bellow a given threshold), we do not add a restitution velocity bias +// contactPoint.restitutionBias = 0.0; +// decimal deltaVDotN = deltaV.dot(contactPoint.normal); +// if (deltaVDotN < -RESTITUTION_VELOCITY_THRESHOLD) { +// contactPoint.restitutionBias = manifold.restitutionFactor * deltaVDotN; +// } + +// // If the warm starting of the contact solver is active +// if (mIsWarmStartingActive) { + +// // Get the cached accumulated impulses from the previous step +// contactPoint.penetrationImpulse = externalContact->getPenetrationImpulse(); +// contactPoint.friction1Impulse = externalContact->getFrictionImpulse1(); +// contactPoint.friction2Impulse = externalContact->getFrictionImpulse2(); +// contactPoint.rollingResistanceImpulse = externalContact->getRollingResistanceImpulse(); +// } + +// // Initialize the split impulses to zero +// contactPoint.penetrationSplitImpulse = 0.0; + +// // If we solve the friction constraints at the center of the contact manifold +// if (mIsSolveFrictionAtContactManifoldCenterActive) { +// manifold.normal += contactPoint.normal; +// } + //} + +// // Compute the inverse K matrix for the rolling resistance constraint +// manifold.inverseRollingResistance.setToZero(); +// if (manifold.rollingResistanceFactor > 0 && (manifold.isBody1DynamicType || manifold.isBody2DynamicType)) { +// manifold.inverseRollingResistance = manifold.inverseInertiaTensorBody1 + manifold.inverseInertiaTensorBody2; +// manifold.inverseRollingResistance = manifold.inverseRollingResistance.getInverse(); +// } + + // If we solve the friction constraints at the center of the contact manifold + //if (mIsSolveFrictionAtContactManifoldCenterActive) { + +// manifold.normal.normalize(); + +// Vector3 deltaVFrictionPoint = v2 + w2.cross(manifold.r2Friction) - +// v1 - w1.cross(manifold.r1Friction); + +// // Compute the friction vectors +// computeFrictionVectors(deltaVFrictionPoint, manifold); + +// // Compute the inverse mass matrix K for the friction constraints at the center of +// // the contact manifold +// manifold.r1CrossT1 = manifold.r1Friction.cross(manifold.frictionVector1); +// manifold.r1CrossT2 = manifold.r1Friction.cross(manifold.frictionVector2); +// manifold.r2CrossT1 = manifold.r2Friction.cross(manifold.frictionVector1); +// manifold.r2CrossT2 = manifold.r2Friction.cross(manifold.frictionVector2); +// decimal friction1Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + +// ((I1 * manifold.r1CrossT1).cross(manifold.r1Friction)).dot( +// manifold.frictionVector1) + +// ((I2 * manifold.r2CrossT1).cross(manifold.r2Friction)).dot( +// manifold.frictionVector1); +// decimal friction2Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + +// ((I1 * manifold.r1CrossT2).cross(manifold.r1Friction)).dot( +// manifold.frictionVector2) + +// ((I2 * manifold.r2CrossT2).cross(manifold.r2Friction)).dot( +// manifold.frictionVector2); +// decimal frictionTwistMass = manifold.normal.dot(manifold.inverseInertiaTensorBody1 * +// manifold.normal) + +// manifold.normal.dot(manifold.inverseInertiaTensorBody2 * +// manifold.normal); +// friction1Mass > 0.0 ? manifold.inverseFriction1Mass = decimal(1.0)/friction1Mass +// : decimal(0.0); +// friction2Mass > 0.0 ? manifold.inverseFriction2Mass = decimal(1.0)/friction2Mass +// : decimal(0.0); +// frictionTwistMass > 0.0 ? manifold.inverseTwistFrictionMass = decimal(1.0) / +// frictionTwistMass : +// decimal(0.0); + //} + //} } // Warm start the solver. @@ -333,6 +467,9 @@ void ContactSolver::initializeContactConstraints() { /// the solution of the linear system void ContactSolver::warmStart() { + /* + PROFILE("ContactSolver::warmStart()"); + // Check that warm starting is active if (!mIsWarmStartingActive) return; @@ -498,285 +635,516 @@ void ContactSolver::warmStart() { contactManifold.rollingResistanceImpulse = Vector3::zero(); } } + */ } -// Solve the contacts -void ContactSolver::solve() { +// Reset the total penetration impulse of friction constraints +void ContactSolver::resetTotalPenetrationImpulse() { - PROFILE("ContactSolver::solve()"); + for (uint i=0; i SLOP) biasPenetrationDepth = -(beta/mTimeStep) * + max(0.0f, float(mPenetrationConstraints[i].penetrationDepth - SLOP)); + decimal b = biasPenetrationDepth + mPenetrationConstraints[i].restitutionBias; - // --------- Penetration --------- // - - // Compute J*v - Vector3 deltaV = v2 + w2.cross(contactPoint.r2) - v1 - w1.cross(contactPoint.r1); - decimal deltaVDotN = deltaV.dot(contactPoint.normal); - decimal Jv = deltaVDotN; - - // Compute the bias "b" of the constraint - decimal beta = mIsSplitImpulseActive ? BETA_SPLIT_IMPULSE : BETA; - decimal biasPenetrationDepth = 0.0; - if (contactPoint.penetrationDepth > SLOP) biasPenetrationDepth = -(beta/mTimeStep) * - max(0.0f, float(contactPoint.penetrationDepth - SLOP)); - decimal b = biasPenetrationDepth + contactPoint.restitutionBias; - - // Compute the Lagrange multiplier lambda - if (mIsSplitImpulseActive) { - deltaLambda = - (Jv + contactPoint.restitutionBias) * - contactPoint.inversePenetrationMass; - } - else { - deltaLambda = - (Jv + b) * contactPoint.inversePenetrationMass; - } - lambdaTemp = contactPoint.penetrationImpulse; - contactPoint.penetrationImpulse = std::max(contactPoint.penetrationImpulse + - deltaLambda, decimal(0.0)); - deltaLambda = contactPoint.penetrationImpulse - lambdaTemp; - - // Compute the impulse P=J^T * lambda - const Impulse impulsePenetration = computePenetrationImpulse(deltaLambda, - contactPoint); - - // Apply the impulse to the bodies of the constraint - applyImpulse(impulsePenetration, contactManifold); - - sumPenetrationImpulse += contactPoint.penetrationImpulse; - - // If the split impulse position correction is active - if (mIsSplitImpulseActive) { - - // Split impulse (position correction) - const Vector3& v1Split = mSplitLinearVelocities[contactManifold.indexBody1]; - const Vector3& w1Split = mSplitAngularVelocities[contactManifold.indexBody1]; - const Vector3& v2Split = mSplitLinearVelocities[contactManifold.indexBody2]; - const Vector3& w2Split = mSplitAngularVelocities[contactManifold.indexBody2]; - Vector3 deltaVSplit = v2Split + w2Split.cross(contactPoint.r2) - - v1Split - w1Split.cross(contactPoint.r1); - decimal JvSplit = deltaVSplit.dot(contactPoint.normal); - decimal deltaLambdaSplit = - (JvSplit + biasPenetrationDepth) * - contactPoint.inversePenetrationMass; - decimal lambdaTempSplit = contactPoint.penetrationSplitImpulse; - contactPoint.penetrationSplitImpulse = std::max( - contactPoint.penetrationSplitImpulse + - deltaLambdaSplit, decimal(0.0)); - deltaLambda = contactPoint.penetrationSplitImpulse - lambdaTempSplit; - - // Compute the impulse P=J^T * lambda - const Impulse splitImpulsePenetration = computePenetrationImpulse( - deltaLambdaSplit, contactPoint); - - applySplitImpulse(splitImpulsePenetration, contactManifold); - } - - // If we do not solve the friction constraints at the center of the contact manifold - if (!mIsSolveFrictionAtContactManifoldCenterActive) { - - // --------- Friction 1 --------- // - - // Compute J*v - deltaV = v2 + w2.cross(contactPoint.r2) - v1 - w1.cross(contactPoint.r1); - Jv = deltaV.dot(contactPoint.frictionVector1); - - // Compute the Lagrange multiplier lambda - deltaLambda = -Jv; - deltaLambda *= contactPoint.inverseFriction1Mass; - decimal frictionLimit = contactManifold.frictionCoefficient * - contactPoint.penetrationImpulse; - lambdaTemp = contactPoint.friction1Impulse; - contactPoint.friction1Impulse = std::max(-frictionLimit, - std::min(contactPoint.friction1Impulse - + deltaLambda, frictionLimit)); - deltaLambda = contactPoint.friction1Impulse - lambdaTemp; - - // Compute the impulse P=J^T * lambda - const Impulse impulseFriction1 = computeFriction1Impulse(deltaLambda, - contactPoint); - - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseFriction1, contactManifold); - - // --------- Friction 2 --------- // - - // Compute J*v - deltaV = v2 + w2.cross(contactPoint.r2) - v1 - w1.cross(contactPoint.r1); - Jv = deltaV.dot(contactPoint.frictionVector2); - - // Compute the Lagrange multiplier lambda - deltaLambda = -Jv; - deltaLambda *= contactPoint.inverseFriction2Mass; - frictionLimit = contactManifold.frictionCoefficient * - contactPoint.penetrationImpulse; - lambdaTemp = contactPoint.friction2Impulse; - contactPoint.friction2Impulse = std::max(-frictionLimit, - std::min(contactPoint.friction2Impulse - + deltaLambda, frictionLimit)); - deltaLambda = contactPoint.friction2Impulse - lambdaTemp; - - // Compute the impulse P=J^T * lambda - const Impulse impulseFriction2 = computeFriction2Impulse(deltaLambda, - contactPoint); - - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseFriction2, contactManifold); - - // --------- Rolling resistance constraint --------- // - - if (contactManifold.rollingResistanceFactor > 0) { - - // Compute J*v - const Vector3 JvRolling = w2 - w1; - - // Compute the Lagrange multiplier lambda - Vector3 deltaLambdaRolling = contactManifold.inverseRollingResistance * (-JvRolling); - decimal rollingLimit = contactManifold.rollingResistanceFactor * contactPoint.penetrationImpulse; - Vector3 lambdaTempRolling = contactPoint.rollingResistanceImpulse; - contactPoint.rollingResistanceImpulse = clamp(contactPoint.rollingResistanceImpulse + - deltaLambdaRolling, rollingLimit); - deltaLambdaRolling = contactPoint.rollingResistanceImpulse - lambdaTempRolling; - - // Compute the impulse P=J^T * lambda - const Impulse impulseRolling(Vector3::zero(), -deltaLambdaRolling, - Vector3::zero(), deltaLambdaRolling); - - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseRolling, contactManifold); - } - } + // Compute the Lagrange multiplier lambda + if (mIsSplitImpulseActive) { + deltaLambda = - (Jv + mPenetrationConstraints[i].restitutionBias) * + mPenetrationConstraints[i].inversePenetrationMass; } + else { + deltaLambda = - (Jv + b) * mPenetrationConstraints[i].inversePenetrationMass; + } + lambdaTemp = mPenetrationConstraints[i].penetrationImpulse; + mPenetrationConstraints[i].penetrationImpulse = std::max(mPenetrationConstraints[i].penetrationImpulse + + deltaLambda, decimal(0.0)); + deltaLambda = mPenetrationConstraints[i].penetrationImpulse - lambdaTemp; - // If we solve the friction constraints at the center of the contact manifold - if (mIsSolveFrictionAtContactManifoldCenterActive) { + // Add the penetration impulse to the total impulse of the corresponding friction constraint + mFrictionConstraints[mPenetrationConstraints[i].indexFrictionConstraint].totalPenetrationImpulse += mPenetrationConstraints[i].penetrationImpulse; - // ------ First friction constraint at the center of the contact manifol ------ // + // Update the velocities of the body 1 by applying the impulse P=J^T * lambda + Vector3 linearImpulse = mPenetrationConstraints[i].normal * deltaLambda; + v1 += mPenetrationConstraints[i].massInverseBody1 * (-linearImpulse); + w1 += mPenetrationConstraints[i].inverseInertiaTensorBody1 * (-mPenetrationConstraints[i].r1CrossN * deltaLambda); - // Compute J*v - Vector3 deltaV = v2 + w2.cross(contactManifold.r2Friction) - - v1 - w1.cross(contactManifold.r1Friction); - decimal Jv = deltaV.dot(contactManifold.frictionVector1); + // Update the velocities of the body 1 by applying the impulse P=J^T * lambda + v2 += mPenetrationConstraints[i].massInverseBody2 * linearImpulse; + w2 += mPenetrationConstraints[i].inverseInertiaTensorBody2 * (mPenetrationConstraints[i].r2CrossN * deltaLambda); - // Compute the Lagrange multiplier lambda - decimal deltaLambda = -Jv * contactManifold.inverseFriction1Mass; - decimal frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; - lambdaTemp = contactManifold.friction1Impulse; - contactManifold.friction1Impulse = std::max(-frictionLimit, - std::min(contactManifold.friction1Impulse + - deltaLambda, frictionLimit)); - deltaLambda = contactManifold.friction1Impulse - lambdaTemp; + // If the split impulse position correction is active + if (mIsSplitImpulseActive) { - // Compute the impulse P=J^T * lambda - Vector3 linearImpulseBody1 = -contactManifold.frictionVector1 * deltaLambda; - Vector3 angularImpulseBody1 = -contactManifold.r1CrossT1 * deltaLambda; - Vector3 linearImpulseBody2 = contactManifold.frictionVector1 * deltaLambda; - Vector3 angularImpulseBody2 = contactManifold.r2CrossT1 * deltaLambda; - const Impulse impulseFriction1(linearImpulseBody1, angularImpulseBody1, - linearImpulseBody2, angularImpulseBody2); + // Split impulse (position correction) + const Vector3& v1Split = mSplitLinearVelocities[mPenetrationConstraints[i].indexBody1]; + const Vector3& w1Split = mSplitAngularVelocities[mPenetrationConstraints[i].indexBody1]; + const Vector3& v2Split = mSplitLinearVelocities[mPenetrationConstraints[i].indexBody2]; + const Vector3& w2Split = mSplitAngularVelocities[mPenetrationConstraints[i].indexBody2]; + Vector3 deltaVSplit = v2Split + w2Split.cross(mPenetrationConstraints[i].r2) - + v1Split - w1Split.cross(mPenetrationConstraints[i].r1); + decimal JvSplit = deltaVSplit.dot(mPenetrationConstraints[i].normal); + decimal deltaLambdaSplit = - (JvSplit + biasPenetrationDepth) * + mPenetrationConstraints[i].inversePenetrationMass; + decimal lambdaTempSplit = mPenetrationConstraints[i].penetrationSplitImpulse; + mPenetrationConstraints[i].penetrationSplitImpulse = std::max( + mPenetrationConstraints[i].penetrationSplitImpulse + + deltaLambdaSplit, decimal(0.0)); + deltaLambda = mPenetrationConstraints[i].penetrationSplitImpulse - lambdaTempSplit; - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseFriction1, contactManifold); + // Update the velocities of the body 1 by applying the impulse P=J^T * lambda + Vector3 linearImpulse = mPenetrationConstraints[i].normal * deltaLambdaSplit; + mSplitLinearVelocities[mPenetrationConstraints[i].indexBody1] += mPenetrationConstraints[i].massInverseBody1 * (-linearImpulse); + mSplitAngularVelocities[mPenetrationConstraints[i].indexBody1] += mPenetrationConstraints[i].inverseInertiaTensorBody1 * (-mPenetrationConstraints[i].r1CrossN * deltaLambdaSplit); - // ------ Second friction constraint at the center of the contact manifol ----- // - - // Compute J*v - deltaV = v2 + w2.cross(contactManifold.r2Friction) - - v1 - w1.cross(contactManifold.r1Friction); - Jv = deltaV.dot(contactManifold.frictionVector2); - - // Compute the Lagrange multiplier lambda - deltaLambda = -Jv * contactManifold.inverseFriction2Mass; - frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; - lambdaTemp = contactManifold.friction2Impulse; - contactManifold.friction2Impulse = std::max(-frictionLimit, - std::min(contactManifold.friction2Impulse + - deltaLambda, frictionLimit)); - deltaLambda = contactManifold.friction2Impulse - lambdaTemp; - - // Compute the impulse P=J^T * lambda - linearImpulseBody1 = -contactManifold.frictionVector2 * deltaLambda; - angularImpulseBody1 = -contactManifold.r1CrossT2 * deltaLambda; - linearImpulseBody2 = contactManifold.frictionVector2 * deltaLambda; - angularImpulseBody2 = contactManifold.r2CrossT2 * deltaLambda; - const Impulse impulseFriction2(linearImpulseBody1, angularImpulseBody1, - linearImpulseBody2, angularImpulseBody2); - - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseFriction2, contactManifold); - - // ------ Twist friction constraint at the center of the contact manifol ------ // - - // Compute J*v - deltaV = w2 - w1; - Jv = deltaV.dot(contactManifold.normal); - - deltaLambda = -Jv * (contactManifold.inverseTwistFrictionMass); - frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; - lambdaTemp = contactManifold.frictionTwistImpulse; - contactManifold.frictionTwistImpulse = std::max(-frictionLimit, - std::min(contactManifold.frictionTwistImpulse - + deltaLambda, frictionLimit)); - deltaLambda = contactManifold.frictionTwistImpulse - lambdaTemp; - - // Compute the impulse P=J^T * lambda - linearImpulseBody1 = Vector3(0.0, 0.0, 0.0); - angularImpulseBody1 = -contactManifold.normal * deltaLambda; - linearImpulseBody2 = Vector3(0.0, 0.0, 0.0);; - angularImpulseBody2 = contactManifold.normal * deltaLambda; - const Impulse impulseTwistFriction(linearImpulseBody1, angularImpulseBody1, - linearImpulseBody2, angularImpulseBody2); - - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseTwistFriction, contactManifold); - - // --------- Rolling resistance constraint at the center of the contact manifold --------- // - - if (contactManifold.rollingResistanceFactor > 0) { - - // Compute J*v - const Vector3 JvRolling = w2 - w1; - - // Compute the Lagrange multiplier lambda - Vector3 deltaLambdaRolling = contactManifold.inverseRollingResistance * (-JvRolling); - decimal rollingLimit = contactManifold.rollingResistanceFactor * sumPenetrationImpulse; - Vector3 lambdaTempRolling = contactManifold.rollingResistanceImpulse; - contactManifold.rollingResistanceImpulse = clamp(contactManifold.rollingResistanceImpulse + - deltaLambdaRolling, rollingLimit); - deltaLambdaRolling = contactManifold.rollingResistanceImpulse - lambdaTempRolling; - - // Compute the impulse P=J^T * lambda - angularImpulseBody1 = -deltaLambdaRolling; - angularImpulseBody2 = deltaLambdaRolling; - const Impulse impulseRolling(Vector3::zero(), angularImpulseBody1, - Vector3::zero(), angularImpulseBody2); - - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseRolling, contactManifold); - } + // Update the velocities of the body 1 by applying the impulse P=J^T * lambda + mSplitLinearVelocities[mPenetrationConstraints[i].indexBody2] += mPenetrationConstraints[i].massInverseBody2 * linearImpulse; + mSplitAngularVelocities[mPenetrationConstraints[i].indexBody2] += mPenetrationConstraints[i].inverseInertiaTensorBody2 * (mPenetrationConstraints[i].r2CrossN * deltaLambdaSplit); } } } +// Solve the friction constraints +void ContactSolver::solveFrictionConstraints() { + + // TODO : Check that the FrictionConstraint struct only contains variables that are + // used in this method, nothing more + + PROFILE("ContactSolver::solveFrictionConstraints()"); + + for (uint i=0; i 0) { + + // Compute J*v + const Vector3 JvRolling = w2 - w1; + + // Compute the Lagrange multiplier lambda + Vector3 deltaLambdaRolling = mFrictionConstraints[i].inverseRollingResistance * (-JvRolling); + decimal rollingLimit = mFrictionConstraints[i].rollingResistanceFactor * mFrictionConstraints[i].totalPenetrationImpulse; + Vector3 lambdaTempRolling = mFrictionConstraints[i].rollingResistanceImpulse; + mFrictionConstraints[i].rollingResistanceImpulse = clamp(mFrictionConstraints[i].rollingResistanceImpulse + + deltaLambdaRolling, rollingLimit); + deltaLambdaRolling = mFrictionConstraints[i].rollingResistanceImpulse - lambdaTempRolling; + + // Compute the impulse P=J^T * lambda + angularImpulseBody1 = -deltaLambdaRolling; + angularImpulseBody2 = deltaLambdaRolling; + + // Update the velocities of the body 1 by applying the impulse P + w1 += mFrictionConstraints[i].inverseInertiaTensorBody1 * angularImpulseBody1; + + // Update the velocities of the body 1 by applying the impulse P + w2 += mFrictionConstraints[i].inverseInertiaTensorBody2 * angularImpulseBody2; + } + } +} + +// Solve the contacts +//void ContactSolver::solve() { + +// PROFILE("ContactSolver::solve()"); + +// decimal deltaLambda; +// decimal lambdaTemp; + +// // For each contact manifold +// for (uint c=0; c SLOP) biasPenetrationDepth = -(beta/mTimeStep) * +// max(0.0f, float(contactPoint.penetrationDepth - SLOP)); +// decimal b = biasPenetrationDepth + contactPoint.restitutionBias; + +// // Compute the Lagrange multiplier lambda +// if (mIsSplitImpulseActive) { +// deltaLambda = - (Jv + contactPoint.restitutionBias) * +// contactPoint.inversePenetrationMass; +// } +// else { +// deltaLambda = - (Jv + b) * contactPoint.inversePenetrationMass; +// } +// lambdaTemp = contactPoint.penetrationImpulse; +// contactPoint.penetrationImpulse = std::max(contactPoint.penetrationImpulse + +// deltaLambda, decimal(0.0)); +// deltaLambda = contactPoint.penetrationImpulse - lambdaTemp; + +// // Compute the impulse P=J^T * lambda +// const Impulse impulsePenetration = computePenetrationImpulse(deltaLambda, +// contactPoint); + +// // Apply the impulse to the bodies of the constraint +// applyImpulse(impulsePenetration, contactManifold); + +// sumPenetrationImpulse += contactPoint.penetrationImpulse; + +// // If the split impulse position correction is active +// if (mIsSplitImpulseActive) { + +// // Split impulse (position correction) +// const Vector3& v1Split = mSplitLinearVelocities[contactManifold.indexBody1]; +// const Vector3& w1Split = mSplitAngularVelocities[contactManifold.indexBody1]; +// const Vector3& v2Split = mSplitLinearVelocities[contactManifold.indexBody2]; +// const Vector3& w2Split = mSplitAngularVelocities[contactManifold.indexBody2]; +// Vector3 deltaVSplit = v2Split + w2Split.cross(contactPoint.r2) - +// v1Split - w1Split.cross(contactPoint.r1); +// decimal JvSplit = deltaVSplit.dot(contactPoint.normal); +// decimal deltaLambdaSplit = - (JvSplit + biasPenetrationDepth) * +// contactPoint.inversePenetrationMass; +// decimal lambdaTempSplit = contactPoint.penetrationSplitImpulse; +// contactPoint.penetrationSplitImpulse = std::max( +// contactPoint.penetrationSplitImpulse + +// deltaLambdaSplit, decimal(0.0)); +// deltaLambda = contactPoint.penetrationSplitImpulse - lambdaTempSplit; + +// // Compute the impulse P=J^T * lambda +// const Impulse splitImpulsePenetration = computePenetrationImpulse( +// deltaLambdaSplit, contactPoint); + +// applySplitImpulse(splitImpulsePenetration, contactManifold); +// } + +// // If we do not solve the friction constraints at the center of the contact manifold +// if (!mIsSolveFrictionAtContactManifoldCenterActive) { + +// // --------- Friction 1 --------- // + +// // Compute J*v +// deltaV = v2 + w2.cross(contactPoint.r2) - v1 - w1.cross(contactPoint.r1); +// Jv = deltaV.dot(contactPoint.frictionVector1); + +// // Compute the Lagrange multiplier lambda +// deltaLambda = -Jv; +// deltaLambda *= contactPoint.inverseFriction1Mass; +// decimal frictionLimit = contactManifold.frictionCoefficient * +// contactPoint.penetrationImpulse; +// lambdaTemp = contactPoint.friction1Impulse; +// contactPoint.friction1Impulse = std::max(-frictionLimit, +// std::min(contactPoint.friction1Impulse +// + deltaLambda, frictionLimit)); +// deltaLambda = contactPoint.friction1Impulse - lambdaTemp; + +// // Compute the impulse P=J^T * lambda +// const Impulse impulseFriction1 = computeFriction1Impulse(deltaLambda, +// contactPoint); + +// // Apply the impulses to the bodies of the constraint +// applyImpulse(impulseFriction1, contactManifold); + +// // --------- Friction 2 --------- // + +// // Compute J*v +// deltaV = v2 + w2.cross(contactPoint.r2) - v1 - w1.cross(contactPoint.r1); +// Jv = deltaV.dot(contactPoint.frictionVector2); + +// // Compute the Lagrange multiplier lambda +// deltaLambda = -Jv; +// deltaLambda *= contactPoint.inverseFriction2Mass; +// frictionLimit = contactManifold.frictionCoefficient * +// contactPoint.penetrationImpulse; +// lambdaTemp = contactPoint.friction2Impulse; +// contactPoint.friction2Impulse = std::max(-frictionLimit, +// std::min(contactPoint.friction2Impulse +// + deltaLambda, frictionLimit)); +// deltaLambda = contactPoint.friction2Impulse - lambdaTemp; + +// // Compute the impulse P=J^T * lambda +// const Impulse impulseFriction2 = computeFriction2Impulse(deltaLambda, +// contactPoint); + +// // Apply the impulses to the bodies of the constraint +// applyImpulse(impulseFriction2, contactManifold); + +// // --------- Rolling resistance constraint --------- // + +// if (contactManifold.rollingResistanceFactor > 0) { + +// // Compute J*v +// const Vector3 JvRolling = w2 - w1; + +// // Compute the Lagrange multiplier lambda +// Vector3 deltaLambdaRolling = contactManifold.inverseRollingResistance * (-JvRolling); +// decimal rollingLimit = contactManifold.rollingResistanceFactor * contactPoint.penetrationImpulse; +// Vector3 lambdaTempRolling = contactPoint.rollingResistanceImpulse; +// contactPoint.rollingResistanceImpulse = clamp(contactPoint.rollingResistanceImpulse + +// deltaLambdaRolling, rollingLimit); +// deltaLambdaRolling = contactPoint.rollingResistanceImpulse - lambdaTempRolling; + +// // Compute the impulse P=J^T * lambda +// const Impulse impulseRolling(Vector3::zero(), -deltaLambdaRolling, +// Vector3::zero(), deltaLambdaRolling); + +// // Apply the impulses to the bodies of the constraint +// applyImpulse(impulseRolling, contactManifold); +// } +// } + //} + + // If we solve the friction constraints at the center of the contact manifold +// if (mIsSolveFrictionAtContactManifoldCenterActive) { + +// // ------ First friction constraint at the center of the contact manifol ------ // + +// // Compute J*v +// Vector3 deltaV = v2 + w2.cross(contactManifold.r2Friction) +// - v1 - w1.cross(contactManifold.r1Friction); +// decimal Jv = deltaV.dot(contactManifold.frictionVector1); + +// // Compute the Lagrange multiplier lambda +// decimal deltaLambda = -Jv * contactManifold.inverseFriction1Mass; +// decimal frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; +// lambdaTemp = contactManifold.friction1Impulse; +// contactManifold.friction1Impulse = std::max(-frictionLimit, +// std::min(contactManifold.friction1Impulse + +// deltaLambda, frictionLimit)); +// deltaLambda = contactManifold.friction1Impulse - lambdaTemp; + +// // Compute the impulse P=J^T * lambda +// Vector3 linearImpulseBody1 = -contactManifold.frictionVector1 * deltaLambda; +// Vector3 angularImpulseBody1 = -contactManifold.r1CrossT1 * deltaLambda; +// Vector3 linearImpulseBody2 = contactManifold.frictionVector1 * deltaLambda; +// Vector3 angularImpulseBody2 = contactManifold.r2CrossT1 * deltaLambda; +// const Impulse impulseFriction1(linearImpulseBody1, angularImpulseBody1, +// linearImpulseBody2, angularImpulseBody2); + +// // Apply the impulses to the bodies of the constraint +// applyImpulse(impulseFriction1, contactManifold); + +// // ------ Second friction constraint at the center of the contact manifol ----- // + +// // Compute J*v +// deltaV = v2 + w2.cross(contactManifold.r2Friction) +// - v1 - w1.cross(contactManifold.r1Friction); +// Jv = deltaV.dot(contactManifold.frictionVector2); + +// // Compute the Lagrange multiplier lambda +// deltaLambda = -Jv * contactManifold.inverseFriction2Mass; +// frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; +// lambdaTemp = contactManifold.friction2Impulse; +// contactManifold.friction2Impulse = std::max(-frictionLimit, +// std::min(contactManifold.friction2Impulse + +// deltaLambda, frictionLimit)); +// deltaLambda = contactManifold.friction2Impulse - lambdaTemp; + +// // Compute the impulse P=J^T * lambda +// linearImpulseBody1 = -contactManifold.frictionVector2 * deltaLambda; +// angularImpulseBody1 = -contactManifold.r1CrossT2 * deltaLambda; +// linearImpulseBody2 = contactManifold.frictionVector2 * deltaLambda; +// angularImpulseBody2 = contactManifold.r2CrossT2 * deltaLambda; +// const Impulse impulseFriction2(linearImpulseBody1, angularImpulseBody1, +// linearImpulseBody2, angularImpulseBody2); + +// // Apply the impulses to the bodies of the constraint +// applyImpulse(impulseFriction2, contactManifold); + +// // ------ Twist friction constraint at the center of the contact manifol ------ // + +// // Compute J*v +// deltaV = w2 - w1; +// Jv = deltaV.dot(contactManifold.normal); + +// deltaLambda = -Jv * (contactManifold.inverseTwistFrictionMass); +// frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; +// lambdaTemp = contactManifold.frictionTwistImpulse; +// contactManifold.frictionTwistImpulse = std::max(-frictionLimit, +// std::min(contactManifold.frictionTwistImpulse +// + deltaLambda, frictionLimit)); +// deltaLambda = contactManifold.frictionTwistImpulse - lambdaTemp; + +// // Compute the impulse P=J^T * lambda +// linearImpulseBody1 = Vector3(0.0, 0.0, 0.0); +// angularImpulseBody1 = -contactManifold.normal * deltaLambda; +// linearImpulseBody2 = Vector3(0.0, 0.0, 0.0);; +// angularImpulseBody2 = contactManifold.normal * deltaLambda; +// const Impulse impulseTwistFriction(linearImpulseBody1, angularImpulseBody1, +// linearImpulseBody2, angularImpulseBody2); + +// // Apply the impulses to the bodies of the constraint +// applyImpulse(impulseTwistFriction, contactManifold); + +// // --------- Rolling resistance constraint at the center of the contact manifold --------- // + +// if (contactManifold.rollingResistanceFactor > 0) { + +// // Compute J*v +// const Vector3 JvRolling = w2 - w1; + +// // Compute the Lagrange multiplier lambda +// Vector3 deltaLambdaRolling = contactManifold.inverseRollingResistance * (-JvRolling); +// decimal rollingLimit = contactManifold.rollingResistanceFactor * sumPenetrationImpulse; +// Vector3 lambdaTempRolling = contactManifold.rollingResistanceImpulse; +// contactManifold.rollingResistanceImpulse = clamp(contactManifold.rollingResistanceImpulse + +// deltaLambdaRolling, rollingLimit); +// deltaLambdaRolling = contactManifold.rollingResistanceImpulse - lambdaTempRolling; + +// // Compute the impulse P=J^T * lambda +// angularImpulseBody1 = -deltaLambdaRolling; +// angularImpulseBody2 = deltaLambdaRolling; +// const Impulse impulseRolling(Vector3::zero(), angularImpulseBody1, +// Vector3::zero(), angularImpulseBody2); + +// // Apply the impulses to the bodies of the constraint +// applyImpulse(impulseRolling, contactManifold); +// } +// } +// } +//} + // Store the computed impulses to use them to // warm start the solver at the next iteration void ContactSolver::storeImpulses() { + /* // For each contact manifold for (uint c=0; csetFrictionVector1(manifold.frictionVector1); manifold.externalContactManifold->setFrictionVector2(manifold.frictionVector2); } + */ } +/* // Apply an impulse to the two bodies of a constraint void ContactSolver::applyImpulse(const Impulse& impulse, const ContactManifoldSolver& manifold) { + PROFILE("ContactSolver::applyImpulse()"); + // Update the velocities of the body 1 by applying the impulse P mLinearVelocities[manifold.indexBody1] += manifold.massInverseBody1 * impulse.linearImpulseBody1; @@ -820,7 +1192,9 @@ void ContactSolver::applyImpulse(const Impulse& impulse, mAngularVelocities[manifold.indexBody2] += manifold.inverseInertiaTensorBody2 * impulse.angularImpulseBody2; } +*/ +/* // Apply an impulse to the two bodies of a constraint void ContactSolver::applySplitImpulse(const Impulse& impulse, const ContactManifoldSolver& manifold) { @@ -837,46 +1211,48 @@ void ContactSolver::applySplitImpulse(const Impulse& impulse, mSplitAngularVelocities[manifold.indexBody2] += manifold.inverseInertiaTensorBody2 * impulse.angularImpulseBody2; } +*/ +// TODO : Delete this // Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction plane // for a contact point. The two vectors have to be such that : t1 x t2 = contactNormal. -void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, - ContactPointSolver& contactPoint) const { +//void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, +// ContactPointSolver& contactPoint) const { - assert(contactPoint.normal.length() > 0.0); +// assert(contactPoint.normal.length() > 0.0); - // Compute the velocity difference vector in the tangential plane - Vector3 normalVelocity = deltaVelocity.dot(contactPoint.normal) * contactPoint.normal; - Vector3 tangentVelocity = deltaVelocity - normalVelocity; +// // Compute the velocity difference vector in the tangential plane +// Vector3 normalVelocity = deltaVelocity.dot(contactPoint.normal) * contactPoint.normal; +// Vector3 tangentVelocity = deltaVelocity - normalVelocity; - // If the velocty difference in the tangential plane is not zero - decimal lengthTangenVelocity = tangentVelocity.length(); - if (lengthTangenVelocity > MACHINE_EPSILON) { +// // If the velocty difference in the tangential plane is not zero +// decimal lengthTangenVelocity = tangentVelocity.length(); +// if (lengthTangenVelocity > MACHINE_EPSILON) { - // Compute the first friction vector in the direction of the tangent - // velocity difference - contactPoint.frictionVector1 = tangentVelocity / lengthTangenVelocity; - } - else { +// // Compute the first friction vector in the direction of the tangent +// // velocity difference +// contactPoint.frictionVector1 = tangentVelocity / lengthTangenVelocity; +// } +// else { - // Get any orthogonal vector to the normal as the first friction vector - contactPoint.frictionVector1 = contactPoint.normal.getOneUnitOrthogonalVector(); - } +// // Get any orthogonal vector to the normal as the first friction vector +// contactPoint.frictionVector1 = contactPoint.normal.getOneUnitOrthogonalVector(); +// } - // The second friction vector is computed by the cross product of the firs - // friction vector and the contact normal - contactPoint.frictionVector2 =contactPoint.normal.cross(contactPoint.frictionVector1).getUnit(); -} +// // The second friction vector is computed by the cross product of the firs +// // friction vector and the contact normal +// contactPoint.frictionVector2 =contactPoint.normal.cross(contactPoint.frictionVector1).getUnit(); +//} // Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction plane // for a contact manifold. The two vectors have to be such that : t1 x t2 = contactNormal. void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, - ContactManifoldSolver& contact) const { + FrictionConstraint& frictionConstraint) const { - assert(contact.normal.length() > 0.0); + assert(frictionConstraint.normal.length() > MACHINE_EPSILON); // Compute the velocity difference vector in the tangential plane - Vector3 normalVelocity = deltaVelocity.dot(contact.normal) * contact.normal; + Vector3 normalVelocity = deltaVelocity.dot(frictionConstraint.normal) * frictionConstraint.normal; Vector3 tangentVelocity = deltaVelocity - normalVelocity; // If the velocty difference in the tangential plane is not zero @@ -885,17 +1261,17 @@ void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, // Compute the first friction vector in the direction of the tangent // velocity difference - contact.frictionVector1 = tangentVelocity / lengthTangenVelocity; + frictionConstraint.frictionVector1 = tangentVelocity / lengthTangenVelocity; } else { // Get any orthogonal vector to the normal as the first friction vector - contact.frictionVector1 = contact.normal.getOneUnitOrthogonalVector(); + frictionConstraint.frictionVector1 = frictionConstraint.normal.getOneUnitOrthogonalVector(); } // The second friction vector is computed by the cross product of the firs // friction vector and the contact normal - contact.frictionVector2 = contact.normal.cross(contact.frictionVector1).getUnit(); + frictionConstraint.frictionVector2 = frictionConstraint.normal.cross(frictionConstraint.frictionVector1).getUnit(); } // Clean up the constraint solver @@ -905,4 +1281,14 @@ void ContactSolver::cleanup() { delete[] mContactConstraints; mContactConstraints = nullptr; } + + if (mPenetrationConstraints != nullptr) { + delete[] mPenetrationConstraints; + mPenetrationConstraints = nullptr; + } + + if (mFrictionConstraints != nullptr) { + delete[] mFrictionConstraints; + mFrictionConstraints = nullptr; + } } diff --git a/src/engine/ContactSolver.h b/src/engine/ContactSolver.h index ae2005f4..ef0087a0 100644 --- a/src/engine/ContactSolver.h +++ b/src/engine/ContactSolver.h @@ -39,7 +39,6 @@ /// ReactPhysics3D namespace namespace reactphysics3d { - // Class Contact Solver /** * This class represents the contact solver that is used to solve rigid bodies contacts. @@ -113,6 +112,156 @@ class ContactSolver { private: + struct PenetrationConstraint { + + /// Index of body 1 in the constraint solver + uint indexBody1; + + /// Index of body 2 in the constraint solver + uint indexBody2; + + /// Normal vector of the contact + Vector3 normal; + + /// Vector from the body 1 center to the contact point + Vector3 r1; + + /// Vector from the body 2 center to the contact point + Vector3 r2; + + /// Cross product of r1 with the contact normal + Vector3 r1CrossN; + + /// Cross product of r2 with the contact normal + Vector3 r2CrossN; + + /// Penetration depth + decimal penetrationDepth; + + /// Velocity restitution bias + decimal restitutionBias; + + /// Mix of the restitution factor for two bodies + decimal restitutionFactor; + + /// Accumulated normal impulse + decimal penetrationImpulse; + + /// Accumulated split impulse for penetration correction + decimal penetrationSplitImpulse; + + /// Inverse of the mass of body 1 + decimal massInverseBody1; + + /// Inverse of the mass of body 2 + decimal massInverseBody2; + + /// Inverse of the matrix K for the penenetration + decimal inversePenetrationMass; + + /// Inverse inertia tensor of body 1 + Matrix3x3 inverseInertiaTensorBody1; + + /// Inverse inertia tensor of body 2 + Matrix3x3 inverseInertiaTensorBody2; + + /// Index of the corresponding friction constraint + uint indexFrictionConstraint; + }; + + struct FrictionConstraint { + + /// Index of body 1 in the constraint solver + uint indexBody1; + + /// Index of body 2 in the constraint solver + uint indexBody2; + + /// R1 vector for the friction constraints + Vector3 r1Friction; + + /// R2 vector for the friction constraints + Vector3 r2Friction; + + /// Point on body 1 where to apply the friction constraints + Vector3 frictionPointBody1; + + /// Point on body 2 where to apply the friction constraints + Vector3 frictionPointBody2; + + /// Average normal vector of the contact manifold + Vector3 normal; + + /// Accumulated impulse in the 1st friction direction + decimal friction1Impulse; + + /// Accumulated impulse in the 2nd friction direction + decimal friction2Impulse; + + /// Twist friction impulse at contact manifold center + decimal frictionTwistImpulse; + + /// Accumulated rolling resistance impulse + Vector3 rollingResistanceImpulse; + + /// Rolling resistance factor between the two bodies + decimal rollingResistanceFactor; + + /// Mix friction coefficient for the two bodies + decimal frictionCoefficient; + + /// First friction vector in the tangent plane + Vector3 frictionVector1; + + /// Second friction vector in the tangent plane + Vector3 frictionVector2; + + /// Old 1st friction direction at contact manifold center + Vector3 oldFrictionVector1; + + /// Old 2nd friction direction at contact manifold center + Vector3 oldFrictionVector2; + + /// Cross product of r1 with 1st friction vector + Vector3 r1CrossT1; + + /// Cross product of r1 with 2nd friction vector + Vector3 r1CrossT2; + + /// Cross product of r2 with 1st friction vector + Vector3 r2CrossT1; + + /// Cross product of r2 with 2nd friction vector + Vector3 r2CrossT2; + + /// Total of the all the corresponding penetration impulses + decimal totalPenetrationImpulse; + + /// Inverse of the matrix K for the 1st friction + decimal inverseFriction1Mass; + + /// Inverse of the matrix K for the 2nd friction + decimal inverseFriction2Mass; + + /// Matrix K for the twist friction constraint + decimal inverseTwistFrictionMass; + + /// Matrix K for the rolling resistance constraint + Matrix3x3 inverseRollingResistance; + + /// Inverse of the mass of body 1 + decimal massInverseBody1; + + /// Inverse of the mass of body 2 + decimal massInverseBody2; + + /// Inverse inertia tensor of body 1 + Matrix3x3 inverseInertiaTensorBody1; + + /// Inverse inertia tensor of body 2 + Matrix3x3 inverseInertiaTensorBody2; + }; + // Structure ContactPointSolver /** * Contact solver internal data structure that to store all the @@ -120,6 +269,30 @@ class ContactSolver { */ struct ContactPointSolver { + /// Index of body 1 in the constraint solver + uint indexBody1; + + /// Index of body 2 in the constraint solver + uint indexBody2; + + /// Inverse of the mass of body 1 + decimal massInverseBody1; + + /// Inverse of the mass of body 2 + decimal massInverseBody2; + + /// Inverse inertia tensor of body 1 + Matrix3x3 inverseInertiaTensorBody1; + + /// Inverse inertia tensor of body 2 + Matrix3x3 inverseInertiaTensorBody2; + + /// Point on body 1 where to apply the friction constraints + Vector3 frictionPointBody1; + + /// Point on body 2 where to apply the friction constraints + Vector3 frictionPointBody2; + /// Accumulated normal impulse decimal penetrationImpulse; @@ -139,10 +312,10 @@ class ContactSolver { Vector3 normal; /// First friction vector in the tangent plane - Vector3 frictionVector1; + //Vector3 frictionVector1; /// Second friction vector in the tangent plane - Vector3 frictionVector2; + //Vector3 frictionVector2; /// Old first friction vector in the tangent plane Vector3 oldFrictionVector1; @@ -157,22 +330,22 @@ class ContactSolver { Vector3 r2; /// Cross product of r1 with 1st friction vector - Vector3 r1CrossT1; + //Vector3 r1CrossT1; /// Cross product of r1 with 2nd friction vector - Vector3 r1CrossT2; + //Vector3 r1CrossT2; /// Cross product of r2 with 1st friction vector - Vector3 r2CrossT1; + //Vector3 r2CrossT1; /// Cross product of r2 with 2nd friction vector - Vector3 r2CrossT2; + //Vector3 r2CrossT2; /// Cross product of r1 with the contact normal - Vector3 r1CrossN; + //Vector3 r1CrossN; /// Cross product of r2 with the contact normal - Vector3 r2CrossN; + //Vector3 r2CrossN; /// Penetration depth decimal penetrationDepth; @@ -181,7 +354,7 @@ class ContactSolver { decimal restitutionBias; /// Inverse of the matrix K for the penenetration - decimal inversePenetrationMass; + //decimal inversePenetrationMass; /// Inverse of the matrix K for the 1st friction decimal inverseFriction1Mass; @@ -204,40 +377,40 @@ class ContactSolver { struct ContactManifoldSolver { /// Index of body 1 in the constraint solver - uint indexBody1; + //uint indexBody1; /// Index of body 2 in the constraint solver - uint indexBody2; + //uint indexBody2; /// Inverse of the mass of body 1 - decimal massInverseBody1; + //decimal massInverseBody1; // Inverse of the mass of body 2 - decimal massInverseBody2; + //decimal massInverseBody2; /// Inverse inertia tensor of body 1 - Matrix3x3 inverseInertiaTensorBody1; + //Matrix3x3 inverseInertiaTensorBody1; /// Inverse inertia tensor of body 2 - Matrix3x3 inverseInertiaTensorBody2; + //Matrix3x3 inverseInertiaTensorBody2; /// Contact point constraints - ContactPointSolver contacts[MAX_CONTACT_POINTS_IN_MANIFOLD]; + //ContactPointSolver contacts[MAX_CONTACT_POINTS_IN_MANIFOLD]; /// Number of contact points - uint nbContacts; + //uint nbContacts; /// True if the body 1 is of type dynamic - bool isBody1DynamicType; + //bool isBody1DynamicType; /// True if the body 2 is of type dynamic - bool isBody2DynamicType; + //bool isBody2DynamicType; /// Mix of the restitution factor for two bodies - decimal restitutionFactor; + //decimal restitutionFactor; /// Mix friction coefficient for the two bodies - decimal frictionCoefficient; + //decimal frictionCoefficient; /// Rolling resistance factor between the two bodies decimal rollingResistanceFactor; @@ -248,67 +421,67 @@ class ContactSolver { // - Variables used when friction constraints are apply at the center of the manifold-// /// Average normal vector of the contact manifold - Vector3 normal; + //Vector3 normal; /// Point on body 1 where to apply the friction constraints - Vector3 frictionPointBody1; + //Vector3 frictionPointBody1; /// Point on body 2 where to apply the friction constraints - Vector3 frictionPointBody2; + //Vector3 frictionPointBody2; /// R1 vector for the friction constraints - Vector3 r1Friction; + //Vector3 r1Friction; /// R2 vector for the friction constraints - Vector3 r2Friction; + //Vector3 r2Friction; /// Cross product of r1 with 1st friction vector - Vector3 r1CrossT1; + //Vector3 r1CrossT1; /// Cross product of r1 with 2nd friction vector - Vector3 r1CrossT2; + //Vector3 r1CrossT2; /// Cross product of r2 with 1st friction vector - Vector3 r2CrossT1; + //Vector3 r2CrossT1; /// Cross product of r2 with 2nd friction vector - Vector3 r2CrossT2; + //Vector3 r2CrossT2; /// Matrix K for the first friction constraint - decimal inverseFriction1Mass; + //decimal inverseFriction1Mass; /// Matrix K for the second friction constraint - decimal inverseFriction2Mass; + //decimal inverseFriction2Mass; /// Matrix K for the twist friction constraint - decimal inverseTwistFrictionMass; + //decimal inverseTwistFrictionMass; /// Matrix K for the rolling resistance constraint - Matrix3x3 inverseRollingResistance; + //Matrix3x3 inverseRollingResistance; /// First friction direction at contact manifold center - Vector3 frictionVector1; + //Vector3 frictionVector1; /// Second friction direction at contact manifold center - Vector3 frictionVector2; + //Vector3 frictionVector2; /// Old 1st friction direction at contact manifold center - Vector3 oldFrictionVector1; + //Vector3 oldFrictionVector1; /// Old 2nd friction direction at contact manifold center - Vector3 oldFrictionVector2; + //Vector3 oldFrictionVector2; /// First friction direction impulse at manifold center - decimal friction1Impulse; + //decimal friction1Impulse; /// Second friction direction impulse at manifold center - decimal friction2Impulse; + //decimal friction2Impulse; /// Twist friction impulse at contact manifold center - decimal frictionTwistImpulse; + //decimal frictionTwistImpulse; /// Rolling resistance impulse - Vector3 rollingResistanceImpulse; + //Vector3 rollingResistanceImpulse; }; // -------------------- Constants --------------------- // @@ -336,6 +509,14 @@ class ContactSolver { /// Contact constraints ContactManifoldSolver* mContactConstraints; + PenetrationConstraint* mPenetrationConstraints; + + FrictionConstraint* mFrictionConstraints; + + uint mNbPenetrationConstraints; + + uint mNbFrictionConstraints; + /// Number of contact constraints uint mNbContactManifolds; @@ -364,11 +545,11 @@ class ContactSolver { void initializeContactConstraints(); /// Apply an impulse to the two bodies of a constraint - void applyImpulse(const Impulse& impulse, const ContactManifoldSolver& manifold); + //void applyImpulse(const Impulse& impulse, const ContactManifoldSolver& manifold); /// Apply an impulse to the two bodies of a constraint - void applySplitImpulse(const Impulse& impulse, - const ContactManifoldSolver& manifold); + //void applySplitImpulse(const Impulse& impulse, + // const ContactManifoldSolver& manifold); /// Compute the collision restitution factor from the restitution factor of each body decimal computeMixedRestitutionFactor(RigidBody *body1, @@ -381,29 +562,30 @@ class ContactSolver { /// Compute th mixed rolling resistance factor between two bodies decimal computeMixedRollingResistance(RigidBody* body1, RigidBody* body2) const; + // TODO : Delete this /// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction /// plane for a contact point. The two vectors have to be /// such that : t1 x t2 = contactNormal. - void computeFrictionVectors(const Vector3& deltaVelocity, - ContactPointSolver &contactPoint) const; +// void computeFrictionVectors(const Vector3& deltaVelocity, +// ContactPointSolver &contactPoint) const; /// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction /// plane for a contact manifold. The two vectors have to be /// such that : t1 x t2 = contactNormal. void computeFrictionVectors(const Vector3& deltaVelocity, - ContactManifoldSolver& contactPoint) const; + FrictionConstraint& frictionConstraint) const; /// Compute a penetration constraint impulse - const Impulse computePenetrationImpulse(decimal deltaLambda, - const ContactPointSolver& contactPoint) const; +// const Impulse computePenetrationImpulse(decimal deltaLambda, +// const PenetrationConstraint& constraint) const; /// Compute the first friction constraint impulse const Impulse computeFriction1Impulse(decimal deltaLambda, - const ContactPointSolver& contactPoint) const; + const FrictionConstraint& contactPoint) const; /// Compute the second friction constraint impulse const Impulse computeFriction2Impulse(decimal deltaLambda, - const ContactPointSolver& contactPoint) const; + const FrictionConstraint& contactPoint) const; public: @@ -434,7 +616,16 @@ class ContactSolver { void storeImpulses(); /// Solve the contacts - void solve(); + //void solve(); + + /// Reset the total penetration impulse of friction constraints + void resetTotalPenetrationImpulse(); + + /// Solve the penetration constraints + void solvePenetrationConstraints(); + + /// Solve the friction constraints + void solveFrictionConstraints(); /// Return true if the split impulses position correction technique is used for contacts bool isSplitImpulseActive() const; @@ -502,7 +693,7 @@ inline decimal ContactSolver::computeMixedRestitutionFactor(RigidBody* body1, inline decimal ContactSolver::computeMixedFrictionCoefficient(RigidBody *body1, RigidBody *body2) const { // Use the geometric mean to compute the mixed friction coefficient - return sqrt(body1->getMaterial().getFrictionCoefficient() * + return std::sqrt(body1->getMaterial().getFrictionCoefficient() * body2->getMaterial().getFrictionCoefficient()); } @@ -513,16 +704,16 @@ inline decimal ContactSolver::computeMixedRollingResistance(RigidBody* body1, } // Compute a penetration constraint impulse -inline const Impulse ContactSolver::computePenetrationImpulse(decimal deltaLambda, - const ContactPointSolver& contactPoint) - const { - return Impulse(-contactPoint.normal * deltaLambda, -contactPoint.r1CrossN * deltaLambda, - contactPoint.normal * deltaLambda, contactPoint.r2CrossN * deltaLambda); -} +//inline const Impulse ContactSolver::computePenetrationImpulse(decimal deltaLambda, +// const PenetrationConstraint& constraint) +// const { +// return Impulse(-constraint.normal * deltaLambda, -constraint.r1CrossN * deltaLambda, +// constraint.normal * deltaLambda, constraint.r2CrossN * deltaLambda); +//} // Compute the first friction constraint impulse inline const Impulse ContactSolver::computeFriction1Impulse(decimal deltaLambda, - const ContactPointSolver& contactPoint) + const FrictionConstraint& contactPoint) const { return Impulse(-contactPoint.frictionVector1 * deltaLambda, -contactPoint.r1CrossT1 * deltaLambda, @@ -532,7 +723,7 @@ inline const Impulse ContactSolver::computeFriction1Impulse(decimal deltaLambda, // Compute the second friction constraint impulse inline const Impulse ContactSolver::computeFriction2Impulse(decimal deltaLambda, - const ContactPointSolver& contactPoint) + const FrictionConstraint& contactPoint) const { return Impulse(-contactPoint.frictionVector2 * deltaLambda, -contactPoint.r1CrossT2 * deltaLambda, diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index 2f601edd..4bd7aa19 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -353,6 +353,8 @@ void DynamicsWorld::solveContactsAndConstraints() { PROFILE("DynamicsWorld::solveContactsAndConstraints()"); + // TODO : Do not solve per island but solve every constraints at once + // Set the velocities arrays mContactSolver.setSplitVelocitiesArrays(mSplitLinearVelocities, mSplitAngularVelocities); mContactSolver.setConstrainedVelocitiesArrays(mConstrainedLinearVelocities, @@ -398,7 +400,13 @@ void DynamicsWorld::solveContactsAndConstraints() { } // Solve the contacts - if (isContactsToSolve) mContactSolver.solve(); + if (isContactsToSolve) { + + mContactSolver.resetTotalPenetrationImpulse(); + + mContactSolver.solvePenetrationConstraints(); + mContactSolver.solveFrictionConstraints(); + } } // Cache the lambda values in order to use them in the next diff --git a/src/mathematics/Vector3.cpp b/src/mathematics/Vector3.cpp index ed29a37f..ab2d126d 100644 --- a/src/mathematics/Vector3.cpp +++ b/src/mathematics/Vector3.cpp @@ -65,17 +65,17 @@ Vector3 Vector3::getOneUnitOrthogonalVector() const { assert(length() > MACHINE_EPSILON); // Get the minimum element of the vector - Vector3 vectorAbs(fabs(x), fabs(y), fabs(z)); + Vector3 vectorAbs(std::fabs(x), std::fabs(y), std::fabs(z)); int minElement = vectorAbs.getMinAxis(); if (minElement == 0) { - return Vector3(0.0, -z, y) / sqrt(y*y + z*z); + return Vector3(0.0, -z, y) / std::sqrt(y*y + z*z); } else if (minElement == 1) { - return Vector3(-z, 0.0, x) / sqrt(x*x + z*z); + return Vector3(-z, 0.0, x) / std::sqrt(x*x + z*z); } else { - return Vector3(-y, x, 0.0) / sqrt(x*x + y*y); + return Vector3(-y, x, 0.0) / std::sqrt(x*x + y*y); } } From b4f13308de720524e91f07a03c82744d59b6eba5 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 13 Sep 2016 22:58:17 +0200 Subject: [PATCH 024/248] Optimize warmstarting in contact solver --- src/engine/ContactSolver.cpp | 141 +++++++++++++++++++++++++++++++++-- src/engine/ContactSolver.h | 24 ++++++ src/engine/DynamicsWorld.cpp | 4 +- src/engine/Island.h | 4 +- 4 files changed, 164 insertions(+), 9 deletions(-) diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index 22359b10..4e2e0eec 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -38,15 +38,13 @@ const decimal ContactSolver::BETA = decimal(0.2); const decimal ContactSolver::BETA_SPLIT_IMPULSE = decimal(0.2); const decimal ContactSolver::SLOP= decimal(0.01); -// TODO : Enable warmstarting again - // Constructor ContactSolver::ContactSolver(const std::map& mapBodyToVelocityIndex) :mSplitLinearVelocities(nullptr), mSplitAngularVelocities(nullptr), mContactConstraints(nullptr), mPenetrationConstraints(nullptr), mFrictionConstraints(nullptr), mLinearVelocities(nullptr), mAngularVelocities(nullptr), mMapBodyToConstrainedVelocityIndex(mapBodyToVelocityIndex), - mIsWarmStartingActive(false), mIsSplitImpulseActive(true), + mIsWarmStartingActive(true), mIsSplitImpulseActive(true), mIsSolveFrictionAtContactManifoldCenterActive(true) { } @@ -83,7 +81,7 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { assert(mFrictionConstraints != nullptr); // For each contact manifold of the island - ContactManifold** contactManifolds = island->getContactManifold(); + ContactManifold** contactManifolds = island->getContactManifolds(); for (uint i=0; imCenterOfMassWorld; @@ -131,6 +130,7 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { mFrictionConstraints[mNbFrictionConstraints].frictionCoefficient = computeMixedFrictionCoefficient(body1, body2); mFrictionConstraints[mNbFrictionConstraints].rollingResistanceFactor = computeMixedRollingResistance(body1, body2); internalManifold.externalContactManifold = externalManifold; + mFrictionConstraints[mNbFrictionConstraints].hasAtLeastOneRestingContactPoint = false; //internalManifold.isBody1DynamicType = body1->getType() == BodyType::DYNAMIC; //internalManifold.isBody2DynamicType = body2->getType() == BodyType::DYNAMIC; @@ -167,6 +167,7 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { mPenetrationConstraints[mNbPenetrationConstraints].massInverseBody2 = body2->mMassInverse; mPenetrationConstraints[mNbPenetrationConstraints].restitutionFactor = restitutionFactor; mPenetrationConstraints[mNbPenetrationConstraints].indexFrictionConstraint = mNbFrictionConstraints; + mPenetrationConstraints[mNbPenetrationConstraints].contactPoint = externalContact; // Get the contact point on the two bodies Vector3 p1 = externalContact->getWorldPointOnBody1(); @@ -178,7 +179,10 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { //mPenetrationConstraints[penConstIndex].externalContact = externalContact; mPenetrationConstraints[mNbPenetrationConstraints].normal = externalContact->getNormal(); mPenetrationConstraints[mNbPenetrationConstraints].penetrationDepth = externalContact->getPenetrationDepth(); - //mPenetrationConstraints[penConstIndex].isRestingContact = externalContact->getIsRestingContact(); + mPenetrationConstraints[mNbPenetrationConstraints].isRestingContact = externalContact->getIsRestingContact(); + + mFrictionConstraints[mNbFrictionConstraints].hasAtLeastOneRestingContactPoint |= mPenetrationConstraints[mNbPenetrationConstraints].isRestingContact; + externalContact->setIsRestingContact(true); //mPenetrationConstraints[penConstIndex].oldFrictionVector1 = externalContact->getFrictionVector1(); //mPenetrationConstraints[penConstIndex].oldFrictionVector2 = externalContact->getFrictionVector2(); @@ -467,9 +471,116 @@ void ContactSolver::initializeContactConstraints() { /// the solution of the linear system void ContactSolver::warmStart() { - /* PROFILE("ContactSolver::warmStart()"); + // Penetration constraints + for (uint i=0; isetPenetrationImpulse(mPenetrationConstraints[i].penetrationImpulse); + + } + + // Friction constraints + for (uint i=0; isetFrictionImpulse1(mFrictionConstraints[i].friction1Impulse); + mFrictionConstraints[i].contactManifold->setFrictionImpulse2(mFrictionConstraints[i].friction2Impulse); + mFrictionConstraints[i].contactManifold->setFrictionTwistImpulse(mFrictionConstraints[i].frictionTwistImpulse); + mFrictionConstraints[i].contactManifold->setRollingResistanceImpulse(mFrictionConstraints[i].rollingResistanceImpulse); + mFrictionConstraints[i].contactManifold->setFrictionVector1(mFrictionConstraints[i].frictionVector1); + mFrictionConstraints[i].contactManifold->setFrictionVector2(mFrictionConstraints[i].frictionVector2); + } + /* // For each contact manifold for (uint c=0; c Date: Fri, 16 Sep 2016 20:02:38 +0200 Subject: [PATCH 025/248] Fix issue in contact solver --- src/engine/ContactSolver.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index 4e2e0eec..a0db1119 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -832,7 +832,7 @@ void ContactSolver::solvePenetrationConstraints() { mPenetrationConstraints[i].penetrationSplitImpulse = std::max( mPenetrationConstraints[i].penetrationSplitImpulse + deltaLambdaSplit, decimal(0.0)); - deltaLambda = mPenetrationConstraints[i].penetrationSplitImpulse - lambdaTempSplit; + deltaLambdaSplit = mPenetrationConstraints[i].penetrationSplitImpulse - lambdaTempSplit; // Update the velocities of the body 1 by applying the impulse P=J^T * lambda Vector3 linearImpulse = mPenetrationConstraints[i].normal * deltaLambdaSplit; From 92460791e651bf62216a14992c4bfb7da5926952 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 21 Sep 2016 22:01:14 +0200 Subject: [PATCH 026/248] Refactor PoolAllocator and add SingleFrameAllocator --- ...{MemoryAllocator.cpp => PoolAllocator.cpp} | 16 ++-- .../{MemoryAllocator.h => PoolAllocator.h} | 12 +-- src/memory/SingleFrameAllocator.cpp | 80 +++++++++++++++++++ src/memory/SingleFrameAllocator.h | 76 ++++++++++++++++++ 4 files changed, 170 insertions(+), 14 deletions(-) rename src/memory/{MemoryAllocator.cpp => PoolAllocator.cpp} (95%) rename src/memory/{MemoryAllocator.h => PoolAllocator.h} (96%) create mode 100644 src/memory/SingleFrameAllocator.cpp create mode 100644 src/memory/SingleFrameAllocator.h diff --git a/src/memory/MemoryAllocator.cpp b/src/memory/PoolAllocator.cpp similarity index 95% rename from src/memory/MemoryAllocator.cpp rename to src/memory/PoolAllocator.cpp index 46c47e14..dc1306bc 100644 --- a/src/memory/MemoryAllocator.cpp +++ b/src/memory/PoolAllocator.cpp @@ -24,19 +24,19 @@ ********************************************************************************/ // Libraries -#include "MemoryAllocator.h" +#include "PoolAllocator.h" #include #include using namespace reactphysics3d; // Initialization of static variables -bool MemoryAllocator::isMapSizeToHeadIndexInitialized = false; -size_t MemoryAllocator::mUnitSizes[NB_HEAPS]; -int MemoryAllocator::mMapSizeToHeapIndex[MAX_UNIT_SIZE + 1]; +bool PoolAllocator::isMapSizeToHeadIndexInitialized = false; +size_t PoolAllocator::mUnitSizes[NB_HEAPS]; +int PoolAllocator::mMapSizeToHeapIndex[MAX_UNIT_SIZE + 1]; // Constructor -MemoryAllocator::MemoryAllocator() { +PoolAllocator::PoolAllocator() { // Allocate some memory to manage the blocks mNbAllocatedMemoryBlocks = 64; @@ -78,7 +78,7 @@ MemoryAllocator::MemoryAllocator() { } // Destructor -MemoryAllocator::~MemoryAllocator() { +PoolAllocator::~PoolAllocator() { // Release the memory allocated for each block for (uint i=0; i @@ -33,14 +33,14 @@ /// ReactPhysics3D namespace namespace reactphysics3d { -// Class MemoryAllocator +// Class PoolAllocator /** * This class is used to efficiently allocate memory on the heap. * It allows us to allocate small blocks of memory (smaller or equal to 1024 bytes) * efficiently. This implementation is inspired by the small block allocator * described here : http://www.codeproject.com/useritems/Small_Block_Allocator.asp */ -class MemoryAllocator { +class PoolAllocator { private : @@ -126,10 +126,10 @@ class MemoryAllocator { // -------------------- Methods -------------------- // /// Constructor - MemoryAllocator(); + PoolAllocator(); /// Destructor - ~MemoryAllocator(); + ~PoolAllocator(); /// Allocate memory of a given size (in bytes) and return a pointer to the /// allocated memory. diff --git a/src/memory/SingleFrameAllocator.cpp b/src/memory/SingleFrameAllocator.cpp new file mode 100644 index 00000000..a2e436cd --- /dev/null +++ b/src/memory/SingleFrameAllocator.cpp @@ -0,0 +1,80 @@ +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "SingleFrameAllocator.h" +#include +#include + +using namespace reactphysics3d; + +// Constructor +SingleFrameAllocator::SingleFrameAllocator(size_t totalSizeBytes) + : mTotalSizeBytes(totalSizeBytes), mCurrentOffset(0) { + + // Allocate a whole block of memory at the beginning + mMemoryBufferStart = static_cast(malloc(mTotalSizeBytes)); + assert(mMemoryBufferStart != nullptr); +} + +// Destructor +SingleFrameAllocator::~SingleFrameAllocator() { + + // Release the memory allocated at the beginning + free(mMemoryBufferStart); +} + + +// Allocate memory of a given size (in bytes) and return a pointer to the +// allocated memory. +void* SingleFrameAllocator::allocate(size_t size) { + + // Check that there is enough remaining memory in the buffer + if (static_cast(mCurrentOffset) + size > mTotalSizeBytes) { + + // This should never occur. If it does, you must increase the initial + // size of memory of this allocator + assert(false); + + // Return null + return nullptr; + } + + // Next available memory location + void* nextAvailableMemory = mMemoryBufferStart + mCurrentOffset; + + // Increment the offset + mCurrentOffset += size; + + // Return the next available memory location + return nextAvailableMemory; +} + +// Reset the marker of the current allocated memory +void SingleFrameAllocator::reset() { + + // Reset the current offset at the beginning of the block + mCurrentOffset = 0; +} diff --git a/src/memory/SingleFrameAllocator.h b/src/memory/SingleFrameAllocator.h new file mode 100644 index 00000000..e3151f0a --- /dev/null +++ b/src/memory/SingleFrameAllocator.h @@ -0,0 +1,76 @@ +/******************************************************************************** +* 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_SINGLE_FRAME_ALLOCATOR_H +#define REACTPHYSICS3D_SINGLE_FRAME_ALLOCATOR_H + +// Libraries +#include +#include "configuration.h" + +/// ReactPhysics3D namespace +namespace reactphysics3d { + +// Class SingleFrameAllocator +/** + * This class represent a memory allocator used to efficiently allocate + * memory on the heap that is used during a single frame. + */ +class SingleFrameAllocator { + + private : + + // -------------------- Attributes -------------------- // + + /// Total size (in bytes) of memory of the allocator + size_t mTotalSizeBytes; + + /// Pointer to the beginning of the allocated memory block + char* mMemoryBufferStart; + + /// Pointer to the next available memory location in the buffer + int mCurrentOffset; + + public : + + // -------------------- Methods -------------------- // + + /// Constructor + SingleFrameAllocator(size_t totalSizeBytes); + + /// Destructor + ~SingleFrameAllocator(); + + /// Allocate memory of a given size (in bytes) + void* allocate(size_t size); + + /// Reset the marker of the current allocated memory + void reset(); + +}; + +} + +#endif From e014f00afc71bf62e78d02fba1e2fea3e957fbb3 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 21 Sep 2016 22:03:45 +0200 Subject: [PATCH 027/248] Refactor memory allocator and refactor contact solver --- CMakeLists.txt | 6 +- src/body/CollisionBody.cpp | 10 +- src/body/CollisionBody.h | 2 +- src/body/RigidBody.cpp | 4 +- src/body/RigidBody.h | 4 +- src/collision/CollisionDetection.cpp | 22 +- src/collision/CollisionDetection.h | 8 +- src/collision/ContactManifold.cpp | 2 +- src/collision/ContactManifold.h | 6 +- src/collision/ContactManifoldSet.cpp | 2 +- src/collision/ContactManifoldSet.h | 4 +- src/collision/narrowphase/CollisionDispatch.h | 2 +- .../narrowphase/DefaultCollisionDispatch.cpp | 2 +- .../narrowphase/DefaultCollisionDispatch.h | 2 +- src/collision/narrowphase/EPA/EPAAlgorithm.h | 8 +- src/collision/narrowphase/GJK/GJKAlgorithm.h | 4 +- .../narrowphase/GJK/VoronoiSimplex.cpp | 1 - .../narrowphase/NarrowPhaseAlgorithm.cpp | 2 +- .../narrowphase/NarrowPhaseAlgorithm.h | 6 +- src/collision/shapes/CollisionShape.h | 2 +- src/configuration.h | 3 + src/engine/CollisionWorld.cpp | 6 +- src/engine/CollisionWorld.h | 6 +- src/engine/ContactSolver.cpp | 805 ++---------------- src/engine/ContactSolver.h | 249 +----- src/engine/DynamicsWorld.cpp | 103 ++- src/engine/DynamicsWorld.h | 3 + src/engine/Island.cpp | 2 +- src/engine/Island.h | 6 +- src/engine/OverlappingPair.cpp | 2 +- src/engine/OverlappingPair.h | 2 +- 31 files changed, 201 insertions(+), 1085 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index e85693d7..69f20522 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -174,8 +174,10 @@ SET (REACTPHYSICS3D_SOURCES "src/mathematics/Vector3.h" "src/mathematics/Ray.h" "src/mathematics/Vector3.cpp" - "src/memory/MemoryAllocator.h" - "src/memory/MemoryAllocator.cpp" + "src/memory/PoolAllocator.h" + "src/memory/PoolAllocator.cpp" + "src/memory/SingleFrameAllocator.h" + "src/memory/SingleFrameAllocator.cpp" "src/memory/Stack.h" ) diff --git a/src/body/CollisionBody.cpp b/src/body/CollisionBody.cpp index daa4a71e..db22f606 100644 --- a/src/body/CollisionBody.cpp +++ b/src/body/CollisionBody.cpp @@ -70,7 +70,7 @@ ProxyShape* CollisionBody::addCollisionShape(CollisionShape* collisionShape, const Transform& transform) { // Create a new proxy collision shape to attach the collision shape to the body - ProxyShape* proxyShape = new (mWorld.mMemoryAllocator.allocate( + ProxyShape* proxyShape = new (mWorld.mPoolAllocator.allocate( sizeof(ProxyShape))) ProxyShape(this, collisionShape, transform, decimal(1)); @@ -116,7 +116,7 @@ void CollisionBody::removeCollisionShape(const ProxyShape* proxyShape) { } current->~ProxyShape(); - mWorld.mMemoryAllocator.release(current, sizeof(ProxyShape)); + mWorld.mPoolAllocator.release(current, sizeof(ProxyShape)); mNbCollisionShapes--; return; } @@ -136,7 +136,7 @@ void CollisionBody::removeCollisionShape(const ProxyShape* proxyShape) { } elementToRemove->~ProxyShape(); - mWorld.mMemoryAllocator.release(elementToRemove, sizeof(ProxyShape)); + mWorld.mPoolAllocator.release(elementToRemove, sizeof(ProxyShape)); mNbCollisionShapes--; return; } @@ -162,7 +162,7 @@ void CollisionBody::removeAllCollisionShapes() { } current->~ProxyShape(); - mWorld.mMemoryAllocator.release(current, sizeof(ProxyShape)); + mWorld.mPoolAllocator.release(current, sizeof(ProxyShape)); // Get the next element in the list current = nextElement; @@ -181,7 +181,7 @@ void CollisionBody::resetContactManifoldsList() { // Delete the current element currentElement->~ContactManifoldListElement(); - mWorld.mMemoryAllocator.release(currentElement, sizeof(ContactManifoldListElement)); + mWorld.mPoolAllocator.release(currentElement, sizeof(ContactManifoldListElement)); currentElement = nextElement; } diff --git a/src/body/CollisionBody.h b/src/body/CollisionBody.h index 5fda6958..bd5c7818 100644 --- a/src/body/CollisionBody.h +++ b/src/body/CollisionBody.h @@ -34,7 +34,7 @@ #include "collision/shapes/AABB.h" #include "collision/shapes/CollisionShape.h" #include "collision/RaycastInfo.h" -#include "memory/MemoryAllocator.h" +#include "memory/PoolAllocator.h" #include "configuration.h" /// Namespace reactphysics3d diff --git a/src/body/RigidBody.cpp b/src/body/RigidBody.cpp index ff77b228..74ee8a05 100644 --- a/src/body/RigidBody.cpp +++ b/src/body/RigidBody.cpp @@ -166,7 +166,7 @@ void RigidBody::setMass(decimal mass) { } // Remove a joint from the joints list -void RigidBody::removeJointFromJointsList(MemoryAllocator& memoryAllocator, const Joint* joint) { +void RigidBody::removeJointFromJointsList(PoolAllocator& memoryAllocator, const Joint* joint) { assert(joint != nullptr); assert(mJointsList != nullptr); @@ -214,7 +214,7 @@ ProxyShape* RigidBody::addCollisionShape(CollisionShape* collisionShape, decimal mass) { // Create a new proxy collision shape to attach the collision shape to the body - ProxyShape* proxyShape = new (mWorld.mMemoryAllocator.allocate( + ProxyShape* proxyShape = new (mWorld.mPoolAllocator.allocate( sizeof(ProxyShape))) ProxyShape(this, collisionShape, transform, mass); diff --git a/src/body/RigidBody.h b/src/body/RigidBody.h index 8fb36d0e..0ffc6257 100644 --- a/src/body/RigidBody.h +++ b/src/body/RigidBody.h @@ -31,7 +31,7 @@ #include "CollisionBody.h" #include "engine/Material.h" #include "mathematics/mathematics.h" -#include "memory/MemoryAllocator.h" +#include "memory/PoolAllocator.h" /// Namespace reactphysics3d namespace reactphysics3d { @@ -104,7 +104,7 @@ class RigidBody : public CollisionBody { // -------------------- Methods -------------------- // /// Remove a joint from the joints list - void removeJointFromJointsList(MemoryAllocator& memoryAllocator, const Joint* joint); + void removeJointFromJointsList(PoolAllocator& memoryAllocator, const Joint* joint); /// Update the transform of the body after a change of the center of mass void updateTransformWithCenterOfMass(); diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 7d9f6fb2..c3caa97a 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -41,7 +41,7 @@ using namespace reactphysics3d; using namespace std; // Constructor -CollisionDetection::CollisionDetection(CollisionWorld* world, MemoryAllocator& memoryAllocator) +CollisionDetection::CollisionDetection(CollisionWorld* world, PoolAllocator& memoryAllocator) : mMemoryAllocator(memoryAllocator), mWorld(world), mBroadPhaseAlgorithm(*this), mIsCollisionShapesAdded(false) { @@ -189,7 +189,7 @@ void CollisionDetection::computeNarrowPhase() { // Destroy the overlapping pair itToRemove->second->~OverlappingPair(); - mWorld->mMemoryAllocator.release(itToRemove->second, sizeof(OverlappingPair)); + mWorld->mPoolAllocator.release(itToRemove->second, sizeof(OverlappingPair)); mOverlappingPairs.erase(itToRemove); continue; } @@ -294,7 +294,7 @@ void CollisionDetection::computeNarrowPhaseBetweenShapes(CollisionCallback* call // Destroy the overlapping pair itToRemove->second->~OverlappingPair(); - mWorld->mMemoryAllocator.release(itToRemove->second, sizeof(OverlappingPair)); + mWorld->mPoolAllocator.release(itToRemove->second, sizeof(OverlappingPair)); mOverlappingPairs.erase(itToRemove); continue; } @@ -370,8 +370,8 @@ void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, Pro shape2->getCollisionShape()->getType()); // Create the overlapping pair and add it into the set of overlapping pairs - OverlappingPair* newPair = new (mWorld->mMemoryAllocator.allocate(sizeof(OverlappingPair))) - OverlappingPair(shape1, shape2, nbMaxManifolds, mWorld->mMemoryAllocator); + OverlappingPair* newPair = new (mWorld->mPoolAllocator.allocate(sizeof(OverlappingPair))) + OverlappingPair(shape1, shape2, nbMaxManifolds, mWorld->mPoolAllocator); assert(newPair != nullptr); #ifndef NDEBUG @@ -400,7 +400,7 @@ void CollisionDetection::removeProxyCollisionShape(ProxyShape* proxyShape) { // Destroy the overlapping pair itToRemove->second->~OverlappingPair(); - mWorld->mMemoryAllocator.release(itToRemove->second, sizeof(OverlappingPair)); + mWorld->mPoolAllocator.release(itToRemove->second, sizeof(OverlappingPair)); mOverlappingPairs.erase(itToRemove); } else { @@ -434,7 +434,7 @@ void CollisionDetection::createContact(OverlappingPair* overlappingPair, const ContactPointInfo& contactInfo) { // Create a new contact - ContactPoint* contact = new (mWorld->mMemoryAllocator.allocate(sizeof(ContactPoint))) + ContactPoint* contact = new (mWorld->mPoolAllocator.allocate(sizeof(ContactPoint))) ContactPoint(contactInfo); // Add the contact to the contact manifold set of the corresponding overlapping pair @@ -477,7 +477,7 @@ void CollisionDetection::addContactManifoldToBody(OverlappingPair* pair) { // Add the contact manifold at the beginning of the linked // list of contact manifolds of the first body - void* allocatedMemory1 = mWorld->mMemoryAllocator.allocate(sizeof(ContactManifoldListElement)); + void* allocatedMemory1 = mWorld->mPoolAllocator.allocate(sizeof(ContactManifoldListElement)); ContactManifoldListElement* listElement1 = new (allocatedMemory1) ContactManifoldListElement(contactManifold, body1->mContactManifoldsList); @@ -485,7 +485,7 @@ void CollisionDetection::addContactManifoldToBody(OverlappingPair* pair) { // Add the contact manifold at the beginning of the linked // list of the contact manifolds of the second body - void* allocatedMemory2 = mWorld->mMemoryAllocator.allocate(sizeof(ContactManifoldListElement)); + void* allocatedMemory2 = mWorld->mPoolAllocator.allocate(sizeof(ContactManifoldListElement)); ContactManifoldListElement* listElement2 = new (allocatedMemory2) ContactManifoldListElement(contactManifold, body2->mContactManifoldsList); @@ -520,8 +520,8 @@ EventListener* CollisionDetection::getWorldEventListener() { } /// Return a reference to the world memory allocator -MemoryAllocator& CollisionDetection::getWorldMemoryAllocator() { - return mWorld->mMemoryAllocator; +PoolAllocator& CollisionDetection::getWorldMemoryAllocator() { + return mWorld->mPoolAllocator; } // Called by a narrow-phase collision algorithm when a new contact has been found diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index 75f278ba..0fe486c4 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -32,7 +32,7 @@ #include "engine/OverlappingPair.h" #include "engine/EventListener.h" #include "narrowphase/DefaultCollisionDispatch.h" -#include "memory/MemoryAllocator.h" +#include "memory/PoolAllocator.h" #include "constraint/ContactPoint.h" #include #include @@ -93,7 +93,7 @@ class CollisionDetection : public NarrowPhaseCallback { NarrowPhaseAlgorithm* mCollisionMatrix[NB_COLLISION_SHAPE_TYPES][NB_COLLISION_SHAPE_TYPES]; /// Reference to the memory allocator - MemoryAllocator& mMemoryAllocator; + PoolAllocator& mMemoryAllocator; /// Pointer to the physics world CollisionWorld* mWorld; @@ -143,7 +143,7 @@ class CollisionDetection : public NarrowPhaseCallback { // -------------------- Methods -------------------- // /// Constructor - CollisionDetection(CollisionWorld* world, MemoryAllocator& memoryAllocator); + CollisionDetection(CollisionWorld* world, PoolAllocator& memoryAllocator); /// Destructor ~CollisionDetection() = default; @@ -220,7 +220,7 @@ class CollisionDetection : public NarrowPhaseCallback { EventListener* getWorldEventListener(); /// Return a reference to the world memory allocator - MemoryAllocator& getWorldMemoryAllocator(); + PoolAllocator& getWorldMemoryAllocator(); /// Called by a narrow-phase collision algorithm when a new contact has been found virtual void notifyContact(OverlappingPair* overlappingPair, const ContactPointInfo& contactInfo) override; diff --git a/src/collision/ContactManifold.cpp b/src/collision/ContactManifold.cpp index cfa905ff..ff15bce6 100644 --- a/src/collision/ContactManifold.cpp +++ b/src/collision/ContactManifold.cpp @@ -31,7 +31,7 @@ using namespace reactphysics3d; // Constructor ContactManifold::ContactManifold(ProxyShape* shape1, ProxyShape* shape2, - MemoryAllocator& memoryAllocator, short normalDirectionId) + PoolAllocator& memoryAllocator, short normalDirectionId) : mShape1(shape1), mShape2(shape2), mNormalDirectionId(normalDirectionId), mNbContactPoints(0), mFrictionImpulse1(0.0), mFrictionImpulse2(0.0), mFrictionTwistImpulse(0.0), mIsAlreadyInIsland(false), diff --git a/src/collision/ContactManifold.h b/src/collision/ContactManifold.h index eb7716df..2f77e9b2 100644 --- a/src/collision/ContactManifold.h +++ b/src/collision/ContactManifold.h @@ -31,7 +31,7 @@ #include "body/CollisionBody.h" #include "collision/ProxyShape.h" #include "constraint/ContactPoint.h" -#include "memory/MemoryAllocator.h" +#include "memory/PoolAllocator.h" /// ReactPhysics3D namespace namespace reactphysics3d { @@ -126,7 +126,7 @@ class ContactManifold { bool mIsAlreadyInIsland; /// Reference to the memory allocator - MemoryAllocator& mMemoryAllocator; + PoolAllocator& mMemoryAllocator; // -------------------- Methods -------------------- // @@ -151,7 +151,7 @@ class ContactManifold { /// Constructor ContactManifold(ProxyShape* shape1, ProxyShape* shape2, - MemoryAllocator& memoryAllocator, short int normalDirectionId); + PoolAllocator& memoryAllocator, short int normalDirectionId); /// Destructor ~ContactManifold(); diff --git a/src/collision/ContactManifoldSet.cpp b/src/collision/ContactManifoldSet.cpp index 54e3614e..26f3a66f 100644 --- a/src/collision/ContactManifoldSet.cpp +++ b/src/collision/ContactManifoldSet.cpp @@ -30,7 +30,7 @@ using namespace reactphysics3d; // Constructor ContactManifoldSet::ContactManifoldSet(ProxyShape* shape1, ProxyShape* shape2, - MemoryAllocator& memoryAllocator, int nbMaxManifolds) + PoolAllocator& memoryAllocator, int nbMaxManifolds) : mNbMaxManifolds(nbMaxManifolds), mNbManifolds(0), mShape1(shape1), mShape2(shape2), mMemoryAllocator(memoryAllocator) { assert(nbMaxManifolds >= 1); diff --git a/src/collision/ContactManifoldSet.h b/src/collision/ContactManifoldSet.h index b167f506..21944e36 100644 --- a/src/collision/ContactManifoldSet.h +++ b/src/collision/ContactManifoldSet.h @@ -61,7 +61,7 @@ class ContactManifoldSet { ProxyShape* mShape2; /// Reference to the memory allocator - MemoryAllocator& mMemoryAllocator; + PoolAllocator& mMemoryAllocator; /// Contact manifolds of the set ContactManifold* mManifolds[MAX_MANIFOLDS_IN_CONTACT_MANIFOLD_SET]; @@ -88,7 +88,7 @@ class ContactManifoldSet { /// Constructor ContactManifoldSet(ProxyShape* shape1, ProxyShape* shape2, - MemoryAllocator& memoryAllocator, int nbMaxManifolds); + PoolAllocator& memoryAllocator, int nbMaxManifolds); /// Destructor ~ContactManifoldSet(); diff --git a/src/collision/narrowphase/CollisionDispatch.h b/src/collision/narrowphase/CollisionDispatch.h index 8fa24f87..6e027721 100644 --- a/src/collision/narrowphase/CollisionDispatch.h +++ b/src/collision/narrowphase/CollisionDispatch.h @@ -51,7 +51,7 @@ class CollisionDispatch { /// Initialize the collision dispatch configuration virtual void init(CollisionDetection* collisionDetection, - MemoryAllocator* memoryAllocator) { + PoolAllocator* memoryAllocator) { } diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.cpp b/src/collision/narrowphase/DefaultCollisionDispatch.cpp index 109b5de3..f6812d74 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.cpp +++ b/src/collision/narrowphase/DefaultCollisionDispatch.cpp @@ -31,7 +31,7 @@ using namespace reactphysics3d; /// Initialize the collision dispatch configuration void DefaultCollisionDispatch::init(CollisionDetection* collisionDetection, - MemoryAllocator* memoryAllocator) { + PoolAllocator* memoryAllocator) { // Initialize the collision algorithms mSphereVsSphereAlgorithm.init(collisionDetection, memoryAllocator); diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.h b/src/collision/narrowphase/DefaultCollisionDispatch.h index 9bf15b11..5dd07bf2 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.h +++ b/src/collision/narrowphase/DefaultCollisionDispatch.h @@ -63,7 +63,7 @@ class DefaultCollisionDispatch : public CollisionDispatch { /// Initialize the collision dispatch configuration virtual void init(CollisionDetection* collisionDetection, - MemoryAllocator* memoryAllocator) override; + PoolAllocator* memoryAllocator) override; /// Select and return the narrow-phase collision detection algorithm to /// use between two types of collision shapes. diff --git a/src/collision/narrowphase/EPA/EPAAlgorithm.h b/src/collision/narrowphase/EPA/EPAAlgorithm.h index f585ac15..05a78eea 100644 --- a/src/collision/narrowphase/EPA/EPAAlgorithm.h +++ b/src/collision/narrowphase/EPA/EPAAlgorithm.h @@ -34,7 +34,7 @@ #include "collision/narrowphase/NarrowPhaseAlgorithm.h" #include "mathematics/mathematics.h" #include "TriangleEPA.h" -#include "memory/MemoryAllocator.h" +#include "memory/PoolAllocator.h" #include /// ReactPhysics3D namespace @@ -88,7 +88,7 @@ class EPAAlgorithm { // -------------------- Attributes -------------------- // /// Reference to the memory allocator - MemoryAllocator* mMemoryAllocator; + PoolAllocator* mMemoryAllocator; /// Triangle comparison operator TriangleComparison mTriangleComparison; @@ -120,7 +120,7 @@ class EPAAlgorithm { EPAAlgorithm& operator=(const EPAAlgorithm& algorithm) = delete; /// Initalize the algorithm - void init(MemoryAllocator* memoryAllocator); + void init(PoolAllocator* memoryAllocator); /// Compute the penetration depth with EPA algorithm. bool computePenetrationDepthAndContactPoints(const VoronoiSimplex& simplex, @@ -151,7 +151,7 @@ inline void EPAAlgorithm::addFaceCandidate(TriangleEPA* triangle, TriangleEPA** } // Initalize the algorithm -inline void EPAAlgorithm::init(MemoryAllocator* memoryAllocator) { +inline void EPAAlgorithm::init(PoolAllocator* memoryAllocator) { mMemoryAllocator = memoryAllocator; } diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.h b/src/collision/narrowphase/GJK/GJKAlgorithm.h index e81ee9b3..b6cce5c2 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.h +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.h @@ -94,7 +94,7 @@ class GJKAlgorithm : public NarrowPhaseAlgorithm { /// Initalize the algorithm virtual void init(CollisionDetection* collisionDetection, - MemoryAllocator* memoryAllocator) override; + PoolAllocator* memoryAllocator) override; /// Compute a contact info if the two bounding volumes collide. virtual void testCollision(const CollisionShapeInfo& shape1Info, @@ -110,7 +110,7 @@ class GJKAlgorithm : public NarrowPhaseAlgorithm { // Initalize the algorithm inline void GJKAlgorithm::init(CollisionDetection* collisionDetection, - MemoryAllocator* memoryAllocator) { + PoolAllocator* memoryAllocator) { NarrowPhaseAlgorithm::init(collisionDetection, memoryAllocator); mAlgoEPA.init(memoryAllocator); } diff --git a/src/collision/narrowphase/GJK/VoronoiSimplex.cpp b/src/collision/narrowphase/GJK/VoronoiSimplex.cpp index 382ccc9b..590182ac 100644 --- a/src/collision/narrowphase/GJK/VoronoiSimplex.cpp +++ b/src/collision/narrowphase/GJK/VoronoiSimplex.cpp @@ -563,7 +563,6 @@ bool VoronoiSimplex::computeClosestPointOnTetrahedron(const Vector3& a, const Ve if (squareDist < closestSquareDistance) { // Use it as the current closest point - closestSquareDistance = squareDist; baryCoordsAB.setAllValues(0.0, triangleBaryCoords[0]); baryCoordsCD.setAllValues(triangleBaryCoords[2], triangleBaryCoords[1]); bitsUsedPoints = mapTriangleUsedVerticesToTetrahedron(tempUsedVertices, 1, 3, 2); diff --git a/src/collision/narrowphase/NarrowPhaseAlgorithm.cpp b/src/collision/narrowphase/NarrowPhaseAlgorithm.cpp index 0fbbe5fe..782f8d6f 100644 --- a/src/collision/narrowphase/NarrowPhaseAlgorithm.cpp +++ b/src/collision/narrowphase/NarrowPhaseAlgorithm.cpp @@ -36,7 +36,7 @@ NarrowPhaseAlgorithm::NarrowPhaseAlgorithm() } // Initalize the algorithm -void NarrowPhaseAlgorithm::init(CollisionDetection* collisionDetection, MemoryAllocator* memoryAllocator) { +void NarrowPhaseAlgorithm::init(CollisionDetection* collisionDetection, PoolAllocator* memoryAllocator) { mCollisionDetection = collisionDetection; mMemoryAllocator = memoryAllocator; } diff --git a/src/collision/narrowphase/NarrowPhaseAlgorithm.h b/src/collision/narrowphase/NarrowPhaseAlgorithm.h index 30b216f0..0759d138 100644 --- a/src/collision/narrowphase/NarrowPhaseAlgorithm.h +++ b/src/collision/narrowphase/NarrowPhaseAlgorithm.h @@ -29,7 +29,7 @@ // Libraries #include "body/Body.h" #include "constraint/ContactPoint.h" -#include "memory/MemoryAllocator.h" +#include "memory/PoolAllocator.h" #include "engine/OverlappingPair.h" #include "collision/CollisionShapeInfo.h" @@ -71,7 +71,7 @@ class NarrowPhaseAlgorithm { CollisionDetection* mCollisionDetection; /// Pointer to the memory allocator - MemoryAllocator* mMemoryAllocator; + PoolAllocator* mMemoryAllocator; /// Overlapping pair of the bodies currently tested for collision OverlappingPair* mCurrentOverlappingPair; @@ -93,7 +93,7 @@ class NarrowPhaseAlgorithm { NarrowPhaseAlgorithm& operator=(const NarrowPhaseAlgorithm& algorithm) = delete; /// Initalize the algorithm - virtual void init(CollisionDetection* collisionDetection, MemoryAllocator* memoryAllocator); + virtual void init(CollisionDetection* collisionDetection, PoolAllocator* memoryAllocator); /// Set the current overlapping pair of bodies void setCurrentOverlappingPair(OverlappingPair* overlappingPair); diff --git a/src/collision/shapes/CollisionShape.h b/src/collision/shapes/CollisionShape.h index 1e2e3f14..b33ed4f1 100644 --- a/src/collision/shapes/CollisionShape.h +++ b/src/collision/shapes/CollisionShape.h @@ -34,7 +34,7 @@ #include "mathematics/Ray.h" #include "AABB.h" #include "collision/RaycastInfo.h" -#include "memory/MemoryAllocator.h" +#include "memory/PoolAllocator.h" /// ReactPhysics3D namespace namespace reactphysics3d { diff --git a/src/configuration.h b/src/configuration.h index 4364c548..87747756 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -144,6 +144,9 @@ constexpr int NB_MAX_CONTACT_MANIFOLDS_CONVEX_SHAPE = 1; /// least one concave collision shape. constexpr int NB_MAX_CONTACT_MANIFOLDS_CONCAVE_SHAPE = 3; +/// Size (in bytes) of the single frame allocator +constexpr size_t SIZE_SINGLE_FRAME_ALLOCATOR_BYTES = 1048576; + } #endif diff --git a/src/engine/CollisionWorld.cpp b/src/engine/CollisionWorld.cpp index 68e37625..b1b004ec 100644 --- a/src/engine/CollisionWorld.cpp +++ b/src/engine/CollisionWorld.cpp @@ -33,7 +33,7 @@ using namespace std; // Constructor CollisionWorld::CollisionWorld() - : mCollisionDetection(this, mMemoryAllocator), mCurrentBodyID(0), + : mCollisionDetection(this, mPoolAllocator), mCurrentBodyID(0), mEventListener(nullptr) { } @@ -66,7 +66,7 @@ CollisionBody* CollisionWorld::createCollisionBody(const Transform& transform) { assert(bodyID < std::numeric_limits::max()); // Create the collision body - CollisionBody* collisionBody = new (mMemoryAllocator.allocate(sizeof(CollisionBody))) + CollisionBody* collisionBody = new (mPoolAllocator.allocate(sizeof(CollisionBody))) CollisionBody(transform, *this, bodyID); assert(collisionBody != nullptr); @@ -97,7 +97,7 @@ void CollisionWorld::destroyCollisionBody(CollisionBody* collisionBody) { mBodies.erase(collisionBody); // Free the object from the memory allocator - mMemoryAllocator.release(collisionBody, sizeof(CollisionBody)); + mPoolAllocator.release(collisionBody, sizeof(CollisionBody)); } // Return the next available body ID diff --git a/src/engine/CollisionWorld.h b/src/engine/CollisionWorld.h index 77189e89..d04acb4e 100644 --- a/src/engine/CollisionWorld.h +++ b/src/engine/CollisionWorld.h @@ -39,7 +39,7 @@ #include "collision/CollisionDetection.h" #include "constraint/Joint.h" #include "constraint/ContactPoint.h" -#include "memory/MemoryAllocator.h" +#include "memory/PoolAllocator.h" #include "EventListener.h" /// Namespace reactphysics3d @@ -72,8 +72,8 @@ class CollisionWorld { /// List of free ID for rigid bodies std::vector mFreeBodiesIDs; - /// Memory allocator - MemoryAllocator mMemoryAllocator; + /// Pool Memory allocator + PoolAllocator mPoolAllocator; /// Pointer to an event listener object EventListener* mEventListener; diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index a0db1119..b271aa6e 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -39,55 +39,75 @@ const decimal ContactSolver::BETA_SPLIT_IMPULSE = decimal(0.2); const decimal ContactSolver::SLOP= decimal(0.01); // Constructor -ContactSolver::ContactSolver(const std::map& mapBodyToVelocityIndex) +ContactSolver::ContactSolver(const std::map& mapBodyToVelocityIndex, + SingleFrameAllocator& singleFrameAllocator) :mSplitLinearVelocities(nullptr), mSplitAngularVelocities(nullptr), - mContactConstraints(nullptr), mPenetrationConstraints(nullptr), - mFrictionConstraints(nullptr), mLinearVelocities(nullptr), mAngularVelocities(nullptr), + mSingleFrameAllocator(singleFrameAllocator), + mPenetrationConstraints(nullptr), mFrictionConstraints(nullptr), + mLinearVelocities(nullptr), mAngularVelocities(nullptr), mMapBodyToConstrainedVelocityIndex(mapBodyToVelocityIndex), mIsWarmStartingActive(true), mIsSplitImpulseActive(true), mIsSolveFrictionAtContactManifoldCenterActive(true) { } +// Initialize the contact constraints +void ContactSolver::init(Island** islands, uint nbIslands, decimal timeStep) { + + mTimeStep = timeStep; + + // TODO : Try not to count manifolds here + // Count the contact manifolds + uint nbContactManifolds = 0; + for (uint i = 0; i < nbIslands; i++) { + nbContactManifolds += islands[i]->getNbContactManifolds(); + } + + mNbFrictionConstraints = 0; + mNbPenetrationConstraints = 0; + + mPenetrationConstraints = nullptr; + mFrictionConstraints = nullptr; + + if (nbContactManifolds == 0) return; + + // TODO : Count exactly the number of constraints to allocate here + uint nbPenetrationConstraints = nbContactManifolds * MAX_CONTACT_POINTS_IN_MANIFOLD; + mPenetrationConstraints = static_cast(mSingleFrameAllocator.allocate(sizeof(PenetrationConstraint) * nbPenetrationConstraints)); + //mPenetrationConstraints = new PenetrationConstraint[nbPenetrationConstraints]; + assert(mPenetrationConstraints != nullptr); + //mPenetrationConstraints = new PenetrationConstraint[mNbContactManifolds * 4]; + + mFrictionConstraints = static_cast(mSingleFrameAllocator.allocate(sizeof(FrictionConstraint) * nbContactManifolds)); + //mFrictionConstraints = new FrictionConstraint[nbContactManifolds]; + assert(mFrictionConstraints != nullptr); + //mFrictionConstraints = new FrictionConstraint[mNbContactManifolds]; + + // For each island of the world + for (uint islandIndex = 0; islandIndex < nbIslands; islandIndex++) { + initializeForIsland(islands[islandIndex]); + } + + // Warmstarting + warmStart(); +} + // Initialize the constraint solver for a given island -void ContactSolver::initializeForIsland(decimal dt, Island* island) { +void ContactSolver::initializeForIsland(Island* island) { PROFILE("ContactSolver::initializeForIsland()"); assert(island != nullptr); assert(island->getNbBodies() > 0); - assert(island->getNbContactManifolds() > 0); assert(mSplitLinearVelocities != nullptr); assert(mSplitAngularVelocities != nullptr); - // Set the current time step - mTimeStep = dt; - - mNbContactManifolds = island->getNbContactManifolds(); - - mNbFrictionConstraints = 0; - mNbPenetrationConstraints = 0; - - // TODO : Try to do faster allocation here - mContactConstraints = new ContactManifoldSolver[mNbContactManifolds]; - assert(mContactConstraints != nullptr); - - // TODO : Count exactly the number of constraints to allocate here (do not reallocate each frame) - mPenetrationConstraints = new PenetrationConstraint[mNbContactManifolds * 4]; - assert(mPenetrationConstraints != nullptr); - - // TODO : Do not reallocate each frame) - mFrictionConstraints = new FrictionConstraint[mNbContactManifolds]; - assert(mFrictionConstraints != nullptr); - // For each contact manifold of the island ContactManifold** contactManifolds = island->getContactManifolds(); - for (uint i=0; igetNbContactManifolds(); i++) { ContactManifold* externalManifold = contactManifolds[i]; - ContactManifoldSolver& internalManifold = mContactConstraints[i]; - assert(externalManifold->getNbContactPoints() > 0); // Get the two bodies of the contact @@ -100,6 +120,7 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { uint indexBody1 = mMapBodyToConstrainedVelocityIndex.find(body1)->second; uint indexBody2 = mMapBodyToConstrainedVelocityIndex.find(body2)->second; + new (mFrictionConstraints + mNbFrictionConstraints) FrictionConstraint(); mFrictionConstraints[mNbFrictionConstraints].indexBody1 = indexBody1; mFrictionConstraints[mNbFrictionConstraints].indexBody2 = indexBody2; mFrictionConstraints[mNbFrictionConstraints].contactManifold = externalManifold; @@ -129,7 +150,6 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { decimal restitutionFactor = computeMixedRestitutionFactor(body1, body2); mFrictionConstraints[mNbFrictionConstraints].frictionCoefficient = computeMixedFrictionCoefficient(body1, body2); mFrictionConstraints[mNbFrictionConstraints].rollingResistanceFactor = computeMixedRollingResistance(body1, body2); - internalManifold.externalContactManifold = externalManifold; mFrictionConstraints[mNbFrictionConstraints].hasAtLeastOneRestingContactPoint = false; //internalManifold.isBody1DynamicType = body1->getType() == BodyType::DYNAMIC; //internalManifold.isBody2DynamicType = body2->getType() == BodyType::DYNAMIC; @@ -159,6 +179,7 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { // Get a contact point ContactPoint* externalContact = externalManifold->getContactPoint(c); + new (mPenetrationConstraints + mNbPenetrationConstraints) PenetrationConstraint(); mPenetrationConstraints[mNbPenetrationConstraints].indexBody1 = indexBody1; mPenetrationConstraints[mNbPenetrationConstraints].indexBody2 = indexBody2; mPenetrationConstraints[mNbPenetrationConstraints].inverseInertiaTensorBody1 = I1; @@ -301,168 +322,19 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { frictionTwistMass > decimal(0.0) ? mFrictionConstraints[mNbFrictionConstraints].inverseTwistFrictionMass = decimal(1.0) / frictionTwistMass : decimal(0.0); - //} mNbFrictionConstraints++; } - - // Fill-in all the matrices needed to solve the LCP problem - //initializeContactConstraints(); } -// TODO : Delete this method -// Initialize the contact constraints before solving the system -void ContactSolver::initializeContactConstraints() { +// Solve the contact constraints of one iteration of the solve +void ContactSolver::solve() { - PROFILE("ContactSolver::initializeContactConstraints()"); - - // For each contact constraint - //for (uint c=0; c decimal(0.0)); - // ContactManifoldSolver& manifold = mContactConstraints[c]; - -// // Get the inertia tensors of both bodies -// Matrix3x3& I1 = manifold.inverseInertiaTensorBody1; -// Matrix3x3& I2 = manifold.inverseInertiaTensorBody2; - - // If we solve the friction constraints at the center of the contact manifold -// if (mIsSolveFrictionAtContactManifoldCenterActive) { -// manifold.normal = Vector3(0.0, 0.0, 0.0); -// } - - // Get the velocities of the bodies -// const Vector3& v1 = mLinearVelocities[manifold.indexBody1]; -// const Vector3& w1 = mAngularVelocities[manifold.indexBody1]; -// const Vector3& v2 = mLinearVelocities[manifold.indexBody2]; -// const Vector3& w2 = mAngularVelocities[manifold.indexBody2]; - - // For each contact point constraint - //for (uint i=0; i 0.0 ? contactPoint.inversePenetrationMass = decimal(1.0) / -// massPenetration : -// decimal(0.0); - - // If we do not solve the friction constraints at the center of the contact manifold -// if (!mIsSolveFrictionAtContactManifoldCenterActive) { - -// // Compute the friction vectors -// computeFrictionVectors(deltaV, contactPoint); - -// contactPoint.r1CrossT1 = contactPoint.r1.cross(contactPoint.frictionVector1); -// contactPoint.r1CrossT2 = contactPoint.r1.cross(contactPoint.frictionVector2); -// contactPoint.r2CrossT1 = contactPoint.r2.cross(contactPoint.frictionVector1); -// contactPoint.r2CrossT2 = contactPoint.r2.cross(contactPoint.frictionVector2); - -// // Compute the inverse mass matrix K for the friction -// // constraints at each contact point -// decimal friction1Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + -// ((I1 * contactPoint.r1CrossT1).cross(contactPoint.r1)).dot( -// contactPoint.frictionVector1) + -// ((I2 * contactPoint.r2CrossT1).cross(contactPoint.r2)).dot( -// contactPoint.frictionVector1); -// decimal friction2Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + -// ((I1 * contactPoint.r1CrossT2).cross(contactPoint.r1)).dot( -// contactPoint.frictionVector2) + -// ((I2 * contactPoint.r2CrossT2).cross(contactPoint.r2)).dot( -// contactPoint.frictionVector2); -// friction1Mass > 0.0 ? contactPoint.inverseFriction1Mass = decimal(1.0) / -// friction1Mass : -// decimal(0.0); -// friction2Mass > 0.0 ? contactPoint.inverseFriction2Mass = decimal(1.0) / -// friction2Mass : -// decimal(0.0); -// } - - // Compute the restitution velocity bias "b". We compute this here instead - // of inside the solve() method because we need to use the velocity difference - // at the beginning of the contact. Note that if it is a resting contact (normal - // velocity bellow a given threshold), we do not add a restitution velocity bias -// contactPoint.restitutionBias = 0.0; -// decimal deltaVDotN = deltaV.dot(contactPoint.normal); -// if (deltaVDotN < -RESTITUTION_VELOCITY_THRESHOLD) { -// contactPoint.restitutionBias = manifold.restitutionFactor * deltaVDotN; -// } - -// // If the warm starting of the contact solver is active -// if (mIsWarmStartingActive) { - -// // Get the cached accumulated impulses from the previous step -// contactPoint.penetrationImpulse = externalContact->getPenetrationImpulse(); -// contactPoint.friction1Impulse = externalContact->getFrictionImpulse1(); -// contactPoint.friction2Impulse = externalContact->getFrictionImpulse2(); -// contactPoint.rollingResistanceImpulse = externalContact->getRollingResistanceImpulse(); -// } - -// // Initialize the split impulses to zero -// contactPoint.penetrationSplitImpulse = 0.0; - -// // If we solve the friction constraints at the center of the contact manifold -// if (mIsSolveFrictionAtContactManifoldCenterActive) { -// manifold.normal += contactPoint.normal; -// } - //} - -// // Compute the inverse K matrix for the rolling resistance constraint -// manifold.inverseRollingResistance.setToZero(); -// if (manifold.rollingResistanceFactor > 0 && (manifold.isBody1DynamicType || manifold.isBody2DynamicType)) { -// manifold.inverseRollingResistance = manifold.inverseInertiaTensorBody1 + manifold.inverseInertiaTensorBody2; -// manifold.inverseRollingResistance = manifold.inverseRollingResistance.getInverse(); -// } - - // If we solve the friction constraints at the center of the contact manifold - //if (mIsSolveFrictionAtContactManifoldCenterActive) { - -// manifold.normal.normalize(); - -// Vector3 deltaVFrictionPoint = v2 + w2.cross(manifold.r2Friction) - -// v1 - w1.cross(manifold.r1Friction); - -// // Compute the friction vectors -// computeFrictionVectors(deltaVFrictionPoint, manifold); - -// // Compute the inverse mass matrix K for the friction constraints at the center of -// // the contact manifold -// manifold.r1CrossT1 = manifold.r1Friction.cross(manifold.frictionVector1); -// manifold.r1CrossT2 = manifold.r1Friction.cross(manifold.frictionVector2); -// manifold.r2CrossT1 = manifold.r2Friction.cross(manifold.frictionVector1); -// manifold.r2CrossT2 = manifold.r2Friction.cross(manifold.frictionVector2); -// decimal friction1Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + -// ((I1 * manifold.r1CrossT1).cross(manifold.r1Friction)).dot( -// manifold.frictionVector1) + -// ((I2 * manifold.r2CrossT1).cross(manifold.r2Friction)).dot( -// manifold.frictionVector1); -// decimal friction2Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + -// ((I1 * manifold.r1CrossT2).cross(manifold.r1Friction)).dot( -// manifold.frictionVector2) + -// ((I2 * manifold.r2CrossT2).cross(manifold.r2Friction)).dot( -// manifold.frictionVector2); -// decimal frictionTwistMass = manifold.normal.dot(manifold.inverseInertiaTensorBody1 * -// manifold.normal) + -// manifold.normal.dot(manifold.inverseInertiaTensorBody2 * -// manifold.normal); -// friction1Mass > 0.0 ? manifold.inverseFriction1Mass = decimal(1.0)/friction1Mass -// : decimal(0.0); -// friction2Mass > 0.0 ? manifold.inverseFriction2Mass = decimal(1.0)/friction2Mass -// : decimal(0.0); -// frictionTwistMass > 0.0 ? manifold.inverseTwistFrictionMass = decimal(1.0) / -// frictionTwistMass : -// decimal(0.0); - //} - //} + resetTotalPenetrationImpulse(); + solvePenetrationConstraints(); + solveFrictionConstraints(); } // Warm start the solver. @@ -576,177 +448,6 @@ void ContactSolver::warmStart() { mFrictionConstraints[i].rollingResistanceImpulse.setToZero(); } } - - - /* - - - // Check that warm starting is active - if (!mIsWarmStartingActive) return; - - // For each constraint - for (uint c=0; c 0) { - - // Compute the impulse P = J^T * lambda - const Impulse impulseRollingResistance(Vector3::zero(), -contactPoint.rollingResistanceImpulse, - Vector3::zero(), contactPoint.rollingResistanceImpulse); - - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseRollingResistance, contactManifold); - } - } - } - else { // If it is a new contact point - - // Initialize the accumulated impulses to zero - contactPoint.penetrationImpulse = 0.0; - contactPoint.friction1Impulse = 0.0; - contactPoint.friction2Impulse = 0.0; - contactPoint.rollingResistanceImpulse = Vector3::zero(); - } - } - - // If we solve the friction constraints at the center of the contact manifold and there is - // at least one resting contact point in the contact manifold - if (mIsSolveFrictionAtContactManifoldCenterActive && atLeastOneRestingContactPoint) { - - // Project the old friction impulses (with old friction vectors) into the new friction - // vectors to get the new friction impulses - Vector3 oldFrictionImpulse = contactManifold.friction1Impulse * - contactManifold.oldFrictionVector1 + - contactManifold.friction2Impulse * - contactManifold.oldFrictionVector2; - contactManifold.friction1Impulse = oldFrictionImpulse.dot( - contactManifold.frictionVector1); - contactManifold.friction2Impulse = oldFrictionImpulse.dot( - contactManifold.frictionVector2); - - // ------ First friction constraint at the center of the contact manifold ------ // - - // Compute the impulse P = J^T * lambda - Vector3 linearImpulseBody1 = -contactManifold.frictionVector1 * - contactManifold.friction1Impulse; - Vector3 angularImpulseBody1 = -contactManifold.r1CrossT1 * - contactManifold.friction1Impulse; - Vector3 linearImpulseBody2 = contactManifold.frictionVector1 * - contactManifold.friction1Impulse; - Vector3 angularImpulseBody2 = contactManifold.r2CrossT1 * - contactManifold.friction1Impulse; - const Impulse impulseFriction1(linearImpulseBody1, angularImpulseBody1, - linearImpulseBody2, angularImpulseBody2); - - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseFriction1, contactManifold); - - // ------ Second friction constraint at the center of the contact manifold ----- // - - // Compute the impulse P = J^T * lambda - linearImpulseBody1 = -contactManifold.frictionVector2 * - contactManifold.friction2Impulse; - angularImpulseBody1 = -contactManifold.r1CrossT2 * - contactManifold.friction2Impulse; - linearImpulseBody2 = contactManifold.frictionVector2 * - contactManifold.friction2Impulse; - angularImpulseBody2 = contactManifold.r2CrossT2 * - contactManifold.friction2Impulse; - const Impulse impulseFriction2(linearImpulseBody1, angularImpulseBody1, - linearImpulseBody2, angularImpulseBody2); - - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseFriction2, contactManifold); - - // ------ Twist friction constraint at the center of the contact manifold ------ // - - // Compute the impulse P = J^T * lambda - linearImpulseBody1 = Vector3(0.0, 0.0, 0.0); - angularImpulseBody1 = -contactManifold.normal * contactManifold.frictionTwistImpulse; - linearImpulseBody2 = Vector3(0.0, 0.0, 0.0); - angularImpulseBody2 = contactManifold.normal * contactManifold.frictionTwistImpulse; - const Impulse impulseTwistFriction(linearImpulseBody1, angularImpulseBody1, - linearImpulseBody2, angularImpulseBody2); - - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseTwistFriction, contactManifold); - - // ------ Rolling resistance at the center of the contact manifold ------ // - - // Compute the impulse P = J^T * lambda - angularImpulseBody1 = -contactManifold.rollingResistanceImpulse; - angularImpulseBody2 = contactManifold.rollingResistanceImpulse; - const Impulse impulseRollingResistance(Vector3::zero(), angularImpulseBody1, - Vector3::zero(), angularImpulseBody2); - - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseRollingResistance, contactManifold); - } - else { // If it is a new contact manifold - - // Initialize the accumulated impulses to zero - contactManifold.friction1Impulse = 0.0; - contactManifold.friction2Impulse = 0.0; - contactManifold.frictionTwistImpulse = 0.0; - contactManifold.rollingResistanceImpulse = Vector3::zero(); - } - } - */ } // Reset the total penetration impulse of friction constraints @@ -978,288 +679,13 @@ void ContactSolver::solveFrictionConstraints() { } } -// Solve the contacts -//void ContactSolver::solve() { - -// PROFILE("ContactSolver::solve()"); - -// decimal deltaLambda; -// decimal lambdaTemp; - -// // For each contact manifold -// for (uint c=0; c SLOP) biasPenetrationDepth = -(beta/mTimeStep) * -// max(0.0f, float(contactPoint.penetrationDepth - SLOP)); -// decimal b = biasPenetrationDepth + contactPoint.restitutionBias; - -// // Compute the Lagrange multiplier lambda -// if (mIsSplitImpulseActive) { -// deltaLambda = - (Jv + contactPoint.restitutionBias) * -// contactPoint.inversePenetrationMass; -// } -// else { -// deltaLambda = - (Jv + b) * contactPoint.inversePenetrationMass; -// } -// lambdaTemp = contactPoint.penetrationImpulse; -// contactPoint.penetrationImpulse = std::max(contactPoint.penetrationImpulse + -// deltaLambda, decimal(0.0)); -// deltaLambda = contactPoint.penetrationImpulse - lambdaTemp; - -// // Compute the impulse P=J^T * lambda -// const Impulse impulsePenetration = computePenetrationImpulse(deltaLambda, -// contactPoint); - -// // Apply the impulse to the bodies of the constraint -// applyImpulse(impulsePenetration, contactManifold); - -// sumPenetrationImpulse += contactPoint.penetrationImpulse; - -// // If the split impulse position correction is active -// if (mIsSplitImpulseActive) { - -// // Split impulse (position correction) -// const Vector3& v1Split = mSplitLinearVelocities[contactManifold.indexBody1]; -// const Vector3& w1Split = mSplitAngularVelocities[contactManifold.indexBody1]; -// const Vector3& v2Split = mSplitLinearVelocities[contactManifold.indexBody2]; -// const Vector3& w2Split = mSplitAngularVelocities[contactManifold.indexBody2]; -// Vector3 deltaVSplit = v2Split + w2Split.cross(contactPoint.r2) - -// v1Split - w1Split.cross(contactPoint.r1); -// decimal JvSplit = deltaVSplit.dot(contactPoint.normal); -// decimal deltaLambdaSplit = - (JvSplit + biasPenetrationDepth) * -// contactPoint.inversePenetrationMass; -// decimal lambdaTempSplit = contactPoint.penetrationSplitImpulse; -// contactPoint.penetrationSplitImpulse = std::max( -// contactPoint.penetrationSplitImpulse + -// deltaLambdaSplit, decimal(0.0)); -// deltaLambda = contactPoint.penetrationSplitImpulse - lambdaTempSplit; - -// // Compute the impulse P=J^T * lambda -// const Impulse splitImpulsePenetration = computePenetrationImpulse( -// deltaLambdaSplit, contactPoint); - -// applySplitImpulse(splitImpulsePenetration, contactManifold); -// } - -// // If we do not solve the friction constraints at the center of the contact manifold -// if (!mIsSolveFrictionAtContactManifoldCenterActive) { - -// // --------- Friction 1 --------- // - -// // Compute J*v -// deltaV = v2 + w2.cross(contactPoint.r2) - v1 - w1.cross(contactPoint.r1); -// Jv = deltaV.dot(contactPoint.frictionVector1); - -// // Compute the Lagrange multiplier lambda -// deltaLambda = -Jv; -// deltaLambda *= contactPoint.inverseFriction1Mass; -// decimal frictionLimit = contactManifold.frictionCoefficient * -// contactPoint.penetrationImpulse; -// lambdaTemp = contactPoint.friction1Impulse; -// contactPoint.friction1Impulse = std::max(-frictionLimit, -// std::min(contactPoint.friction1Impulse -// + deltaLambda, frictionLimit)); -// deltaLambda = contactPoint.friction1Impulse - lambdaTemp; - -// // Compute the impulse P=J^T * lambda -// const Impulse impulseFriction1 = computeFriction1Impulse(deltaLambda, -// contactPoint); - -// // Apply the impulses to the bodies of the constraint -// applyImpulse(impulseFriction1, contactManifold); - -// // --------- Friction 2 --------- // - -// // Compute J*v -// deltaV = v2 + w2.cross(contactPoint.r2) - v1 - w1.cross(contactPoint.r1); -// Jv = deltaV.dot(contactPoint.frictionVector2); - -// // Compute the Lagrange multiplier lambda -// deltaLambda = -Jv; -// deltaLambda *= contactPoint.inverseFriction2Mass; -// frictionLimit = contactManifold.frictionCoefficient * -// contactPoint.penetrationImpulse; -// lambdaTemp = contactPoint.friction2Impulse; -// contactPoint.friction2Impulse = std::max(-frictionLimit, -// std::min(contactPoint.friction2Impulse -// + deltaLambda, frictionLimit)); -// deltaLambda = contactPoint.friction2Impulse - lambdaTemp; - -// // Compute the impulse P=J^T * lambda -// const Impulse impulseFriction2 = computeFriction2Impulse(deltaLambda, -// contactPoint); - -// // Apply the impulses to the bodies of the constraint -// applyImpulse(impulseFriction2, contactManifold); - -// // --------- Rolling resistance constraint --------- // - -// if (contactManifold.rollingResistanceFactor > 0) { - -// // Compute J*v -// const Vector3 JvRolling = w2 - w1; - -// // Compute the Lagrange multiplier lambda -// Vector3 deltaLambdaRolling = contactManifold.inverseRollingResistance * (-JvRolling); -// decimal rollingLimit = contactManifold.rollingResistanceFactor * contactPoint.penetrationImpulse; -// Vector3 lambdaTempRolling = contactPoint.rollingResistanceImpulse; -// contactPoint.rollingResistanceImpulse = clamp(contactPoint.rollingResistanceImpulse + -// deltaLambdaRolling, rollingLimit); -// deltaLambdaRolling = contactPoint.rollingResistanceImpulse - lambdaTempRolling; - -// // Compute the impulse P=J^T * lambda -// const Impulse impulseRolling(Vector3::zero(), -deltaLambdaRolling, -// Vector3::zero(), deltaLambdaRolling); - -// // Apply the impulses to the bodies of the constraint -// applyImpulse(impulseRolling, contactManifold); -// } -// } - //} - - // If we solve the friction constraints at the center of the contact manifold -// if (mIsSolveFrictionAtContactManifoldCenterActive) { - -// // ------ First friction constraint at the center of the contact manifol ------ // - -// // Compute J*v -// Vector3 deltaV = v2 + w2.cross(contactManifold.r2Friction) -// - v1 - w1.cross(contactManifold.r1Friction); -// decimal Jv = deltaV.dot(contactManifold.frictionVector1); - -// // Compute the Lagrange multiplier lambda -// decimal deltaLambda = -Jv * contactManifold.inverseFriction1Mass; -// decimal frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; -// lambdaTemp = contactManifold.friction1Impulse; -// contactManifold.friction1Impulse = std::max(-frictionLimit, -// std::min(contactManifold.friction1Impulse + -// deltaLambda, frictionLimit)); -// deltaLambda = contactManifold.friction1Impulse - lambdaTemp; - -// // Compute the impulse P=J^T * lambda -// Vector3 linearImpulseBody1 = -contactManifold.frictionVector1 * deltaLambda; -// Vector3 angularImpulseBody1 = -contactManifold.r1CrossT1 * deltaLambda; -// Vector3 linearImpulseBody2 = contactManifold.frictionVector1 * deltaLambda; -// Vector3 angularImpulseBody2 = contactManifold.r2CrossT1 * deltaLambda; -// const Impulse impulseFriction1(linearImpulseBody1, angularImpulseBody1, -// linearImpulseBody2, angularImpulseBody2); - -// // Apply the impulses to the bodies of the constraint -// applyImpulse(impulseFriction1, contactManifold); - -// // ------ Second friction constraint at the center of the contact manifol ----- // - -// // Compute J*v -// deltaV = v2 + w2.cross(contactManifold.r2Friction) -// - v1 - w1.cross(contactManifold.r1Friction); -// Jv = deltaV.dot(contactManifold.frictionVector2); - -// // Compute the Lagrange multiplier lambda -// deltaLambda = -Jv * contactManifold.inverseFriction2Mass; -// frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; -// lambdaTemp = contactManifold.friction2Impulse; -// contactManifold.friction2Impulse = std::max(-frictionLimit, -// std::min(contactManifold.friction2Impulse + -// deltaLambda, frictionLimit)); -// deltaLambda = contactManifold.friction2Impulse - lambdaTemp; - -// // Compute the impulse P=J^T * lambda -// linearImpulseBody1 = -contactManifold.frictionVector2 * deltaLambda; -// angularImpulseBody1 = -contactManifold.r1CrossT2 * deltaLambda; -// linearImpulseBody2 = contactManifold.frictionVector2 * deltaLambda; -// angularImpulseBody2 = contactManifold.r2CrossT2 * deltaLambda; -// const Impulse impulseFriction2(linearImpulseBody1, angularImpulseBody1, -// linearImpulseBody2, angularImpulseBody2); - -// // Apply the impulses to the bodies of the constraint -// applyImpulse(impulseFriction2, contactManifold); - -// // ------ Twist friction constraint at the center of the contact manifol ------ // - -// // Compute J*v -// deltaV = w2 - w1; -// Jv = deltaV.dot(contactManifold.normal); - -// deltaLambda = -Jv * (contactManifold.inverseTwistFrictionMass); -// frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; -// lambdaTemp = contactManifold.frictionTwistImpulse; -// contactManifold.frictionTwistImpulse = std::max(-frictionLimit, -// std::min(contactManifold.frictionTwistImpulse -// + deltaLambda, frictionLimit)); -// deltaLambda = contactManifold.frictionTwistImpulse - lambdaTemp; - -// // Compute the impulse P=J^T * lambda -// linearImpulseBody1 = Vector3(0.0, 0.0, 0.0); -// angularImpulseBody1 = -contactManifold.normal * deltaLambda; -// linearImpulseBody2 = Vector3(0.0, 0.0, 0.0);; -// angularImpulseBody2 = contactManifold.normal * deltaLambda; -// const Impulse impulseTwistFriction(linearImpulseBody1, angularImpulseBody1, -// linearImpulseBody2, angularImpulseBody2); - -// // Apply the impulses to the bodies of the constraint -// applyImpulse(impulseTwistFriction, contactManifold); - -// // --------- Rolling resistance constraint at the center of the contact manifold --------- // - -// if (contactManifold.rollingResistanceFactor > 0) { - -// // Compute J*v -// const Vector3 JvRolling = w2 - w1; - -// // Compute the Lagrange multiplier lambda -// Vector3 deltaLambdaRolling = contactManifold.inverseRollingResistance * (-JvRolling); -// decimal rollingLimit = contactManifold.rollingResistanceFactor * sumPenetrationImpulse; -// Vector3 lambdaTempRolling = contactManifold.rollingResistanceImpulse; -// contactManifold.rollingResistanceImpulse = clamp(contactManifold.rollingResistanceImpulse + -// deltaLambdaRolling, rollingLimit); -// deltaLambdaRolling = contactManifold.rollingResistanceImpulse - lambdaTempRolling; - -// // Compute the impulse P=J^T * lambda -// angularImpulseBody1 = -deltaLambdaRolling; -// angularImpulseBody2 = deltaLambdaRolling; -// const Impulse impulseRolling(Vector3::zero(), angularImpulseBody1, -// Vector3::zero(), angularImpulseBody2); - -// // Apply the impulses to the bodies of the constraint -// applyImpulse(impulseRolling, contactManifold); -// } -// } -// } -//} - // Store the computed impulses to use them to // warm start the solver at the next iteration void ContactSolver::storeImpulses() { // Penetration constraints for (uint i=0; isetPenetrationImpulse(mPenetrationConstraints[i].penetrationImpulse); - } // Friction constraints @@ -1274,105 +700,17 @@ void ContactSolver::storeImpulses() { } /* - // For each contact manifold - for (uint c=0; csetPenetrationImpulse(contactPoint.penetrationImpulse); - contactPoint.externalContact->setFrictionImpulse1(contactPoint.friction1Impulse); - contactPoint.externalContact->setFrictionImpulse2(contactPoint.friction2Impulse); - contactPoint.externalContact->setRollingResistanceImpulse(contactPoint.rollingResistanceImpulse); - - contactPoint.externalContact->setFrictionVector1(contactPoint.frictionVector1); - contactPoint.externalContact->setFrictionVector2(contactPoint.frictionVector2); - } - - manifold.externalContactManifold->setFrictionImpulse1(manifold.friction1Impulse); - manifold.externalContactManifold->setFrictionImpulse2(manifold.friction2Impulse); - manifold.externalContactManifold->setFrictionTwistImpulse(manifold.frictionTwistImpulse); - manifold.externalContactManifold->setRollingResistanceImpulse(manifold.rollingResistanceImpulse); - manifold.externalContactManifold->setFrictionVector1(manifold.frictionVector1); - manifold.externalContactManifold->setFrictionVector2(manifold.frictionVector2); + if (mFrictionConstraints != nullptr) { + delete[] mFrictionConstraints; } */ } -/* -// Apply an impulse to the two bodies of a constraint -void ContactSolver::applyImpulse(const Impulse& impulse, - const ContactManifoldSolver& manifold) { - - PROFILE("ContactSolver::applyImpulse()"); - - // Update the velocities of the body 1 by applying the impulse P - mLinearVelocities[manifold.indexBody1] += manifold.massInverseBody1 * - impulse.linearImpulseBody1; - mAngularVelocities[manifold.indexBody1] += manifold.inverseInertiaTensorBody1 * - impulse.angularImpulseBody1; - - // Update the velocities of the body 1 by applying the impulse P - mLinearVelocities[manifold.indexBody2] += manifold.massInverseBody2 * - impulse.linearImpulseBody2; - mAngularVelocities[manifold.indexBody2] += manifold.inverseInertiaTensorBody2 * - impulse.angularImpulseBody2; -} -*/ - -/* -// Apply an impulse to the two bodies of a constraint -void ContactSolver::applySplitImpulse(const Impulse& impulse, - const ContactManifoldSolver& manifold) { - - // Update the velocities of the body 1 by applying the impulse P - mSplitLinearVelocities[manifold.indexBody1] += manifold.massInverseBody1 * - impulse.linearImpulseBody1; - mSplitAngularVelocities[manifold.indexBody1] += manifold.inverseInertiaTensorBody1 * - impulse.angularImpulseBody1; - - // Update the velocities of the body 1 by applying the impulse P - mSplitLinearVelocities[manifold.indexBody2] += manifold.massInverseBody2 * - impulse.linearImpulseBody2; - mSplitAngularVelocities[manifold.indexBody2] += manifold.inverseInertiaTensorBody2 * - impulse.angularImpulseBody2; -} -*/ - -// TODO : Delete this -// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction plane -// for a contact point. The two vectors have to be such that : t1 x t2 = contactNormal. -//void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, -// ContactPointSolver& contactPoint) const { - -// assert(contactPoint.normal.length() > 0.0); - -// // Compute the velocity difference vector in the tangential plane -// Vector3 normalVelocity = deltaVelocity.dot(contactPoint.normal) * contactPoint.normal; -// Vector3 tangentVelocity = deltaVelocity - normalVelocity; - -// // If the velocty difference in the tangential plane is not zero -// decimal lengthTangenVelocity = tangentVelocity.length(); -// if (lengthTangenVelocity > MACHINE_EPSILON) { - -// // Compute the first friction vector in the direction of the tangent -// // velocity difference -// contactPoint.frictionVector1 = tangentVelocity / lengthTangenVelocity; -// } -// else { - -// // Get any orthogonal vector to the normal as the first friction vector -// contactPoint.frictionVector1 = contactPoint.normal.getOneUnitOrthogonalVector(); -// } - -// // The second friction vector is computed by the cross product of the firs -// // friction vector and the contact normal -// contactPoint.frictionVector2 =contactPoint.normal.cross(contactPoint.frictionVector1).getUnit(); -//} - // Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction plane // for a contact manifold. The two vectors have to be such that : t1 x t2 = contactNormal. void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, @@ -1402,22 +740,3 @@ void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, // friction vector and the contact normal frictionConstraint.frictionVector2 = frictionConstraint.normal.cross(frictionConstraint.frictionVector1).getUnit(); } - -// Clean up the constraint solver -void ContactSolver::cleanup() { - - if (mContactConstraints != nullptr) { - delete[] mContactConstraints; - mContactConstraints = nullptr; - } - - if (mPenetrationConstraints != nullptr) { - delete[] mPenetrationConstraints; - mPenetrationConstraints = nullptr; - } - - if (mFrictionConstraints != nullptr) { - delete[] mFrictionConstraints; - mFrictionConstraints = nullptr; - } -} diff --git a/src/engine/ContactSolver.h b/src/engine/ContactSolver.h index f3f5dfa7..e5d5840d 100644 --- a/src/engine/ContactSolver.h +++ b/src/engine/ContactSolver.h @@ -31,6 +31,7 @@ #include "configuration.h" #include "constraint/Joint.h" #include "collision/ContactManifold.h" +#include "memory/SingleFrameAllocator.h" #include "Island.h" #include "Impulse.h" #include @@ -278,228 +279,6 @@ class ContactSolver { bool hasAtLeastOneRestingContactPoint; }; - // Structure ContactPointSolver - /** - * Contact solver internal data structure that to store all the - * information relative to a contact point - */ - struct ContactPointSolver { - - /// Index of body 1 in the constraint solver - uint indexBody1; - - /// Index of body 2 in the constraint solver - uint indexBody2; - - /// Inverse of the mass of body 1 - decimal massInverseBody1; - - /// Inverse of the mass of body 2 - decimal massInverseBody2; - - /// Inverse inertia tensor of body 1 - Matrix3x3 inverseInertiaTensorBody1; - - /// Inverse inertia tensor of body 2 - Matrix3x3 inverseInertiaTensorBody2; - - /// Point on body 1 where to apply the friction constraints - Vector3 frictionPointBody1; - - /// Point on body 2 where to apply the friction constraints - Vector3 frictionPointBody2; - - /// Accumulated normal impulse - decimal penetrationImpulse; - - /// Accumulated impulse in the 1st friction direction - decimal friction1Impulse; - - /// Accumulated impulse in the 2nd friction direction - decimal friction2Impulse; - - /// Accumulated split impulse for penetration correction - decimal penetrationSplitImpulse; - - /// Accumulated rolling resistance impulse - Vector3 rollingResistanceImpulse; - - /// Normal vector of the contact - Vector3 normal; - - /// First friction vector in the tangent plane - //Vector3 frictionVector1; - - /// Second friction vector in the tangent plane - //Vector3 frictionVector2; - - /// Old first friction vector in the tangent plane - Vector3 oldFrictionVector1; - - /// Old second friction vector in the tangent plane - Vector3 oldFrictionVector2; - - /// Vector from the body 1 center to the contact point - Vector3 r1; - - /// Vector from the body 2 center to the contact point - Vector3 r2; - - /// Cross product of r1 with 1st friction vector - //Vector3 r1CrossT1; - - /// Cross product of r1 with 2nd friction vector - //Vector3 r1CrossT2; - - /// Cross product of r2 with 1st friction vector - //Vector3 r2CrossT1; - - /// Cross product of r2 with 2nd friction vector - //Vector3 r2CrossT2; - - /// Cross product of r1 with the contact normal - //Vector3 r1CrossN; - - /// Cross product of r2 with the contact normal - //Vector3 r2CrossN; - - /// Penetration depth - decimal penetrationDepth; - - /// Velocity restitution bias - decimal restitutionBias; - - /// Inverse of the matrix K for the penenetration - //decimal inversePenetrationMass; - - /// Inverse of the matrix K for the 1st friction - decimal inverseFriction1Mass; - - /// Inverse of the matrix K for the 2nd friction - decimal inverseFriction2Mass; - - /// True if the contact was existing last time step - bool isRestingContact; - - /// Pointer to the external contact - ContactPoint* externalContact; - }; - - // Structure ContactManifoldSolver - /** - * Contact solver internal data structure to store all the - * information relative to a contact manifold. - */ - struct ContactManifoldSolver { - - /// Index of body 1 in the constraint solver - //uint indexBody1; - - /// Index of body 2 in the constraint solver - //uint indexBody2; - - /// Inverse of the mass of body 1 - //decimal massInverseBody1; - - // Inverse of the mass of body 2 - //decimal massInverseBody2; - - /// Inverse inertia tensor of body 1 - //Matrix3x3 inverseInertiaTensorBody1; - - /// Inverse inertia tensor of body 2 - //Matrix3x3 inverseInertiaTensorBody2; - - /// Contact point constraints - //ContactPointSolver contacts[MAX_CONTACT_POINTS_IN_MANIFOLD]; - - /// Number of contact points - //uint nbContacts; - - /// True if the body 1 is of type dynamic - //bool isBody1DynamicType; - - /// True if the body 2 is of type dynamic - //bool isBody2DynamicType; - - /// Mix of the restitution factor for two bodies - //decimal restitutionFactor; - - /// Mix friction coefficient for the two bodies - //decimal frictionCoefficient; - - /// Rolling resistance factor between the two bodies - decimal rollingResistanceFactor; - - /// Pointer to the external contact manifold - ContactManifold* externalContactManifold; - - // - Variables used when friction constraints are apply at the center of the manifold-// - - /// Average normal vector of the contact manifold - //Vector3 normal; - - /// Point on body 1 where to apply the friction constraints - //Vector3 frictionPointBody1; - - /// Point on body 2 where to apply the friction constraints - //Vector3 frictionPointBody2; - - /// R1 vector for the friction constraints - //Vector3 r1Friction; - - /// R2 vector for the friction constraints - //Vector3 r2Friction; - - /// Cross product of r1 with 1st friction vector - //Vector3 r1CrossT1; - - /// Cross product of r1 with 2nd friction vector - //Vector3 r1CrossT2; - - /// Cross product of r2 with 1st friction vector - //Vector3 r2CrossT1; - - /// Cross product of r2 with 2nd friction vector - //Vector3 r2CrossT2; - - /// Matrix K for the first friction constraint - //decimal inverseFriction1Mass; - - /// Matrix K for the second friction constraint - //decimal inverseFriction2Mass; - - /// Matrix K for the twist friction constraint - //decimal inverseTwistFrictionMass; - - /// Matrix K for the rolling resistance constraint - //Matrix3x3 inverseRollingResistance; - - /// First friction direction at contact manifold center - //Vector3 frictionVector1; - - /// Second friction direction at contact manifold center - //Vector3 frictionVector2; - - /// Old 1st friction direction at contact manifold center - //Vector3 oldFrictionVector1; - - /// Old 2nd friction direction at contact manifold center - //Vector3 oldFrictionVector2; - - /// First friction direction impulse at manifold center - //decimal friction1Impulse; - - /// Second friction direction impulse at manifold center - //decimal friction2Impulse; - - /// Twist friction impulse at contact manifold center - //decimal frictionTwistImpulse; - - /// Rolling resistance impulse - //Vector3 rollingResistanceImpulse; - }; - // -------------------- Constants --------------------- // /// Beta value for the penetration depth position correction without split impulses @@ -519,12 +298,12 @@ class ContactSolver { /// Split angular velocities for the position contact solver (split impulse) Vector3* mSplitAngularVelocities; + /// Reference to the single frame memory allocator + SingleFrameAllocator& mSingleFrameAllocator; + /// Current time step decimal mTimeStep; - /// Contact constraints - ContactManifoldSolver* mContactConstraints; - PenetrationConstraint* mPenetrationConstraints; FrictionConstraint* mFrictionConstraints; @@ -533,9 +312,6 @@ class ContactSolver { uint mNbFrictionConstraints; - /// Number of contact constraints - uint mNbContactManifolds; - /// Array of linear velocities Vector3* mLinearVelocities; @@ -557,8 +333,8 @@ class ContactSolver { // -------------------- Methods -------------------- // - /// Initialize the contact constraints before solving the system - void initializeContactConstraints(); + /// Initialize the constraint solver for a given island + void initializeForIsland(Island* island); /// Apply an impulse to the two bodies of a constraint //void applyImpulse(const Impulse& impulse, const ContactManifoldSolver& manifold); @@ -608,13 +384,17 @@ class ContactSolver { // -------------------- Methods -------------------- // /// Constructor - ContactSolver(const std::map& mapBodyToVelocityIndex); + ContactSolver(const std::map& mapBodyToVelocityIndex, + SingleFrameAllocator& singleFrameAllocator); /// Destructor ~ContactSolver() = default; - /// Initialize the constraint solver for a given island - void initializeForIsland(decimal dt, Island* island); + /// Initialize the contact constraints + void init(Island** islands, uint nbIslands, decimal timeStep); + + /// Solve the contact constraints of one iteration of the solve + void solve(); /// Set the split velocities arrays void setSplitVelocitiesArrays(Vector3* splitLinearVelocities, @@ -653,9 +433,6 @@ class ContactSolver { /// the contact manifold instead of solving them at each contact point void setIsSolveFrictionAtContactManifoldCenterActive(bool isActive); - /// Clean up the constraint solver - void cleanup(); - /// Return true if warmstarting is active bool IsWarmStartingActive() const; }; diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index 189ef0e0..0b1110af 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -40,7 +40,8 @@ using namespace std; */ DynamicsWorld::DynamicsWorld(const Vector3 &gravity) : CollisionWorld(), - mContactSolver(mMapBodyToConstrainedVelocityIndex), + mSingleFrameAllocator(SIZE_SINGLE_FRAME_ALLOCATOR_BYTES), + mContactSolver(mMapBodyToConstrainedVelocityIndex, mSingleFrameAllocator), mConstraintSolver(mMapBodyToConstrainedVelocityIndex), mNbVelocitySolverIterations(DEFAULT_VELOCITY_SOLVER_NB_ITERATIONS), mNbPositionSolverIterations(DEFAULT_POSITION_SOLVER_NB_ITERATIONS), @@ -82,10 +83,10 @@ DynamicsWorld::~DynamicsWorld() { mIslands[i]->~Island(); // Release the allocated memory for the island - mMemoryAllocator.release(mIslands[i], sizeof(Island)); + mPoolAllocator.release(mIslands[i], sizeof(Island)); } if (mNbIslandsCapacity > 0) { - mMemoryAllocator.release(mIslands, sizeof(Island*) * mNbIslandsCapacity); + mPoolAllocator.release(mIslands, sizeof(Island*) * mNbIslandsCapacity); } // Release the memory allocated for the bodies velocity arrays @@ -161,6 +162,9 @@ void DynamicsWorld::update(decimal timeStep) { // Reset the external force and torque applied to the bodies resetBodiesForceAndTorque(); + + // Reset the single frame memory allocator + mSingleFrameAllocator.reset(); } // Integrate position and orientation of the rigid bodies. @@ -364,27 +368,28 @@ void DynamicsWorld::solveContactsAndConstraints() { mConstraintSolver.setConstrainedPositionsArrays(mConstrainedPositions, mConstrainedOrientations); - // ---------- Solve velocity constraints for joints and contacts ---------- // + // Initialize the contact solver + mContactSolver.init(mIslands, mNbIslands, mTimeStep); // For each island of the world for (uint islandIndex = 0; islandIndex < mNbIslands; islandIndex++) { // Check if there are contacts and constraints to solve bool isConstraintsToSolve = mIslands[islandIndex]->getNbJoints() > 0; - bool isContactsToSolve = mIslands[islandIndex]->getNbContactManifolds() > 0; - if (!isConstraintsToSolve && !isContactsToSolve) continue; + //bool isContactsToSolve = mIslands[islandIndex]->getNbContactManifolds() > 0; + //if (!isConstraintsToSolve && !isContactsToSolve) continue; // If there are contacts in the current island - if (isContactsToSolve) { +// if (isContactsToSolve) { - // Initialize the solver - mContactSolver.initializeForIsland(mTimeStep, mIslands[islandIndex]); +// // Initialize the solver +// mContactSolver.initializeForIsland(mTimeStep, mIslands[islandIndex]); - // Warm start the contact solver - if (mContactSolver.IsWarmStartingActive()) { - mContactSolver.warmStart(); - } - } +// // Warm start the contact solver +// if (mContactSolver.IsWarmStartingActive()) { +// mContactSolver.warmStart(); +// } +// } // If there are constraints if (isConstraintsToSolve) { @@ -392,32 +397,40 @@ void DynamicsWorld::solveContactsAndConstraints() { // Initialize the constraint solver mConstraintSolver.initializeForIsland(mTimeStep, mIslands[islandIndex]); } + } // For each iteration of the velocity solver for (uint i=0; igetNbJoints() > 0; + if (isConstraintsToSolve) { + mConstraintSolver.solveVelocityConstraints(mIslands[islandIndex]); + } } + mContactSolver.solve(); + // Solve the contacts - if (isContactsToSolve) { +// if (isContactsToSolve) { - mContactSolver.resetTotalPenetrationImpulse(); +// mContactSolver.resetTotalPenetrationImpulse(); - mContactSolver.solvePenetrationConstraints(); - mContactSolver.solveFrictionConstraints(); - } +// mContactSolver.solvePenetrationConstraints(); +// mContactSolver.solveFrictionConstraints(); +// } } // Cache the lambda values in order to use them in the next // step and cleanup the contact solver - if (isContactsToSolve) { - mContactSolver.storeImpulses(); - mContactSolver.cleanup(); - } - } +// if (isContactsToSolve) { +// mContactSolver.storeImpulses(); +// mContactSolver.cleanup(); +// } + //} + + mContactSolver.storeImpulses(); } // Solve the position error correction of the constraints @@ -456,7 +469,7 @@ RigidBody* DynamicsWorld::createRigidBody(const Transform& transform) { assert(bodyID < std::numeric_limits::max()); // Create the rigid body - RigidBody* rigidBody = new (mMemoryAllocator.allocate(sizeof(RigidBody))) RigidBody(transform, + RigidBody* rigidBody = new (mPoolAllocator.allocate(sizeof(RigidBody))) RigidBody(transform, *this, bodyID); assert(rigidBody != nullptr); @@ -497,7 +510,7 @@ void DynamicsWorld::destroyRigidBody(RigidBody* rigidBody) { mRigidBodies.erase(rigidBody); // Free the object from the memory allocator - mMemoryAllocator.release(rigidBody, sizeof(RigidBody)); + mPoolAllocator.release(rigidBody, sizeof(RigidBody)); } // Create a joint between two bodies in the world and return a pointer to the new joint @@ -515,7 +528,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { // Ball-and-Socket joint case JointType::BALLSOCKETJOINT: { - void* allocatedMemory = mMemoryAllocator.allocate(sizeof(BallAndSocketJoint)); + void* allocatedMemory = mPoolAllocator.allocate(sizeof(BallAndSocketJoint)); const BallAndSocketJointInfo& info = static_cast( jointInfo); newJoint = new (allocatedMemory) BallAndSocketJoint(info); @@ -525,7 +538,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { // Slider joint case JointType::SLIDERJOINT: { - void* allocatedMemory = mMemoryAllocator.allocate(sizeof(SliderJoint)); + void* allocatedMemory = mPoolAllocator.allocate(sizeof(SliderJoint)); const SliderJointInfo& info = static_cast(jointInfo); newJoint = new (allocatedMemory) SliderJoint(info); break; @@ -534,7 +547,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { // Hinge joint case JointType::HINGEJOINT: { - void* allocatedMemory = mMemoryAllocator.allocate(sizeof(HingeJoint)); + void* allocatedMemory = mPoolAllocator.allocate(sizeof(HingeJoint)); const HingeJointInfo& info = static_cast(jointInfo); newJoint = new (allocatedMemory) HingeJoint(info); break; @@ -543,7 +556,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { // Fixed joint case JointType::FIXEDJOINT: { - void* allocatedMemory = mMemoryAllocator.allocate(sizeof(FixedJoint)); + void* allocatedMemory = mPoolAllocator.allocate(sizeof(FixedJoint)); const FixedJointInfo& info = static_cast(jointInfo); newJoint = new (allocatedMemory) FixedJoint(info); break; @@ -596,8 +609,8 @@ void DynamicsWorld::destroyJoint(Joint* joint) { mJoints.erase(joint); // Remove the joint from the joint list of the bodies involved in the joint - joint->mBody1->removeJointFromJointsList(mMemoryAllocator, joint); - joint->mBody2->removeJointFromJointsList(mMemoryAllocator, joint); + joint->mBody1->removeJointFromJointsList(mPoolAllocator, joint); + joint->mBody2->removeJointFromJointsList(mPoolAllocator, joint); size_t nbBytes = joint->getSizeInBytes(); @@ -605,7 +618,7 @@ void DynamicsWorld::destroyJoint(Joint* joint) { joint->~Joint(); // Release the allocated memory - mMemoryAllocator.release(joint, nbBytes); + mPoolAllocator.release(joint, nbBytes); } // Add the joint to the list of joints of the two bodies involved in the joint @@ -614,13 +627,13 @@ void DynamicsWorld::addJointToBody(Joint* joint) { assert(joint != nullptr); // Add the joint at the beginning of the linked list of joints of the first body - void* allocatedMemory1 = mMemoryAllocator.allocate(sizeof(JointListElement)); + void* allocatedMemory1 = mPoolAllocator.allocate(sizeof(JointListElement)); JointListElement* jointListElement1 = new (allocatedMemory1) JointListElement(joint, joint->mBody1->mJointsList); joint->mBody1->mJointsList = jointListElement1; // Add the joint at the beginning of the linked list of joints of the second body - void* allocatedMemory2 = mMemoryAllocator.allocate(sizeof(JointListElement)); + void* allocatedMemory2 = mPoolAllocator.allocate(sizeof(JointListElement)); JointListElement* jointListElement2 = new (allocatedMemory2) JointListElement(joint, joint->mBody2->mJointsList); joint->mBody2->mJointsList = jointListElement2; @@ -646,16 +659,16 @@ void DynamicsWorld::computeIslands() { mIslands[i]->~Island(); // Release the allocated memory for the island - mMemoryAllocator.release(mIslands[i], sizeof(Island)); + mPoolAllocator.release(mIslands[i], sizeof(Island)); } // Allocate and create the array of islands if (mNbIslandsCapacity != nbBodies && nbBodies > 0) { if (mNbIslandsCapacity > 0) { - mMemoryAllocator.release(mIslands, sizeof(Island*) * mNbIslandsCapacity); + mPoolAllocator.release(mIslands, sizeof(Island*) * mNbIslandsCapacity); } mNbIslandsCapacity = nbBodies; - mIslands = (Island**)mMemoryAllocator.allocate(sizeof(Island*) * mNbIslandsCapacity); + mIslands = (Island**)mPoolAllocator.allocate(sizeof(Island*) * mNbIslandsCapacity); } mNbIslands = 0; @@ -672,7 +685,7 @@ void DynamicsWorld::computeIslands() { // Create a stack (using an array) for the rigid bodies to visit during the Depth First Search size_t nbBytesStack = sizeof(RigidBody*) * nbBodies; - RigidBody** stackBodiesToVisit = (RigidBody**)mMemoryAllocator.allocate(nbBytesStack); + RigidBody** stackBodiesToVisit = (RigidBody**)mPoolAllocator.allocate(nbBytesStack); // For each rigid body of the world for (std::set::iterator it = mRigidBodies.begin(); it != mRigidBodies.end(); ++it) { @@ -695,10 +708,10 @@ void DynamicsWorld::computeIslands() { body->mIsAlreadyInIsland = true; // Create the new island - void* allocatedMemoryIsland = mMemoryAllocator.allocate(sizeof(Island)); + void* allocatedMemoryIsland = mPoolAllocator.allocate(sizeof(Island)); mIslands[mNbIslands] = new (allocatedMemoryIsland) Island(nbBodies, nbContactManifolds, - mJoints.size(), mMemoryAllocator); + mJoints.size(), mPoolAllocator); // While there are still some bodies to visit in the stack while (stackIndex > 0) { @@ -790,7 +803,7 @@ void DynamicsWorld::computeIslands() { } // Release the allocated memory for the stack of bodies to visit - mMemoryAllocator.release(stackBodiesToVisit, nbBytesStack); + mPoolAllocator.release(stackBodiesToVisit, nbBytesStack); } // Put bodies to sleep if needed. diff --git a/src/engine/DynamicsWorld.h b/src/engine/DynamicsWorld.h index 7dc715c9..542e0f4b 100644 --- a/src/engine/DynamicsWorld.h +++ b/src/engine/DynamicsWorld.h @@ -50,6 +50,9 @@ class DynamicsWorld : public CollisionWorld { // -------------------- Attributes -------------------- // + /// Single frame Memory allocator + SingleFrameAllocator mSingleFrameAllocator; + /// Contact solver ContactSolver mContactSolver; diff --git a/src/engine/Island.cpp b/src/engine/Island.cpp index 41560bde..8cf743a3 100644 --- a/src/engine/Island.cpp +++ b/src/engine/Island.cpp @@ -30,7 +30,7 @@ using namespace reactphysics3d; // Constructor Island::Island(uint nbMaxBodies, uint nbMaxContactManifolds, uint nbMaxJoints, - MemoryAllocator& memoryAllocator) + PoolAllocator& memoryAllocator) : mBodies(nullptr), mContactManifolds(nullptr), mJoints(nullptr), mNbBodies(0), mNbContactManifolds(0), mNbJoints(0), mMemoryAllocator(memoryAllocator) { diff --git a/src/engine/Island.h b/src/engine/Island.h index 512a0d1b..227a78e5 100644 --- a/src/engine/Island.h +++ b/src/engine/Island.h @@ -27,7 +27,7 @@ #define REACTPHYSICS3D_ISLAND_H // Libraries -#include "memory/MemoryAllocator.h" +#include "memory/PoolAllocator.h" #include "body/RigidBody.h" #include "constraint/Joint.h" #include "collision/ContactManifold.h" @@ -64,7 +64,7 @@ class Island { uint mNbJoints; /// Reference to the memory allocator - MemoryAllocator& mMemoryAllocator; + PoolAllocator& mMemoryAllocator; /// Number of bytes allocated for the bodies array size_t mNbAllocatedBytesBodies; @@ -81,7 +81,7 @@ class Island { /// Constructor Island(uint nbMaxBodies, uint nbMaxContactManifolds, uint nbMaxJoints, - MemoryAllocator& memoryAllocator); + PoolAllocator& memoryAllocator); /// Destructor ~Island(); diff --git a/src/engine/OverlappingPair.cpp b/src/engine/OverlappingPair.cpp index 7efca599..48658f5c 100644 --- a/src/engine/OverlappingPair.cpp +++ b/src/engine/OverlappingPair.cpp @@ -31,7 +31,7 @@ using namespace reactphysics3d; // Constructor OverlappingPair::OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, - int nbMaxContactManifolds, MemoryAllocator& memoryAllocator) + int nbMaxContactManifolds, PoolAllocator& memoryAllocator) : mContactManifoldSet(shape1, shape2, memoryAllocator, nbMaxContactManifolds), mCachedSeparatingAxis(0.0, 1.0, 0.0) { diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index 7995b0d2..70ee1c3f 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -63,7 +63,7 @@ class OverlappingPair { /// Constructor OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, - int nbMaxContactManifolds, MemoryAllocator& memoryAllocator); + int nbMaxContactManifolds, PoolAllocator& memoryAllocator); /// Destructor ~OverlappingPair() = default; From 8f4979f4a2e50419dc25a5696c83dca45932e047 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 22 Sep 2016 23:24:03 +0200 Subject: [PATCH 028/248] Allocate memory in the SingleFrameAllocator in the update() method --- src/engine/DynamicsWorld.cpp | 96 +++++++++--------------------------- src/engine/DynamicsWorld.h | 6 --- src/engine/Island.cpp | 24 +++------ src/engine/Island.h | 16 +----- 4 files changed, 34 insertions(+), 108 deletions(-) diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index 0b1110af..91312546 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -49,8 +49,7 @@ DynamicsWorld::DynamicsWorld(const Vector3 &gravity) mIsGravityEnabled(true), mConstrainedLinearVelocities(nullptr), mConstrainedAngularVelocities(nullptr), mSplitLinearVelocities(nullptr), mSplitAngularVelocities(nullptr), mConstrainedPositions(nullptr), - mConstrainedOrientations(nullptr), mNbIslands(0), - mNbIslandsCapacity(0), mIslands(nullptr), mNbBodiesCapacity(0), + mConstrainedOrientations(nullptr), mNbIslands(0), mIslands(nullptr), mSleepLinearVelocity(DEFAULT_SLEEP_LINEAR_VELOCITY), mSleepAngularVelocity(DEFAULT_SLEEP_ANGULAR_VELOCITY), mTimeBeforeSleep(DEFAULT_TIME_BEFORE_SLEEP) { @@ -76,29 +75,6 @@ DynamicsWorld::~DynamicsWorld() { destroyRigidBody(*itToRemove); } - // Release the memory allocated for the islands - for (uint i=0; i~Island(); - - // Release the allocated memory for the island - mPoolAllocator.release(mIslands[i], sizeof(Island)); - } - if (mNbIslandsCapacity > 0) { - mPoolAllocator.release(mIslands, sizeof(Island*) * mNbIslandsCapacity); - } - - // Release the memory allocated for the bodies velocity arrays - if (mNbBodiesCapacity > 0) { - delete[] mSplitLinearVelocities; - delete[] mSplitAngularVelocities; - delete[] mConstrainedLinearVelocities; - delete[] mConstrainedAngularVelocities; - delete[] mConstrainedPositions; - delete[] mConstrainedOrientations; - } - assert(mJoints.size() == 0); assert(mRigidBodies.size() == 0); @@ -245,31 +221,26 @@ void DynamicsWorld::updateBodiesState() { // Initialize the bodies velocities arrays for the next simulation step. void DynamicsWorld::initVelocityArrays() { + PROFILE("DynamicsWorld::initVelocityArrays()"); + // Allocate memory for the bodies velocity arrays uint nbBodies = mRigidBodies.size(); - if (mNbBodiesCapacity != nbBodies && nbBodies > 0) { - if (mNbBodiesCapacity > 0) { - delete[] mSplitLinearVelocities; - delete[] mSplitAngularVelocities; - } - mNbBodiesCapacity = nbBodies; - // TODO : Use better memory allocation here - mSplitLinearVelocities = new Vector3[mNbBodiesCapacity]; - mSplitAngularVelocities = new Vector3[mNbBodiesCapacity]; - mConstrainedLinearVelocities = new Vector3[mNbBodiesCapacity]; - mConstrainedAngularVelocities = new Vector3[mNbBodiesCapacity]; - mConstrainedPositions = new Vector3[mNbBodiesCapacity]; - mConstrainedOrientations = new Quaternion[mNbBodiesCapacity]; - assert(mSplitLinearVelocities != nullptr); - assert(mSplitAngularVelocities != nullptr); - assert(mConstrainedLinearVelocities != nullptr); - assert(mConstrainedAngularVelocities != nullptr); - assert(mConstrainedPositions != nullptr); - assert(mConstrainedOrientations != nullptr); - } + + mSplitLinearVelocities = static_cast(mSingleFrameAllocator.allocate(nbBodies * sizeof(Vector3))); + mSplitAngularVelocities = static_cast(mSingleFrameAllocator.allocate(nbBodies * sizeof(Vector3))); + mConstrainedLinearVelocities = static_cast(mSingleFrameAllocator.allocate(nbBodies * sizeof(Vector3))); + mConstrainedAngularVelocities = static_cast(mSingleFrameAllocator.allocate(nbBodies * sizeof(Vector3))); + mConstrainedPositions = static_cast(mSingleFrameAllocator.allocate(nbBodies * sizeof(Vector3))); + mConstrainedOrientations = static_cast(mSingleFrameAllocator.allocate(nbBodies * sizeof(Quaternion))); + assert(mSplitLinearVelocities != nullptr); + assert(mSplitAngularVelocities != nullptr); + assert(mConstrainedLinearVelocities != nullptr); + assert(mConstrainedAngularVelocities != nullptr); + assert(mConstrainedPositions != nullptr); + assert(mConstrainedOrientations != nullptr); // Reset the velocities arrays - for (uint i=0; i~Island(); - - // Release the allocated memory for the island - mPoolAllocator.release(mIslands[i], sizeof(Island)); - } - - // Allocate and create the array of islands - if (mNbIslandsCapacity != nbBodies && nbBodies > 0) { - if (mNbIslandsCapacity > 0) { - mPoolAllocator.release(mIslands, sizeof(Island*) * mNbIslandsCapacity); - } - mNbIslandsCapacity = nbBodies; - mIslands = (Island**)mPoolAllocator.allocate(sizeof(Island*) * mNbIslandsCapacity); - } + // Allocate and create the array of islands pointer. This memory is allocated + // in the single frame allocator + mIslands = static_cast(mSingleFrameAllocator.allocate(sizeof(Island*) * nbBodies)); mNbIslands = 0; int nbContactManifolds = 0; @@ -685,7 +641,7 @@ void DynamicsWorld::computeIslands() { // Create a stack (using an array) for the rigid bodies to visit during the Depth First Search size_t nbBytesStack = sizeof(RigidBody*) * nbBodies; - RigidBody** stackBodiesToVisit = (RigidBody**)mPoolAllocator.allocate(nbBytesStack); + RigidBody** stackBodiesToVisit = static_cast(mSingleFrameAllocator.allocate(nbBytesStack)); // For each rigid body of the world for (std::set::iterator it = mRigidBodies.begin(); it != mRigidBodies.end(); ++it) { @@ -708,10 +664,9 @@ void DynamicsWorld::computeIslands() { body->mIsAlreadyInIsland = true; // Create the new island - void* allocatedMemoryIsland = mPoolAllocator.allocate(sizeof(Island)); - mIslands[mNbIslands] = new (allocatedMemoryIsland) Island(nbBodies, - nbContactManifolds, - mJoints.size(), mPoolAllocator); + void* allocatedMemoryIsland = mSingleFrameAllocator.allocate(sizeof(Island)); + mIslands[mNbIslands] = new (allocatedMemoryIsland) Island(nbBodies, nbContactManifolds, mJoints.size(), + mSingleFrameAllocator); // While there are still some bodies to visit in the stack while (stackIndex > 0) { @@ -801,9 +756,6 @@ void DynamicsWorld::computeIslands() { mNbIslands++; } - - // Release the allocated memory for the stack of bodies to visit - mPoolAllocator.release(stackBodiesToVisit, nbBytesStack); } // Put bodies to sleep if needed. diff --git a/src/engine/DynamicsWorld.h b/src/engine/DynamicsWorld.h index 542e0f4b..dec383a1 100644 --- a/src/engine/DynamicsWorld.h +++ b/src/engine/DynamicsWorld.h @@ -109,15 +109,9 @@ class DynamicsWorld : public CollisionWorld { /// Number of islands in the world uint mNbIslands; - /// Current allocated capacity for the islands - uint mNbIslandsCapacity; - /// Array with all the islands of awaken bodies Island** mIslands; - /// Current allocated capacity for the bodies - uint mNbBodiesCapacity; - /// Sleep linear velocity threshold decimal mSleepLinearVelocity; diff --git a/src/engine/Island.cpp b/src/engine/Island.cpp index 8cf743a3..19eef304 100644 --- a/src/engine/Island.cpp +++ b/src/engine/Island.cpp @@ -29,26 +29,18 @@ using namespace reactphysics3d; // Constructor -Island::Island(uint nbMaxBodies, uint nbMaxContactManifolds, uint nbMaxJoints, - PoolAllocator& memoryAllocator) +Island::Island(uint nbMaxBodies, uint nbMaxContactManifolds, uint nbMaxJoints, SingleFrameAllocator& allocator) : mBodies(nullptr), mContactManifolds(nullptr), mJoints(nullptr), mNbBodies(0), - mNbContactManifolds(0), mNbJoints(0), mMemoryAllocator(memoryAllocator) { + mNbContactManifolds(0), mNbJoints(0) { - // Allocate memory for the arrays - mNbAllocatedBytesBodies = sizeof(RigidBody*) * nbMaxBodies; - mBodies = (RigidBody**) mMemoryAllocator.allocate(mNbAllocatedBytesBodies); - mNbAllocatedBytesContactManifolds = sizeof(ContactManifold*) * nbMaxContactManifolds; - mContactManifolds = (ContactManifold**) mMemoryAllocator.allocate( - mNbAllocatedBytesContactManifolds); - mNbAllocatedBytesJoints = sizeof(Joint*) * nbMaxJoints; - mJoints = (Joint**) mMemoryAllocator.allocate(mNbAllocatedBytesJoints); + // Allocate memory for the arrays on the single frame allocator + mBodies = static_cast(allocator.allocate(sizeof(RigidBody*) * nbMaxBodies)); + mContactManifolds = static_cast(allocator.allocate(sizeof(ContactManifold*) * nbMaxContactManifolds)); + mJoints = static_cast(allocator.allocate(sizeof(Joint*) * nbMaxJoints)); } // Destructor Island::~Island() { - - // Release the memory of the arrays - mMemoryAllocator.release(mBodies, mNbAllocatedBytesBodies); - mMemoryAllocator.release(mContactManifolds, mNbAllocatedBytesContactManifolds); - mMemoryAllocator.release(mJoints, mNbAllocatedBytesJoints); + // This destructor is never called because memory is allocated on the + // single frame allocator } diff --git a/src/engine/Island.h b/src/engine/Island.h index 227a78e5..5f370004 100644 --- a/src/engine/Island.h +++ b/src/engine/Island.h @@ -27,7 +27,7 @@ #define REACTPHYSICS3D_ISLAND_H // Libraries -#include "memory/PoolAllocator.h" +#include "memory/SingleFrameAllocator.h" #include "body/RigidBody.h" #include "constraint/Joint.h" #include "collision/ContactManifold.h" @@ -63,25 +63,13 @@ class Island { /// Current number of joints in the island uint mNbJoints; - /// Reference to the memory allocator - PoolAllocator& mMemoryAllocator; - - /// Number of bytes allocated for the bodies array - size_t mNbAllocatedBytesBodies; - - /// Number of bytes allocated for the contact manifolds array - size_t mNbAllocatedBytesContactManifolds; - - /// Number of bytes allocated for the joints array - size_t mNbAllocatedBytesJoints; - public: // -------------------- Methods -------------------- // /// Constructor Island(uint nbMaxBodies, uint nbMaxContactManifolds, uint nbMaxJoints, - PoolAllocator& memoryAllocator); + SingleFrameAllocator& allocator); /// Destructor ~Island(); From c59781519167421c05525e0b48586b16df64f5e8 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 26 Sep 2016 22:51:30 +0200 Subject: [PATCH 029/248] Remove unecessary variables in constraints and cache inverse inertia world tensor of bodies --- src/body/RigidBody.cpp | 17 ++++ src/body/RigidBody.h | 23 +++-- src/engine/ContactSolver.cpp | 163 +++++++++++++---------------------- src/engine/ContactSolver.h | 13 --- src/engine/DynamicsWorld.cpp | 3 + 5 files changed, 97 insertions(+), 122 deletions(-) diff --git a/src/body/RigidBody.cpp b/src/body/RigidBody.cpp index 74ee8a05..6e6a55e6 100644 --- a/src/body/RigidBody.cpp +++ b/src/body/RigidBody.cpp @@ -46,6 +46,9 @@ RigidBody::RigidBody(const Transform& transform, CollisionWorld& world, bodyinde // Compute the inverse mass mMassInverse = decimal(1.0) / mInitMass; + + // Update the world inverse inertia tensor + updateInertiaTensorInverseWorld(); } // Destructor @@ -90,11 +93,15 @@ void RigidBody::setType(BodyType type) { mMassInverse = decimal(0.0); mInertiaTensorLocal.setToZero(); mInertiaTensorLocalInverse.setToZero(); + mInertiaTensorInverseWorld.setToZero(); } else { // If it is a dynamic body mMassInverse = decimal(1.0) / mInitMass; mInertiaTensorLocalInverse = mInertiaTensorLocal.getInverse(); + + // Update the world inverse inertia tensor + updateInertiaTensorInverseWorld(); } // Awake the body @@ -125,6 +132,9 @@ void RigidBody::setInertiaTensorLocal(const Matrix3x3& inertiaTensorLocal) { // Compute the inverse local inertia tensor mInertiaTensorLocalInverse = mInertiaTensorLocal.getInverse(); + + // Update the world inverse inertia tensor + updateInertiaTensorInverseWorld(); } // Set the local center of mass of the body (in local-space coordinates) @@ -314,6 +324,9 @@ void RigidBody::setTransform(const Transform& transform) { // Update the linear velocity of the center of mass mLinearVelocity += mAngularVelocity.cross(mCenterOfMassWorld - oldCenterOfMass); + // Update the world inverse inertia tensor + updateInertiaTensorInverseWorld(); + // Update the broad-phase state of the body updateBroadPhaseState(); } @@ -326,6 +339,7 @@ void RigidBody::recomputeMassInformation() { mMassInverse = decimal(0.0); mInertiaTensorLocal.setToZero(); mInertiaTensorLocalInverse.setToZero(); + mInertiaTensorInverseWorld.setToZero(); mCenterOfMassLocal.setToZero(); // If it is STATIC or KINEMATIC body @@ -386,6 +400,9 @@ void RigidBody::recomputeMassInformation() { // Compute the local inverse inertia tensor mInertiaTensorLocalInverse = mInertiaTensorLocal.getInverse(); + // Update the world inverse inertia tensor + updateInertiaTensorInverseWorld(); + // Update the linear velocity of the center of mass mLinearVelocity += mAngularVelocity.cross(mCenterOfMassWorld - oldCenterOfMass); } diff --git a/src/body/RigidBody.h b/src/body/RigidBody.h index 0ffc6257..a38b53d5 100644 --- a/src/body/RigidBody.h +++ b/src/body/RigidBody.h @@ -83,6 +83,9 @@ class RigidBody : public CollisionBody { /// Inverse of the inertia tensor of the body Matrix3x3 mInertiaTensorLocalInverse; + /// Inverse of the world inertia tensor of the body + Matrix3x3 mInertiaTensorInverseWorld; + /// Inverse of the mass of the body decimal mMassInverse; @@ -112,6 +115,9 @@ class RigidBody : public CollisionBody { /// Update the broad-phase state for this body (because it has moved for instance) virtual void updateBroadPhaseState() const override; + /// Update the world inverse inertia tensor of the body + void updateInertiaTensorInverseWorld(); + public : // -------------------- Methods -------------------- // @@ -291,12 +297,19 @@ inline Matrix3x3 RigidBody::getInertiaTensorWorld() const { */ inline Matrix3x3 RigidBody::getInertiaTensorInverseWorld() const { - // TODO : DO NOT RECOMPUTE THE MATRIX MULTIPLICATION EVERY TIME. WE NEED TO STORE THE - // INVERSE WORLD TENSOR IN THE CLASS AND UPLDATE IT WHEN THE ORIENTATION OF THE BODY CHANGES - // Compute and return the inertia tensor in world coordinates - return mTransform.getOrientation().getMatrix() * mInertiaTensorLocalInverse * - mTransform.getOrientation().getMatrix().getTranspose(); + return mInertiaTensorInverseWorld; +} + +// Update the world inverse inertia tensor of the body +/// The inertia tensor I_w in world coordinates is computed with the +/// local inverse inertia tensor I_b^-1 in body coordinates +/// by I_w = R * I_b^-1 * R^T +/// where R is the rotation matrix (and R^T its transpose) of the +/// current orientation quaternion of the body +inline void RigidBody::updateInertiaTensorInverseWorld() { + Matrix3x3 orientation = mTransform.getOrientation().getMatrix(); + mInertiaTensorInverseWorld = orientation * mInertiaTensorLocalInverse * orientation.getTranspose(); } // Return true if the gravity needs to be applied to this rigid body diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index b271aa6e..d2218136 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -36,7 +36,7 @@ using namespace std; // Constants initialization const decimal ContactSolver::BETA = decimal(0.2); const decimal ContactSolver::BETA_SPLIT_IMPULSE = decimal(0.2); -const decimal ContactSolver::SLOP= decimal(0.01); +const decimal ContactSolver::SLOP = decimal(0.01); // Constructor ContactSolver::ContactSolver(const std::map& mapBodyToVelocityIndex, @@ -74,14 +74,10 @@ void ContactSolver::init(Island** islands, uint nbIslands, decimal timeStep) { // TODO : Count exactly the number of constraints to allocate here uint nbPenetrationConstraints = nbContactManifolds * MAX_CONTACT_POINTS_IN_MANIFOLD; mPenetrationConstraints = static_cast(mSingleFrameAllocator.allocate(sizeof(PenetrationConstraint) * nbPenetrationConstraints)); - //mPenetrationConstraints = new PenetrationConstraint[nbPenetrationConstraints]; assert(mPenetrationConstraints != nullptr); - //mPenetrationConstraints = new PenetrationConstraint[mNbContactManifolds * 4]; mFrictionConstraints = static_cast(mSingleFrameAllocator.allocate(sizeof(FrictionConstraint) * nbContactManifolds)); - //mFrictionConstraints = new FrictionConstraint[nbContactManifolds]; assert(mFrictionConstraints != nullptr); - //mFrictionConstraints = new FrictionConstraint[mNbContactManifolds]; // For each island of the world for (uint islandIndex = 0; islandIndex < nbIslands; islandIndex++) { @@ -146,23 +142,17 @@ void ContactSolver::initializeForIsland(Island* island) { // contact manifold mFrictionConstraints[mNbFrictionConstraints].massInverseBody1 = body1->mMassInverse; mFrictionConstraints[mNbFrictionConstraints].massInverseBody2 = body2->mMassInverse; - //internalManifold.nbContacts = externalManifold->getNbContactPoints(); decimal restitutionFactor = computeMixedRestitutionFactor(body1, body2); mFrictionConstraints[mNbFrictionConstraints].frictionCoefficient = computeMixedFrictionCoefficient(body1, body2); mFrictionConstraints[mNbFrictionConstraints].rollingResistanceFactor = computeMixedRollingResistance(body1, body2); mFrictionConstraints[mNbFrictionConstraints].hasAtLeastOneRestingContactPoint = false; - //internalManifold.isBody1DynamicType = body1->getType() == BodyType::DYNAMIC; - //internalManifold.isBody2DynamicType = body2->getType() == BodyType::DYNAMIC; bool isBody1DynamicType = body1->getType() == BodyType::DYNAMIC; bool isBody2DynamicType = body2->getType() == BodyType::DYNAMIC; - // If we solve the friction constraints at the center of the contact manifold - //if (mIsSolveFrictionAtContactManifoldCenterActive) { - mFrictionConstraints[mNbFrictionConstraints].frictionPointBody1 = Vector3::zero(); - mFrictionConstraints[mNbFrictionConstraints].frictionPointBody2 = Vector3::zero(); - mFrictionConstraints[mNbFrictionConstraints].normal = Vector3::zero(); - //} + Vector3 frictionPointBody1; + Vector3 frictionPointBody2; + mFrictionConstraints[mNbFrictionConstraints].normal.setToZero(); // Compute the inverse K matrix for the rolling resistance constraint mFrictionConstraints[mNbFrictionConstraints].inverseRollingResistance.setToZero(); @@ -186,7 +176,6 @@ void ContactSolver::initializeForIsland(Island* island) { mPenetrationConstraints[mNbPenetrationConstraints].inverseInertiaTensorBody2 = I2; mPenetrationConstraints[mNbPenetrationConstraints].massInverseBody1 = body1->mMassInverse; mPenetrationConstraints[mNbPenetrationConstraints].massInverseBody2 = body2->mMassInverse; - mPenetrationConstraints[mNbPenetrationConstraints].restitutionFactor = restitutionFactor; mPenetrationConstraints[mNbPenetrationConstraints].indexFrictionConstraint = mNbFrictionConstraints; mPenetrationConstraints[mNbPenetrationConstraints].contactPoint = externalContact; @@ -196,8 +185,6 @@ void ContactSolver::initializeForIsland(Island* island) { mPenetrationConstraints[mNbPenetrationConstraints].r1 = p1 - x1; mPenetrationConstraints[mNbPenetrationConstraints].r2 = p2 - x2; - - //mPenetrationConstraints[penConstIndex].externalContact = externalContact; mPenetrationConstraints[mNbPenetrationConstraints].normal = externalContact->getNormal(); mPenetrationConstraints[mNbPenetrationConstraints].penetrationDepth = externalContact->getPenetrationDepth(); mPenetrationConstraints[mNbPenetrationConstraints].isRestingContact = externalContact->getIsRestingContact(); @@ -205,18 +192,10 @@ void ContactSolver::initializeForIsland(Island* island) { mFrictionConstraints[mNbFrictionConstraints].hasAtLeastOneRestingContactPoint |= mPenetrationConstraints[mNbPenetrationConstraints].isRestingContact; externalContact->setIsRestingContact(true); - //mPenetrationConstraints[penConstIndex].oldFrictionVector1 = externalContact->getFrictionVector1(); - //mPenetrationConstraints[penConstIndex].oldFrictionVector2 = externalContact->getFrictionVector2(); mPenetrationConstraints[mNbPenetrationConstraints].penetrationImpulse = 0.0; - //mPenetrationConstraints[penConstIndex].friction1Impulse = 0.0; - //mPenetrationConstraints[penConstIndex].friction2Impulse = 0.0; - //mPenetrationConstraints[penConstIndex].rollingResistanceImpulse = Vector3::zero(); - // If we solve the friction constraints at the center of the contact manifold - //if (mIsSolveFrictionAtContactManifoldCenterActive) { - mFrictionConstraints[mNbFrictionConstraints].frictionPointBody1 += p1; - mFrictionConstraints[mNbFrictionConstraints].frictionPointBody2 += p2; - //} + frictionPointBody1 += p1; + frictionPointBody2 += p2; // Compute the velocity difference Vector3 deltaV = v2 + w2.cross(mPenetrationConstraints[mNbPenetrationConstraints].r2) - v1 - w1.cross(mPenetrationConstraints[mNbPenetrationConstraints].r1); @@ -238,7 +217,7 @@ void ContactSolver::initializeForIsland(Island* island) { mPenetrationConstraints[mNbPenetrationConstraints].restitutionBias = 0.0; decimal deltaVDotN = deltaV.dot(mPenetrationConstraints[mNbPenetrationConstraints].normal); if (deltaVDotN < -RESTITUTION_VELOCITY_THRESHOLD) { - mPenetrationConstraints[mNbPenetrationConstraints].restitutionBias = mPenetrationConstraints[mNbPenetrationConstraints].restitutionFactor * deltaVDotN; + mPenetrationConstraints[mNbPenetrationConstraints].restitutionBias = restitutionFactor * deltaVDotN; } // If the warm starting of the contact solver is active @@ -251,77 +230,70 @@ void ContactSolver::initializeForIsland(Island* island) { // Initialize the split impulses to zero mPenetrationConstraints[mNbPenetrationConstraints].penetrationSplitImpulse = 0.0; - // If we solve the friction constraints at the center of the contact manifold - //if (mIsSolveFrictionAtContactManifoldCenterActive) { - mFrictionConstraints[mNbFrictionConstraints].normal += mPenetrationConstraints[mNbPenetrationConstraints].normal; - //} + mFrictionConstraints[mNbFrictionConstraints].normal += mPenetrationConstraints[mNbPenetrationConstraints].normal; mNbPenetrationConstraints++; nbContacts++; } - // If we solve the friction constraints at the center of the contact manifold - //if (mIsSolveFrictionAtContactManifoldCenterActive) { + frictionPointBody1 /= nbContacts; + frictionPointBody2 /= nbContacts; + mFrictionConstraints[mNbFrictionConstraints].r1Friction = frictionPointBody1 - x1; + mFrictionConstraints[mNbFrictionConstraints].r2Friction = frictionPointBody2 - x2; + mFrictionConstraints[mNbFrictionConstraints].oldFrictionVector1 = externalManifold->getFrictionVector1(); + mFrictionConstraints[mNbFrictionConstraints].oldFrictionVector2 = externalManifold->getFrictionVector2(); - //mFrictionConstraints[mNbFrictionConstraints].normal = Vector3::zero(); - mFrictionConstraints[mNbFrictionConstraints].frictionPointBody1 /= nbContacts; - mFrictionConstraints[mNbFrictionConstraints].frictionPointBody2 /= nbContacts; - mFrictionConstraints[mNbFrictionConstraints].r1Friction = mFrictionConstraints[mNbFrictionConstraints].frictionPointBody1 - x1; - mFrictionConstraints[mNbFrictionConstraints].r2Friction = mFrictionConstraints[mNbFrictionConstraints].frictionPointBody2 - x2; - mFrictionConstraints[mNbFrictionConstraints].oldFrictionVector1 = externalManifold->getFrictionVector1(); - mFrictionConstraints[mNbFrictionConstraints].oldFrictionVector2 = externalManifold->getFrictionVector2(); + // If warm starting is active + if (mIsWarmStartingActive) { - // If warm starting is active - if (mIsWarmStartingActive) { + // Initialize the accumulated impulses with the previous step accumulated impulses + mFrictionConstraints[mNbFrictionConstraints].friction1Impulse = externalManifold->getFrictionImpulse1(); + mFrictionConstraints[mNbFrictionConstraints].friction2Impulse = externalManifold->getFrictionImpulse2(); + mFrictionConstraints[mNbFrictionConstraints].frictionTwistImpulse = externalManifold->getFrictionTwistImpulse(); + } + else { - // Initialize the accumulated impulses with the previous step accumulated impulses - mFrictionConstraints[mNbFrictionConstraints].friction1Impulse = externalManifold->getFrictionImpulse1(); - mFrictionConstraints[mNbFrictionConstraints].friction2Impulse = externalManifold->getFrictionImpulse2(); - mFrictionConstraints[mNbFrictionConstraints].frictionTwistImpulse = externalManifold->getFrictionTwistImpulse(); - } - else { + // Initialize the accumulated impulses to zero + mFrictionConstraints[mNbFrictionConstraints].friction1Impulse = 0.0; + mFrictionConstraints[mNbFrictionConstraints].friction2Impulse = 0.0; + mFrictionConstraints[mNbFrictionConstraints].frictionTwistImpulse = 0.0; + mFrictionConstraints[mNbFrictionConstraints].rollingResistanceImpulse = Vector3(0, 0, 0); + } - // Initialize the accumulated impulses to zero - mFrictionConstraints[mNbFrictionConstraints].friction1Impulse = 0.0; - mFrictionConstraints[mNbFrictionConstraints].friction2Impulse = 0.0; - mFrictionConstraints[mNbFrictionConstraints].frictionTwistImpulse = 0.0; - mFrictionConstraints[mNbFrictionConstraints].rollingResistanceImpulse = Vector3(0, 0, 0); - } + mFrictionConstraints[mNbFrictionConstraints].normal.normalize(); - mFrictionConstraints[mNbFrictionConstraints].normal.normalize(); + Vector3 deltaVFrictionPoint = v2 + w2.cross(mFrictionConstraints[mNbFrictionConstraints].r2Friction) - + v1 - w1.cross(mFrictionConstraints[mNbFrictionConstraints].r1Friction); - Vector3 deltaVFrictionPoint = v2 + w2.cross(mFrictionConstraints[mNbFrictionConstraints].r2Friction) - - v1 - w1.cross(mFrictionConstraints[mNbFrictionConstraints].r1Friction); + // Compute the friction vectors + computeFrictionVectors(deltaVFrictionPoint, mFrictionConstraints[mNbFrictionConstraints]); - // Compute the friction vectors - computeFrictionVectors(deltaVFrictionPoint, mFrictionConstraints[mNbFrictionConstraints]); - - // Compute the inverse mass matrix K for the friction constraints at the center of the contact manifold - mFrictionConstraints[mNbFrictionConstraints].r1CrossT1 = mFrictionConstraints[mNbFrictionConstraints].r1Friction.cross(mFrictionConstraints[mNbFrictionConstraints].frictionVector1); - mFrictionConstraints[mNbFrictionConstraints].r1CrossT2 = mFrictionConstraints[mNbFrictionConstraints].r1Friction.cross(mFrictionConstraints[mNbFrictionConstraints].frictionVector2); - mFrictionConstraints[mNbFrictionConstraints].r2CrossT1 = mFrictionConstraints[mNbFrictionConstraints].r2Friction.cross(mFrictionConstraints[mNbFrictionConstraints].frictionVector1); - mFrictionConstraints[mNbFrictionConstraints].r2CrossT2 = mFrictionConstraints[mNbFrictionConstraints].r2Friction.cross(mFrictionConstraints[mNbFrictionConstraints].frictionVector2); - decimal friction1Mass = mFrictionConstraints[mNbFrictionConstraints].massInverseBody1 + mFrictionConstraints[mNbFrictionConstraints].massInverseBody2 + - ((I1 * mFrictionConstraints[mNbFrictionConstraints].r1CrossT1).cross(mFrictionConstraints[mNbFrictionConstraints].r1Friction)).dot( - mFrictionConstraints[mNbFrictionConstraints].frictionVector1) + - ((I2 * mFrictionConstraints[mNbFrictionConstraints].r2CrossT1).cross(mFrictionConstraints[mNbFrictionConstraints].r2Friction)).dot( - mFrictionConstraints[mNbFrictionConstraints].frictionVector1); - decimal friction2Mass = mFrictionConstraints[mNbFrictionConstraints].massInverseBody1 + mFrictionConstraints[mNbFrictionConstraints].massInverseBody2 + - ((I1 * mFrictionConstraints[mNbFrictionConstraints].r1CrossT2).cross(mFrictionConstraints[mNbFrictionConstraints].r1Friction)).dot( - mFrictionConstraints[mNbFrictionConstraints].frictionVector2) + - ((I2 * mFrictionConstraints[mNbFrictionConstraints].r2CrossT2).cross(mFrictionConstraints[mNbFrictionConstraints].r2Friction)).dot( - mFrictionConstraints[mNbFrictionConstraints].frictionVector2); - decimal frictionTwistMass = mFrictionConstraints[mNbFrictionConstraints].normal.dot(mFrictionConstraints[mNbFrictionConstraints].inverseInertiaTensorBody1 * - mFrictionConstraints[mNbFrictionConstraints].normal) + - mFrictionConstraints[mNbFrictionConstraints].normal.dot(mFrictionConstraints[mNbFrictionConstraints].inverseInertiaTensorBody2 * - mFrictionConstraints[mNbFrictionConstraints].normal); - friction1Mass > decimal(0.0) ? mFrictionConstraints[mNbFrictionConstraints].inverseFriction1Mass = decimal(1.0)/friction1Mass - : decimal(0.0); - friction2Mass > decimal(0.0) ? mFrictionConstraints[mNbFrictionConstraints].inverseFriction2Mass = decimal(1.0)/friction2Mass - : decimal(0.0); - frictionTwistMass > decimal(0.0) ? mFrictionConstraints[mNbFrictionConstraints].inverseTwistFrictionMass = decimal(1.0) / - frictionTwistMass : - decimal(0.0); + // Compute the inverse mass matrix K for the friction constraints at the center of the contact manifold + mFrictionConstraints[mNbFrictionConstraints].r1CrossT1 = mFrictionConstraints[mNbFrictionConstraints].r1Friction.cross(mFrictionConstraints[mNbFrictionConstraints].frictionVector1); + mFrictionConstraints[mNbFrictionConstraints].r1CrossT2 = mFrictionConstraints[mNbFrictionConstraints].r1Friction.cross(mFrictionConstraints[mNbFrictionConstraints].frictionVector2); + mFrictionConstraints[mNbFrictionConstraints].r2CrossT1 = mFrictionConstraints[mNbFrictionConstraints].r2Friction.cross(mFrictionConstraints[mNbFrictionConstraints].frictionVector1); + mFrictionConstraints[mNbFrictionConstraints].r2CrossT2 = mFrictionConstraints[mNbFrictionConstraints].r2Friction.cross(mFrictionConstraints[mNbFrictionConstraints].frictionVector2); + decimal friction1Mass = mFrictionConstraints[mNbFrictionConstraints].massInverseBody1 + mFrictionConstraints[mNbFrictionConstraints].massInverseBody2 + + ((I1 * mFrictionConstraints[mNbFrictionConstraints].r1CrossT1).cross(mFrictionConstraints[mNbFrictionConstraints].r1Friction)).dot( + mFrictionConstraints[mNbFrictionConstraints].frictionVector1) + + ((I2 * mFrictionConstraints[mNbFrictionConstraints].r2CrossT1).cross(mFrictionConstraints[mNbFrictionConstraints].r2Friction)).dot( + mFrictionConstraints[mNbFrictionConstraints].frictionVector1); + decimal friction2Mass = mFrictionConstraints[mNbFrictionConstraints].massInverseBody1 + mFrictionConstraints[mNbFrictionConstraints].massInverseBody2 + + ((I1 * mFrictionConstraints[mNbFrictionConstraints].r1CrossT2).cross(mFrictionConstraints[mNbFrictionConstraints].r1Friction)).dot( + mFrictionConstraints[mNbFrictionConstraints].frictionVector2) + + ((I2 * mFrictionConstraints[mNbFrictionConstraints].r2CrossT2).cross(mFrictionConstraints[mNbFrictionConstraints].r2Friction)).dot( + mFrictionConstraints[mNbFrictionConstraints].frictionVector2); + decimal frictionTwistMass = mFrictionConstraints[mNbFrictionConstraints].normal.dot(mFrictionConstraints[mNbFrictionConstraints].inverseInertiaTensorBody1 * + mFrictionConstraints[mNbFrictionConstraints].normal) + + mFrictionConstraints[mNbFrictionConstraints].normal.dot(mFrictionConstraints[mNbFrictionConstraints].inverseInertiaTensorBody2 * + mFrictionConstraints[mNbFrictionConstraints].normal); + friction1Mass > decimal(0.0) ? mFrictionConstraints[mNbFrictionConstraints].inverseFriction1Mass = decimal(1.0)/friction1Mass + : decimal(0.0); + friction2Mass > decimal(0.0) ? mFrictionConstraints[mNbFrictionConstraints].inverseFriction2Mass = decimal(1.0)/friction2Mass + : decimal(0.0); + frictionTwistMass > decimal(0.0) ? mFrictionConstraints[mNbFrictionConstraints].inverseTwistFrictionMass = decimal(1.0) / + frictionTwistMass : + decimal(0.0); mNbFrictionConstraints++; } @@ -463,9 +435,6 @@ void ContactSolver::solvePenetrationConstraints() { PROFILE("ContactSolver::solvePenetrationConstraints()"); - // TODO : Check that the PenetrationConstraint struct only contains variables that are - // used in this method, nothing more - // TODO : Maybe solve split impulses and normal impulses separately decimal deltaLambda; @@ -550,9 +519,6 @@ void ContactSolver::solvePenetrationConstraints() { // Solve the friction constraints void ContactSolver::solveFrictionConstraints() { - // TODO : Check that the FrictionConstraint struct only contains variables that are - // used in this method, nothing more - PROFILE("ContactSolver::solveFrictionConstraints()"); for (uint i=0; isetFrictionVector1(mFrictionConstraints[i].frictionVector1); mFrictionConstraints[i].contactManifold->setFrictionVector2(mFrictionConstraints[i].frictionVector2); } - - /* - if (mPenetrationConstraints != nullptr) { - // TODO : Delete this - delete[] mPenetrationConstraints; - } - - if (mFrictionConstraints != nullptr) { - delete[] mFrictionConstraints; - } - */ } // Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction plane diff --git a/src/engine/ContactSolver.h b/src/engine/ContactSolver.h index e5d5840d..0e710c6f 100644 --- a/src/engine/ContactSolver.h +++ b/src/engine/ContactSolver.h @@ -115,8 +115,6 @@ class ContactSolver { struct PenetrationConstraint { - // TODO : Pack bools into a single value - /// Index of body 1 in the constraint solver uint indexBody1; @@ -144,9 +142,6 @@ class ContactSolver { /// Velocity restitution bias decimal restitutionBias; - /// Mix of the restitution factor for two bodies - decimal restitutionFactor; - /// Accumulated normal impulse decimal penetrationImpulse; @@ -180,8 +175,6 @@ class ContactSolver { struct FrictionConstraint { - // TODO : Pack bools into a single value - /// Index of body 1 in the constraint solver uint indexBody1; @@ -194,12 +187,6 @@ class ContactSolver { /// R2 vector for the friction constraints Vector3 r2Friction; - /// Point on body 1 where to apply the friction constraints - Vector3 frictionPointBody1; - - /// Point on body 2 where to apply the friction constraints - Vector3 frictionPointBody2; - /// Average normal vector of the contact manifold Vector3 normal; diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index 91312546..b8a48ddc 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -212,6 +212,9 @@ void DynamicsWorld::updateBodiesState() { // Update the transform of the body (using the new center of mass and new orientation) bodies[b]->updateTransformWithCenterOfMass(); + // Update the world inverse inertia tensor of the body + bodies[b]->updateInertiaTensorInverseWorld(); + // Update the broad-phase state of the body bodies[b]->updateBroadPhaseState(); } From 54be20c5d3bd9400aa71c1767faff8167fa9a808 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 2 Oct 2016 15:10:19 +0200 Subject: [PATCH 030/248] Increase the default size of the single frame memory allocator --- src/configuration.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/configuration.h b/src/configuration.h index 87747756..c14783d8 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -145,7 +145,7 @@ constexpr int NB_MAX_CONTACT_MANIFOLDS_CONVEX_SHAPE = 1; constexpr int NB_MAX_CONTACT_MANIFOLDS_CONCAVE_SHAPE = 3; /// Size (in bytes) of the single frame allocator -constexpr size_t SIZE_SINGLE_FRAME_ALLOCATOR_BYTES = 1048576; +constexpr size_t SIZE_SINGLE_FRAME_ALLOCATOR_BYTES = 15728640; // 15 Mb } From 25fddd6fb2481f727ce1c1f1d688d8abaa635d16 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sat, 8 Oct 2016 01:18:56 +0200 Subject: [PATCH 031/248] Back to previous contact solver --- src/engine/ContactSolver.cpp | 1161 ++++++++++++++++++++-------------- src/engine/ContactSolver.h | 319 +++++----- src/engine/DynamicsWorld.cpp | 57 +- 3 files changed, 878 insertions(+), 659 deletions(-) diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index d2218136..d8c3a644 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -36,14 +36,13 @@ using namespace std; // Constants initialization const decimal ContactSolver::BETA = decimal(0.2); const decimal ContactSolver::BETA_SPLIT_IMPULSE = decimal(0.2); -const decimal ContactSolver::SLOP = decimal(0.01); +const decimal ContactSolver::SLOP= decimal(0.01); // Constructor ContactSolver::ContactSolver(const std::map& mapBodyToVelocityIndex, - SingleFrameAllocator& singleFrameAllocator) + SingleFrameAllocator& allocator) :mSplitLinearVelocities(nullptr), mSplitAngularVelocities(nullptr), - mSingleFrameAllocator(singleFrameAllocator), - mPenetrationConstraints(nullptr), mFrictionConstraints(nullptr), + mContactConstraints(nullptr), mSingleFrameAllocator(allocator), mLinearVelocities(nullptr), mAngularVelocities(nullptr), mMapBodyToConstrainedVelocityIndex(mapBodyToVelocityIndex), mIsWarmStartingActive(true), mIsSplitImpulseActive(true), @@ -51,59 +50,33 @@ ContactSolver::ContactSolver(const std::map& mapBodyToVelocity } -// Initialize the contact constraints -void ContactSolver::init(Island** islands, uint nbIslands, decimal timeStep) { - - mTimeStep = timeStep; - - // TODO : Try not to count manifolds here - // Count the contact manifolds - uint nbContactManifolds = 0; - for (uint i = 0; i < nbIslands; i++) { - nbContactManifolds += islands[i]->getNbContactManifolds(); - } - - mNbFrictionConstraints = 0; - mNbPenetrationConstraints = 0; - - mPenetrationConstraints = nullptr; - mFrictionConstraints = nullptr; - - if (nbContactManifolds == 0) return; - - // TODO : Count exactly the number of constraints to allocate here - uint nbPenetrationConstraints = nbContactManifolds * MAX_CONTACT_POINTS_IN_MANIFOLD; - mPenetrationConstraints = static_cast(mSingleFrameAllocator.allocate(sizeof(PenetrationConstraint) * nbPenetrationConstraints)); - assert(mPenetrationConstraints != nullptr); - - mFrictionConstraints = static_cast(mSingleFrameAllocator.allocate(sizeof(FrictionConstraint) * nbContactManifolds)); - assert(mFrictionConstraints != nullptr); - - // For each island of the world - for (uint islandIndex = 0; islandIndex < nbIslands; islandIndex++) { - initializeForIsland(islands[islandIndex]); - } - - // Warmstarting - warmStart(); -} - // Initialize the constraint solver for a given island -void ContactSolver::initializeForIsland(Island* island) { +void ContactSolver::initializeForIsland(decimal dt, Island* island) { PROFILE("ContactSolver::initializeForIsland()"); assert(island != nullptr); assert(island->getNbBodies() > 0); + assert(island->getNbContactManifolds() > 0); assert(mSplitLinearVelocities != nullptr); assert(mSplitAngularVelocities != nullptr); + // Set the current time step + mTimeStep = dt; + + mNbContactManifolds = island->getNbContactManifolds(); + + mContactConstraints = new ContactManifoldSolver[mNbContactManifolds]; + assert(mContactConstraints != nullptr); + // For each contact manifold of the island ContactManifold** contactManifolds = island->getContactManifolds(); - for (uint i=0; igetNbContactManifolds(); i++) { + for (uint i=0; igetNbContactPoints() > 0); // Get the two bodies of the contact @@ -112,535 +85,692 @@ void ContactSolver::initializeForIsland(Island* island) { assert(body1 != nullptr); assert(body2 != nullptr); - // TODO : Check if we have a better way to find the body index - uint indexBody1 = mMapBodyToConstrainedVelocityIndex.find(body1)->second; - uint indexBody2 = mMapBodyToConstrainedVelocityIndex.find(body2)->second; - - new (mFrictionConstraints + mNbFrictionConstraints) FrictionConstraint(); - mFrictionConstraints[mNbFrictionConstraints].indexBody1 = indexBody1; - mFrictionConstraints[mNbFrictionConstraints].indexBody2 = indexBody2; - mFrictionConstraints[mNbFrictionConstraints].contactManifold = externalManifold; - // Get the position of the two bodies const Vector3& x1 = body1->mCenterOfMassWorld; const Vector3& x2 = body2->mCenterOfMassWorld; - // Get the velocities of the bodies - const Vector3& v1 = mLinearVelocities[indexBody1]; - const Vector3& w1 = mAngularVelocities[indexBody1]; - const Vector3& v2 = mLinearVelocities[indexBody2]; - const Vector3& w2 = mAngularVelocities[indexBody2]; - - // Get the inertia tensors of both bodies - Matrix3x3 I1 = body1->getInertiaTensorInverseWorld(); - Matrix3x3 I2 = body2->getInertiaTensorInverseWorld(); - - mFrictionConstraints[mNbFrictionConstraints].inverseInertiaTensorBody1 = I1; - mFrictionConstraints[mNbFrictionConstraints].inverseInertiaTensorBody2 = I2; - // Initialize the internal contact manifold structure using the external // contact manifold - mFrictionConstraints[mNbFrictionConstraints].massInverseBody1 = body1->mMassInverse; - mFrictionConstraints[mNbFrictionConstraints].massInverseBody2 = body2->mMassInverse; - decimal restitutionFactor = computeMixedRestitutionFactor(body1, body2); - mFrictionConstraints[mNbFrictionConstraints].frictionCoefficient = computeMixedFrictionCoefficient(body1, body2); - mFrictionConstraints[mNbFrictionConstraints].rollingResistanceFactor = computeMixedRollingResistance(body1, body2); - mFrictionConstraints[mNbFrictionConstraints].hasAtLeastOneRestingContactPoint = false; + internalManifold.indexBody1 = mMapBodyToConstrainedVelocityIndex.find(body1)->second; + internalManifold.indexBody2 = mMapBodyToConstrainedVelocityIndex.find(body2)->second; + internalManifold.inverseInertiaTensorBody1 = body1->getInertiaTensorInverseWorld(); + internalManifold.inverseInertiaTensorBody2 = body2->getInertiaTensorInverseWorld(); + internalManifold.massInverseBody1 = body1->mMassInverse; + internalManifold.massInverseBody2 = body2->mMassInverse; + internalManifold.nbContacts = externalManifold->getNbContactPoints(); + internalManifold.restitutionFactor = computeMixedRestitutionFactor(body1, body2); + internalManifold.frictionCoefficient = computeMixedFrictionCoefficient(body1, body2); + internalManifold.rollingResistanceFactor = computeMixedRollingResistance(body1, body2); + internalManifold.externalContactManifold = externalManifold; + internalManifold.isBody1DynamicType = body1->getType() == BodyType::DYNAMIC; + internalManifold.isBody2DynamicType = body2->getType() == BodyType::DYNAMIC; - bool isBody1DynamicType = body1->getType() == BodyType::DYNAMIC; - bool isBody2DynamicType = body2->getType() == BodyType::DYNAMIC; - - Vector3 frictionPointBody1; - Vector3 frictionPointBody2; - mFrictionConstraints[mNbFrictionConstraints].normal.setToZero(); - - // Compute the inverse K matrix for the rolling resistance constraint - mFrictionConstraints[mNbFrictionConstraints].inverseRollingResistance.setToZero(); - if (mFrictionConstraints[mNbFrictionConstraints].rollingResistanceFactor > 0 && (isBody1DynamicType || isBody2DynamicType)) { - mFrictionConstraints[mNbFrictionConstraints].inverseRollingResistance = I1 + I2; - mFrictionConstraints[mNbFrictionConstraints].inverseRollingResistance = mFrictionConstraints[mNbFrictionConstraints].inverseRollingResistance.getInverse(); + // If we solve the friction constraints at the center of the contact manifold + if (mIsSolveFrictionAtContactManifoldCenterActive) { + internalManifold.frictionPointBody1 = Vector3::zero(); + internalManifold.frictionPointBody2 = Vector3::zero(); } - int nbContacts = 0; - // For each contact point of the contact manifold for (uint c=0; cgetNbContactPoints(); c++) { + ContactPointSolver& contactPoint = internalManifold.contacts[c]; + // Get a contact point ContactPoint* externalContact = externalManifold->getContactPoint(c); - new (mPenetrationConstraints + mNbPenetrationConstraints) PenetrationConstraint(); - mPenetrationConstraints[mNbPenetrationConstraints].indexBody1 = indexBody1; - mPenetrationConstraints[mNbPenetrationConstraints].indexBody2 = indexBody2; - mPenetrationConstraints[mNbPenetrationConstraints].inverseInertiaTensorBody1 = I1; - mPenetrationConstraints[mNbPenetrationConstraints].inverseInertiaTensorBody2 = I2; - mPenetrationConstraints[mNbPenetrationConstraints].massInverseBody1 = body1->mMassInverse; - mPenetrationConstraints[mNbPenetrationConstraints].massInverseBody2 = body2->mMassInverse; - mPenetrationConstraints[mNbPenetrationConstraints].indexFrictionConstraint = mNbFrictionConstraints; - mPenetrationConstraints[mNbPenetrationConstraints].contactPoint = externalContact; - // Get the contact point on the two bodies Vector3 p1 = externalContact->getWorldPointOnBody1(); Vector3 p2 = externalContact->getWorldPointOnBody2(); - mPenetrationConstraints[mNbPenetrationConstraints].r1 = p1 - x1; - mPenetrationConstraints[mNbPenetrationConstraints].r2 = p2 - x2; - mPenetrationConstraints[mNbPenetrationConstraints].normal = externalContact->getNormal(); - mPenetrationConstraints[mNbPenetrationConstraints].penetrationDepth = externalContact->getPenetrationDepth(); - mPenetrationConstraints[mNbPenetrationConstraints].isRestingContact = externalContact->getIsRestingContact(); - - mFrictionConstraints[mNbFrictionConstraints].hasAtLeastOneRestingContactPoint |= mPenetrationConstraints[mNbPenetrationConstraints].isRestingContact; - + contactPoint.externalContact = externalContact; + contactPoint.normal = externalContact->getNormal(); + contactPoint.r1 = p1 - x1; + contactPoint.r2 = p2 - x2; + contactPoint.penetrationDepth = externalContact->getPenetrationDepth(); + contactPoint.isRestingContact = externalContact->getIsRestingContact(); externalContact->setIsRestingContact(true); - mPenetrationConstraints[mNbPenetrationConstraints].penetrationImpulse = 0.0; + contactPoint.oldFrictionVector1 = externalContact->getFrictionVector1(); + contactPoint.oldFrictionVector2 = externalContact->getFrictionVector2(); + contactPoint.penetrationImpulse = 0.0; + contactPoint.friction1Impulse = 0.0; + contactPoint.friction2Impulse = 0.0; + contactPoint.rollingResistanceImpulse = Vector3::zero(); - frictionPointBody1 += p1; - frictionPointBody2 += p2; + // If we solve the friction constraints at the center of the contact manifold + if (mIsSolveFrictionAtContactManifoldCenterActive) { + internalManifold.frictionPointBody1 += p1; + internalManifold.frictionPointBody2 += p2; + } + } + + // If we solve the friction constraints at the center of the contact manifold + if (mIsSolveFrictionAtContactManifoldCenterActive) { + + internalManifold.frictionPointBody1 /=static_cast(internalManifold.nbContacts); + internalManifold.frictionPointBody2 /=static_cast(internalManifold.nbContacts); + internalManifold.r1Friction = internalManifold.frictionPointBody1 - x1; + internalManifold.r2Friction = internalManifold.frictionPointBody2 - x2; + internalManifold.oldFrictionVector1 = externalManifold->getFrictionVector1(); + internalManifold.oldFrictionVector2 = externalManifold->getFrictionVector2(); + + // If warm starting is active + if (mIsWarmStartingActive) { + + // Initialize the accumulated impulses with the previous step accumulated impulses + internalManifold.friction1Impulse = externalManifold->getFrictionImpulse1(); + internalManifold.friction2Impulse = externalManifold->getFrictionImpulse2(); + internalManifold.frictionTwistImpulse = externalManifold->getFrictionTwistImpulse(); + } + else { + + // Initialize the accumulated impulses to zero + internalManifold.friction1Impulse = 0.0; + internalManifold.friction2Impulse = 0.0; + internalManifold.frictionTwistImpulse = 0.0; + internalManifold.rollingResistanceImpulse = Vector3(0, 0, 0); + } + } + } + + // Fill-in all the matrices needed to solve the LCP problem + initializeContactConstraints(); +} + +// Initialize the contact constraints before solving the system +void ContactSolver::initializeContactConstraints() { + + // For each contact constraint + for (uint c=0; c decimal(0.0) ? mPenetrationConstraints[mNbPenetrationConstraints].inversePenetrationMass = decimal(1.0) / + decimal massPenetration = manifold.massInverseBody1 + manifold.massInverseBody2 + + ((I1 * contactPoint.r1CrossN).cross(contactPoint.r1)).dot(contactPoint.normal) + + ((I2 * contactPoint.r2CrossN).cross(contactPoint.r2)).dot(contactPoint.normal); + massPenetration > 0.0 ? contactPoint.inversePenetrationMass = decimal(1.0) / massPenetration : decimal(0.0); + // If we do not solve the friction constraints at the center of the contact manifold + if (!mIsSolveFrictionAtContactManifoldCenterActive) { + + // Compute the friction vectors + computeFrictionVectors(deltaV, contactPoint); + + contactPoint.r1CrossT1 = contactPoint.r1.cross(contactPoint.frictionVector1); + contactPoint.r1CrossT2 = contactPoint.r1.cross(contactPoint.frictionVector2); + contactPoint.r2CrossT1 = contactPoint.r2.cross(contactPoint.frictionVector1); + contactPoint.r2CrossT2 = contactPoint.r2.cross(contactPoint.frictionVector2); + + // Compute the inverse mass matrix K for the friction + // constraints at each contact point + decimal friction1Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + + ((I1 * contactPoint.r1CrossT1).cross(contactPoint.r1)).dot( + contactPoint.frictionVector1) + + ((I2 * contactPoint.r2CrossT1).cross(contactPoint.r2)).dot( + contactPoint.frictionVector1); + decimal friction2Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + + ((I1 * contactPoint.r1CrossT2).cross(contactPoint.r1)).dot( + contactPoint.frictionVector2) + + ((I2 * contactPoint.r2CrossT2).cross(contactPoint.r2)).dot( + contactPoint.frictionVector2); + friction1Mass > 0.0 ? contactPoint.inverseFriction1Mass = decimal(1.0) / + friction1Mass : + decimal(0.0); + friction2Mass > 0.0 ? contactPoint.inverseFriction2Mass = decimal(1.0) / + friction2Mass : + decimal(0.0); + } + // Compute the restitution velocity bias "b". We compute this here instead // of inside the solve() method because we need to use the velocity difference // at the beginning of the contact. Note that if it is a resting contact (normal // velocity bellow a given threshold), we do not add a restitution velocity bias - mPenetrationConstraints[mNbPenetrationConstraints].restitutionBias = 0.0; - decimal deltaVDotN = deltaV.dot(mPenetrationConstraints[mNbPenetrationConstraints].normal); + contactPoint.restitutionBias = 0.0; + decimal deltaVDotN = deltaV.dot(contactPoint.normal); if (deltaVDotN < -RESTITUTION_VELOCITY_THRESHOLD) { - mPenetrationConstraints[mNbPenetrationConstraints].restitutionBias = restitutionFactor * deltaVDotN; + contactPoint.restitutionBias = manifold.restitutionFactor * deltaVDotN; } // If the warm starting of the contact solver is active if (mIsWarmStartingActive) { // Get the cached accumulated impulses from the previous step - mPenetrationConstraints[mNbPenetrationConstraints].penetrationImpulse = externalContact->getPenetrationImpulse(); + contactPoint.penetrationImpulse = externalContact->getPenetrationImpulse(); + contactPoint.friction1Impulse = externalContact->getFrictionImpulse1(); + contactPoint.friction2Impulse = externalContact->getFrictionImpulse2(); + contactPoint.rollingResistanceImpulse = externalContact->getRollingResistanceImpulse(); } // Initialize the split impulses to zero - mPenetrationConstraints[mNbPenetrationConstraints].penetrationSplitImpulse = 0.0; + contactPoint.penetrationSplitImpulse = 0.0; - mFrictionConstraints[mNbFrictionConstraints].normal += mPenetrationConstraints[mNbPenetrationConstraints].normal; - - mNbPenetrationConstraints++; - nbContacts++; + // If we solve the friction constraints at the center of the contact manifold + if (mIsSolveFrictionAtContactManifoldCenterActive) { + manifold.normal += contactPoint.normal; + } } - frictionPointBody1 /= nbContacts; - frictionPointBody2 /= nbContacts; - mFrictionConstraints[mNbFrictionConstraints].r1Friction = frictionPointBody1 - x1; - mFrictionConstraints[mNbFrictionConstraints].r2Friction = frictionPointBody2 - x2; - mFrictionConstraints[mNbFrictionConstraints].oldFrictionVector1 = externalManifold->getFrictionVector1(); - mFrictionConstraints[mNbFrictionConstraints].oldFrictionVector2 = externalManifold->getFrictionVector2(); - - // If warm starting is active - if (mIsWarmStartingActive) { - - // Initialize the accumulated impulses with the previous step accumulated impulses - mFrictionConstraints[mNbFrictionConstraints].friction1Impulse = externalManifold->getFrictionImpulse1(); - mFrictionConstraints[mNbFrictionConstraints].friction2Impulse = externalManifold->getFrictionImpulse2(); - mFrictionConstraints[mNbFrictionConstraints].frictionTwistImpulse = externalManifold->getFrictionTwistImpulse(); - } - else { - - // Initialize the accumulated impulses to zero - mFrictionConstraints[mNbFrictionConstraints].friction1Impulse = 0.0; - mFrictionConstraints[mNbFrictionConstraints].friction2Impulse = 0.0; - mFrictionConstraints[mNbFrictionConstraints].frictionTwistImpulse = 0.0; - mFrictionConstraints[mNbFrictionConstraints].rollingResistanceImpulse = Vector3(0, 0, 0); + // Compute the inverse K matrix for the rolling resistance constraint + manifold.inverseRollingResistance.setToZero(); + if (manifold.rollingResistanceFactor > 0 && (manifold.isBody1DynamicType || manifold.isBody2DynamicType)) { + manifold.inverseRollingResistance = manifold.inverseInertiaTensorBody1 + manifold.inverseInertiaTensorBody2; + manifold.inverseRollingResistance = manifold.inverseRollingResistance.getInverse(); } - mFrictionConstraints[mNbFrictionConstraints].normal.normalize(); + // If we solve the friction constraints at the center of the contact manifold + if (mIsSolveFrictionAtContactManifoldCenterActive) { - Vector3 deltaVFrictionPoint = v2 + w2.cross(mFrictionConstraints[mNbFrictionConstraints].r2Friction) - - v1 - w1.cross(mFrictionConstraints[mNbFrictionConstraints].r1Friction); + manifold.normal.normalize(); - // Compute the friction vectors - computeFrictionVectors(deltaVFrictionPoint, mFrictionConstraints[mNbFrictionConstraints]); + Vector3 deltaVFrictionPoint = v2 + w2.cross(manifold.r2Friction) - + v1 - w1.cross(manifold.r1Friction); - // Compute the inverse mass matrix K for the friction constraints at the center of the contact manifold - mFrictionConstraints[mNbFrictionConstraints].r1CrossT1 = mFrictionConstraints[mNbFrictionConstraints].r1Friction.cross(mFrictionConstraints[mNbFrictionConstraints].frictionVector1); - mFrictionConstraints[mNbFrictionConstraints].r1CrossT2 = mFrictionConstraints[mNbFrictionConstraints].r1Friction.cross(mFrictionConstraints[mNbFrictionConstraints].frictionVector2); - mFrictionConstraints[mNbFrictionConstraints].r2CrossT1 = mFrictionConstraints[mNbFrictionConstraints].r2Friction.cross(mFrictionConstraints[mNbFrictionConstraints].frictionVector1); - mFrictionConstraints[mNbFrictionConstraints].r2CrossT2 = mFrictionConstraints[mNbFrictionConstraints].r2Friction.cross(mFrictionConstraints[mNbFrictionConstraints].frictionVector2); - decimal friction1Mass = mFrictionConstraints[mNbFrictionConstraints].massInverseBody1 + mFrictionConstraints[mNbFrictionConstraints].massInverseBody2 + - ((I1 * mFrictionConstraints[mNbFrictionConstraints].r1CrossT1).cross(mFrictionConstraints[mNbFrictionConstraints].r1Friction)).dot( - mFrictionConstraints[mNbFrictionConstraints].frictionVector1) + - ((I2 * mFrictionConstraints[mNbFrictionConstraints].r2CrossT1).cross(mFrictionConstraints[mNbFrictionConstraints].r2Friction)).dot( - mFrictionConstraints[mNbFrictionConstraints].frictionVector1); - decimal friction2Mass = mFrictionConstraints[mNbFrictionConstraints].massInverseBody1 + mFrictionConstraints[mNbFrictionConstraints].massInverseBody2 + - ((I1 * mFrictionConstraints[mNbFrictionConstraints].r1CrossT2).cross(mFrictionConstraints[mNbFrictionConstraints].r1Friction)).dot( - mFrictionConstraints[mNbFrictionConstraints].frictionVector2) + - ((I2 * mFrictionConstraints[mNbFrictionConstraints].r2CrossT2).cross(mFrictionConstraints[mNbFrictionConstraints].r2Friction)).dot( - mFrictionConstraints[mNbFrictionConstraints].frictionVector2); - decimal frictionTwistMass = mFrictionConstraints[mNbFrictionConstraints].normal.dot(mFrictionConstraints[mNbFrictionConstraints].inverseInertiaTensorBody1 * - mFrictionConstraints[mNbFrictionConstraints].normal) + - mFrictionConstraints[mNbFrictionConstraints].normal.dot(mFrictionConstraints[mNbFrictionConstraints].inverseInertiaTensorBody2 * - mFrictionConstraints[mNbFrictionConstraints].normal); - friction1Mass > decimal(0.0) ? mFrictionConstraints[mNbFrictionConstraints].inverseFriction1Mass = decimal(1.0)/friction1Mass - : decimal(0.0); - friction2Mass > decimal(0.0) ? mFrictionConstraints[mNbFrictionConstraints].inverseFriction2Mass = decimal(1.0)/friction2Mass - : decimal(0.0); - frictionTwistMass > decimal(0.0) ? mFrictionConstraints[mNbFrictionConstraints].inverseTwistFrictionMass = decimal(1.0) / - frictionTwistMass : - decimal(0.0); + // Compute the friction vectors + computeFrictionVectors(deltaVFrictionPoint, manifold); - mNbFrictionConstraints++; + // Compute the inverse mass matrix K for the friction constraints at the center of + // the contact manifold + manifold.r1CrossT1 = manifold.r1Friction.cross(manifold.frictionVector1); + manifold.r1CrossT2 = manifold.r1Friction.cross(manifold.frictionVector2); + manifold.r2CrossT1 = manifold.r2Friction.cross(manifold.frictionVector1); + manifold.r2CrossT2 = manifold.r2Friction.cross(manifold.frictionVector2); + decimal friction1Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + + ((I1 * manifold.r1CrossT1).cross(manifold.r1Friction)).dot( + manifold.frictionVector1) + + ((I2 * manifold.r2CrossT1).cross(manifold.r2Friction)).dot( + manifold.frictionVector1); + decimal friction2Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + + ((I1 * manifold.r1CrossT2).cross(manifold.r1Friction)).dot( + manifold.frictionVector2) + + ((I2 * manifold.r2CrossT2).cross(manifold.r2Friction)).dot( + manifold.frictionVector2); + decimal frictionTwistMass = manifold.normal.dot(manifold.inverseInertiaTensorBody1 * + manifold.normal) + + manifold.normal.dot(manifold.inverseInertiaTensorBody2 * + manifold.normal); + friction1Mass > 0.0 ? manifold.inverseFriction1Mass = decimal(1.0)/friction1Mass + : decimal(0.0); + friction2Mass > 0.0 ? manifold.inverseFriction2Mass = decimal(1.0)/friction2Mass + : decimal(0.0); + frictionTwistMass > 0.0 ? manifold.inverseTwistFrictionMass = decimal(1.0) / + frictionTwistMass : + decimal(0.0); + } } } -// Solve the contact constraints of one iteration of the solve -void ContactSolver::solve() { - - assert(mTimeStep > decimal(0.0)); - - resetTotalPenetrationImpulse(); - solvePenetrationConstraints(); - solveFrictionConstraints(); -} - // Warm start the solver. /// For each constraint, we apply the previous impulse (from the previous step) /// at the beginning. With this technique, we will converge faster towards /// the solution of the linear system void ContactSolver::warmStart() { - PROFILE("ContactSolver::warmStart()"); + // Check that warm starting is active + if (!mIsWarmStartingActive) return; - // Penetration constraints - for (uint i=0; i 0) { + + // Compute the impulse P = J^T * lambda + const Impulse impulseRollingResistance(Vector3::zero(), -contactPoint.rollingResistanceImpulse, + Vector3::zero(), contactPoint.rollingResistanceImpulse); + + // Apply the impulses to the bodies of the constraint + applyImpulse(impulseRollingResistance, contactManifold); + } + } + } + else { // If it is a new contact point + + // Initialize the accumulated impulses to zero + contactPoint.penetrationImpulse = 0.0; + contactPoint.friction1Impulse = 0.0; + contactPoint.friction2Impulse = 0.0; + contactPoint.rollingResistanceImpulse = Vector3::zero(); + } } - else { // If it is a new contact point - - // Initialize the accumulated impulses to zero - mPenetrationConstraints[i].penetrationImpulse = 0.0; - } - } - - // Friction constraints - for (uint i=0; i SLOP) biasPenetrationDepth = -(beta/mTimeStep) * - max(0.0f, float(mPenetrationConstraints[i].penetrationDepth - SLOP)); - decimal b = biasPenetrationDepth + mPenetrationConstraints[i].restitutionBias; + ContactPointSolver& contactPoint = contactManifold.contacts[i]; - // Compute the Lagrange multiplier lambda - if (mIsSplitImpulseActive) { - deltaLambda = - (Jv + mPenetrationConstraints[i].restitutionBias) * - mPenetrationConstraints[i].inversePenetrationMass; - } - else { - deltaLambda = - (Jv + b) * mPenetrationConstraints[i].inversePenetrationMass; - } - lambdaTemp = mPenetrationConstraints[i].penetrationImpulse; - mPenetrationConstraints[i].penetrationImpulse = std::max(mPenetrationConstraints[i].penetrationImpulse + - deltaLambda, decimal(0.0)); - deltaLambda = mPenetrationConstraints[i].penetrationImpulse - lambdaTemp; - - // Add the penetration impulse to the total impulse of the corresponding friction constraint - mFrictionConstraints[mPenetrationConstraints[i].indexFrictionConstraint].totalPenetrationImpulse += mPenetrationConstraints[i].penetrationImpulse; - - // Update the velocities of the body 1 by applying the impulse P=J^T * lambda - Vector3 linearImpulse = mPenetrationConstraints[i].normal * deltaLambda; - v1 += mPenetrationConstraints[i].massInverseBody1 * (-linearImpulse); - w1 += mPenetrationConstraints[i].inverseInertiaTensorBody1 * (-mPenetrationConstraints[i].r1CrossN * deltaLambda); - - // Update the velocities of the body 1 by applying the impulse P=J^T * lambda - v2 += mPenetrationConstraints[i].massInverseBody2 * linearImpulse; - w2 += mPenetrationConstraints[i].inverseInertiaTensorBody2 * (mPenetrationConstraints[i].r2CrossN * deltaLambda); - - // If the split impulse position correction is active - if (mIsSplitImpulseActive) { - - // Split impulse (position correction) - const Vector3& v1Split = mSplitLinearVelocities[mPenetrationConstraints[i].indexBody1]; - const Vector3& w1Split = mSplitAngularVelocities[mPenetrationConstraints[i].indexBody1]; - const Vector3& v2Split = mSplitLinearVelocities[mPenetrationConstraints[i].indexBody2]; - const Vector3& w2Split = mSplitAngularVelocities[mPenetrationConstraints[i].indexBody2]; - Vector3 deltaVSplit = v2Split + w2Split.cross(mPenetrationConstraints[i].r2) - - v1Split - w1Split.cross(mPenetrationConstraints[i].r1); - decimal JvSplit = deltaVSplit.dot(mPenetrationConstraints[i].normal); - decimal deltaLambdaSplit = - (JvSplit + biasPenetrationDepth) * - mPenetrationConstraints[i].inversePenetrationMass; - decimal lambdaTempSplit = mPenetrationConstraints[i].penetrationSplitImpulse; - mPenetrationConstraints[i].penetrationSplitImpulse = std::max( - mPenetrationConstraints[i].penetrationSplitImpulse + - deltaLambdaSplit, decimal(0.0)); - deltaLambdaSplit = mPenetrationConstraints[i].penetrationSplitImpulse - lambdaTempSplit; - - // Update the velocities of the body 1 by applying the impulse P=J^T * lambda - Vector3 linearImpulse = mPenetrationConstraints[i].normal * deltaLambdaSplit; - mSplitLinearVelocities[mPenetrationConstraints[i].indexBody1] += mPenetrationConstraints[i].massInverseBody1 * (-linearImpulse); - mSplitAngularVelocities[mPenetrationConstraints[i].indexBody1] += mPenetrationConstraints[i].inverseInertiaTensorBody1 * (-mPenetrationConstraints[i].r1CrossN * deltaLambdaSplit); - - // Update the velocities of the body 1 by applying the impulse P=J^T * lambda - mSplitLinearVelocities[mPenetrationConstraints[i].indexBody2] += mPenetrationConstraints[i].massInverseBody2 * linearImpulse; - mSplitAngularVelocities[mPenetrationConstraints[i].indexBody2] += mPenetrationConstraints[i].inverseInertiaTensorBody2 * (mPenetrationConstraints[i].r2CrossN * deltaLambdaSplit); - } - } -} - -// Solve the friction constraints -void ContactSolver::solveFrictionConstraints() { - - PROFILE("ContactSolver::solveFrictionConstraints()"); - - for (uint i=0; i 0) { + // --------- Penetration --------- // // Compute J*v - const Vector3 JvRolling = w2 - w1; + Vector3 deltaV = v2 + w2.cross(contactPoint.r2) - v1 - w1.cross(contactPoint.r1); + decimal deltaVDotN = deltaV.dot(contactPoint.normal); + decimal Jv = deltaVDotN; + + // Compute the bias "b" of the constraint + decimal beta = mIsSplitImpulseActive ? BETA_SPLIT_IMPULSE : BETA; + decimal biasPenetrationDepth = 0.0; + if (contactPoint.penetrationDepth > SLOP) biasPenetrationDepth = -(beta/mTimeStep) * + max(0.0f, float(contactPoint.penetrationDepth - SLOP)); + decimal b = biasPenetrationDepth + contactPoint.restitutionBias; // Compute the Lagrange multiplier lambda - Vector3 deltaLambdaRolling = mFrictionConstraints[i].inverseRollingResistance * (-JvRolling); - decimal rollingLimit = mFrictionConstraints[i].rollingResistanceFactor * mFrictionConstraints[i].totalPenetrationImpulse; - Vector3 lambdaTempRolling = mFrictionConstraints[i].rollingResistanceImpulse; - mFrictionConstraints[i].rollingResistanceImpulse = clamp(mFrictionConstraints[i].rollingResistanceImpulse + - deltaLambdaRolling, rollingLimit); - deltaLambdaRolling = mFrictionConstraints[i].rollingResistanceImpulse - lambdaTempRolling; + if (mIsSplitImpulseActive) { + deltaLambda = - (Jv + contactPoint.restitutionBias) * + contactPoint.inversePenetrationMass; + } + else { + deltaLambda = - (Jv + b) * contactPoint.inversePenetrationMass; + } + lambdaTemp = contactPoint.penetrationImpulse; + contactPoint.penetrationImpulse = std::max(contactPoint.penetrationImpulse + + deltaLambda, decimal(0.0)); + deltaLambda = contactPoint.penetrationImpulse - lambdaTemp; // Compute the impulse P=J^T * lambda - angularImpulseBody1 = -deltaLambdaRolling; - angularImpulseBody2 = deltaLambdaRolling; + const Impulse impulsePenetration = computePenetrationImpulse(deltaLambda, + contactPoint); - // Update the velocities of the body 1 by applying the impulse P - w1 += mFrictionConstraints[i].inverseInertiaTensorBody1 * angularImpulseBody1; + // Apply the impulse to the bodies of the constraint + applyImpulse(impulsePenetration, contactManifold); - // Update the velocities of the body 1 by applying the impulse P - w2 += mFrictionConstraints[i].inverseInertiaTensorBody2 * angularImpulseBody2; + sumPenetrationImpulse += contactPoint.penetrationImpulse; + + // If the split impulse position correction is active + if (mIsSplitImpulseActive) { + + // Split impulse (position correction) + const Vector3& v1Split = mSplitLinearVelocities[contactManifold.indexBody1]; + const Vector3& w1Split = mSplitAngularVelocities[contactManifold.indexBody1]; + const Vector3& v2Split = mSplitLinearVelocities[contactManifold.indexBody2]; + const Vector3& w2Split = mSplitAngularVelocities[contactManifold.indexBody2]; + Vector3 deltaVSplit = v2Split + w2Split.cross(contactPoint.r2) - + v1Split - w1Split.cross(contactPoint.r1); + decimal JvSplit = deltaVSplit.dot(contactPoint.normal); + decimal deltaLambdaSplit = - (JvSplit + biasPenetrationDepth) * + contactPoint.inversePenetrationMass; + decimal lambdaTempSplit = contactPoint.penetrationSplitImpulse; + contactPoint.penetrationSplitImpulse = std::max( + contactPoint.penetrationSplitImpulse + + deltaLambdaSplit, decimal(0.0)); + deltaLambda = contactPoint.penetrationSplitImpulse - lambdaTempSplit; + + // Compute the impulse P=J^T * lambda + const Impulse splitImpulsePenetration = computePenetrationImpulse( + deltaLambdaSplit, contactPoint); + + applySplitImpulse(splitImpulsePenetration, contactManifold); + } + + // If we do not solve the friction constraints at the center of the contact manifold + if (!mIsSolveFrictionAtContactManifoldCenterActive) { + + // --------- Friction 1 --------- // + + // Compute J*v + deltaV = v2 + w2.cross(contactPoint.r2) - v1 - w1.cross(contactPoint.r1); + Jv = deltaV.dot(contactPoint.frictionVector1); + + // Compute the Lagrange multiplier lambda + deltaLambda = -Jv; + deltaLambda *= contactPoint.inverseFriction1Mass; + decimal frictionLimit = contactManifold.frictionCoefficient * + contactPoint.penetrationImpulse; + lambdaTemp = contactPoint.friction1Impulse; + contactPoint.friction1Impulse = std::max(-frictionLimit, + std::min(contactPoint.friction1Impulse + + deltaLambda, frictionLimit)); + deltaLambda = contactPoint.friction1Impulse - lambdaTemp; + + // Compute the impulse P=J^T * lambda + const Impulse impulseFriction1 = computeFriction1Impulse(deltaLambda, + contactPoint); + + // Apply the impulses to the bodies of the constraint + applyImpulse(impulseFriction1, contactManifold); + + // --------- Friction 2 --------- // + + // Compute J*v + deltaV = v2 + w2.cross(contactPoint.r2) - v1 - w1.cross(contactPoint.r1); + Jv = deltaV.dot(contactPoint.frictionVector2); + + // Compute the Lagrange multiplier lambda + deltaLambda = -Jv; + deltaLambda *= contactPoint.inverseFriction2Mass; + frictionLimit = contactManifold.frictionCoefficient * + contactPoint.penetrationImpulse; + lambdaTemp = contactPoint.friction2Impulse; + contactPoint.friction2Impulse = std::max(-frictionLimit, + std::min(contactPoint.friction2Impulse + + deltaLambda, frictionLimit)); + deltaLambda = contactPoint.friction2Impulse - lambdaTemp; + + // Compute the impulse P=J^T * lambda + const Impulse impulseFriction2 = computeFriction2Impulse(deltaLambda, + contactPoint); + + // Apply the impulses to the bodies of the constraint + applyImpulse(impulseFriction2, contactManifold); + + // --------- Rolling resistance constraint --------- // + + if (contactManifold.rollingResistanceFactor > 0) { + + // Compute J*v + const Vector3 JvRolling = w2 - w1; + + // Compute the Lagrange multiplier lambda + Vector3 deltaLambdaRolling = contactManifold.inverseRollingResistance * (-JvRolling); + decimal rollingLimit = contactManifold.rollingResistanceFactor * contactPoint.penetrationImpulse; + Vector3 lambdaTempRolling = contactPoint.rollingResistanceImpulse; + contactPoint.rollingResistanceImpulse = clamp(contactPoint.rollingResistanceImpulse + + deltaLambdaRolling, rollingLimit); + deltaLambdaRolling = contactPoint.rollingResistanceImpulse - lambdaTempRolling; + + // Compute the impulse P=J^T * lambda + const Impulse impulseRolling(Vector3::zero(), -deltaLambdaRolling, + Vector3::zero(), deltaLambdaRolling); + + // Apply the impulses to the bodies of the constraint + applyImpulse(impulseRolling, contactManifold); + } + } + } + + // If we solve the friction constraints at the center of the contact manifold + if (mIsSolveFrictionAtContactManifoldCenterActive) { + + // ------ First friction constraint at the center of the contact manifol ------ // + + // Compute J*v + Vector3 deltaV = v2 + w2.cross(contactManifold.r2Friction) + - v1 - w1.cross(contactManifold.r1Friction); + decimal Jv = deltaV.dot(contactManifold.frictionVector1); + + // Compute the Lagrange multiplier lambda + decimal deltaLambda = -Jv * contactManifold.inverseFriction1Mass; + decimal frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; + lambdaTemp = contactManifold.friction1Impulse; + contactManifold.friction1Impulse = std::max(-frictionLimit, + std::min(contactManifold.friction1Impulse + + deltaLambda, frictionLimit)); + deltaLambda = contactManifold.friction1Impulse - lambdaTemp; + + // Compute the impulse P=J^T * lambda + Vector3 linearImpulseBody1 = -contactManifold.frictionVector1 * deltaLambda; + Vector3 angularImpulseBody1 = -contactManifold.r1CrossT1 * deltaLambda; + Vector3 linearImpulseBody2 = contactManifold.frictionVector1 * deltaLambda; + Vector3 angularImpulseBody2 = contactManifold.r2CrossT1 * deltaLambda; + const Impulse impulseFriction1(linearImpulseBody1, angularImpulseBody1, + linearImpulseBody2, angularImpulseBody2); + + // Apply the impulses to the bodies of the constraint + applyImpulse(impulseFriction1, contactManifold); + + // ------ Second friction constraint at the center of the contact manifol ----- // + + // Compute J*v + deltaV = v2 + w2.cross(contactManifold.r2Friction) + - v1 - w1.cross(contactManifold.r1Friction); + Jv = deltaV.dot(contactManifold.frictionVector2); + + // Compute the Lagrange multiplier lambda + deltaLambda = -Jv * contactManifold.inverseFriction2Mass; + frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; + lambdaTemp = contactManifold.friction2Impulse; + contactManifold.friction2Impulse = std::max(-frictionLimit, + std::min(contactManifold.friction2Impulse + + deltaLambda, frictionLimit)); + deltaLambda = contactManifold.friction2Impulse - lambdaTemp; + + // Compute the impulse P=J^T * lambda + linearImpulseBody1 = -contactManifold.frictionVector2 * deltaLambda; + angularImpulseBody1 = -contactManifold.r1CrossT2 * deltaLambda; + linearImpulseBody2 = contactManifold.frictionVector2 * deltaLambda; + angularImpulseBody2 = contactManifold.r2CrossT2 * deltaLambda; + const Impulse impulseFriction2(linearImpulseBody1, angularImpulseBody1, + linearImpulseBody2, angularImpulseBody2); + + // Apply the impulses to the bodies of the constraint + applyImpulse(impulseFriction2, contactManifold); + + // ------ Twist friction constraint at the center of the contact manifol ------ // + + // Compute J*v + deltaV = w2 - w1; + Jv = deltaV.dot(contactManifold.normal); + + deltaLambda = -Jv * (contactManifold.inverseTwistFrictionMass); + frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; + lambdaTemp = contactManifold.frictionTwistImpulse; + contactManifold.frictionTwistImpulse = std::max(-frictionLimit, + std::min(contactManifold.frictionTwistImpulse + + deltaLambda, frictionLimit)); + deltaLambda = contactManifold.frictionTwistImpulse - lambdaTemp; + + // Compute the impulse P=J^T * lambda + linearImpulseBody1 = Vector3(0.0, 0.0, 0.0); + angularImpulseBody1 = -contactManifold.normal * deltaLambda; + linearImpulseBody2 = Vector3(0.0, 0.0, 0.0);; + angularImpulseBody2 = contactManifold.normal * deltaLambda; + const Impulse impulseTwistFriction(linearImpulseBody1, angularImpulseBody1, + linearImpulseBody2, angularImpulseBody2); + + // Apply the impulses to the bodies of the constraint + applyImpulse(impulseTwistFriction, contactManifold); + + // --------- Rolling resistance constraint at the center of the contact manifold --------- // + + if (contactManifold.rollingResistanceFactor > 0) { + + // Compute J*v + const Vector3 JvRolling = w2 - w1; + + // Compute the Lagrange multiplier lambda + Vector3 deltaLambdaRolling = contactManifold.inverseRollingResistance * (-JvRolling); + decimal rollingLimit = contactManifold.rollingResistanceFactor * sumPenetrationImpulse; + Vector3 lambdaTempRolling = contactManifold.rollingResistanceImpulse; + contactManifold.rollingResistanceImpulse = clamp(contactManifold.rollingResistanceImpulse + + deltaLambdaRolling, rollingLimit); + deltaLambdaRolling = contactManifold.rollingResistanceImpulse - lambdaTempRolling; + + // Compute the impulse P=J^T * lambda + angularImpulseBody1 = -deltaLambdaRolling; + angularImpulseBody2 = deltaLambdaRolling; + const Impulse impulseRolling(Vector3::zero(), angularImpulseBody1, + Vector3::zero(), angularImpulseBody2); + + // Apply the impulses to the bodies of the constraint + applyImpulse(impulseRolling, contactManifold); + } } } } @@ -649,32 +779,76 @@ void ContactSolver::solveFrictionConstraints() { // warm start the solver at the next iteration void ContactSolver::storeImpulses() { - // Penetration constraints - for (uint i=0; isetPenetrationImpulse(mPenetrationConstraints[i].penetrationImpulse); - } + // For each contact manifold + for (uint c=0; csetFrictionImpulse1(mFrictionConstraints[i].friction1Impulse); - mFrictionConstraints[i].contactManifold->setFrictionImpulse2(mFrictionConstraints[i].friction2Impulse); - mFrictionConstraints[i].contactManifold->setFrictionTwistImpulse(mFrictionConstraints[i].frictionTwistImpulse); - mFrictionConstraints[i].contactManifold->setRollingResistanceImpulse(mFrictionConstraints[i].rollingResistanceImpulse); - mFrictionConstraints[i].contactManifold->setFrictionVector1(mFrictionConstraints[i].frictionVector1); - mFrictionConstraints[i].contactManifold->setFrictionVector2(mFrictionConstraints[i].frictionVector2); + for (uint i=0; isetPenetrationImpulse(contactPoint.penetrationImpulse); + contactPoint.externalContact->setFrictionImpulse1(contactPoint.friction1Impulse); + contactPoint.externalContact->setFrictionImpulse2(contactPoint.friction2Impulse); + contactPoint.externalContact->setRollingResistanceImpulse(contactPoint.rollingResistanceImpulse); + + contactPoint.externalContact->setFrictionVector1(contactPoint.frictionVector1); + contactPoint.externalContact->setFrictionVector2(contactPoint.frictionVector2); + } + + manifold.externalContactManifold->setFrictionImpulse1(manifold.friction1Impulse); + manifold.externalContactManifold->setFrictionImpulse2(manifold.friction2Impulse); + manifold.externalContactManifold->setFrictionTwistImpulse(manifold.frictionTwistImpulse); + manifold.externalContactManifold->setRollingResistanceImpulse(manifold.rollingResistanceImpulse); + manifold.externalContactManifold->setFrictionVector1(manifold.frictionVector1); + manifold.externalContactManifold->setFrictionVector2(manifold.frictionVector2); } } -// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction plane -// for a contact manifold. The two vectors have to be such that : t1 x t2 = contactNormal. -void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, - FrictionConstraint& frictionConstraint) const { +// Apply an impulse to the two bodies of a constraint +void ContactSolver::applyImpulse(const Impulse& impulse, + const ContactManifoldSolver& manifold) { - assert(frictionConstraint.normal.length() > MACHINE_EPSILON); + // Update the velocities of the body 1 by applying the impulse P + mLinearVelocities[manifold.indexBody1] += manifold.massInverseBody1 * + impulse.linearImpulseBody1; + mAngularVelocities[manifold.indexBody1] += manifold.inverseInertiaTensorBody1 * + impulse.angularImpulseBody1; + + // Update the velocities of the body 1 by applying the impulse P + mLinearVelocities[manifold.indexBody2] += manifold.massInverseBody2 * + impulse.linearImpulseBody2; + mAngularVelocities[manifold.indexBody2] += manifold.inverseInertiaTensorBody2 * + impulse.angularImpulseBody2; +} + +// Apply an impulse to the two bodies of a constraint +void ContactSolver::applySplitImpulse(const Impulse& impulse, + const ContactManifoldSolver& manifold) { + + // Update the velocities of the body 1 by applying the impulse P + mSplitLinearVelocities[manifold.indexBody1] += manifold.massInverseBody1 * + impulse.linearImpulseBody1; + mSplitAngularVelocities[manifold.indexBody1] += manifold.inverseInertiaTensorBody1 * + impulse.angularImpulseBody1; + + // Update the velocities of the body 1 by applying the impulse P + mSplitLinearVelocities[manifold.indexBody2] += manifold.massInverseBody2 * + impulse.linearImpulseBody2; + mSplitAngularVelocities[manifold.indexBody2] += manifold.inverseInertiaTensorBody2 * + impulse.angularImpulseBody2; +} + +// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction plane +// for a contact point. The two vectors have to be such that : t1 x t2 = contactNormal. +void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, + ContactPointSolver& contactPoint) const { + + assert(contactPoint.normal.length() > 0.0); // Compute the velocity difference vector in the tangential plane - Vector3 normalVelocity = deltaVelocity.dot(frictionConstraint.normal) * frictionConstraint.normal; + Vector3 normalVelocity = deltaVelocity.dot(contactPoint.normal) * contactPoint.normal; Vector3 tangentVelocity = deltaVelocity - normalVelocity; // If the velocty difference in the tangential plane is not zero @@ -683,15 +857,54 @@ void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, // Compute the first friction vector in the direction of the tangent // velocity difference - frictionConstraint.frictionVector1 = tangentVelocity / lengthTangenVelocity; + contactPoint.frictionVector1 = tangentVelocity / lengthTangenVelocity; } else { // Get any orthogonal vector to the normal as the first friction vector - frictionConstraint.frictionVector1 = frictionConstraint.normal.getOneUnitOrthogonalVector(); + contactPoint.frictionVector1 = contactPoint.normal.getOneUnitOrthogonalVector(); } // The second friction vector is computed by the cross product of the firs // friction vector and the contact normal - frictionConstraint.frictionVector2 = frictionConstraint.normal.cross(frictionConstraint.frictionVector1).getUnit(); + contactPoint.frictionVector2 =contactPoint.normal.cross(contactPoint.frictionVector1).getUnit(); +} + +// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction plane +// for a contact manifold. The two vectors have to be such that : t1 x t2 = contactNormal. +void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, + ContactManifoldSolver& contact) const { + + assert(contact.normal.length() > 0.0); + + // Compute the velocity difference vector in the tangential plane + Vector3 normalVelocity = deltaVelocity.dot(contact.normal) * contact.normal; + Vector3 tangentVelocity = deltaVelocity - normalVelocity; + + // If the velocty difference in the tangential plane is not zero + decimal lengthTangenVelocity = tangentVelocity.length(); + if (lengthTangenVelocity > MACHINE_EPSILON) { + + // Compute the first friction vector in the direction of the tangent + // velocity difference + contact.frictionVector1 = tangentVelocity / lengthTangenVelocity; + } + else { + + // Get any orthogonal vector to the normal as the first friction vector + contact.frictionVector1 = contact.normal.getOneUnitOrthogonalVector(); + } + + // The second friction vector is computed by the cross product of the firs + // friction vector and the contact normal + contact.frictionVector2 = contact.normal.cross(contact.frictionVector1).getUnit(); +} + +// Clean up the constraint solver +void ContactSolver::cleanup() { + + if (mContactConstraints != nullptr) { + delete[] mContactConstraints; + mContactConstraints = nullptr; + } } diff --git a/src/engine/ContactSolver.h b/src/engine/ContactSolver.h index 0e710c6f..7fd4442f 100644 --- a/src/engine/ContactSolver.h +++ b/src/engine/ContactSolver.h @@ -31,7 +31,6 @@ #include "configuration.h" #include "constraint/Joint.h" #include "collision/ContactManifold.h" -#include "memory/SingleFrameAllocator.h" #include "Island.h" #include "Impulse.h" #include @@ -40,6 +39,7 @@ /// ReactPhysics3D namespace namespace reactphysics3d { + // Class Contact Solver /** * This class represents the contact solver that is used to solve rigid bodies contacts. @@ -113,100 +113,30 @@ class ContactSolver { private: - struct PenetrationConstraint { - - /// Index of body 1 in the constraint solver - uint indexBody1; - - /// Index of body 2 in the constraint solver - uint indexBody2; - - /// Normal vector of the contact - Vector3 normal; - - /// Vector from the body 1 center to the contact point - Vector3 r1; - - /// Vector from the body 2 center to the contact point - Vector3 r2; - - /// Cross product of r1 with the contact normal - Vector3 r1CrossN; - - /// Cross product of r2 with the contact normal - Vector3 r2CrossN; - - /// Penetration depth - decimal penetrationDepth; - - /// Velocity restitution bias - decimal restitutionBias; + // Structure ContactPointSolver + /** + * Contact solver internal data structure that to store all the + * information relative to a contact point + */ + struct ContactPointSolver { /// Accumulated normal impulse decimal penetrationImpulse; - /// Accumulated split impulse for penetration correction - decimal penetrationSplitImpulse; - - /// Inverse of the mass of body 1 - decimal massInverseBody1; - - /// Inverse of the mass of body 2 - decimal massInverseBody2; - - /// Inverse of the matrix K for the penenetration - decimal inversePenetrationMass; - - /// Inverse inertia tensor of body 1 - Matrix3x3 inverseInertiaTensorBody1; - - /// Inverse inertia tensor of body 2 - Matrix3x3 inverseInertiaTensorBody2; - - /// Index of the corresponding friction constraint - uint indexFrictionConstraint; - - /// Pointer to the corresponding contact point - ContactPoint* contactPoint; - - /// True if this constraint is for a resting contact - bool isRestingContact; - }; - - struct FrictionConstraint { - - /// Index of body 1 in the constraint solver - uint indexBody1; - - /// Index of body 2 in the constraint solver - uint indexBody2; - - /// R1 vector for the friction constraints - Vector3 r1Friction; - - /// R2 vector for the friction constraints - Vector3 r2Friction; - - /// Average normal vector of the contact manifold - Vector3 normal; - /// Accumulated impulse in the 1st friction direction decimal friction1Impulse; /// Accumulated impulse in the 2nd friction direction decimal friction2Impulse; - /// Twist friction impulse at contact manifold center - decimal frictionTwistImpulse; + /// Accumulated split impulse for penetration correction + decimal penetrationSplitImpulse; /// Accumulated rolling resistance impulse Vector3 rollingResistanceImpulse; - /// Rolling resistance factor between the two bodies - decimal rollingResistanceFactor; - - /// Mix friction coefficient for the two bodies - decimal frictionCoefficient; + /// Normal vector of the contact + Vector3 normal; /// First friction vector in the tangent plane Vector3 frictionVector1; @@ -214,12 +144,18 @@ class ContactSolver { /// Second friction vector in the tangent plane Vector3 frictionVector2; - /// Old 1st friction direction at contact manifold center + /// Old first friction vector in the tangent plane Vector3 oldFrictionVector1; - /// Old 2nd friction direction at contact manifold center + /// Old second friction vector in the tangent plane Vector3 oldFrictionVector2; + /// Vector from the body 1 center to the contact point + Vector3 r1; + + /// Vector from the body 2 center to the contact point + Vector3 r2; + /// Cross product of r1 with 1st friction vector Vector3 r1CrossT1; @@ -232,8 +168,20 @@ class ContactSolver { /// Cross product of r2 with 2nd friction vector Vector3 r2CrossT2; - /// Total of the all the corresponding penetration impulses - decimal totalPenetrationImpulse; + /// Cross product of r1 with the contact normal + Vector3 r1CrossN; + + /// Cross product of r2 with the contact normal + Vector3 r2CrossN; + + /// Penetration depth + decimal penetrationDepth; + + /// Velocity restitution bias + decimal restitutionBias; + + /// Inverse of the matrix K for the penenetration + decimal inversePenetrationMass; /// Inverse of the matrix K for the 1st friction decimal inverseFriction1Mass; @@ -241,16 +189,30 @@ class ContactSolver { /// Inverse of the matrix K for the 2nd friction decimal inverseFriction2Mass; - /// Matrix K for the twist friction constraint - decimal inverseTwistFrictionMass; + /// True if the contact was existing last time step + bool isRestingContact; - /// Matrix K for the rolling resistance constraint - Matrix3x3 inverseRollingResistance; + /// Pointer to the external contact + ContactPoint* externalContact; + }; + + // Structure ContactManifoldSolver + /** + * Contact solver internal data structure to store all the + * information relative to a contact manifold. + */ + struct ContactManifoldSolver { + + /// Index of body 1 in the constraint solver + uint indexBody1; + + /// Index of body 2 in the constraint solver + uint indexBody2; /// Inverse of the mass of body 1 decimal massInverseBody1; - /// Inverse of the mass of body 2 + // Inverse of the mass of body 2 decimal massInverseBody2; /// Inverse inertia tensor of body 1 @@ -259,11 +221,94 @@ class ContactSolver { /// Inverse inertia tensor of body 2 Matrix3x3 inverseInertiaTensorBody2; - /// Pointer to the corresponding contact manifold - ContactManifold* contactManifold; + /// Contact point constraints + ContactPointSolver contacts[MAX_CONTACT_POINTS_IN_MANIFOLD]; - /// True if the original contact manifold has at least one resting contact - bool hasAtLeastOneRestingContactPoint; + /// Number of contact points + uint nbContacts; + + /// True if the body 1 is of type dynamic + bool isBody1DynamicType; + + /// True if the body 2 is of type dynamic + bool isBody2DynamicType; + + /// Mix of the restitution factor for two bodies + decimal restitutionFactor; + + /// Mix friction coefficient for the two bodies + decimal frictionCoefficient; + + /// Rolling resistance factor between the two bodies + decimal rollingResistanceFactor; + + /// Pointer to the external contact manifold + ContactManifold* externalContactManifold; + + // - Variables used when friction constraints are apply at the center of the manifold-// + + /// Average normal vector of the contact manifold + Vector3 normal; + + /// Point on body 1 where to apply the friction constraints + Vector3 frictionPointBody1; + + /// Point on body 2 where to apply the friction constraints + Vector3 frictionPointBody2; + + /// R1 vector for the friction constraints + Vector3 r1Friction; + + /// R2 vector for the friction constraints + Vector3 r2Friction; + + /// Cross product of r1 with 1st friction vector + Vector3 r1CrossT1; + + /// Cross product of r1 with 2nd friction vector + Vector3 r1CrossT2; + + /// Cross product of r2 with 1st friction vector + Vector3 r2CrossT1; + + /// Cross product of r2 with 2nd friction vector + Vector3 r2CrossT2; + + /// Matrix K for the first friction constraint + decimal inverseFriction1Mass; + + /// Matrix K for the second friction constraint + decimal inverseFriction2Mass; + + /// Matrix K for the twist friction constraint + decimal inverseTwistFrictionMass; + + /// Matrix K for the rolling resistance constraint + Matrix3x3 inverseRollingResistance; + + /// First friction direction at contact manifold center + Vector3 frictionVector1; + + /// Second friction direction at contact manifold center + Vector3 frictionVector2; + + /// Old 1st friction direction at contact manifold center + Vector3 oldFrictionVector1; + + /// Old 2nd friction direction at contact manifold center + Vector3 oldFrictionVector2; + + /// First friction direction impulse at manifold center + decimal friction1Impulse; + + /// Second friction direction impulse at manifold center + decimal friction2Impulse; + + /// Twist friction impulse at contact manifold center + decimal frictionTwistImpulse; + + /// Rolling resistance impulse + Vector3 rollingResistanceImpulse; }; // -------------------- Constants --------------------- // @@ -285,19 +330,17 @@ class ContactSolver { /// Split angular velocities for the position contact solver (split impulse) Vector3* mSplitAngularVelocities; - /// Reference to the single frame memory allocator - SingleFrameAllocator& mSingleFrameAllocator; - /// Current time step decimal mTimeStep; - PenetrationConstraint* mPenetrationConstraints; + /// Contact constraints + ContactManifoldSolver* mContactConstraints; - FrictionConstraint* mFrictionConstraints; + /// Number of contact constraints + uint mNbContactManifolds; - uint mNbPenetrationConstraints; - - uint mNbFrictionConstraints; + /// Single frame memory allocator + SingleFrameAllocator& mSingleFrameAllocator; /// Array of linear velocities Vector3* mLinearVelocities; @@ -320,15 +363,15 @@ class ContactSolver { // -------------------- Methods -------------------- // - /// Initialize the constraint solver for a given island - void initializeForIsland(Island* island); + /// Initialize the contact constraints before solving the system + void initializeContactConstraints(); /// Apply an impulse to the two bodies of a constraint - //void applyImpulse(const Impulse& impulse, const ContactManifoldSolver& manifold); + void applyImpulse(const Impulse& impulse, const ContactManifoldSolver& manifold); /// Apply an impulse to the two bodies of a constraint - //void applySplitImpulse(const Impulse& impulse, - // const ContactManifoldSolver& manifold); + void applySplitImpulse(const Impulse& impulse, + const ContactManifoldSolver& manifold); /// Compute the collision restitution factor from the restitution factor of each body decimal computeMixedRestitutionFactor(RigidBody *body1, @@ -341,30 +384,29 @@ class ContactSolver { /// Compute th mixed rolling resistance factor between two bodies decimal computeMixedRollingResistance(RigidBody* body1, RigidBody* body2) const; - // TODO : Delete this /// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction /// plane for a contact point. The two vectors have to be /// such that : t1 x t2 = contactNormal. -// void computeFrictionVectors(const Vector3& deltaVelocity, -// ContactPointSolver &contactPoint) const; + void computeFrictionVectors(const Vector3& deltaVelocity, + ContactPointSolver &contactPoint) const; /// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction /// plane for a contact manifold. The two vectors have to be /// such that : t1 x t2 = contactNormal. void computeFrictionVectors(const Vector3& deltaVelocity, - FrictionConstraint& frictionConstraint) const; + ContactManifoldSolver& contactPoint) const; /// Compute a penetration constraint impulse -// const Impulse computePenetrationImpulse(decimal deltaLambda, -// const PenetrationConstraint& constraint) const; + const Impulse computePenetrationImpulse(decimal deltaLambda, + const ContactPointSolver& contactPoint) const; /// Compute the first friction constraint impulse const Impulse computeFriction1Impulse(decimal deltaLambda, - const FrictionConstraint& contactPoint) const; + const ContactPointSolver& contactPoint) const; /// Compute the second friction constraint impulse const Impulse computeFriction2Impulse(decimal deltaLambda, - const FrictionConstraint& contactPoint) const; + const ContactPointSolver& contactPoint) const; public: @@ -372,16 +414,13 @@ class ContactSolver { /// Constructor ContactSolver(const std::map& mapBodyToVelocityIndex, - SingleFrameAllocator& singleFrameAllocator); + SingleFrameAllocator& allocator); /// Destructor ~ContactSolver() = default; - /// Initialize the contact constraints - void init(Island** islands, uint nbIslands, decimal timeStep); - - /// Solve the contact constraints of one iteration of the solve - void solve(); + /// Initialize the constraint solver for a given island + void initializeForIsland(decimal dt, Island* island); /// Set the split velocities arrays void setSplitVelocitiesArrays(Vector3* splitLinearVelocities, @@ -399,16 +438,7 @@ class ContactSolver { void storeImpulses(); /// Solve the contacts - //void solve(); - - /// Reset the total penetration impulse of friction constraints - void resetTotalPenetrationImpulse(); - - /// Solve the penetration constraints - void solvePenetrationConstraints(); - - /// Solve the friction constraints - void solveFrictionConstraints(); + void solve(); /// Return true if the split impulses position correction technique is used for contacts bool isSplitImpulseActive() const; @@ -420,8 +450,8 @@ class ContactSolver { /// the contact manifold instead of solving them at each contact point void setIsSolveFrictionAtContactManifoldCenterActive(bool isActive); - /// Return true if warmstarting is active - bool IsWarmStartingActive() const; + /// Clean up the constraint solver + void cleanup(); }; // Set the split velocities arrays @@ -476,7 +506,7 @@ inline decimal ContactSolver::computeMixedRestitutionFactor(RigidBody* body1, inline decimal ContactSolver::computeMixedFrictionCoefficient(RigidBody *body1, RigidBody *body2) const { // Use the geometric mean to compute the mixed friction coefficient - return std::sqrt(body1->getMaterial().getFrictionCoefficient() * + return sqrt(body1->getMaterial().getFrictionCoefficient() * body2->getMaterial().getFrictionCoefficient()); } @@ -487,16 +517,16 @@ inline decimal ContactSolver::computeMixedRollingResistance(RigidBody* body1, } // Compute a penetration constraint impulse -//inline const Impulse ContactSolver::computePenetrationImpulse(decimal deltaLambda, -// const PenetrationConstraint& constraint) -// const { -// return Impulse(-constraint.normal * deltaLambda, -constraint.r1CrossN * deltaLambda, -// constraint.normal * deltaLambda, constraint.r2CrossN * deltaLambda); -//} +inline const Impulse ContactSolver::computePenetrationImpulse(decimal deltaLambda, + const ContactPointSolver& contactPoint) + const { + return Impulse(-contactPoint.normal * deltaLambda, -contactPoint.r1CrossN * deltaLambda, + contactPoint.normal * deltaLambda, contactPoint.r2CrossN * deltaLambda); +} // Compute the first friction constraint impulse inline const Impulse ContactSolver::computeFriction1Impulse(decimal deltaLambda, - const FrictionConstraint& contactPoint) + const ContactPointSolver& contactPoint) const { return Impulse(-contactPoint.frictionVector1 * deltaLambda, -contactPoint.r1CrossT1 * deltaLambda, @@ -506,7 +536,7 @@ inline const Impulse ContactSolver::computeFriction1Impulse(decimal deltaLambda, // Compute the second friction constraint impulse inline const Impulse ContactSolver::computeFriction2Impulse(decimal deltaLambda, - const FrictionConstraint& contactPoint) + const ContactPointSolver& contactPoint) const { return Impulse(-contactPoint.frictionVector2 * deltaLambda, -contactPoint.r1CrossT2 * deltaLambda, @@ -514,11 +544,6 @@ inline const Impulse ContactSolver::computeFriction2Impulse(decimal deltaLambda, contactPoint.r2CrossT2 * deltaLambda); } -// Return true if warmstarting is active -inline bool ContactSolver::IsWarmStartingActive() const { - return mIsWarmStartingActive; -} - } #endif diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index b8a48ddc..c40d5ec5 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -331,8 +331,6 @@ void DynamicsWorld::solveContactsAndConstraints() { PROFILE("DynamicsWorld::solveContactsAndConstraints()"); - // TODO : Do not solve per island but solve every constraints at once - // Set the velocities arrays mContactSolver.setSplitVelocitiesArrays(mSplitLinearVelocities, mSplitAngularVelocities); mContactSolver.setConstrainedVelocitiesArrays(mConstrainedLinearVelocities, @@ -342,28 +340,25 @@ void DynamicsWorld::solveContactsAndConstraints() { mConstraintSolver.setConstrainedPositionsArrays(mConstrainedPositions, mConstrainedOrientations); - // Initialize the contact solver - mContactSolver.init(mIslands, mNbIslands, mTimeStep); + // ---------- Solve velocity constraints for joints and contacts ---------- // // For each island of the world for (uint islandIndex = 0; islandIndex < mNbIslands; islandIndex++) { // Check if there are contacts and constraints to solve bool isConstraintsToSolve = mIslands[islandIndex]->getNbJoints() > 0; - //bool isContactsToSolve = mIslands[islandIndex]->getNbContactManifolds() > 0; - //if (!isConstraintsToSolve && !isContactsToSolve) continue; + bool isContactsToSolve = mIslands[islandIndex]->getNbContactManifolds() > 0; + if (!isConstraintsToSolve && !isContactsToSolve) continue; // If there are contacts in the current island -// if (isContactsToSolve) { + if (isContactsToSolve) { -// // Initialize the solver -// mContactSolver.initializeForIsland(mTimeStep, mIslands[islandIndex]); + // Initialize the solver + mContactSolver.initializeForIsland(mTimeStep, mIslands[islandIndex]); -// // Warm start the contact solver -// if (mContactSolver.IsWarmStartingActive()) { -// mContactSolver.warmStart(); -// } -// } + // Warm start the contact solver + mContactSolver.warmStart(); + } // If there are constraints if (isConstraintsToSolve) { @@ -371,40 +366,26 @@ void DynamicsWorld::solveContactsAndConstraints() { // Initialize the constraint solver mConstraintSolver.initializeForIsland(mTimeStep, mIslands[islandIndex]); } - } // For each iteration of the velocity solver for (uint i=0; igetNbJoints() > 0; - if (isConstraintsToSolve) { - mConstraintSolver.solveVelocityConstraints(mIslands[islandIndex]); - } + // Solve the constraints + if (isConstraintsToSolve) { + mConstraintSolver.solveVelocityConstraints(mIslands[islandIndex]); } - mContactSolver.solve(); - // Solve the contacts -// if (isContactsToSolve) { - -// mContactSolver.resetTotalPenetrationImpulse(); - -// mContactSolver.solvePenetrationConstraints(); -// mContactSolver.solveFrictionConstraints(); -// } - } + if (isContactsToSolve) mContactSolver.solve(); + } // Cache the lambda values in order to use them in the next // step and cleanup the contact solver -// if (isContactsToSolve) { -// mContactSolver.storeImpulses(); -// mContactSolver.cleanup(); -// } - //} - - mContactSolver.storeImpulses(); + if (isContactsToSolve) { + mContactSolver.storeImpulses(); + mContactSolver.cleanup(); + } + } } // Solve the position error correction of the constraints From 3ab2b8608c99a9f40737f9104114628920d624a2 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sat, 8 Oct 2016 16:58:28 +0200 Subject: [PATCH 032/248] Always solve friction at the center of the manifold and always use warmstarting --- src/engine/ContactSolver.cpp | 477 +++++++++++------------------------ src/engine/ContactSolver.h | 17 -- src/engine/DynamicsWorld.h | 14 - 3 files changed, 142 insertions(+), 366 deletions(-) diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index d8c3a644..77abee5d 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -45,8 +45,7 @@ ContactSolver::ContactSolver(const std::map& mapBodyToVelocity mContactConstraints(nullptr), mSingleFrameAllocator(allocator), mLinearVelocities(nullptr), mAngularVelocities(nullptr), mMapBodyToConstrainedVelocityIndex(mapBodyToVelocityIndex), - mIsWarmStartingActive(true), mIsSplitImpulseActive(true), - mIsSolveFrictionAtContactManifoldCenterActive(true) { + mIsSplitImpulseActive(true) { } @@ -105,11 +104,8 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { internalManifold.isBody1DynamicType = body1->getType() == BodyType::DYNAMIC; internalManifold.isBody2DynamicType = body2->getType() == BodyType::DYNAMIC; - // If we solve the friction constraints at the center of the contact manifold - if (mIsSolveFrictionAtContactManifoldCenterActive) { - internalManifold.frictionPointBody1 = Vector3::zero(); - internalManifold.frictionPointBody2 = Vector3::zero(); - } + internalManifold.frictionPointBody1 = Vector3::zero(); + internalManifold.frictionPointBody2 = Vector3::zero(); // For each contact point of the contact manifold for (uint c=0; cgetNbContactPoints(); c++) { @@ -137,40 +133,22 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { contactPoint.friction2Impulse = 0.0; contactPoint.rollingResistanceImpulse = Vector3::zero(); - // If we solve the friction constraints at the center of the contact manifold - if (mIsSolveFrictionAtContactManifoldCenterActive) { - internalManifold.frictionPointBody1 += p1; - internalManifold.frictionPointBody2 += p2; - } + internalManifold.frictionPointBody1 += p1; + internalManifold.frictionPointBody2 += p2; } - // If we solve the friction constraints at the center of the contact manifold - if (mIsSolveFrictionAtContactManifoldCenterActive) { - internalManifold.frictionPointBody1 /=static_cast(internalManifold.nbContacts); - internalManifold.frictionPointBody2 /=static_cast(internalManifold.nbContacts); - internalManifold.r1Friction = internalManifold.frictionPointBody1 - x1; - internalManifold.r2Friction = internalManifold.frictionPointBody2 - x2; - internalManifold.oldFrictionVector1 = externalManifold->getFrictionVector1(); - internalManifold.oldFrictionVector2 = externalManifold->getFrictionVector2(); + internalManifold.frictionPointBody1 /=static_cast(internalManifold.nbContacts); + internalManifold.frictionPointBody2 /=static_cast(internalManifold.nbContacts); + internalManifold.r1Friction = internalManifold.frictionPointBody1 - x1; + internalManifold.r2Friction = internalManifold.frictionPointBody2 - x2; + internalManifold.oldFrictionVector1 = externalManifold->getFrictionVector1(); + internalManifold.oldFrictionVector2 = externalManifold->getFrictionVector2(); - // If warm starting is active - if (mIsWarmStartingActive) { - - // Initialize the accumulated impulses with the previous step accumulated impulses - internalManifold.friction1Impulse = externalManifold->getFrictionImpulse1(); - internalManifold.friction2Impulse = externalManifold->getFrictionImpulse2(); - internalManifold.frictionTwistImpulse = externalManifold->getFrictionTwistImpulse(); - } - else { - - // Initialize the accumulated impulses to zero - internalManifold.friction1Impulse = 0.0; - internalManifold.friction2Impulse = 0.0; - internalManifold.frictionTwistImpulse = 0.0; - internalManifold.rollingResistanceImpulse = Vector3(0, 0, 0); - } - } + // Initialize the accumulated impulses with the previous step accumulated impulses + internalManifold.friction1Impulse = externalManifold->getFrictionImpulse1(); + internalManifold.friction2Impulse = externalManifold->getFrictionImpulse2(); + internalManifold.frictionTwistImpulse = externalManifold->getFrictionTwistImpulse(); } // Fill-in all the matrices needed to solve the LCP problem @@ -190,9 +168,7 @@ void ContactSolver::initializeContactConstraints() { Matrix3x3& I2 = manifold.inverseInertiaTensorBody2; // If we solve the friction constraints at the center of the contact manifold - if (mIsSolveFrictionAtContactManifoldCenterActive) { - manifold.normal = Vector3(0.0, 0.0, 0.0); - } + manifold.normal.setToZero(); // Get the velocities of the bodies const Vector3& v1 = mLinearVelocities[manifold.indexBody1]; @@ -220,37 +196,6 @@ void ContactSolver::initializeContactConstraints() { massPenetration : decimal(0.0); - // If we do not solve the friction constraints at the center of the contact manifold - if (!mIsSolveFrictionAtContactManifoldCenterActive) { - - // Compute the friction vectors - computeFrictionVectors(deltaV, contactPoint); - - contactPoint.r1CrossT1 = contactPoint.r1.cross(contactPoint.frictionVector1); - contactPoint.r1CrossT2 = contactPoint.r1.cross(contactPoint.frictionVector2); - contactPoint.r2CrossT1 = contactPoint.r2.cross(contactPoint.frictionVector1); - contactPoint.r2CrossT2 = contactPoint.r2.cross(contactPoint.frictionVector2); - - // Compute the inverse mass matrix K for the friction - // constraints at each contact point - decimal friction1Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + - ((I1 * contactPoint.r1CrossT1).cross(contactPoint.r1)).dot( - contactPoint.frictionVector1) + - ((I2 * contactPoint.r2CrossT1).cross(contactPoint.r2)).dot( - contactPoint.frictionVector1); - decimal friction2Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + - ((I1 * contactPoint.r1CrossT2).cross(contactPoint.r1)).dot( - contactPoint.frictionVector2) + - ((I2 * contactPoint.r2CrossT2).cross(contactPoint.r2)).dot( - contactPoint.frictionVector2); - friction1Mass > 0.0 ? contactPoint.inverseFriction1Mass = decimal(1.0) / - friction1Mass : - decimal(0.0); - friction2Mass > 0.0 ? contactPoint.inverseFriction2Mass = decimal(1.0) / - friction2Mass : - decimal(0.0); - } - // Compute the restitution velocity bias "b". We compute this here instead // of inside the solve() method because we need to use the velocity difference // at the beginning of the contact. Note that if it is a resting contact (normal @@ -261,23 +206,16 @@ void ContactSolver::initializeContactConstraints() { contactPoint.restitutionBias = manifold.restitutionFactor * deltaVDotN; } - // If the warm starting of the contact solver is active - if (mIsWarmStartingActive) { - - // Get the cached accumulated impulses from the previous step - contactPoint.penetrationImpulse = externalContact->getPenetrationImpulse(); - contactPoint.friction1Impulse = externalContact->getFrictionImpulse1(); - contactPoint.friction2Impulse = externalContact->getFrictionImpulse2(); - contactPoint.rollingResistanceImpulse = externalContact->getRollingResistanceImpulse(); - } + // Get the cached accumulated impulses from the previous step + contactPoint.penetrationImpulse = externalContact->getPenetrationImpulse(); + contactPoint.friction1Impulse = externalContact->getFrictionImpulse1(); + contactPoint.friction2Impulse = externalContact->getFrictionImpulse2(); + contactPoint.rollingResistanceImpulse = externalContact->getRollingResistanceImpulse(); // Initialize the split impulses to zero contactPoint.penetrationSplitImpulse = 0.0; - // If we solve the friction constraints at the center of the contact manifold - if (mIsSolveFrictionAtContactManifoldCenterActive) { - manifold.normal += contactPoint.normal; - } + manifold.normal += contactPoint.normal; } // Compute the inverse K matrix for the rolling resistance constraint @@ -287,45 +225,41 @@ void ContactSolver::initializeContactConstraints() { manifold.inverseRollingResistance = manifold.inverseRollingResistance.getInverse(); } - // If we solve the friction constraints at the center of the contact manifold - if (mIsSolveFrictionAtContactManifoldCenterActive) { + manifold.normal.normalize(); - manifold.normal.normalize(); + Vector3 deltaVFrictionPoint = v2 + w2.cross(manifold.r2Friction) - + v1 - w1.cross(manifold.r1Friction); - Vector3 deltaVFrictionPoint = v2 + w2.cross(manifold.r2Friction) - - v1 - w1.cross(manifold.r1Friction); + // Compute the friction vectors + computeFrictionVectors(deltaVFrictionPoint, manifold); - // Compute the friction vectors - computeFrictionVectors(deltaVFrictionPoint, manifold); - - // Compute the inverse mass matrix K for the friction constraints at the center of - // the contact manifold - manifold.r1CrossT1 = manifold.r1Friction.cross(manifold.frictionVector1); - manifold.r1CrossT2 = manifold.r1Friction.cross(manifold.frictionVector2); - manifold.r2CrossT1 = manifold.r2Friction.cross(manifold.frictionVector1); - manifold.r2CrossT2 = manifold.r2Friction.cross(manifold.frictionVector2); - decimal friction1Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + - ((I1 * manifold.r1CrossT1).cross(manifold.r1Friction)).dot( - manifold.frictionVector1) + - ((I2 * manifold.r2CrossT1).cross(manifold.r2Friction)).dot( - manifold.frictionVector1); - decimal friction2Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + - ((I1 * manifold.r1CrossT2).cross(manifold.r1Friction)).dot( - manifold.frictionVector2) + - ((I2 * manifold.r2CrossT2).cross(manifold.r2Friction)).dot( - manifold.frictionVector2); - decimal frictionTwistMass = manifold.normal.dot(manifold.inverseInertiaTensorBody1 * - manifold.normal) + - manifold.normal.dot(manifold.inverseInertiaTensorBody2 * - manifold.normal); - friction1Mass > 0.0 ? manifold.inverseFriction1Mass = decimal(1.0)/friction1Mass - : decimal(0.0); - friction2Mass > 0.0 ? manifold.inverseFriction2Mass = decimal(1.0)/friction2Mass - : decimal(0.0); - frictionTwistMass > 0.0 ? manifold.inverseTwistFrictionMass = decimal(1.0) / - frictionTwistMass : - decimal(0.0); - } + // Compute the inverse mass matrix K for the friction constraints at the center of + // the contact manifold + manifold.r1CrossT1 = manifold.r1Friction.cross(manifold.frictionVector1); + manifold.r1CrossT2 = manifold.r1Friction.cross(manifold.frictionVector2); + manifold.r2CrossT1 = manifold.r2Friction.cross(manifold.frictionVector1); + manifold.r2CrossT2 = manifold.r2Friction.cross(manifold.frictionVector2); + decimal friction1Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + + ((I1 * manifold.r1CrossT1).cross(manifold.r1Friction)).dot( + manifold.frictionVector1) + + ((I2 * manifold.r2CrossT1).cross(manifold.r2Friction)).dot( + manifold.frictionVector1); + decimal friction2Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + + ((I1 * manifold.r1CrossT2).cross(manifold.r1Friction)).dot( + manifold.frictionVector2) + + ((I2 * manifold.r2CrossT2).cross(manifold.r2Friction)).dot( + manifold.frictionVector2); + decimal frictionTwistMass = manifold.normal.dot(manifold.inverseInertiaTensorBody1 * + manifold.normal) + + manifold.normal.dot(manifold.inverseInertiaTensorBody2 * + manifold.normal); + friction1Mass > 0.0 ? manifold.inverseFriction1Mass = decimal(1.0)/friction1Mass + : decimal(0.0); + friction2Mass > 0.0 ? manifold.inverseFriction2Mass = decimal(1.0)/friction2Mass + : decimal(0.0); + frictionTwistMass > 0.0 ? manifold.inverseTwistFrictionMass = decimal(1.0) / + frictionTwistMass : + decimal(0.0); } } @@ -335,9 +269,6 @@ void ContactSolver::initializeContactConstraints() { /// the solution of the linear system void ContactSolver::warmStart() { - // Check that warm starting is active - if (!mIsWarmStartingActive) return; - // For each constraint for (uint c=0; c 0) { - - // Compute the impulse P = J^T * lambda - const Impulse impulseRollingResistance(Vector3::zero(), -contactPoint.rollingResistanceImpulse, - Vector3::zero(), contactPoint.rollingResistanceImpulse); - - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseRollingResistance, contactManifold); - } - } } else { // If it is a new contact point @@ -420,7 +306,7 @@ void ContactSolver::warmStart() { // If we solve the friction constraints at the center of the contact manifold and there is // at least one resting contact point in the contact manifold - if (mIsSolveFrictionAtContactManifoldCenterActive && atLeastOneRestingContactPoint) { + if (atLeastOneRestingContactPoint) { // Project the old friction impulses (with old friction vectors) into the new friction // vectors to get the new friction impulses @@ -588,189 +474,110 @@ void ContactSolver::solve() { applySplitImpulse(splitImpulsePenetration, contactManifold); } - - // If we do not solve the friction constraints at the center of the contact manifold - if (!mIsSolveFrictionAtContactManifoldCenterActive) { - - // --------- Friction 1 --------- // - - // Compute J*v - deltaV = v2 + w2.cross(contactPoint.r2) - v1 - w1.cross(contactPoint.r1); - Jv = deltaV.dot(contactPoint.frictionVector1); - - // Compute the Lagrange multiplier lambda - deltaLambda = -Jv; - deltaLambda *= contactPoint.inverseFriction1Mass; - decimal frictionLimit = contactManifold.frictionCoefficient * - contactPoint.penetrationImpulse; - lambdaTemp = contactPoint.friction1Impulse; - contactPoint.friction1Impulse = std::max(-frictionLimit, - std::min(contactPoint.friction1Impulse - + deltaLambda, frictionLimit)); - deltaLambda = contactPoint.friction1Impulse - lambdaTemp; - - // Compute the impulse P=J^T * lambda - const Impulse impulseFriction1 = computeFriction1Impulse(deltaLambda, - contactPoint); - - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseFriction1, contactManifold); - - // --------- Friction 2 --------- // - - // Compute J*v - deltaV = v2 + w2.cross(contactPoint.r2) - v1 - w1.cross(contactPoint.r1); - Jv = deltaV.dot(contactPoint.frictionVector2); - - // Compute the Lagrange multiplier lambda - deltaLambda = -Jv; - deltaLambda *= contactPoint.inverseFriction2Mass; - frictionLimit = contactManifold.frictionCoefficient * - contactPoint.penetrationImpulse; - lambdaTemp = contactPoint.friction2Impulse; - contactPoint.friction2Impulse = std::max(-frictionLimit, - std::min(contactPoint.friction2Impulse - + deltaLambda, frictionLimit)); - deltaLambda = contactPoint.friction2Impulse - lambdaTemp; - - // Compute the impulse P=J^T * lambda - const Impulse impulseFriction2 = computeFriction2Impulse(deltaLambda, - contactPoint); - - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseFriction2, contactManifold); - - // --------- Rolling resistance constraint --------- // - - if (contactManifold.rollingResistanceFactor > 0) { - - // Compute J*v - const Vector3 JvRolling = w2 - w1; - - // Compute the Lagrange multiplier lambda - Vector3 deltaLambdaRolling = contactManifold.inverseRollingResistance * (-JvRolling); - decimal rollingLimit = contactManifold.rollingResistanceFactor * contactPoint.penetrationImpulse; - Vector3 lambdaTempRolling = contactPoint.rollingResistanceImpulse; - contactPoint.rollingResistanceImpulse = clamp(contactPoint.rollingResistanceImpulse + - deltaLambdaRolling, rollingLimit); - deltaLambdaRolling = contactPoint.rollingResistanceImpulse - lambdaTempRolling; - - // Compute the impulse P=J^T * lambda - const Impulse impulseRolling(Vector3::zero(), -deltaLambdaRolling, - Vector3::zero(), deltaLambdaRolling); - - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseRolling, contactManifold); - } - } } - // If we solve the friction constraints at the center of the contact manifold - if (mIsSolveFrictionAtContactManifoldCenterActive) { + // ------ First friction constraint at the center of the contact manifol ------ // - // ------ First friction constraint at the center of the contact manifol ------ // + // Compute J*v + Vector3 deltaV = v2 + w2.cross(contactManifold.r2Friction) + - v1 - w1.cross(contactManifold.r1Friction); + decimal Jv = deltaV.dot(contactManifold.frictionVector1); - // Compute J*v - Vector3 deltaV = v2 + w2.cross(contactManifold.r2Friction) - - v1 - w1.cross(contactManifold.r1Friction); - decimal Jv = deltaV.dot(contactManifold.frictionVector1); + // Compute the Lagrange multiplier lambda + decimal deltaLambda = -Jv * contactManifold.inverseFriction1Mass; + decimal frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; + lambdaTemp = contactManifold.friction1Impulse; + contactManifold.friction1Impulse = std::max(-frictionLimit, + std::min(contactManifold.friction1Impulse + + deltaLambda, frictionLimit)); + deltaLambda = contactManifold.friction1Impulse - lambdaTemp; - // Compute the Lagrange multiplier lambda - decimal deltaLambda = -Jv * contactManifold.inverseFriction1Mass; - decimal frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; - lambdaTemp = contactManifold.friction1Impulse; - contactManifold.friction1Impulse = std::max(-frictionLimit, - std::min(contactManifold.friction1Impulse + - deltaLambda, frictionLimit)); - deltaLambda = contactManifold.friction1Impulse - lambdaTemp; + // Compute the impulse P=J^T * lambda + Vector3 linearImpulseBody1 = -contactManifold.frictionVector1 * deltaLambda; + Vector3 angularImpulseBody1 = -contactManifold.r1CrossT1 * deltaLambda; + Vector3 linearImpulseBody2 = contactManifold.frictionVector1 * deltaLambda; + Vector3 angularImpulseBody2 = contactManifold.r2CrossT1 * deltaLambda; + const Impulse impulseFriction1(linearImpulseBody1, angularImpulseBody1, + linearImpulseBody2, angularImpulseBody2); - // Compute the impulse P=J^T * lambda - Vector3 linearImpulseBody1 = -contactManifold.frictionVector1 * deltaLambda; - Vector3 angularImpulseBody1 = -contactManifold.r1CrossT1 * deltaLambda; - Vector3 linearImpulseBody2 = contactManifold.frictionVector1 * deltaLambda; - Vector3 angularImpulseBody2 = contactManifold.r2CrossT1 * deltaLambda; - const Impulse impulseFriction1(linearImpulseBody1, angularImpulseBody1, + // Apply the impulses to the bodies of the constraint + applyImpulse(impulseFriction1, contactManifold); + + // ------ Second friction constraint at the center of the contact manifol ----- // + + // Compute J*v + deltaV = v2 + w2.cross(contactManifold.r2Friction) + - v1 - w1.cross(contactManifold.r1Friction); + Jv = deltaV.dot(contactManifold.frictionVector2); + + // Compute the Lagrange multiplier lambda + deltaLambda = -Jv * contactManifold.inverseFriction2Mass; + frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; + lambdaTemp = contactManifold.friction2Impulse; + contactManifold.friction2Impulse = std::max(-frictionLimit, + std::min(contactManifold.friction2Impulse + + deltaLambda, frictionLimit)); + deltaLambda = contactManifold.friction2Impulse - lambdaTemp; + + // Compute the impulse P=J^T * lambda + linearImpulseBody1 = -contactManifold.frictionVector2 * deltaLambda; + angularImpulseBody1 = -contactManifold.r1CrossT2 * deltaLambda; + linearImpulseBody2 = contactManifold.frictionVector2 * deltaLambda; + angularImpulseBody2 = contactManifold.r2CrossT2 * deltaLambda; + const Impulse impulseFriction2(linearImpulseBody1, angularImpulseBody1, + linearImpulseBody2, angularImpulseBody2); + + // Apply the impulses to the bodies of the constraint + applyImpulse(impulseFriction2, contactManifold); + + // ------ Twist friction constraint at the center of the contact manifol ------ // + + // Compute J*v + deltaV = w2 - w1; + Jv = deltaV.dot(contactManifold.normal); + + deltaLambda = -Jv * (contactManifold.inverseTwistFrictionMass); + frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; + lambdaTemp = contactManifold.frictionTwistImpulse; + contactManifold.frictionTwistImpulse = std::max(-frictionLimit, + std::min(contactManifold.frictionTwistImpulse + + deltaLambda, frictionLimit)); + deltaLambda = contactManifold.frictionTwistImpulse - lambdaTemp; + + // Compute the impulse P=J^T * lambda + linearImpulseBody1 = Vector3(0.0, 0.0, 0.0); + angularImpulseBody1 = -contactManifold.normal * deltaLambda; + linearImpulseBody2 = Vector3(0.0, 0.0, 0.0);; + angularImpulseBody2 = contactManifold.normal * deltaLambda; + const Impulse impulseTwistFriction(linearImpulseBody1, angularImpulseBody1, linearImpulseBody2, angularImpulseBody2); - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseFriction1, contactManifold); + // Apply the impulses to the bodies of the constraint + applyImpulse(impulseTwistFriction, contactManifold); - // ------ Second friction constraint at the center of the contact manifol ----- // + // --------- Rolling resistance constraint at the center of the contact manifold --------- // + + if (contactManifold.rollingResistanceFactor > 0) { // Compute J*v - deltaV = v2 + w2.cross(contactManifold.r2Friction) - - v1 - w1.cross(contactManifold.r1Friction); - Jv = deltaV.dot(contactManifold.frictionVector2); + const Vector3 JvRolling = w2 - w1; // Compute the Lagrange multiplier lambda - deltaLambda = -Jv * contactManifold.inverseFriction2Mass; - frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; - lambdaTemp = contactManifold.friction2Impulse; - contactManifold.friction2Impulse = std::max(-frictionLimit, - std::min(contactManifold.friction2Impulse + - deltaLambda, frictionLimit)); - deltaLambda = contactManifold.friction2Impulse - lambdaTemp; + Vector3 deltaLambdaRolling = contactManifold.inverseRollingResistance * (-JvRolling); + decimal rollingLimit = contactManifold.rollingResistanceFactor * sumPenetrationImpulse; + Vector3 lambdaTempRolling = contactManifold.rollingResistanceImpulse; + contactManifold.rollingResistanceImpulse = clamp(contactManifold.rollingResistanceImpulse + + deltaLambdaRolling, rollingLimit); + deltaLambdaRolling = contactManifold.rollingResistanceImpulse - lambdaTempRolling; // Compute the impulse P=J^T * lambda - linearImpulseBody1 = -contactManifold.frictionVector2 * deltaLambda; - angularImpulseBody1 = -contactManifold.r1CrossT2 * deltaLambda; - linearImpulseBody2 = contactManifold.frictionVector2 * deltaLambda; - angularImpulseBody2 = contactManifold.r2CrossT2 * deltaLambda; - const Impulse impulseFriction2(linearImpulseBody1, angularImpulseBody1, - linearImpulseBody2, angularImpulseBody2); + angularImpulseBody1 = -deltaLambdaRolling; + angularImpulseBody2 = deltaLambdaRolling; + const Impulse impulseRolling(Vector3::zero(), angularImpulseBody1, + Vector3::zero(), angularImpulseBody2); // Apply the impulses to the bodies of the constraint - applyImpulse(impulseFriction2, contactManifold); - - // ------ Twist friction constraint at the center of the contact manifol ------ // - - // Compute J*v - deltaV = w2 - w1; - Jv = deltaV.dot(contactManifold.normal); - - deltaLambda = -Jv * (contactManifold.inverseTwistFrictionMass); - frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; - lambdaTemp = contactManifold.frictionTwistImpulse; - contactManifold.frictionTwistImpulse = std::max(-frictionLimit, - std::min(contactManifold.frictionTwistImpulse - + deltaLambda, frictionLimit)); - deltaLambda = contactManifold.frictionTwistImpulse - lambdaTemp; - - // Compute the impulse P=J^T * lambda - linearImpulseBody1 = Vector3(0.0, 0.0, 0.0); - angularImpulseBody1 = -contactManifold.normal * deltaLambda; - linearImpulseBody2 = Vector3(0.0, 0.0, 0.0);; - angularImpulseBody2 = contactManifold.normal * deltaLambda; - const Impulse impulseTwistFriction(linearImpulseBody1, angularImpulseBody1, - linearImpulseBody2, angularImpulseBody2); - - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseTwistFriction, contactManifold); - - // --------- Rolling resistance constraint at the center of the contact manifold --------- // - - if (contactManifold.rollingResistanceFactor > 0) { - - // Compute J*v - const Vector3 JvRolling = w2 - w1; - - // Compute the Lagrange multiplier lambda - Vector3 deltaLambdaRolling = contactManifold.inverseRollingResistance * (-JvRolling); - decimal rollingLimit = contactManifold.rollingResistanceFactor * sumPenetrationImpulse; - Vector3 lambdaTempRolling = contactManifold.rollingResistanceImpulse; - contactManifold.rollingResistanceImpulse = clamp(contactManifold.rollingResistanceImpulse + - deltaLambdaRolling, rollingLimit); - deltaLambdaRolling = contactManifold.rollingResistanceImpulse - lambdaTempRolling; - - // Compute the impulse P=J^T * lambda - angularImpulseBody1 = -deltaLambdaRolling; - angularImpulseBody2 = deltaLambdaRolling; - const Impulse impulseRolling(Vector3::zero(), angularImpulseBody1, - Vector3::zero(), angularImpulseBody2); - - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseRolling, contactManifold); - } + applyImpulse(impulseRolling, contactManifold); } } } diff --git a/src/engine/ContactSolver.h b/src/engine/ContactSolver.h index 7fd4442f..5af9433a 100644 --- a/src/engine/ContactSolver.h +++ b/src/engine/ContactSolver.h @@ -351,16 +351,9 @@ class ContactSolver { /// Reference to the map of rigid body to their index in the constrained velocities array const std::map& mMapBodyToConstrainedVelocityIndex; - /// True if the warm starting of the solver is active - bool mIsWarmStartingActive; - /// True if the split impulse position correction is active bool mIsSplitImpulseActive; - /// True if we solve 3 friction constraints at the contact manifold center only - /// instead of 2 friction constraints at each contact point - bool mIsSolveFrictionAtContactManifoldCenterActive; - // -------------------- Methods -------------------- // /// Initialize the contact constraints before solving the system @@ -446,10 +439,6 @@ class ContactSolver { /// Activate or Deactivate the split impulses for contacts void setIsSplitImpulseActive(bool isActive); - /// Activate or deactivate the solving of friction constraints at the center of - /// the contact manifold instead of solving them at each contact point - void setIsSolveFrictionAtContactManifoldCenterActive(bool isActive); - /// Clean up the constraint solver void cleanup(); }; @@ -486,12 +475,6 @@ inline void ContactSolver::setIsSplitImpulseActive(bool isActive) { mIsSplitImpulseActive = isActive; } -// Activate or deactivate the solving of friction constraints at the center of -// the contact manifold instead of solving them at each contact point -inline void ContactSolver::setIsSolveFrictionAtContactManifoldCenterActive(bool isActive) { - mIsSolveFrictionAtContactManifoldCenterActive = isActive; -} - // Compute the collision restitution factor from the restitution factor of each body inline decimal ContactSolver::computeMixedRestitutionFactor(RigidBody* body1, RigidBody* body2) const { diff --git a/src/engine/DynamicsWorld.h b/src/engine/DynamicsWorld.h index dec383a1..746e8255 100644 --- a/src/engine/DynamicsWorld.h +++ b/src/engine/DynamicsWorld.h @@ -204,10 +204,6 @@ class DynamicsWorld : public CollisionWorld { /// Set the position correction technique used for joints void setJointsPositionCorrectionTechnique(JointsPositionCorrectionTechnique technique); - /// Activate or deactivate the solving of friction constraints at the center of - /// the contact manifold instead of solving them at each contact point - void setIsSolveFrictionAtContactManifoldCenterActive(bool isActive); - /// Create a rigid body into the physics world. RigidBody* createRigidBody(const Transform& transform); @@ -367,16 +363,6 @@ inline void DynamicsWorld::setJointsPositionCorrectionTechnique( } } -// Activate or deactivate the solving of friction constraints at the center of -// the contact manifold instead of solving them at each contact point -/** - * @param isActive True if you want the friction to be solved at the center of - * the contact manifold and false otherwise - */ -inline void DynamicsWorld::setIsSolveFrictionAtContactManifoldCenterActive(bool isActive) { - mContactSolver.setIsSolveFrictionAtContactManifoldCenterActive(isActive); -} - // Return the gravity vector of the world /** * @return The current gravity vector (in meter per seconds squared) From a4a141483b31d46049a9165e9e9a93021b36a7ec Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sat, 8 Oct 2016 23:04:22 +0200 Subject: [PATCH 033/248] Remove init contact constraint method --- src/engine/ContactSolver.cpp | 190 ++++++++++++++--------------------- src/engine/ContactSolver.h | 3 - 2 files changed, 76 insertions(+), 117 deletions(-) diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index 77abee5d..0a09f5d8 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -103,10 +103,16 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { internalManifold.externalContactManifold = externalManifold; internalManifold.isBody1DynamicType = body1->getType() == BodyType::DYNAMIC; internalManifold.isBody2DynamicType = body2->getType() == BodyType::DYNAMIC; - + internalManifold.normal.setToZero(); internalManifold.frictionPointBody1 = Vector3::zero(); internalManifold.frictionPointBody2 = Vector3::zero(); + // Get the velocities of the bodies + const Vector3& v1 = mLinearVelocities[internalManifold.indexBody1]; + const Vector3& w1 = mAngularVelocities[internalManifold.indexBody1]; + const Vector3& v2 = mLinearVelocities[internalManifold.indexBody2]; + const Vector3& w2 = mAngularVelocities[internalManifold.indexBody2]; + // For each contact point of the contact manifold for (uint c=0; cgetNbContactPoints(); c++) { @@ -128,13 +134,38 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { externalContact->setIsRestingContact(true); contactPoint.oldFrictionVector1 = externalContact->getFrictionVector1(); contactPoint.oldFrictionVector2 = externalContact->getFrictionVector2(); - contactPoint.penetrationImpulse = 0.0; - contactPoint.friction1Impulse = 0.0; - contactPoint.friction2Impulse = 0.0; - contactPoint.rollingResistanceImpulse = Vector3::zero(); + contactPoint.penetrationImpulse = externalContact->getPenetrationImpulse(); + contactPoint.penetrationSplitImpulse = 0.0; + contactPoint.friction1Impulse = externalContact->getFrictionImpulse1(); + contactPoint.friction2Impulse = externalContact->getFrictionImpulse2(); + contactPoint.rollingResistanceImpulse = externalContact->getRollingResistanceImpulse(); internalManifold.frictionPointBody1 += p1; internalManifold.frictionPointBody2 += p2; + + // Compute the velocity difference + Vector3 deltaV = v2 + w2.cross(contactPoint.r2) - v1 - w1.cross(contactPoint.r1); + + contactPoint.r1CrossN = contactPoint.r1.cross(contactPoint.normal); + contactPoint.r2CrossN = contactPoint.r2.cross(contactPoint.normal); + + // Compute the inverse mass matrix K for the penetration constraint + decimal massPenetration = internalManifold.massInverseBody1 + internalManifold.massInverseBody2 + + ((internalManifold.inverseInertiaTensorBody1 * contactPoint.r1CrossN).cross(contactPoint.r1)).dot(contactPoint.normal) + + ((internalManifold.inverseInertiaTensorBody2 * contactPoint.r2CrossN).cross(contactPoint.r2)).dot(contactPoint.normal); + contactPoint.inversePenetrationMass = massPenetration > decimal(0.0) ? decimal(1.0) / massPenetration : decimal(0.0); + + // Compute the restitution velocity bias "b". We compute this here instead + // of inside the solve() method because we need to use the velocity difference + // at the beginning of the contact. Note that if it is a resting contact (normal + // velocity bellow a given threshold), we do not add a restitution velocity bias + contactPoint.restitutionBias = 0.0; + decimal deltaVDotN = deltaV.dot(contactPoint.normal); + if (deltaVDotN < -RESTITUTION_VELOCITY_THRESHOLD) { + contactPoint.restitutionBias = internalManifold.restitutionFactor * deltaVDotN; + } + + internalManifold.normal += contactPoint.normal; } @@ -149,120 +180,51 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { internalManifold.friction1Impulse = externalManifold->getFrictionImpulse1(); internalManifold.friction2Impulse = externalManifold->getFrictionImpulse2(); internalManifold.frictionTwistImpulse = externalManifold->getFrictionTwistImpulse(); + + // Compute the inverse K matrix for the rolling resistance constraint + internalManifold.inverseRollingResistance.setToZero(); + if (internalManifold.rollingResistanceFactor > 0 && (internalManifold.isBody1DynamicType || internalManifold.isBody2DynamicType)) { + internalManifold.inverseRollingResistance = internalManifold.inverseInertiaTensorBody1 + internalManifold.inverseInertiaTensorBody2; + internalManifold.inverseRollingResistance = internalManifold.inverseRollingResistance.getInverse(); + } + + internalManifold.normal.normalize(); + + Vector3 deltaVFrictionPoint = v2 + w2.cross(internalManifold.r2Friction) - + v1 - w1.cross(internalManifold.r1Friction); + + // Compute the friction vectors + computeFrictionVectors(deltaVFrictionPoint, internalManifold); + + // Compute the inverse mass matrix K for the friction constraints at the center of + // the contact manifold + internalManifold.r1CrossT1 = internalManifold.r1Friction.cross(internalManifold.frictionVector1); + internalManifold.r1CrossT2 = internalManifold.r1Friction.cross(internalManifold.frictionVector2); + internalManifold.r2CrossT1 = internalManifold.r2Friction.cross(internalManifold.frictionVector1); + internalManifold.r2CrossT2 = internalManifold.r2Friction.cross(internalManifold.frictionVector2); + decimal friction1Mass = internalManifold.massInverseBody1 + internalManifold.massInverseBody2 + + ((internalManifold.inverseInertiaTensorBody1 * internalManifold.r1CrossT1).cross(internalManifold.r1Friction)).dot( + internalManifold.frictionVector1) + + ((internalManifold.inverseInertiaTensorBody2 * internalManifold.r2CrossT1).cross(internalManifold.r2Friction)).dot( + internalManifold.frictionVector1); + decimal friction2Mass = internalManifold.massInverseBody1 + internalManifold.massInverseBody2 + + ((internalManifold.inverseInertiaTensorBody1 * internalManifold.r1CrossT2).cross(internalManifold.r1Friction)).dot( + internalManifold.frictionVector2) + + ((internalManifold.inverseInertiaTensorBody2 * internalManifold.r2CrossT2).cross(internalManifold.r2Friction)).dot( + internalManifold.frictionVector2); + decimal frictionTwistMass = internalManifold.normal.dot(internalManifold.inverseInertiaTensorBody1 * + internalManifold.normal) + + internalManifold.normal.dot(internalManifold.inverseInertiaTensorBody2 * + internalManifold.normal); + internalManifold.inverseFriction1Mass = friction1Mass > decimal(0.0) ? decimal(1.0) / friction1Mass : decimal(0.0); + internalManifold.inverseFriction2Mass = friction2Mass > decimal(0.0) ? decimal(1.0) / friction2Mass : decimal(0.0); + internalManifold.inverseTwistFrictionMass = frictionTwistMass > decimal(0.0) ? decimal(1.0) / frictionTwistMass : decimal(0.0); } // Fill-in all the matrices needed to solve the LCP problem initializeContactConstraints(); } -// Initialize the contact constraints before solving the system -void ContactSolver::initializeContactConstraints() { - - // For each contact constraint - for (uint c=0; c 0.0 ? contactPoint.inversePenetrationMass = decimal(1.0) / - massPenetration : - decimal(0.0); - - // Compute the restitution velocity bias "b". We compute this here instead - // of inside the solve() method because we need to use the velocity difference - // at the beginning of the contact. Note that if it is a resting contact (normal - // velocity bellow a given threshold), we do not add a restitution velocity bias - contactPoint.restitutionBias = 0.0; - decimal deltaVDotN = deltaV.dot(contactPoint.normal); - if (deltaVDotN < -RESTITUTION_VELOCITY_THRESHOLD) { - contactPoint.restitutionBias = manifold.restitutionFactor * deltaVDotN; - } - - // Get the cached accumulated impulses from the previous step - contactPoint.penetrationImpulse = externalContact->getPenetrationImpulse(); - contactPoint.friction1Impulse = externalContact->getFrictionImpulse1(); - contactPoint.friction2Impulse = externalContact->getFrictionImpulse2(); - contactPoint.rollingResistanceImpulse = externalContact->getRollingResistanceImpulse(); - - // Initialize the split impulses to zero - contactPoint.penetrationSplitImpulse = 0.0; - - manifold.normal += contactPoint.normal; - } - - // Compute the inverse K matrix for the rolling resistance constraint - manifold.inverseRollingResistance.setToZero(); - if (manifold.rollingResistanceFactor > 0 && (manifold.isBody1DynamicType || manifold.isBody2DynamicType)) { - manifold.inverseRollingResistance = manifold.inverseInertiaTensorBody1 + manifold.inverseInertiaTensorBody2; - manifold.inverseRollingResistance = manifold.inverseRollingResistance.getInverse(); - } - - manifold.normal.normalize(); - - Vector3 deltaVFrictionPoint = v2 + w2.cross(manifold.r2Friction) - - v1 - w1.cross(manifold.r1Friction); - - // Compute the friction vectors - computeFrictionVectors(deltaVFrictionPoint, manifold); - - // Compute the inverse mass matrix K for the friction constraints at the center of - // the contact manifold - manifold.r1CrossT1 = manifold.r1Friction.cross(manifold.frictionVector1); - manifold.r1CrossT2 = manifold.r1Friction.cross(manifold.frictionVector2); - manifold.r2CrossT1 = manifold.r2Friction.cross(manifold.frictionVector1); - manifold.r2CrossT2 = manifold.r2Friction.cross(manifold.frictionVector2); - decimal friction1Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + - ((I1 * manifold.r1CrossT1).cross(manifold.r1Friction)).dot( - manifold.frictionVector1) + - ((I2 * manifold.r2CrossT1).cross(manifold.r2Friction)).dot( - manifold.frictionVector1); - decimal friction2Mass = manifold.massInverseBody1 + manifold.massInverseBody2 + - ((I1 * manifold.r1CrossT2).cross(manifold.r1Friction)).dot( - manifold.frictionVector2) + - ((I2 * manifold.r2CrossT2).cross(manifold.r2Friction)).dot( - manifold.frictionVector2); - decimal frictionTwistMass = manifold.normal.dot(manifold.inverseInertiaTensorBody1 * - manifold.normal) + - manifold.normal.dot(manifold.inverseInertiaTensorBody2 * - manifold.normal); - friction1Mass > 0.0 ? manifold.inverseFriction1Mass = decimal(1.0)/friction1Mass - : decimal(0.0); - friction2Mass > 0.0 ? manifold.inverseFriction2Mass = decimal(1.0)/friction2Mass - : decimal(0.0); - frictionTwistMass > 0.0 ? manifold.inverseTwistFrictionMass = decimal(1.0) / - frictionTwistMass : - decimal(0.0); - } -} - // Warm start the solver. /// For each constraint, we apply the previous impulse (from the previous step) /// at the beginning. With this technique, we will converge faster towards @@ -682,7 +644,7 @@ void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, ContactManifoldSolver& contact) const { - assert(contact.normal.length() > 0.0); + assert(contact.normal.length() > decimal(0.0)); // Compute the velocity difference vector in the tangential plane Vector3 normalVelocity = deltaVelocity.dot(contact.normal) * contact.normal; diff --git a/src/engine/ContactSolver.h b/src/engine/ContactSolver.h index 5af9433a..a465fa5a 100644 --- a/src/engine/ContactSolver.h +++ b/src/engine/ContactSolver.h @@ -356,9 +356,6 @@ class ContactSolver { // -------------------- Methods -------------------- // - /// Initialize the contact constraints before solving the system - void initializeContactConstraints(); - /// Apply an impulse to the two bodies of a constraint void applyImpulse(const Impulse& impulse, const ContactManifoldSolver& manifold); From 7b5dce927e006d2ab17a8dff3d4f853bcffe1c4d Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 10 Oct 2016 23:30:32 +0200 Subject: [PATCH 034/248] Fix issue with split impulse and refactor contact solver --- src/engine/ContactSolver.cpp | 196 +++++++++++++++-------------------- src/engine/ContactSolver.h | 49 +-------- 2 files changed, 82 insertions(+), 163 deletions(-) diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index 0a09f5d8..d02c773d 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -220,9 +220,6 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { internalManifold.inverseFriction2Mass = friction2Mass > decimal(0.0) ? decimal(1.0) / friction2Mass : decimal(0.0); internalManifold.inverseTwistFrictionMass = frictionTwistMass > decimal(0.0) ? decimal(1.0) / frictionTwistMass : decimal(0.0); } - - // Fill-in all the matrices needed to solve the LCP problem - initializeContactConstraints(); } // Warm start the solver. @@ -249,12 +246,14 @@ void ContactSolver::warmStart() { // --------- Penetration --------- // - // Compute the impulse P = J^T * lambda - const Impulse impulsePenetration = computePenetrationImpulse( - contactPoint.penetrationImpulse, contactPoint); + // Update the velocities of the body 1 by applying the impulse P + Vector3 impulsePenetration = contactPoint.normal * contactPoint.penetrationImpulse; + mLinearVelocities[contactManifold.indexBody1] += contactManifold.massInverseBody1 * (-impulsePenetration); + mAngularVelocities[contactManifold.indexBody1] += contactManifold.inverseInertiaTensorBody1 * (-contactPoint.r1CrossN * contactPoint.penetrationImpulse); - // Apply the impulse to the bodies of the constraint - applyImpulse(impulsePenetration, contactManifold); + // Update the velocities of the body 2 by applying the impulse P + mLinearVelocities[contactManifold.indexBody2] += contactManifold.massInverseBody2 * impulsePenetration; + mAngularVelocities[contactManifold.indexBody2] += contactManifold.inverseInertiaTensorBody2 * (contactPoint.r2CrossN * contactPoint.penetrationImpulse); } else { // If it is a new contact point @@ -272,72 +271,66 @@ void ContactSolver::warmStart() { // Project the old friction impulses (with old friction vectors) into the new friction // vectors to get the new friction impulses - Vector3 oldFrictionImpulse = contactManifold.friction1Impulse * - contactManifold.oldFrictionVector1 + - contactManifold.friction2Impulse * - contactManifold.oldFrictionVector2; - contactManifold.friction1Impulse = oldFrictionImpulse.dot( - contactManifold.frictionVector1); - contactManifold.friction2Impulse = oldFrictionImpulse.dot( - contactManifold.frictionVector2); + Vector3 oldFrictionImpulse = contactManifold.friction1Impulse * contactManifold.oldFrictionVector1 + + contactManifold.friction2Impulse * contactManifold.oldFrictionVector2; + contactManifold.friction1Impulse = oldFrictionImpulse.dot(contactManifold.frictionVector1); + contactManifold.friction2Impulse = oldFrictionImpulse.dot(contactManifold.frictionVector2); // ------ First friction constraint at the center of the contact manifold ------ // // Compute the impulse P = J^T * lambda - Vector3 linearImpulseBody1 = -contactManifold.frictionVector1 * - contactManifold.friction1Impulse; Vector3 angularImpulseBody1 = -contactManifold.r1CrossT1 * contactManifold.friction1Impulse; Vector3 linearImpulseBody2 = contactManifold.frictionVector1 * contactManifold.friction1Impulse; Vector3 angularImpulseBody2 = contactManifold.r2CrossT1 * contactManifold.friction1Impulse; - const Impulse impulseFriction1(linearImpulseBody1, angularImpulseBody1, - linearImpulseBody2, angularImpulseBody2); - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseFriction1, contactManifold); + // Update the velocities of the body 1 by applying the impulse P + mLinearVelocities[contactManifold.indexBody1] += contactManifold.massInverseBody1 * (-linearImpulseBody2); + mAngularVelocities[contactManifold.indexBody1] += contactManifold.inverseInertiaTensorBody1 * angularImpulseBody1; + + // Update the velocities of the body 1 by applying the impulse P + mLinearVelocities[contactManifold.indexBody2] += contactManifold.massInverseBody2 * linearImpulseBody2; + mAngularVelocities[contactManifold.indexBody2] += contactManifold.inverseInertiaTensorBody2 * angularImpulseBody2; // ------ Second friction constraint at the center of the contact manifold ----- // // Compute the impulse P = J^T * lambda - linearImpulseBody1 = -contactManifold.frictionVector2 * - contactManifold.friction2Impulse; - angularImpulseBody1 = -contactManifold.r1CrossT2 * - contactManifold.friction2Impulse; - linearImpulseBody2 = contactManifold.frictionVector2 * - contactManifold.friction2Impulse; - angularImpulseBody2 = contactManifold.r2CrossT2 * - contactManifold.friction2Impulse; - const Impulse impulseFriction2(linearImpulseBody1, angularImpulseBody1, - linearImpulseBody2, angularImpulseBody2); + angularImpulseBody1 = -contactManifold.r1CrossT2 * contactManifold.friction2Impulse; + linearImpulseBody2 = contactManifold.frictionVector2 * contactManifold.friction2Impulse; + angularImpulseBody2 = contactManifold.r2CrossT2 * contactManifold.friction2Impulse; - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseFriction2, contactManifold); + // Update the velocities of the body 1 by applying the impulse P + mLinearVelocities[contactManifold.indexBody1] += contactManifold.massInverseBody1 * (-linearImpulseBody2); + mAngularVelocities[contactManifold.indexBody1] += contactManifold.inverseInertiaTensorBody1 * angularImpulseBody1; + + // Update the velocities of the body 2 by applying the impulse P + mLinearVelocities[contactManifold.indexBody2] += contactManifold.massInverseBody2 * linearImpulseBody2; + mAngularVelocities[contactManifold.indexBody2] += contactManifold.inverseInertiaTensorBody2 * angularImpulseBody2; // ------ Twist friction constraint at the center of the contact manifold ------ // // Compute the impulse P = J^T * lambda - linearImpulseBody1 = Vector3(0.0, 0.0, 0.0); angularImpulseBody1 = -contactManifold.normal * contactManifold.frictionTwistImpulse; - linearImpulseBody2 = Vector3(0.0, 0.0, 0.0); angularImpulseBody2 = contactManifold.normal * contactManifold.frictionTwistImpulse; - const Impulse impulseTwistFriction(linearImpulseBody1, angularImpulseBody1, - linearImpulseBody2, angularImpulseBody2); - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseTwistFriction, contactManifold); + // Update the velocities of the body 1 by applying the impulse P + mAngularVelocities[contactManifold.indexBody1] += contactManifold.inverseInertiaTensorBody1 * angularImpulseBody1; + + // Update the velocities of the body 2 by applying the impulse P + mAngularVelocities[contactManifold.indexBody2] += contactManifold.inverseInertiaTensorBody2 * angularImpulseBody2; // ------ Rolling resistance at the center of the contact manifold ------ // // Compute the impulse P = J^T * lambda - angularImpulseBody1 = -contactManifold.rollingResistanceImpulse; angularImpulseBody2 = contactManifold.rollingResistanceImpulse; - const Impulse impulseRollingResistance(Vector3::zero(), angularImpulseBody1, - Vector3::zero(), angularImpulseBody2); - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseRollingResistance, contactManifold); + // Update the velocities of the body 1 by applying the impulse P + mAngularVelocities[contactManifold.indexBody1] += contactManifold.inverseInertiaTensorBody1 * (-angularImpulseBody2); + + // Update the velocities of the body 1 by applying the impulse P + mAngularVelocities[contactManifold.indexBody2] += contactManifold.inverseInertiaTensorBody2 * angularImpulseBody2; } else { // If it is a new contact manifold @@ -402,12 +395,15 @@ void ContactSolver::solve() { deltaLambda, decimal(0.0)); deltaLambda = contactPoint.penetrationImpulse - lambdaTemp; - // Compute the impulse P=J^T * lambda - const Impulse impulsePenetration = computePenetrationImpulse(deltaLambda, - contactPoint); + Vector3 linearImpulse = contactPoint.normal * deltaLambda; - // Apply the impulse to the bodies of the constraint - applyImpulse(impulsePenetration, contactManifold); + // Update the velocities of the body 1 by applying the impulse P + mLinearVelocities[contactManifold.indexBody1] += contactManifold.massInverseBody1 * (-linearImpulse); + mAngularVelocities[contactManifold.indexBody1] += contactManifold.inverseInertiaTensorBody1 * (-contactPoint.r1CrossN * deltaLambda); + + // Update the velocities of the body 2 by applying the impulse P + mLinearVelocities[contactManifold.indexBody2] += contactManifold.massInverseBody2 * linearImpulse; + mAngularVelocities[contactManifold.indexBody2] += contactManifold.inverseInertiaTensorBody2 * (contactPoint.r2CrossN * deltaLambda); sumPenetrationImpulse += contactPoint.penetrationImpulse; @@ -428,13 +424,19 @@ void ContactSolver::solve() { contactPoint.penetrationSplitImpulse = std::max( contactPoint.penetrationSplitImpulse + deltaLambdaSplit, decimal(0.0)); - deltaLambda = contactPoint.penetrationSplitImpulse - lambdaTempSplit; + deltaLambdaSplit = contactPoint.penetrationSplitImpulse - lambdaTempSplit; - // Compute the impulse P=J^T * lambda - const Impulse splitImpulsePenetration = computePenetrationImpulse( - deltaLambdaSplit, contactPoint); + Vector3 linearImpulse = contactPoint.normal * deltaLambdaSplit; - applySplitImpulse(splitImpulsePenetration, contactManifold); + // Update the velocities of the body 1 by applying the impulse P + mSplitLinearVelocities[contactManifold.indexBody1] += contactManifold.massInverseBody1 * (-linearImpulse); + mSplitAngularVelocities[contactManifold.indexBody1] += contactManifold.inverseInertiaTensorBody1 * + (-contactPoint.r1CrossN * deltaLambdaSplit); + + // Update the velocities of the body 1 by applying the impulse P + mSplitLinearVelocities[contactManifold.indexBody2] += contactManifold.massInverseBody2 * linearImpulse; + mSplitAngularVelocities[contactManifold.indexBody2] += contactManifold.inverseInertiaTensorBody2 * + contactPoint.r2CrossN * deltaLambdaSplit; } } @@ -455,21 +457,22 @@ void ContactSolver::solve() { deltaLambda = contactManifold.friction1Impulse - lambdaTemp; // Compute the impulse P=J^T * lambda - Vector3 linearImpulseBody1 = -contactManifold.frictionVector1 * deltaLambda; Vector3 angularImpulseBody1 = -contactManifold.r1CrossT1 * deltaLambda; Vector3 linearImpulseBody2 = contactManifold.frictionVector1 * deltaLambda; Vector3 angularImpulseBody2 = contactManifold.r2CrossT1 * deltaLambda; - const Impulse impulseFriction1(linearImpulseBody1, angularImpulseBody1, - linearImpulseBody2, angularImpulseBody2); - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseFriction1, contactManifold); + // Update the velocities of the body 1 by applying the impulse P + mLinearVelocities[contactManifold.indexBody1] += contactManifold.massInverseBody1 * (-linearImpulseBody2); + mAngularVelocities[contactManifold.indexBody1] += contactManifold.inverseInertiaTensorBody1 * angularImpulseBody1; + + // Update the velocities of the body 2 by applying the impulse P + mLinearVelocities[contactManifold.indexBody2] += contactManifold.massInverseBody2 * linearImpulseBody2; + mAngularVelocities[contactManifold.indexBody2] += contactManifold.inverseInertiaTensorBody2 * angularImpulseBody2; // ------ Second friction constraint at the center of the contact manifol ----- // // Compute J*v - deltaV = v2 + w2.cross(contactManifold.r2Friction) - - v1 - w1.cross(contactManifold.r1Friction); + deltaV = v2 + w2.cross(contactManifold.r2Friction) - v1 - w1.cross(contactManifold.r1Friction); Jv = deltaV.dot(contactManifold.frictionVector2); // Compute the Lagrange multiplier lambda @@ -482,15 +485,17 @@ void ContactSolver::solve() { deltaLambda = contactManifold.friction2Impulse - lambdaTemp; // Compute the impulse P=J^T * lambda - linearImpulseBody1 = -contactManifold.frictionVector2 * deltaLambda; angularImpulseBody1 = -contactManifold.r1CrossT2 * deltaLambda; linearImpulseBody2 = contactManifold.frictionVector2 * deltaLambda; angularImpulseBody2 = contactManifold.r2CrossT2 * deltaLambda; - const Impulse impulseFriction2(linearImpulseBody1, angularImpulseBody1, - linearImpulseBody2, angularImpulseBody2); - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseFriction2, contactManifold); + // Update the velocities of the body 1 by applying the impulse P + mLinearVelocities[contactManifold.indexBody1] += contactManifold.massInverseBody1 * (-linearImpulseBody2); + mAngularVelocities[contactManifold.indexBody1] += contactManifold.inverseInertiaTensorBody1 * angularImpulseBody1; + + // Update the velocities of the body 2 by applying the impulse P + mLinearVelocities[contactManifold.indexBody2] += contactManifold.massInverseBody2 * linearImpulseBody2; + mAngularVelocities[contactManifold.indexBody2] += contactManifold.inverseInertiaTensorBody2 * angularImpulseBody2; // ------ Twist friction constraint at the center of the contact manifol ------ // @@ -507,15 +512,13 @@ void ContactSolver::solve() { deltaLambda = contactManifold.frictionTwistImpulse - lambdaTemp; // Compute the impulse P=J^T * lambda - linearImpulseBody1 = Vector3(0.0, 0.0, 0.0); - angularImpulseBody1 = -contactManifold.normal * deltaLambda; - linearImpulseBody2 = Vector3(0.0, 0.0, 0.0);; angularImpulseBody2 = contactManifold.normal * deltaLambda; - const Impulse impulseTwistFriction(linearImpulseBody1, angularImpulseBody1, - linearImpulseBody2, angularImpulseBody2); - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseTwistFriction, contactManifold); + // Update the velocities of the body 1 by applying the impulse P + mAngularVelocities[contactManifold.indexBody1] += contactManifold.inverseInertiaTensorBody1 * (-angularImpulseBody2); + + // Update the velocities of the body 1 by applying the impulse P + mAngularVelocities[contactManifold.indexBody2] += contactManifold.inverseInertiaTensorBody2 * angularImpulseBody2; // --------- Rolling resistance constraint at the center of the contact manifold --------- // @@ -532,14 +535,11 @@ void ContactSolver::solve() { deltaLambdaRolling, rollingLimit); deltaLambdaRolling = contactManifold.rollingResistanceImpulse - lambdaTempRolling; - // Compute the impulse P=J^T * lambda - angularImpulseBody1 = -deltaLambdaRolling; - angularImpulseBody2 = deltaLambdaRolling; - const Impulse impulseRolling(Vector3::zero(), angularImpulseBody1, - Vector3::zero(), angularImpulseBody2); + // Update the velocities of the body 1 by applying the impulse P + mAngularVelocities[contactManifold.indexBody1] += contactManifold.inverseInertiaTensorBody1 * (-deltaLambdaRolling); - // Apply the impulses to the bodies of the constraint - applyImpulse(impulseRolling, contactManifold); + // Update the velocities of the body 2 by applying the impulse P + mAngularVelocities[contactManifold.indexBody2] += contactManifold.inverseInertiaTensorBody2 * deltaLambdaRolling; } } } @@ -575,40 +575,6 @@ void ContactSolver::storeImpulses() { } } -// Apply an impulse to the two bodies of a constraint -void ContactSolver::applyImpulse(const Impulse& impulse, - const ContactManifoldSolver& manifold) { - - // Update the velocities of the body 1 by applying the impulse P - mLinearVelocities[manifold.indexBody1] += manifold.massInverseBody1 * - impulse.linearImpulseBody1; - mAngularVelocities[manifold.indexBody1] += manifold.inverseInertiaTensorBody1 * - impulse.angularImpulseBody1; - - // Update the velocities of the body 1 by applying the impulse P - mLinearVelocities[manifold.indexBody2] += manifold.massInverseBody2 * - impulse.linearImpulseBody2; - mAngularVelocities[manifold.indexBody2] += manifold.inverseInertiaTensorBody2 * - impulse.angularImpulseBody2; -} - -// Apply an impulse to the two bodies of a constraint -void ContactSolver::applySplitImpulse(const Impulse& impulse, - const ContactManifoldSolver& manifold) { - - // Update the velocities of the body 1 by applying the impulse P - mSplitLinearVelocities[manifold.indexBody1] += manifold.massInverseBody1 * - impulse.linearImpulseBody1; - mSplitAngularVelocities[manifold.indexBody1] += manifold.inverseInertiaTensorBody1 * - impulse.angularImpulseBody1; - - // Update the velocities of the body 1 by applying the impulse P - mSplitLinearVelocities[manifold.indexBody2] += manifold.massInverseBody2 * - impulse.linearImpulseBody2; - mSplitAngularVelocities[manifold.indexBody2] += manifold.inverseInertiaTensorBody2 * - impulse.angularImpulseBody2; -} - // Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction plane // for a contact point. The two vectors have to be such that : t1 x t2 = contactNormal. void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, diff --git a/src/engine/ContactSolver.h b/src/engine/ContactSolver.h index a465fa5a..802f7024 100644 --- a/src/engine/ContactSolver.h +++ b/src/engine/ContactSolver.h @@ -356,13 +356,6 @@ class ContactSolver { // -------------------- Methods -------------------- // - /// Apply an impulse to the two bodies of a constraint - void applyImpulse(const Impulse& impulse, const ContactManifoldSolver& manifold); - - /// Apply an impulse to the two bodies of a constraint - void applySplitImpulse(const Impulse& impulse, - const ContactManifoldSolver& manifold); - /// Compute the collision restitution factor from the restitution factor of each body decimal computeMixedRestitutionFactor(RigidBody *body1, RigidBody *body2) const; @@ -386,18 +379,6 @@ class ContactSolver { void computeFrictionVectors(const Vector3& deltaVelocity, ContactManifoldSolver& contactPoint) const; - /// Compute a penetration constraint impulse - const Impulse computePenetrationImpulse(decimal deltaLambda, - const ContactPointSolver& contactPoint) const; - - /// Compute the first friction constraint impulse - const Impulse computeFriction1Impulse(decimal deltaLambda, - const ContactPointSolver& contactPoint) const; - - /// Compute the second friction constraint impulse - const Impulse computeFriction2Impulse(decimal deltaLambda, - const ContactPointSolver& contactPoint) const; - public: // -------------------- Methods -------------------- // @@ -486,7 +467,7 @@ inline decimal ContactSolver::computeMixedRestitutionFactor(RigidBody* body1, inline decimal ContactSolver::computeMixedFrictionCoefficient(RigidBody *body1, RigidBody *body2) const { // Use the geometric mean to compute the mixed friction coefficient - return sqrt(body1->getMaterial().getFrictionCoefficient() * + return std::sqrt(body1->getMaterial().getFrictionCoefficient() * body2->getMaterial().getFrictionCoefficient()); } @@ -496,34 +477,6 @@ inline decimal ContactSolver::computeMixedRollingResistance(RigidBody* body1, return decimal(0.5f) * (body1->getMaterial().getRollingResistance() + body2->getMaterial().getRollingResistance()); } -// Compute a penetration constraint impulse -inline const Impulse ContactSolver::computePenetrationImpulse(decimal deltaLambda, - const ContactPointSolver& contactPoint) - const { - return Impulse(-contactPoint.normal * deltaLambda, -contactPoint.r1CrossN * deltaLambda, - contactPoint.normal * deltaLambda, contactPoint.r2CrossN * deltaLambda); -} - -// Compute the first friction constraint impulse -inline const Impulse ContactSolver::computeFriction1Impulse(decimal deltaLambda, - const ContactPointSolver& contactPoint) - const { - return Impulse(-contactPoint.frictionVector1 * deltaLambda, - -contactPoint.r1CrossT1 * deltaLambda, - contactPoint.frictionVector1 * deltaLambda, - contactPoint.r2CrossT1 * deltaLambda); -} - -// Compute the second friction constraint impulse -inline const Impulse ContactSolver::computeFriction2Impulse(decimal deltaLambda, - const ContactPointSolver& contactPoint) - const { - return Impulse(-contactPoint.frictionVector2 * deltaLambda, - -contactPoint.r1CrossT2 * deltaLambda, - contactPoint.frictionVector2 * deltaLambda, - contactPoint.r2CrossT2 * deltaLambda); -} - } #endif From 58ae61d6aaa0c72fad376a8d5fd2e16c10fc4d56 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 11 Oct 2016 20:08:47 +0200 Subject: [PATCH 035/248] Remove Impulse class --- CMakeLists.txt | 1 - src/engine/ContactSolver.h | 1 - src/engine/Impulse.h | 87 -------------------------------------- 3 files changed, 89 deletions(-) delete mode 100644 src/engine/Impulse.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 69f20522..87a02105 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -147,7 +147,6 @@ SET (REACTPHYSICS3D_SOURCES "src/engine/DynamicsWorld.h" "src/engine/DynamicsWorld.cpp" "src/engine/EventListener.h" - "src/engine/Impulse.h" "src/engine/Island.h" "src/engine/Island.cpp" "src/engine/Material.h" diff --git a/src/engine/ContactSolver.h b/src/engine/ContactSolver.h index 802f7024..02a3c390 100644 --- a/src/engine/ContactSolver.h +++ b/src/engine/ContactSolver.h @@ -32,7 +32,6 @@ #include "constraint/Joint.h" #include "collision/ContactManifold.h" #include "Island.h" -#include "Impulse.h" #include #include diff --git a/src/engine/Impulse.h b/src/engine/Impulse.h deleted file mode 100644 index 89e36429..00000000 --- a/src/engine/Impulse.h +++ /dev/null @@ -1,87 +0,0 @@ -/******************************************************************************** -* 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_IMPULSE_H -#define REACTPHYSICS3D_IMPULSE_H - -// Libraries -#include "mathematics/mathematics.h" - -namespace reactphysics3d { - -// Structure Impulse -/** - * Represents an impulse that we can apply to bodies in the contact or constraint solver. - */ -struct Impulse { - - private: - - // -------------------- Methods -------------------- // - - public: - - // -------------------- Attributes -------------------- // - - /// Linear impulse applied to the first body - const Vector3 linearImpulseBody1; - - /// Angular impulse applied to the first body - const Vector3 angularImpulseBody1; - - /// Linear impulse applied to the second body - const Vector3 linearImpulseBody2; - - /// Angular impulse applied to the second body - const Vector3 angularImpulseBody2; - - // -------------------- Methods -------------------- // - - /// Constructor - Impulse(const Vector3& initLinearImpulseBody1, const Vector3& initAngularImpulseBody1, - const Vector3& initLinearImpulseBody2, const Vector3& initAngularImpulseBody2) - : linearImpulseBody1(initLinearImpulseBody1), - angularImpulseBody1(initAngularImpulseBody1), - linearImpulseBody2(initLinearImpulseBody2), - angularImpulseBody2(initAngularImpulseBody2) { - - } - - /// Copy-constructor - Impulse(const Impulse& impulse) - : linearImpulseBody1(impulse.linearImpulseBody1), - angularImpulseBody1(impulse.angularImpulseBody1), - linearImpulseBody2(impulse.linearImpulseBody2), - angularImpulseBody2(impulse.angularImpulseBody2) { - - } - - /// Deleted assignment operator - Impulse& operator=(const Impulse& impulse) = delete; -}; - -} - -#endif From d04cee7d0ae1e8b00da8d700bd11712211f2b17f Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 16 Oct 2016 15:40:38 +0200 Subject: [PATCH 036/248] Change the way to iterate over contacts --- src/engine/ContactSolver.cpp | 561 ++++++++++++++++++----------------- src/engine/ContactSolver.h | 25 +- src/engine/DynamicsWorld.cpp | 49 +-- 3 files changed, 339 insertions(+), 296 deletions(-) diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index d02c773d..b4e28aaa 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -36,7 +36,7 @@ using namespace std; // Constants initialization const decimal ContactSolver::BETA = decimal(0.2); const decimal ContactSolver::BETA_SPLIT_IMPULSE = decimal(0.2); -const decimal ContactSolver::SLOP= decimal(0.01); +const decimal ContactSolver::SLOP = decimal(0.01); // Constructor ContactSolver::ContactSolver(const std::map& mapBodyToVelocityIndex, @@ -49,8 +49,54 @@ ContactSolver::ContactSolver(const std::map& mapBodyToVelocity } +// Initialize the contact constraints +void ContactSolver::init(Island** islands, uint nbIslands, decimal timeStep) { + + PROFILE("ContactSolver::init()"); + + mTimeStep = timeStep; + + // TODO : Try not to count manifolds and contact points here + uint nbContactManifolds = 0; + uint nbContactPoints = 0; + for (uint i = 0; i < nbIslands; i++) { + uint nbManifoldsInIsland = islands[i]->getNbContactManifolds(); + nbContactManifolds += nbManifoldsInIsland; + + for (uint j=0; j < nbManifoldsInIsland; j++) { + nbContactPoints += islands[i]->getContactManifolds()[j]->getNbContactPoints(); + } + } + + mNbContactManifolds = 0; + mNbContactPoints = 0; + + mContactConstraints = nullptr; + mContactPoints = nullptr; + + if (nbContactManifolds == 0 || nbContactPoints == 0) return; + + // TODO : Count exactly the number of constraints to allocate here + mContactPoints = static_cast(mSingleFrameAllocator.allocate(sizeof(ContactPointSolver) * nbContactPoints)); + assert(mContactPoints != nullptr); + + mContactConstraints = static_cast(mSingleFrameAllocator.allocate(sizeof(ContactManifoldSolver) * nbContactManifolds)); + assert(mContactConstraints != nullptr); + + // For each island of the world + for (uint islandIndex = 0; islandIndex < nbIslands; islandIndex++) { + + if (islands[islandIndex]->getNbContactManifolds() > 0) { + initializeForIsland(islands[islandIndex]); + } + } + + // Warmstarting + warmStart(); +} + // Initialize the constraint solver for a given island -void ContactSolver::initializeForIsland(decimal dt, Island* island) { +void ContactSolver::initializeForIsland(Island* island) { PROFILE("ContactSolver::initializeForIsland()"); @@ -60,22 +106,12 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { assert(mSplitLinearVelocities != nullptr); assert(mSplitAngularVelocities != nullptr); - // Set the current time step - mTimeStep = dt; - - mNbContactManifolds = island->getNbContactManifolds(); - - mContactConstraints = new ContactManifoldSolver[mNbContactManifolds]; - assert(mContactConstraints != nullptr); - // For each contact manifold of the island ContactManifold** contactManifolds = island->getContactManifolds(); - for (uint i=0; igetNbContactManifolds(); i++) { ContactManifold* externalManifold = contactManifolds[i]; - ContactManifoldSolver& internalManifold = mContactConstraints[i]; - assert(externalManifold->getNbContactPoints() > 0); // Get the two bodies of the contact @@ -90,34 +126,33 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { // Initialize the internal contact manifold structure using the external // contact manifold - internalManifold.indexBody1 = mMapBodyToConstrainedVelocityIndex.find(body1)->second; - internalManifold.indexBody2 = mMapBodyToConstrainedVelocityIndex.find(body2)->second; - internalManifold.inverseInertiaTensorBody1 = body1->getInertiaTensorInverseWorld(); - internalManifold.inverseInertiaTensorBody2 = body2->getInertiaTensorInverseWorld(); - internalManifold.massInverseBody1 = body1->mMassInverse; - internalManifold.massInverseBody2 = body2->mMassInverse; - internalManifold.nbContacts = externalManifold->getNbContactPoints(); - internalManifold.restitutionFactor = computeMixedRestitutionFactor(body1, body2); - internalManifold.frictionCoefficient = computeMixedFrictionCoefficient(body1, body2); - internalManifold.rollingResistanceFactor = computeMixedRollingResistance(body1, body2); - internalManifold.externalContactManifold = externalManifold; - internalManifold.isBody1DynamicType = body1->getType() == BodyType::DYNAMIC; - internalManifold.isBody2DynamicType = body2->getType() == BodyType::DYNAMIC; - internalManifold.normal.setToZero(); - internalManifold.frictionPointBody1 = Vector3::zero(); - internalManifold.frictionPointBody2 = Vector3::zero(); + new (mContactConstraints + mNbContactManifolds) ContactManifoldSolver(); + mContactConstraints[mNbContactManifolds].indexBody1 = mMapBodyToConstrainedVelocityIndex.find(body1)->second; + mContactConstraints[mNbContactManifolds].indexBody2 = mMapBodyToConstrainedVelocityIndex.find(body2)->second; + mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody1 = body1->getInertiaTensorInverseWorld(); + mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody2 = body2->getInertiaTensorInverseWorld(); + mContactConstraints[mNbContactManifolds].massInverseBody1 = body1->mMassInverse; + mContactConstraints[mNbContactManifolds].massInverseBody2 = body2->mMassInverse; + mContactConstraints[mNbContactManifolds].nbContacts = externalManifold->getNbContactPoints(); + mContactConstraints[mNbContactManifolds].restitutionFactor = computeMixedRestitutionFactor(body1, body2); + mContactConstraints[mNbContactManifolds].frictionCoefficient = computeMixedFrictionCoefficient(body1, body2); + mContactConstraints[mNbContactManifolds].rollingResistanceFactor = computeMixedRollingResistance(body1, body2); + mContactConstraints[mNbContactManifolds].externalContactManifold = externalManifold; + mContactConstraints[mNbContactManifolds].isBody1DynamicType = body1->getType() == BodyType::DYNAMIC; + mContactConstraints[mNbContactManifolds].isBody2DynamicType = body2->getType() == BodyType::DYNAMIC; + mContactConstraints[mNbContactManifolds].normal.setToZero(); + mContactConstraints[mNbContactManifolds].frictionPointBody1 = Vector3::zero(); + mContactConstraints[mNbContactManifolds].frictionPointBody2 = Vector3::zero(); // Get the velocities of the bodies - const Vector3& v1 = mLinearVelocities[internalManifold.indexBody1]; - const Vector3& w1 = mAngularVelocities[internalManifold.indexBody1]; - const Vector3& v2 = mLinearVelocities[internalManifold.indexBody2]; - const Vector3& w2 = mAngularVelocities[internalManifold.indexBody2]; + const Vector3& v1 = mLinearVelocities[mContactConstraints[mNbContactManifolds].indexBody1]; + const Vector3& w1 = mAngularVelocities[mContactConstraints[mNbContactManifolds].indexBody1]; + const Vector3& v2 = mLinearVelocities[mContactConstraints[mNbContactManifolds].indexBody2]; + const Vector3& w2 = mAngularVelocities[mContactConstraints[mNbContactManifolds].indexBody2]; // For each contact point of the contact manifold for (uint c=0; cgetNbContactPoints(); c++) { - ContactPointSolver& contactPoint = internalManifold.contacts[c]; - // Get a contact point ContactPoint* externalContact = externalManifold->getContactPoint(c); @@ -125,100 +160,104 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { Vector3 p1 = externalContact->getWorldPointOnBody1(); Vector3 p2 = externalContact->getWorldPointOnBody2(); - contactPoint.externalContact = externalContact; - contactPoint.normal = externalContact->getNormal(); - contactPoint.r1 = p1 - x1; - contactPoint.r2 = p2 - x2; - contactPoint.penetrationDepth = externalContact->getPenetrationDepth(); - contactPoint.isRestingContact = externalContact->getIsRestingContact(); + new (mContactPoints + mNbContactPoints) ContactPointSolver(); + mContactPoints[mNbContactPoints].externalContact = externalContact; + mContactPoints[mNbContactPoints].normal = externalContact->getNormal(); + mContactPoints[mNbContactPoints].r1 = p1 - x1; + mContactPoints[mNbContactPoints].r2 = p2 - x2; + mContactPoints[mNbContactPoints].penetrationDepth = externalContact->getPenetrationDepth(); + mContactPoints[mNbContactPoints].isRestingContact = externalContact->getIsRestingContact(); externalContact->setIsRestingContact(true); - contactPoint.oldFrictionVector1 = externalContact->getFrictionVector1(); - contactPoint.oldFrictionVector2 = externalContact->getFrictionVector2(); - contactPoint.penetrationImpulse = externalContact->getPenetrationImpulse(); - contactPoint.penetrationSplitImpulse = 0.0; - contactPoint.friction1Impulse = externalContact->getFrictionImpulse1(); - contactPoint.friction2Impulse = externalContact->getFrictionImpulse2(); - contactPoint.rollingResistanceImpulse = externalContact->getRollingResistanceImpulse(); + mContactPoints[mNbContactPoints].oldFrictionVector1 = externalContact->getFrictionVector1(); + mContactPoints[mNbContactPoints].oldFrictionVector2 = externalContact->getFrictionVector2(); + mContactPoints[mNbContactPoints].penetrationImpulse = externalContact->getPenetrationImpulse(); + mContactPoints[mNbContactPoints].penetrationSplitImpulse = 0.0; + mContactPoints[mNbContactPoints].friction1Impulse = externalContact->getFrictionImpulse1(); + mContactPoints[mNbContactPoints].friction2Impulse = externalContact->getFrictionImpulse2(); + mContactPoints[mNbContactPoints].rollingResistanceImpulse = externalContact->getRollingResistanceImpulse(); - internalManifold.frictionPointBody1 += p1; - internalManifold.frictionPointBody2 += p2; + mContactConstraints[mNbContactManifolds].frictionPointBody1 += p1; + mContactConstraints[mNbContactManifolds].frictionPointBody2 += p2; // Compute the velocity difference - Vector3 deltaV = v2 + w2.cross(contactPoint.r2) - v1 - w1.cross(contactPoint.r1); + Vector3 deltaV = v2 + w2.cross(mContactPoints[mNbContactPoints].r2) - v1 - w1.cross(mContactPoints[mNbContactPoints].r1); - contactPoint.r1CrossN = contactPoint.r1.cross(contactPoint.normal); - contactPoint.r2CrossN = contactPoint.r2.cross(contactPoint.normal); + mContactPoints[mNbContactPoints].r1CrossN = mContactPoints[mNbContactPoints].r1.cross(mContactPoints[mNbContactPoints].normal); + mContactPoints[mNbContactPoints].r2CrossN = mContactPoints[mNbContactPoints].r2.cross(mContactPoints[mNbContactPoints].normal); // Compute the inverse mass matrix K for the penetration constraint - decimal massPenetration = internalManifold.massInverseBody1 + internalManifold.massInverseBody2 + - ((internalManifold.inverseInertiaTensorBody1 * contactPoint.r1CrossN).cross(contactPoint.r1)).dot(contactPoint.normal) + - ((internalManifold.inverseInertiaTensorBody2 * contactPoint.r2CrossN).cross(contactPoint.r2)).dot(contactPoint.normal); - contactPoint.inversePenetrationMass = massPenetration > decimal(0.0) ? decimal(1.0) / massPenetration : decimal(0.0); + decimal massPenetration = mContactConstraints[mNbContactManifolds].massInverseBody1 + mContactConstraints[mNbContactManifolds].massInverseBody2 + + ((mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody1 * mContactPoints[mNbContactPoints].r1CrossN).cross(mContactPoints[mNbContactPoints].r1)).dot(mContactPoints[mNbContactPoints].normal) + + ((mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody2 * mContactPoints[mNbContactPoints].r2CrossN).cross(mContactPoints[mNbContactPoints].r2)).dot(mContactPoints[mNbContactPoints].normal); + mContactPoints[mNbContactPoints].inversePenetrationMass = massPenetration > decimal(0.0) ? decimal(1.0) / massPenetration : decimal(0.0); // Compute the restitution velocity bias "b". We compute this here instead // of inside the solve() method because we need to use the velocity difference // at the beginning of the contact. Note that if it is a resting contact (normal // velocity bellow a given threshold), we do not add a restitution velocity bias - contactPoint.restitutionBias = 0.0; - decimal deltaVDotN = deltaV.dot(contactPoint.normal); + mContactPoints[mNbContactPoints].restitutionBias = 0.0; + decimal deltaVDotN = deltaV.dot(mContactPoints[mNbContactPoints].normal); if (deltaVDotN < -RESTITUTION_VELOCITY_THRESHOLD) { - contactPoint.restitutionBias = internalManifold.restitutionFactor * deltaVDotN; + mContactPoints[mNbContactPoints].restitutionBias = mContactConstraints[mNbContactManifolds].restitutionFactor * deltaVDotN; } - internalManifold.normal += contactPoint.normal; + mContactConstraints[mNbContactManifolds].normal += mContactPoints[mNbContactPoints].normal; + + mNbContactPoints++; } - - internalManifold.frictionPointBody1 /=static_cast(internalManifold.nbContacts); - internalManifold.frictionPointBody2 /=static_cast(internalManifold.nbContacts); - internalManifold.r1Friction = internalManifold.frictionPointBody1 - x1; - internalManifold.r2Friction = internalManifold.frictionPointBody2 - x2; - internalManifold.oldFrictionVector1 = externalManifold->getFrictionVector1(); - internalManifold.oldFrictionVector2 = externalManifold->getFrictionVector2(); + mContactConstraints[mNbContactManifolds].frictionPointBody1 /=static_cast(mContactConstraints[mNbContactManifolds].nbContacts); + mContactConstraints[mNbContactManifolds].frictionPointBody2 /=static_cast(mContactConstraints[mNbContactManifolds].nbContacts); + mContactConstraints[mNbContactManifolds].r1Friction = mContactConstraints[mNbContactManifolds].frictionPointBody1 - x1; + mContactConstraints[mNbContactManifolds].r2Friction = mContactConstraints[mNbContactManifolds].frictionPointBody2 - x2; + mContactConstraints[mNbContactManifolds].oldFrictionVector1 = externalManifold->getFrictionVector1(); + mContactConstraints[mNbContactManifolds].oldFrictionVector2 = externalManifold->getFrictionVector2(); // Initialize the accumulated impulses with the previous step accumulated impulses - internalManifold.friction1Impulse = externalManifold->getFrictionImpulse1(); - internalManifold.friction2Impulse = externalManifold->getFrictionImpulse2(); - internalManifold.frictionTwistImpulse = externalManifold->getFrictionTwistImpulse(); + mContactConstraints[mNbContactManifolds].friction1Impulse = externalManifold->getFrictionImpulse1(); + mContactConstraints[mNbContactManifolds].friction2Impulse = externalManifold->getFrictionImpulse2(); + mContactConstraints[mNbContactManifolds].frictionTwistImpulse = externalManifold->getFrictionTwistImpulse(); // Compute the inverse K matrix for the rolling resistance constraint - internalManifold.inverseRollingResistance.setToZero(); - if (internalManifold.rollingResistanceFactor > 0 && (internalManifold.isBody1DynamicType || internalManifold.isBody2DynamicType)) { - internalManifold.inverseRollingResistance = internalManifold.inverseInertiaTensorBody1 + internalManifold.inverseInertiaTensorBody2; - internalManifold.inverseRollingResistance = internalManifold.inverseRollingResistance.getInverse(); + mContactConstraints[mNbContactManifolds].inverseRollingResistance.setToZero(); + if (mContactConstraints[mNbContactManifolds].rollingResistanceFactor > 0 && (mContactConstraints[mNbContactManifolds].isBody1DynamicType || mContactConstraints[mNbContactManifolds].isBody2DynamicType)) { + mContactConstraints[mNbContactManifolds].inverseRollingResistance = mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody1 + mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody2; + mContactConstraints[mNbContactManifolds].inverseRollingResistance = mContactConstraints[mNbContactManifolds].inverseRollingResistance.getInverse(); } - internalManifold.normal.normalize(); + mContactConstraints[mNbContactManifolds].normal.normalize(); - Vector3 deltaVFrictionPoint = v2 + w2.cross(internalManifold.r2Friction) - - v1 - w1.cross(internalManifold.r1Friction); + Vector3 deltaVFrictionPoint = v2 + w2.cross(mContactConstraints[mNbContactManifolds].r2Friction) - + v1 - w1.cross(mContactConstraints[mNbContactManifolds].r1Friction); // Compute the friction vectors - computeFrictionVectors(deltaVFrictionPoint, internalManifold); + computeFrictionVectors(deltaVFrictionPoint, mContactConstraints[mNbContactManifolds]); // Compute the inverse mass matrix K for the friction constraints at the center of // the contact manifold - internalManifold.r1CrossT1 = internalManifold.r1Friction.cross(internalManifold.frictionVector1); - internalManifold.r1CrossT2 = internalManifold.r1Friction.cross(internalManifold.frictionVector2); - internalManifold.r2CrossT1 = internalManifold.r2Friction.cross(internalManifold.frictionVector1); - internalManifold.r2CrossT2 = internalManifold.r2Friction.cross(internalManifold.frictionVector2); - decimal friction1Mass = internalManifold.massInverseBody1 + internalManifold.massInverseBody2 + - ((internalManifold.inverseInertiaTensorBody1 * internalManifold.r1CrossT1).cross(internalManifold.r1Friction)).dot( - internalManifold.frictionVector1) + - ((internalManifold.inverseInertiaTensorBody2 * internalManifold.r2CrossT1).cross(internalManifold.r2Friction)).dot( - internalManifold.frictionVector1); - decimal friction2Mass = internalManifold.massInverseBody1 + internalManifold.massInverseBody2 + - ((internalManifold.inverseInertiaTensorBody1 * internalManifold.r1CrossT2).cross(internalManifold.r1Friction)).dot( - internalManifold.frictionVector2) + - ((internalManifold.inverseInertiaTensorBody2 * internalManifold.r2CrossT2).cross(internalManifold.r2Friction)).dot( - internalManifold.frictionVector2); - decimal frictionTwistMass = internalManifold.normal.dot(internalManifold.inverseInertiaTensorBody1 * - internalManifold.normal) + - internalManifold.normal.dot(internalManifold.inverseInertiaTensorBody2 * - internalManifold.normal); - internalManifold.inverseFriction1Mass = friction1Mass > decimal(0.0) ? decimal(1.0) / friction1Mass : decimal(0.0); - internalManifold.inverseFriction2Mass = friction2Mass > decimal(0.0) ? decimal(1.0) / friction2Mass : decimal(0.0); - internalManifold.inverseTwistFrictionMass = frictionTwistMass > decimal(0.0) ? decimal(1.0) / frictionTwistMass : decimal(0.0); + mContactConstraints[mNbContactManifolds].r1CrossT1 = mContactConstraints[mNbContactManifolds].r1Friction.cross(mContactConstraints[mNbContactManifolds].frictionVector1); + mContactConstraints[mNbContactManifolds].r1CrossT2 = mContactConstraints[mNbContactManifolds].r1Friction.cross(mContactConstraints[mNbContactManifolds].frictionVector2); + mContactConstraints[mNbContactManifolds].r2CrossT1 = mContactConstraints[mNbContactManifolds].r2Friction.cross(mContactConstraints[mNbContactManifolds].frictionVector1); + mContactConstraints[mNbContactManifolds].r2CrossT2 = mContactConstraints[mNbContactManifolds].r2Friction.cross(mContactConstraints[mNbContactManifolds].frictionVector2); + decimal friction1Mass = mContactConstraints[mNbContactManifolds].massInverseBody1 + mContactConstraints[mNbContactManifolds].massInverseBody2 + + ((mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody1 * mContactConstraints[mNbContactManifolds].r1CrossT1).cross(mContactConstraints[mNbContactManifolds].r1Friction)).dot( + mContactConstraints[mNbContactManifolds].frictionVector1) + + ((mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody2 * mContactConstraints[mNbContactManifolds].r2CrossT1).cross(mContactConstraints[mNbContactManifolds].r2Friction)).dot( + mContactConstraints[mNbContactManifolds].frictionVector1); + decimal friction2Mass = mContactConstraints[mNbContactManifolds].massInverseBody1 + mContactConstraints[mNbContactManifolds].massInverseBody2 + + ((mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody1 * mContactConstraints[mNbContactManifolds].r1CrossT2).cross(mContactConstraints[mNbContactManifolds].r1Friction)).dot( + mContactConstraints[mNbContactManifolds].frictionVector2) + + ((mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody2 * mContactConstraints[mNbContactManifolds].r2CrossT2).cross(mContactConstraints[mNbContactManifolds].r2Friction)).dot( + mContactConstraints[mNbContactManifolds].frictionVector2); + decimal frictionTwistMass = mContactConstraints[mNbContactManifolds].normal.dot(mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody1 * + mContactConstraints[mNbContactManifolds].normal) + + mContactConstraints[mNbContactManifolds].normal.dot(mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody2 * + mContactConstraints[mNbContactManifolds].normal); + mContactConstraints[mNbContactManifolds].inverseFriction1Mass = friction1Mass > decimal(0.0) ? decimal(1.0) / friction1Mass : decimal(0.0); + mContactConstraints[mNbContactManifolds].inverseFriction2Mass = friction2Mass > decimal(0.0) ? decimal(1.0) / friction2Mass : decimal(0.0); + mContactConstraints[mNbContactManifolds].inverseTwistFrictionMass = frictionTwistMass > decimal(0.0) ? decimal(1.0) / frictionTwistMass : decimal(0.0); + + mNbContactManifolds++; } } @@ -228,41 +267,41 @@ void ContactSolver::initializeForIsland(decimal dt, Island* island) { /// the solution of the linear system void ContactSolver::warmStart() { + uint contactPointIndex = 0; + // For each constraint for (uint c=0; c SLOP) biasPenetrationDepth = -(beta/mTimeStep) * - max(0.0f, float(contactPoint.penetrationDepth - SLOP)); - decimal b = biasPenetrationDepth + contactPoint.restitutionBias; + if (mContactPoints[contactPointIndex].penetrationDepth > SLOP) biasPenetrationDepth = -(beta/mTimeStep) * + max(0.0f, float(mContactPoints[contactPointIndex].penetrationDepth - SLOP)); + decimal b = biasPenetrationDepth + mContactPoints[contactPointIndex].restitutionBias; // Compute the Lagrange multiplier lambda if (mIsSplitImpulseActive) { - deltaLambda = - (Jv + contactPoint.restitutionBias) * - contactPoint.inversePenetrationMass; + deltaLambda = - (Jv + mContactPoints[contactPointIndex].restitutionBias) * + mContactPoints[contactPointIndex].inversePenetrationMass; } else { - deltaLambda = - (Jv + b) * contactPoint.inversePenetrationMass; + deltaLambda = - (Jv + b) * mContactPoints[contactPointIndex].inversePenetrationMass; } - lambdaTemp = contactPoint.penetrationImpulse; - contactPoint.penetrationImpulse = std::max(contactPoint.penetrationImpulse + + lambdaTemp = mContactPoints[contactPointIndex].penetrationImpulse; + mContactPoints[contactPointIndex].penetrationImpulse = std::max(mContactPoints[contactPointIndex].penetrationImpulse + deltaLambda, decimal(0.0)); - deltaLambda = contactPoint.penetrationImpulse - lambdaTemp; + deltaLambda = mContactPoints[contactPointIndex].penetrationImpulse - lambdaTemp; - Vector3 linearImpulse = contactPoint.normal * deltaLambda; + Vector3 linearImpulse = mContactPoints[contactPointIndex].normal * deltaLambda; // Update the velocities of the body 1 by applying the impulse P - mLinearVelocities[contactManifold.indexBody1] += contactManifold.massInverseBody1 * (-linearImpulse); - mAngularVelocities[contactManifold.indexBody1] += contactManifold.inverseInertiaTensorBody1 * (-contactPoint.r1CrossN * deltaLambda); + mLinearVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].massInverseBody1 * (-linearImpulse); + mAngularVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].inverseInertiaTensorBody1 * (-mContactPoints[contactPointIndex].r1CrossN * deltaLambda); // Update the velocities of the body 2 by applying the impulse P - mLinearVelocities[contactManifold.indexBody2] += contactManifold.massInverseBody2 * linearImpulse; - mAngularVelocities[contactManifold.indexBody2] += contactManifold.inverseInertiaTensorBody2 * (contactPoint.r2CrossN * deltaLambda); + mLinearVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].massInverseBody2 * linearImpulse; + mAngularVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].inverseInertiaTensorBody2 * (mContactPoints[contactPointIndex].r2CrossN * deltaLambda); - sumPenetrationImpulse += contactPoint.penetrationImpulse; + sumPenetrationImpulse += mContactPoints[contactPointIndex].penetrationImpulse; // If the split impulse position correction is active if (mIsSplitImpulseActive) { // Split impulse (position correction) - const Vector3& v1Split = mSplitLinearVelocities[contactManifold.indexBody1]; - const Vector3& w1Split = mSplitAngularVelocities[contactManifold.indexBody1]; - const Vector3& v2Split = mSplitLinearVelocities[contactManifold.indexBody2]; - const Vector3& w2Split = mSplitAngularVelocities[contactManifold.indexBody2]; - Vector3 deltaVSplit = v2Split + w2Split.cross(contactPoint.r2) - - v1Split - w1Split.cross(contactPoint.r1); - decimal JvSplit = deltaVSplit.dot(contactPoint.normal); + const Vector3& v1Split = mSplitLinearVelocities[mContactConstraints[c].indexBody1]; + const Vector3& w1Split = mSplitAngularVelocities[mContactConstraints[c].indexBody1]; + const Vector3& v2Split = mSplitLinearVelocities[mContactConstraints[c].indexBody2]; + const Vector3& w2Split = mSplitAngularVelocities[mContactConstraints[c].indexBody2]; + Vector3 deltaVSplit = v2Split + w2Split.cross(mContactPoints[contactPointIndex].r2) - + v1Split - w1Split.cross(mContactPoints[contactPointIndex].r1); + decimal JvSplit = deltaVSplit.dot(mContactPoints[contactPointIndex].normal); decimal deltaLambdaSplit = - (JvSplit + biasPenetrationDepth) * - contactPoint.inversePenetrationMass; - decimal lambdaTempSplit = contactPoint.penetrationSplitImpulse; - contactPoint.penetrationSplitImpulse = std::max( - contactPoint.penetrationSplitImpulse + + mContactPoints[contactPointIndex].inversePenetrationMass; + decimal lambdaTempSplit = mContactPoints[contactPointIndex].penetrationSplitImpulse; + mContactPoints[contactPointIndex].penetrationSplitImpulse = std::max( + mContactPoints[contactPointIndex].penetrationSplitImpulse + deltaLambdaSplit, decimal(0.0)); - deltaLambdaSplit = contactPoint.penetrationSplitImpulse - lambdaTempSplit; + deltaLambdaSplit = mContactPoints[contactPointIndex].penetrationSplitImpulse - lambdaTempSplit; - Vector3 linearImpulse = contactPoint.normal * deltaLambdaSplit; + Vector3 linearImpulse = mContactPoints[contactPointIndex].normal * deltaLambdaSplit; // Update the velocities of the body 1 by applying the impulse P - mSplitLinearVelocities[contactManifold.indexBody1] += contactManifold.massInverseBody1 * (-linearImpulse); - mSplitAngularVelocities[contactManifold.indexBody1] += contactManifold.inverseInertiaTensorBody1 * - (-contactPoint.r1CrossN * deltaLambdaSplit); + mSplitLinearVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].massInverseBody1 * (-linearImpulse); + mSplitAngularVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].inverseInertiaTensorBody1 * + (-mContactPoints[contactPointIndex].r1CrossN * deltaLambdaSplit); // Update the velocities of the body 1 by applying the impulse P - mSplitLinearVelocities[contactManifold.indexBody2] += contactManifold.massInverseBody2 * linearImpulse; - mSplitAngularVelocities[contactManifold.indexBody2] += contactManifold.inverseInertiaTensorBody2 * - contactPoint.r2CrossN * deltaLambdaSplit; + mSplitLinearVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].massInverseBody2 * linearImpulse; + mSplitAngularVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].inverseInertiaTensorBody2 * + mContactPoints[contactPointIndex].r2CrossN * deltaLambdaSplit; } + + contactPointIndex++; } // ------ First friction constraint at the center of the contact manifol ------ // // Compute J*v - Vector3 deltaV = v2 + w2.cross(contactManifold.r2Friction) - - v1 - w1.cross(contactManifold.r1Friction); - decimal Jv = deltaV.dot(contactManifold.frictionVector1); + Vector3 deltaV = v2 + w2.cross(mContactConstraints[c].r2Friction) + - v1 - w1.cross(mContactConstraints[c].r1Friction); + decimal Jv = deltaV.dot(mContactConstraints[c].frictionVector1); // Compute the Lagrange multiplier lambda - decimal deltaLambda = -Jv * contactManifold.inverseFriction1Mass; - decimal frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; - lambdaTemp = contactManifold.friction1Impulse; - contactManifold.friction1Impulse = std::max(-frictionLimit, - std::min(contactManifold.friction1Impulse + + decimal deltaLambda = -Jv * mContactConstraints[c].inverseFriction1Mass; + decimal frictionLimit = mContactConstraints[c].frictionCoefficient * sumPenetrationImpulse; + lambdaTemp = mContactConstraints[c].friction1Impulse; + mContactConstraints[c].friction1Impulse = std::max(-frictionLimit, + std::min(mContactConstraints[c].friction1Impulse + deltaLambda, frictionLimit)); - deltaLambda = contactManifold.friction1Impulse - lambdaTemp; + deltaLambda = mContactConstraints[c].friction1Impulse - lambdaTemp; // Compute the impulse P=J^T * lambda - Vector3 angularImpulseBody1 = -contactManifold.r1CrossT1 * deltaLambda; - Vector3 linearImpulseBody2 = contactManifold.frictionVector1 * deltaLambda; - Vector3 angularImpulseBody2 = contactManifold.r2CrossT1 * deltaLambda; + Vector3 angularImpulseBody1 = -mContactConstraints[c].r1CrossT1 * deltaLambda; + Vector3 linearImpulseBody2 = mContactConstraints[c].frictionVector1 * deltaLambda; + Vector3 angularImpulseBody2 = mContactConstraints[c].r2CrossT1 * deltaLambda; // Update the velocities of the body 1 by applying the impulse P - mLinearVelocities[contactManifold.indexBody1] += contactManifold.massInverseBody1 * (-linearImpulseBody2); - mAngularVelocities[contactManifold.indexBody1] += contactManifold.inverseInertiaTensorBody1 * angularImpulseBody1; + mLinearVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].massInverseBody1 * (-linearImpulseBody2); + mAngularVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].inverseInertiaTensorBody1 * angularImpulseBody1; // Update the velocities of the body 2 by applying the impulse P - mLinearVelocities[contactManifold.indexBody2] += contactManifold.massInverseBody2 * linearImpulseBody2; - mAngularVelocities[contactManifold.indexBody2] += contactManifold.inverseInertiaTensorBody2 * angularImpulseBody2; + mLinearVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].massInverseBody2 * linearImpulseBody2; + mAngularVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].inverseInertiaTensorBody2 * angularImpulseBody2; // ------ Second friction constraint at the center of the contact manifol ----- // // Compute J*v - deltaV = v2 + w2.cross(contactManifold.r2Friction) - v1 - w1.cross(contactManifold.r1Friction); - Jv = deltaV.dot(contactManifold.frictionVector2); + deltaV = v2 + w2.cross(mContactConstraints[c].r2Friction) - v1 - w1.cross(mContactConstraints[c].r1Friction); + Jv = deltaV.dot(mContactConstraints[c].frictionVector2); // Compute the Lagrange multiplier lambda - deltaLambda = -Jv * contactManifold.inverseFriction2Mass; - frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; - lambdaTemp = contactManifold.friction2Impulse; - contactManifold.friction2Impulse = std::max(-frictionLimit, - std::min(contactManifold.friction2Impulse + + deltaLambda = -Jv * mContactConstraints[c].inverseFriction2Mass; + frictionLimit = mContactConstraints[c].frictionCoefficient * sumPenetrationImpulse; + lambdaTemp = mContactConstraints[c].friction2Impulse; + mContactConstraints[c].friction2Impulse = std::max(-frictionLimit, + std::min(mContactConstraints[c].friction2Impulse + deltaLambda, frictionLimit)); - deltaLambda = contactManifold.friction2Impulse - lambdaTemp; + deltaLambda = mContactConstraints[c].friction2Impulse - lambdaTemp; // Compute the impulse P=J^T * lambda - angularImpulseBody1 = -contactManifold.r1CrossT2 * deltaLambda; - linearImpulseBody2 = contactManifold.frictionVector2 * deltaLambda; - angularImpulseBody2 = contactManifold.r2CrossT2 * deltaLambda; + angularImpulseBody1 = -mContactConstraints[c].r1CrossT2 * deltaLambda; + linearImpulseBody2 = mContactConstraints[c].frictionVector2 * deltaLambda; + angularImpulseBody2 = mContactConstraints[c].r2CrossT2 * deltaLambda; // Update the velocities of the body 1 by applying the impulse P - mLinearVelocities[contactManifold.indexBody1] += contactManifold.massInverseBody1 * (-linearImpulseBody2); - mAngularVelocities[contactManifold.indexBody1] += contactManifold.inverseInertiaTensorBody1 * angularImpulseBody1; + mLinearVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].massInverseBody1 * (-linearImpulseBody2); + mAngularVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].inverseInertiaTensorBody1 * angularImpulseBody1; // Update the velocities of the body 2 by applying the impulse P - mLinearVelocities[contactManifold.indexBody2] += contactManifold.massInverseBody2 * linearImpulseBody2; - mAngularVelocities[contactManifold.indexBody2] += contactManifold.inverseInertiaTensorBody2 * angularImpulseBody2; + mLinearVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].massInverseBody2 * linearImpulseBody2; + mAngularVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].inverseInertiaTensorBody2 * angularImpulseBody2; // ------ Twist friction constraint at the center of the contact manifol ------ // // Compute J*v deltaV = w2 - w1; - Jv = deltaV.dot(contactManifold.normal); + Jv = deltaV.dot(mContactConstraints[c].normal); - deltaLambda = -Jv * (contactManifold.inverseTwistFrictionMass); - frictionLimit = contactManifold.frictionCoefficient * sumPenetrationImpulse; - lambdaTemp = contactManifold.frictionTwistImpulse; - contactManifold.frictionTwistImpulse = std::max(-frictionLimit, - std::min(contactManifold.frictionTwistImpulse + deltaLambda = -Jv * (mContactConstraints[c].inverseTwistFrictionMass); + frictionLimit = mContactConstraints[c].frictionCoefficient * sumPenetrationImpulse; + lambdaTemp = mContactConstraints[c].frictionTwistImpulse; + mContactConstraints[c].frictionTwistImpulse = std::max(-frictionLimit, + std::min(mContactConstraints[c].frictionTwistImpulse + deltaLambda, frictionLimit)); - deltaLambda = contactManifold.frictionTwistImpulse - lambdaTemp; + deltaLambda = mContactConstraints[c].frictionTwistImpulse - lambdaTemp; // Compute the impulse P=J^T * lambda - angularImpulseBody2 = contactManifold.normal * deltaLambda; + angularImpulseBody2 = mContactConstraints[c].normal * deltaLambda; // Update the velocities of the body 1 by applying the impulse P - mAngularVelocities[contactManifold.indexBody1] += contactManifold.inverseInertiaTensorBody1 * (-angularImpulseBody2); + mAngularVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].inverseInertiaTensorBody1 * (-angularImpulseBody2); // Update the velocities of the body 1 by applying the impulse P - mAngularVelocities[contactManifold.indexBody2] += contactManifold.inverseInertiaTensorBody2 * angularImpulseBody2; + mAngularVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].inverseInertiaTensorBody2 * angularImpulseBody2; // --------- Rolling resistance constraint at the center of the contact manifold --------- // - if (contactManifold.rollingResistanceFactor > 0) { + if (mContactConstraints[c].rollingResistanceFactor > 0) { // Compute J*v const Vector3 JvRolling = w2 - w1; // Compute the Lagrange multiplier lambda - Vector3 deltaLambdaRolling = contactManifold.inverseRollingResistance * (-JvRolling); - decimal rollingLimit = contactManifold.rollingResistanceFactor * sumPenetrationImpulse; - Vector3 lambdaTempRolling = contactManifold.rollingResistanceImpulse; - contactManifold.rollingResistanceImpulse = clamp(contactManifold.rollingResistanceImpulse + + Vector3 deltaLambdaRolling = mContactConstraints[c].inverseRollingResistance * (-JvRolling); + decimal rollingLimit = mContactConstraints[c].rollingResistanceFactor * sumPenetrationImpulse; + Vector3 lambdaTempRolling = mContactConstraints[c].rollingResistanceImpulse; + mContactConstraints[c].rollingResistanceImpulse = clamp(mContactConstraints[c].rollingResistanceImpulse + deltaLambdaRolling, rollingLimit); - deltaLambdaRolling = contactManifold.rollingResistanceImpulse - lambdaTempRolling; + deltaLambdaRolling = mContactConstraints[c].rollingResistanceImpulse - lambdaTempRolling; // Update the velocities of the body 1 by applying the impulse P - mAngularVelocities[contactManifold.indexBody1] += contactManifold.inverseInertiaTensorBody1 * (-deltaLambdaRolling); + mAngularVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].inverseInertiaTensorBody1 * (-deltaLambdaRolling); // Update the velocities of the body 2 by applying the impulse P - mAngularVelocities[contactManifold.indexBody2] += contactManifold.inverseInertiaTensorBody2 * deltaLambdaRolling; + mAngularVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].inverseInertiaTensorBody2 * deltaLambdaRolling; } } } @@ -548,30 +586,30 @@ void ContactSolver::solve() { // warm start the solver at the next iteration void ContactSolver::storeImpulses() { + uint contactPointIndex = 0; + // For each contact manifold for (uint c=0; csetPenetrationImpulse(mContactPoints[contactPointIndex].penetrationImpulse); + mContactPoints[contactPointIndex].externalContact->setFrictionImpulse1(mContactPoints[contactPointIndex].friction1Impulse); + mContactPoints[contactPointIndex].externalContact->setFrictionImpulse2(mContactPoints[contactPointIndex].friction2Impulse); + mContactPoints[contactPointIndex].externalContact->setRollingResistanceImpulse(mContactPoints[contactPointIndex].rollingResistanceImpulse); - ContactPointSolver& contactPoint = manifold.contacts[i]; + mContactPoints[contactPointIndex].externalContact->setFrictionVector1(mContactPoints[contactPointIndex].frictionVector1); + mContactPoints[contactPointIndex].externalContact->setFrictionVector2(mContactPoints[contactPointIndex].frictionVector2); - contactPoint.externalContact->setPenetrationImpulse(contactPoint.penetrationImpulse); - contactPoint.externalContact->setFrictionImpulse1(contactPoint.friction1Impulse); - contactPoint.externalContact->setFrictionImpulse2(contactPoint.friction2Impulse); - contactPoint.externalContact->setRollingResistanceImpulse(contactPoint.rollingResistanceImpulse); - - contactPoint.externalContact->setFrictionVector1(contactPoint.frictionVector1); - contactPoint.externalContact->setFrictionVector2(contactPoint.frictionVector2); + contactPointIndex++; } - manifold.externalContactManifold->setFrictionImpulse1(manifold.friction1Impulse); - manifold.externalContactManifold->setFrictionImpulse2(manifold.friction2Impulse); - manifold.externalContactManifold->setFrictionTwistImpulse(manifold.frictionTwistImpulse); - manifold.externalContactManifold->setRollingResistanceImpulse(manifold.rollingResistanceImpulse); - manifold.externalContactManifold->setFrictionVector1(manifold.frictionVector1); - manifold.externalContactManifold->setFrictionVector2(manifold.frictionVector2); + mContactConstraints[c].externalContactManifold->setFrictionImpulse1(mContactConstraints[c].friction1Impulse); + mContactConstraints[c].externalContactManifold->setFrictionImpulse2(mContactConstraints[c].friction2Impulse); + mContactConstraints[c].externalContactManifold->setFrictionTwistImpulse(mContactConstraints[c].frictionTwistImpulse); + mContactConstraints[c].externalContactManifold->setRollingResistanceImpulse(mContactConstraints[c].rollingResistanceImpulse); + mContactConstraints[c].externalContactManifold->setFrictionVector1(mContactConstraints[c].frictionVector1); + mContactConstraints[c].externalContactManifold->setFrictionVector2(mContactConstraints[c].frictionVector2); } } @@ -634,12 +672,3 @@ void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, // friction vector and the contact normal contact.frictionVector2 = contact.normal.cross(contact.frictionVector1).getUnit(); } - -// Clean up the constraint solver -void ContactSolver::cleanup() { - - if (mContactConstraints != nullptr) { - delete[] mContactConstraints; - mContactConstraints = nullptr; - } -} diff --git a/src/engine/ContactSolver.h b/src/engine/ContactSolver.h index 02a3c390..e4e2710e 100644 --- a/src/engine/ContactSolver.h +++ b/src/engine/ContactSolver.h @@ -220,11 +220,8 @@ class ContactSolver { /// Inverse inertia tensor of body 2 Matrix3x3 inverseInertiaTensorBody2; - /// Contact point constraints - ContactPointSolver contacts[MAX_CONTACT_POINTS_IN_MANIFOLD]; - /// Number of contact points - uint nbContacts; + short int nbContacts; /// True if the body 1 is of type dynamic bool isBody1DynamicType; @@ -335,6 +332,12 @@ class ContactSolver { /// Contact constraints ContactManifoldSolver* mContactConstraints; + /// Contact points + ContactPointSolver* mContactPoints; + + /// Number of contact point constraints + uint mNbContactPoints; + /// Number of contact constraints uint mNbContactManifolds; @@ -378,6 +381,9 @@ class ContactSolver { void computeFrictionVectors(const Vector3& deltaVelocity, ContactManifoldSolver& contactPoint) const; + /// Warm start the solver. + void warmStart(); + public: // -------------------- Methods -------------------- // @@ -389,8 +395,11 @@ class ContactSolver { /// Destructor ~ContactSolver() = default; + /// Initialize the contact constraints + void init(Island** islands, uint nbIslands, decimal timeStep); + /// Initialize the constraint solver for a given island - void initializeForIsland(decimal dt, Island* island); + void initializeForIsland(Island* island); /// Set the split velocities arrays void setSplitVelocitiesArrays(Vector3* splitLinearVelocities, @@ -400,9 +409,6 @@ class ContactSolver { void setConstrainedVelocitiesArrays(Vector3* constrainedLinearVelocities, Vector3* constrainedAngularVelocities); - /// Warm start the solver. - void warmStart(); - /// Store the computed impulses to use them to /// warm start the solver at the next iteration void storeImpulses(); @@ -415,9 +421,6 @@ class ContactSolver { /// Activate or Deactivate the split impulses for contacts void setIsSplitImpulseActive(bool isActive); - - /// Clean up the constraint solver - void cleanup(); }; // Set the split velocities arrays diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index c40d5ec5..d52348f8 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -342,23 +342,28 @@ void DynamicsWorld::solveContactsAndConstraints() { // ---------- Solve velocity constraints for joints and contacts ---------- // + // Initialize the contact solver + mContactSolver.init(mIslands, mNbIslands, mTimeStep); + // For each island of the world for (uint islandIndex = 0; islandIndex < mNbIslands; islandIndex++) { // Check if there are contacts and constraints to solve bool isConstraintsToSolve = mIslands[islandIndex]->getNbJoints() > 0; - bool isContactsToSolve = mIslands[islandIndex]->getNbContactManifolds() > 0; - if (!isConstraintsToSolve && !isContactsToSolve) continue; + //bool isContactsToSolve = mIslands[islandIndex]->getNbContactManifolds() > 0; + //if (!isConstraintsToSolve && !isContactsToSolve) continue; // If there are contacts in the current island - if (isContactsToSolve) { +// if (isContactsToSolve) { - // Initialize the solver - mContactSolver.initializeForIsland(mTimeStep, mIslands[islandIndex]); +// // Initialize the solver +// mContactSolver.initializeForIsland(mTimeStep, mIslands[islandIndex]); - // Warm start the contact solver - mContactSolver.warmStart(); - } +// // Warm start the contact solver +// if (mContactSolver.IsWarmStartingActive()) { +// mContactSolver.warmStart(); +// } +// } // If there are constraints if (isConstraintsToSolve) { @@ -366,26 +371,32 @@ void DynamicsWorld::solveContactsAndConstraints() { // Initialize the constraint solver mConstraintSolver.initializeForIsland(mTimeStep, mIslands[islandIndex]); } + } - // For each iteration of the velocity solver - for (uint i=0; igetNbJoints() > 0; if (isConstraintsToSolve) { mConstraintSolver.solveVelocityConstraints(mIslands[islandIndex]); } - - // Solve the contacts - if (isContactsToSolve) mContactSolver.solve(); } - // Cache the lambda values in order to use them in the next - // step and cleanup the contact solver - if (isContactsToSolve) { - mContactSolver.storeImpulses(); - mContactSolver.cleanup(); - } + mContactSolver.solve(); + + // Solve the contacts +// if (isContactsToSolve) { + +// mContactSolver.resetTotalPenetrationImpulse(); + +// mContactSolver.solvePenetrationConstraints(); +// mContactSolver.solveFrictionConstraints(); +// } } + + mContactSolver.storeImpulses(); } // Solve the position error correction of the constraints From 81426293e02d441f0bbefde7712955ceb8c93003 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 16 Oct 2016 23:18:42 +0200 Subject: [PATCH 037/248] Remove unused variables in contact solver --- src/constraint/ContactPoint.cpp | 5 +- src/constraint/ContactPoint.h | 92 --------------------------------- src/engine/ContactSolver.cpp | 58 +++------------------ src/engine/ContactSolver.h | 42 ++------------- 4 files changed, 11 insertions(+), 186 deletions(-) diff --git a/src/constraint/ContactPoint.cpp b/src/constraint/ContactPoint.cpp index 3be8476a..c0d567ea 100644 --- a/src/constraint/ContactPoint.cpp +++ b/src/constraint/ContactPoint.cpp @@ -45,9 +45,6 @@ ContactPoint::ContactPoint(const ContactPointInfo& contactInfo) contactInfo.localPoint2), mIsRestingContact(false) { - mFrictionVectors[0] = Vector3(0, 0, 0); - mFrictionVectors[1] = Vector3(0, 0, 0); - - assert(mPenetrationDepth > 0.0); + assert(mPenetrationDepth > decimal(0.0)); } diff --git a/src/constraint/ContactPoint.h b/src/constraint/ContactPoint.h index d2e8f189..18be17b0 100644 --- a/src/constraint/ContactPoint.h +++ b/src/constraint/ContactPoint.h @@ -128,21 +128,9 @@ class ContactPoint { /// True if the contact is a resting contact (exists for more than one time step) bool mIsRestingContact; - /// Two orthogonal vectors that span the tangential friction plane - Vector3 mFrictionVectors[2]; - /// Cached penetration impulse decimal mPenetrationImpulse; - /// Cached first friction impulse - decimal mFrictionImpulse1; - - /// Cached second friction impulse - decimal mFrictionImpulse2; - - /// Cached rolling resistance impulse - Vector3 mRollingResistanceImpulse; - public : // -------------------- Methods -------------------- // @@ -186,27 +174,9 @@ class ContactPoint { /// Return the cached penetration impulse decimal getPenetrationImpulse() const; - /// Return the cached first friction impulse - decimal getFrictionImpulse1() const; - - /// Return the cached second friction impulse - decimal getFrictionImpulse2() const; - - /// Return the cached rolling resistance impulse - Vector3 getRollingResistanceImpulse() const; - /// Set the cached penetration impulse void setPenetrationImpulse(decimal impulse); - /// Set the first cached friction impulse - void setFrictionImpulse1(decimal impulse); - - /// Set the second cached friction impulse - void setFrictionImpulse2(decimal impulse); - - /// Set the cached rolling resistance impulse - void setRollingResistanceImpulse(const Vector3& impulse); - /// Set the contact world point on body 1 void setWorldPointOnBody1(const Vector3& worldPoint); @@ -219,18 +189,6 @@ class ContactPoint { /// Set the mIsRestingContact variable void setIsRestingContact(bool isRestingContact); - /// Get the first friction vector - Vector3 getFrictionVector1() const; - - /// Set the first friction vector - void setFrictionVector1(const Vector3& frictionVector1); - - /// Get the second friction vector - Vector3 getFrictionVector2() const; - - /// Set the second friction vector - void setFrictionVector2(const Vector3& frictionVector2); - /// Return the penetration depth decimal getPenetrationDepth() const; @@ -283,41 +241,11 @@ inline decimal ContactPoint::getPenetrationImpulse() const { return mPenetrationImpulse; } -// Return the cached first friction impulse -inline decimal ContactPoint::getFrictionImpulse1() const { - return mFrictionImpulse1; -} - -// Return the cached second friction impulse -inline decimal ContactPoint::getFrictionImpulse2() const { - return mFrictionImpulse2; -} - -// Return the cached rolling resistance impulse -inline Vector3 ContactPoint::getRollingResistanceImpulse() const { - return mRollingResistanceImpulse; -} - // Set the cached penetration impulse inline void ContactPoint::setPenetrationImpulse(decimal impulse) { mPenetrationImpulse = impulse; } -// Set the first cached friction impulse -inline void ContactPoint::setFrictionImpulse1(decimal impulse) { - mFrictionImpulse1 = impulse; -} - -// Set the second cached friction impulse -inline void ContactPoint::setFrictionImpulse2(decimal impulse) { - mFrictionImpulse2 = impulse; -} - -// Set the cached rolling resistance impulse -inline void ContactPoint::setRollingResistanceImpulse(const Vector3& impulse) { - mRollingResistanceImpulse = impulse; -} - // Set the contact world point on body 1 inline void ContactPoint::setWorldPointOnBody1(const Vector3& worldPoint) { mWorldPointOnBody1 = worldPoint; @@ -338,26 +266,6 @@ inline void ContactPoint::setIsRestingContact(bool isRestingContact) { mIsRestingContact = isRestingContact; } -// Get the first friction vector -inline Vector3 ContactPoint::getFrictionVector1() const { - return mFrictionVectors[0]; -} - -// Set the first friction vector -inline void ContactPoint::setFrictionVector1(const Vector3& frictionVector1) { - mFrictionVectors[0] = frictionVector1; -} - -// Get the second friction vector -inline Vector3 ContactPoint::getFrictionVector2() const { - return mFrictionVectors[1]; -} - -// Set the second friction vector -inline void ContactPoint::setFrictionVector2(const Vector3& frictionVector2) { - mFrictionVectors[1] = frictionVector2; -} - // Return the penetration depth of the contact inline decimal ContactPoint::getPenetrationDepth() const { return mPenetrationDepth; diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index b4e28aaa..34e86472 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -134,15 +134,12 @@ void ContactSolver::initializeForIsland(Island* island) { mContactConstraints[mNbContactManifolds].massInverseBody1 = body1->mMassInverse; mContactConstraints[mNbContactManifolds].massInverseBody2 = body2->mMassInverse; mContactConstraints[mNbContactManifolds].nbContacts = externalManifold->getNbContactPoints(); - mContactConstraints[mNbContactManifolds].restitutionFactor = computeMixedRestitutionFactor(body1, body2); mContactConstraints[mNbContactManifolds].frictionCoefficient = computeMixedFrictionCoefficient(body1, body2); mContactConstraints[mNbContactManifolds].rollingResistanceFactor = computeMixedRollingResistance(body1, body2); mContactConstraints[mNbContactManifolds].externalContactManifold = externalManifold; - mContactConstraints[mNbContactManifolds].isBody1DynamicType = body1->getType() == BodyType::DYNAMIC; - mContactConstraints[mNbContactManifolds].isBody2DynamicType = body2->getType() == BodyType::DYNAMIC; mContactConstraints[mNbContactManifolds].normal.setToZero(); - mContactConstraints[mNbContactManifolds].frictionPointBody1 = Vector3::zero(); - mContactConstraints[mNbContactManifolds].frictionPointBody2 = Vector3::zero(); + mContactConstraints[mNbContactManifolds].frictionPointBody1.setToZero(); + mContactConstraints[mNbContactManifolds].frictionPointBody2.setToZero(); // Get the velocities of the bodies const Vector3& v1 = mLinearVelocities[mContactConstraints[mNbContactManifolds].indexBody1]; @@ -168,13 +165,8 @@ void ContactSolver::initializeForIsland(Island* island) { mContactPoints[mNbContactPoints].penetrationDepth = externalContact->getPenetrationDepth(); mContactPoints[mNbContactPoints].isRestingContact = externalContact->getIsRestingContact(); externalContact->setIsRestingContact(true); - mContactPoints[mNbContactPoints].oldFrictionVector1 = externalContact->getFrictionVector1(); - mContactPoints[mNbContactPoints].oldFrictionVector2 = externalContact->getFrictionVector2(); mContactPoints[mNbContactPoints].penetrationImpulse = externalContact->getPenetrationImpulse(); mContactPoints[mNbContactPoints].penetrationSplitImpulse = 0.0; - mContactPoints[mNbContactPoints].friction1Impulse = externalContact->getFrictionImpulse1(); - mContactPoints[mNbContactPoints].friction2Impulse = externalContact->getFrictionImpulse2(); - mContactPoints[mNbContactPoints].rollingResistanceImpulse = externalContact->getRollingResistanceImpulse(); mContactConstraints[mNbContactManifolds].frictionPointBody1 += p1; mContactConstraints[mNbContactManifolds].frictionPointBody2 += p2; @@ -197,8 +189,9 @@ void ContactSolver::initializeForIsland(Island* island) { // velocity bellow a given threshold), we do not add a restitution velocity bias mContactPoints[mNbContactPoints].restitutionBias = 0.0; decimal deltaVDotN = deltaV.dot(mContactPoints[mNbContactPoints].normal); + const decimal restitutionFactor = computeMixedRestitutionFactor(body1, body2); if (deltaVDotN < -RESTITUTION_VELOCITY_THRESHOLD) { - mContactPoints[mNbContactPoints].restitutionBias = mContactConstraints[mNbContactManifolds].restitutionFactor * deltaVDotN; + mContactPoints[mNbContactPoints].restitutionBias = restitutionFactor * deltaVDotN; } mContactConstraints[mNbContactManifolds].normal += mContactPoints[mNbContactPoints].normal; @@ -219,8 +212,10 @@ void ContactSolver::initializeForIsland(Island* island) { mContactConstraints[mNbContactManifolds].frictionTwistImpulse = externalManifold->getFrictionTwistImpulse(); // Compute the inverse K matrix for the rolling resistance constraint + bool isBody1DynamicType = body1->getType() == BodyType::DYNAMIC; + bool isBody2DynamicType = body2->getType() == BodyType::DYNAMIC; mContactConstraints[mNbContactManifolds].inverseRollingResistance.setToZero(); - if (mContactConstraints[mNbContactManifolds].rollingResistanceFactor > 0 && (mContactConstraints[mNbContactManifolds].isBody1DynamicType || mContactConstraints[mNbContactManifolds].isBody2DynamicType)) { + if (mContactConstraints[mNbContactManifolds].rollingResistanceFactor > 0 && (isBody1DynamicType || isBody2DynamicType)) { mContactConstraints[mNbContactManifolds].inverseRollingResistance = mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody1 + mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody2; mContactConstraints[mNbContactManifolds].inverseRollingResistance = mContactConstraints[mNbContactManifolds].inverseRollingResistance.getInverse(); } @@ -296,9 +291,6 @@ void ContactSolver::warmStart() { // Initialize the accumulated impulses to zero mContactPoints[contactPointIndex].penetrationImpulse = 0.0; - mContactPoints[contactPointIndex].friction1Impulse = 0.0; - mContactPoints[contactPointIndex].friction2Impulse = 0.0; - mContactPoints[contactPointIndex].rollingResistanceImpulse = Vector3::zero(); } contactPointIndex++; @@ -594,12 +586,6 @@ void ContactSolver::storeImpulses() { for (short int i=0; isetPenetrationImpulse(mContactPoints[contactPointIndex].penetrationImpulse); - mContactPoints[contactPointIndex].externalContact->setFrictionImpulse1(mContactPoints[contactPointIndex].friction1Impulse); - mContactPoints[contactPointIndex].externalContact->setFrictionImpulse2(mContactPoints[contactPointIndex].friction2Impulse); - mContactPoints[contactPointIndex].externalContact->setRollingResistanceImpulse(mContactPoints[contactPointIndex].rollingResistanceImpulse); - - mContactPoints[contactPointIndex].externalContact->setFrictionVector1(mContactPoints[contactPointIndex].frictionVector1); - mContactPoints[contactPointIndex].externalContact->setFrictionVector2(mContactPoints[contactPointIndex].frictionVector2); contactPointIndex++; } @@ -613,36 +599,6 @@ void ContactSolver::storeImpulses() { } } -// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction plane -// for a contact point. The two vectors have to be such that : t1 x t2 = contactNormal. -void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, - ContactPointSolver& contactPoint) const { - - assert(contactPoint.normal.length() > 0.0); - - // Compute the velocity difference vector in the tangential plane - Vector3 normalVelocity = deltaVelocity.dot(contactPoint.normal) * contactPoint.normal; - Vector3 tangentVelocity = deltaVelocity - normalVelocity; - - // If the velocty difference in the tangential plane is not zero - decimal lengthTangenVelocity = tangentVelocity.length(); - if (lengthTangenVelocity > MACHINE_EPSILON) { - - // Compute the first friction vector in the direction of the tangent - // velocity difference - contactPoint.frictionVector1 = tangentVelocity / lengthTangenVelocity; - } - else { - - // Get any orthogonal vector to the normal as the first friction vector - contactPoint.frictionVector1 = contactPoint.normal.getOneUnitOrthogonalVector(); - } - - // The second friction vector is computed by the cross product of the firs - // friction vector and the contact normal - contactPoint.frictionVector2 =contactPoint.normal.cross(contactPoint.frictionVector1).getUnit(); -} - // Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction plane // for a contact manifold. The two vectors have to be such that : t1 x t2 = contactNormal. void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, diff --git a/src/engine/ContactSolver.h b/src/engine/ContactSolver.h index e4e2710e..becd5529 100644 --- a/src/engine/ContactSolver.h +++ b/src/engine/ContactSolver.h @@ -122,33 +122,12 @@ class ContactSolver { /// Accumulated normal impulse decimal penetrationImpulse; - /// Accumulated impulse in the 1st friction direction - decimal friction1Impulse; - - /// Accumulated impulse in the 2nd friction direction - decimal friction2Impulse; - /// Accumulated split impulse for penetration correction decimal penetrationSplitImpulse; - /// Accumulated rolling resistance impulse - Vector3 rollingResistanceImpulse; - /// Normal vector of the contact Vector3 normal; - /// First friction vector in the tangent plane - Vector3 frictionVector1; - - /// Second friction vector in the tangent plane - Vector3 frictionVector2; - - /// Old first friction vector in the tangent plane - Vector3 oldFrictionVector1; - - /// Old second friction vector in the tangent plane - Vector3 oldFrictionVector2; - /// Vector from the body 1 center to the contact point Vector3 r1; @@ -188,11 +167,11 @@ class ContactSolver { /// Inverse of the matrix K for the 2nd friction decimal inverseFriction2Mass; - /// True if the contact was existing last time step - bool isRestingContact; - /// Pointer to the external contact ContactPoint* externalContact; + + /// True if the contact was existing last time step + bool isRestingContact; }; // Structure ContactManifoldSolver @@ -223,15 +202,6 @@ class ContactSolver { /// Number of contact points short int nbContacts; - /// True if the body 1 is of type dynamic - bool isBody1DynamicType; - - /// True if the body 2 is of type dynamic - bool isBody2DynamicType; - - /// Mix of the restitution factor for two bodies - decimal restitutionFactor; - /// Mix friction coefficient for the two bodies decimal frictionCoefficient; @@ -369,12 +339,6 @@ class ContactSolver { /// Compute th mixed rolling resistance factor between two bodies decimal computeMixedRollingResistance(RigidBody* body1, RigidBody* body2) const; - /// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction - /// plane for a contact point. The two vectors have to be - /// such that : t1 x t2 = contactNormal. - void computeFrictionVectors(const Vector3& deltaVelocity, - ContactPointSolver &contactPoint) const; - /// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction /// plane for a contact manifold. The two vectors have to be /// such that : t1 x t2 = contactNormal. From 14bfb0aca4160d8323760ccb8d77f0bbc37fc0a3 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 17 Oct 2016 22:41:33 +0200 Subject: [PATCH 038/248] Some optimizations in contact solver --- src/collision/ContactManifold.h | 6 ++-- src/engine/ContactSolver.h | 58 ++++++++++++--------------------- 2 files changed, 23 insertions(+), 41 deletions(-) diff --git a/src/collision/ContactManifold.h b/src/collision/ContactManifold.h index 2f77e9b2..c36c1476 100644 --- a/src/collision/ContactManifold.h +++ b/src/collision/ContactManifold.h @@ -102,7 +102,7 @@ class ContactManifold { short int mNormalDirectionId; /// Number of contacts in the cache - uint mNbContactPoints; + int8 mNbContactPoints; /// First friction vector of the contact manifold Vector3 mFrictionVector1; @@ -187,7 +187,7 @@ class ContactManifold { void clear(); /// Return the number of contact points in the manifold - uint getNbContactPoints() const; + int8 getNbContactPoints() const; /// Return the first friction vector at the center of the contact manifold const Vector3& getFrictionVector1() const; @@ -264,7 +264,7 @@ inline short int ContactManifold::getNormalDirectionId() const { } // Return the number of contact points in the manifold -inline uint ContactManifold::getNbContactPoints() const { +inline int8 ContactManifold::getNbContactPoints() const { return mNbContactPoints; } diff --git a/src/engine/ContactSolver.h b/src/engine/ContactSolver.h index becd5529..089d8b53 100644 --- a/src/engine/ContactSolver.h +++ b/src/engine/ContactSolver.h @@ -119,11 +119,8 @@ class ContactSolver { */ struct ContactPointSolver { - /// Accumulated normal impulse - decimal penetrationImpulse; - - /// Accumulated split impulse for penetration correction - decimal penetrationSplitImpulse; + /// Pointer to the external contact + ContactPoint* externalContact; /// Normal vector of the contact Vector3 normal; @@ -134,41 +131,26 @@ class ContactSolver { /// Vector from the body 2 center to the contact point Vector3 r2; - /// Cross product of r1 with 1st friction vector - Vector3 r1CrossT1; - - /// Cross product of r1 with 2nd friction vector - Vector3 r1CrossT2; - - /// Cross product of r2 with 1st friction vector - Vector3 r2CrossT1; - - /// Cross product of r2 with 2nd friction vector - Vector3 r2CrossT2; - - /// Cross product of r1 with the contact normal - Vector3 r1CrossN; - - /// Cross product of r2 with the contact normal - Vector3 r2CrossN; - /// Penetration depth decimal penetrationDepth; /// Velocity restitution bias decimal restitutionBias; + /// Accumulated normal impulse + decimal penetrationImpulse; + + /// Accumulated split impulse for penetration correction + decimal penetrationSplitImpulse; + /// Inverse of the matrix K for the penenetration decimal inversePenetrationMass; - /// Inverse of the matrix K for the 1st friction - decimal inverseFriction1Mass; + /// Cross product of r1 with the contact normal + Vector3 r1CrossN; - /// Inverse of the matrix K for the 2nd friction - decimal inverseFriction2Mass; - - /// Pointer to the external contact - ContactPoint* externalContact; + /// Cross product of r2 with the contact normal + Vector3 r2CrossN; /// True if the contact was existing last time step bool isRestingContact; @@ -181,11 +163,14 @@ class ContactSolver { */ struct ContactManifoldSolver { + /// Pointer to the external contact manifold + ContactManifold* externalContactManifold; + /// Index of body 1 in the constraint solver - uint indexBody1; + int32 indexBody1; /// Index of body 2 in the constraint solver - uint indexBody2; + int32 indexBody2; /// Inverse of the mass of body 1 decimal massInverseBody1; @@ -199,18 +184,12 @@ class ContactSolver { /// Inverse inertia tensor of body 2 Matrix3x3 inverseInertiaTensorBody2; - /// Number of contact points - short int nbContacts; - /// Mix friction coefficient for the two bodies decimal frictionCoefficient; /// Rolling resistance factor between the two bodies decimal rollingResistanceFactor; - /// Pointer to the external contact manifold - ContactManifold* externalContactManifold; - // - Variables used when friction constraints are apply at the center of the manifold-// /// Average normal vector of the contact manifold @@ -275,6 +254,9 @@ class ContactSolver { /// Rolling resistance impulse Vector3 rollingResistanceImpulse; + + /// Number of contact points + int8 nbContacts; }; // -------------------- Constants --------------------- // From ce06a4b935e15c7fa4376c549572c8153cfcf02e Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 17 Oct 2016 22:41:58 +0200 Subject: [PATCH 039/248] Change fixed size data types --- src/configuration.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/configuration.h b/src/configuration.h index c14783d8..04cb0956 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -30,6 +30,7 @@ #include #include #include +#include #include "decimal.h" // Windows platform @@ -51,10 +52,9 @@ using luint = long unsigned int; using bodyindex = luint; using bodyindexpair = std::pair; -using int16 = signed short; -using int32 = signed int; -using uint16 = unsigned short; -using uint32 = unsigned int; +using int8 = int8_t; +using int16 = int16_t; +using int32 = int32_t; // ------------------- Enumerations ------------------- // From cc6d3d621d4ef3b976ba091ce953da49f5bd464d Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 20 Oct 2016 19:16:55 +0200 Subject: [PATCH 040/248] Add profiling data --- src/engine/ContactSolver.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index 34e86472..837fdf38 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -262,6 +262,8 @@ void ContactSolver::initializeForIsland(Island* island) { /// the solution of the linear system void ContactSolver::warmStart() { + PROFILE("ContactSolver::warmStart()"); + uint contactPointIndex = 0; // For each constraint @@ -578,6 +580,8 @@ void ContactSolver::solve() { // warm start the solver at the next iteration void ContactSolver::storeImpulses() { + PROFILE("ContactSolver::storeImpulses()"); + uint contactPointIndex = 0; // For each contact manifold @@ -604,6 +608,8 @@ void ContactSolver::storeImpulses() { void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, ContactManifoldSolver& contact) const { + PROFILE("ContactSolver::computeFrictionVectors()"); + assert(contact.normal.length() > decimal(0.0)); // Compute the velocity difference vector in the tangential plane From b3d24e4299a6503bcf1635475ae2da7694bfcb42 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 23 Oct 2016 20:04:52 +0200 Subject: [PATCH 041/248] Cache some calculation in contact solver --- src/engine/ContactSolver.cpp | 45 ++++++++++++++++++------------------ src/engine/ContactSolver.h | 4 ++-- src/mathematics/Vector3.h | 2 +- 3 files changed, 26 insertions(+), 25 deletions(-) diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index 837fdf38..5d61243a 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -174,13 +174,16 @@ void ContactSolver::initializeForIsland(Island* island) { // Compute the velocity difference Vector3 deltaV = v2 + w2.cross(mContactPoints[mNbContactPoints].r2) - v1 - w1.cross(mContactPoints[mNbContactPoints].r1); - mContactPoints[mNbContactPoints].r1CrossN = mContactPoints[mNbContactPoints].r1.cross(mContactPoints[mNbContactPoints].normal); - mContactPoints[mNbContactPoints].r2CrossN = mContactPoints[mNbContactPoints].r2.cross(mContactPoints[mNbContactPoints].normal); + Vector3 r1CrossN = mContactPoints[mNbContactPoints].r1.cross(mContactPoints[mNbContactPoints].normal); + Vector3 r2CrossN = mContactPoints[mNbContactPoints].r2.cross(mContactPoints[mNbContactPoints].normal); + + mContactPoints[mNbContactPoints].i1TimesR1CrossN = mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody1 * r1CrossN; + mContactPoints[mNbContactPoints].i2TimesR2CrossN = mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody2 * r2CrossN; // Compute the inverse mass matrix K for the penetration constraint decimal massPenetration = mContactConstraints[mNbContactManifolds].massInverseBody1 + mContactConstraints[mNbContactManifolds].massInverseBody2 + - ((mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody1 * mContactPoints[mNbContactPoints].r1CrossN).cross(mContactPoints[mNbContactPoints].r1)).dot(mContactPoints[mNbContactPoints].normal) + - ((mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody2 * mContactPoints[mNbContactPoints].r2CrossN).cross(mContactPoints[mNbContactPoints].r2)).dot(mContactPoints[mNbContactPoints].normal); + ((mContactPoints[mNbContactPoints].i1TimesR1CrossN).cross(mContactPoints[mNbContactPoints].r1)).dot(mContactPoints[mNbContactPoints].normal) + + ((mContactPoints[mNbContactPoints].i2TimesR2CrossN).cross(mContactPoints[mNbContactPoints].r2)).dot(mContactPoints[mNbContactPoints].normal); mContactPoints[mNbContactPoints].inversePenetrationMass = massPenetration > decimal(0.0) ? decimal(1.0) / massPenetration : decimal(0.0); // Compute the restitution velocity bias "b". We compute this here instead @@ -282,12 +285,12 @@ void ContactSolver::warmStart() { // Update the velocities of the body 1 by applying the impulse P Vector3 impulsePenetration = mContactPoints[contactPointIndex].normal * mContactPoints[contactPointIndex].penetrationImpulse; - mLinearVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].massInverseBody1 * (-impulsePenetration); - mAngularVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].inverseInertiaTensorBody1 * (-mContactPoints[contactPointIndex].r1CrossN * mContactPoints[contactPointIndex].penetrationImpulse); + mLinearVelocities[mContactConstraints[c].indexBody1] -= mContactConstraints[c].massInverseBody1 * impulsePenetration; + mAngularVelocities[mContactConstraints[c].indexBody1] -= mContactPoints[contactPointIndex].i1TimesR1CrossN * mContactPoints[contactPointIndex].penetrationImpulse; // Update the velocities of the body 2 by applying the impulse P mLinearVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].massInverseBody2 * impulsePenetration; - mAngularVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].inverseInertiaTensorBody2 * (mContactPoints[contactPointIndex].r2CrossN * mContactPoints[contactPointIndex].penetrationImpulse); + mAngularVelocities[mContactConstraints[c].indexBody2] += mContactPoints[contactPointIndex].i2TimesR2CrossN * mContactPoints[contactPointIndex].penetrationImpulse; } else { // If it is a new contact point @@ -320,7 +323,7 @@ void ContactSolver::warmStart() { mContactConstraints[c].friction1Impulse; // Update the velocities of the body 1 by applying the impulse P - mLinearVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].massInverseBody1 * (-linearImpulseBody2); + mLinearVelocities[mContactConstraints[c].indexBody1] -= mContactConstraints[c].massInverseBody1 * linearImpulseBody2; mAngularVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].inverseInertiaTensorBody1 * angularImpulseBody1; // Update the velocities of the body 1 by applying the impulse P @@ -335,7 +338,7 @@ void ContactSolver::warmStart() { angularImpulseBody2 = mContactConstraints[c].r2CrossT2 * mContactConstraints[c].friction2Impulse; // Update the velocities of the body 1 by applying the impulse P - mLinearVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].massInverseBody1 * (-linearImpulseBody2); + mLinearVelocities[mContactConstraints[c].indexBody1] -= mContactConstraints[c].massInverseBody1 * linearImpulseBody2; mAngularVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].inverseInertiaTensorBody1 * angularImpulseBody1; // Update the velocities of the body 2 by applying the impulse P @@ -360,7 +363,7 @@ void ContactSolver::warmStart() { angularImpulseBody2 = mContactConstraints[c].rollingResistanceImpulse; // Update the velocities of the body 1 by applying the impulse P - mAngularVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].inverseInertiaTensorBody1 * (-angularImpulseBody2); + mAngularVelocities[mContactConstraints[c].indexBody1] -= mContactConstraints[c].inverseInertiaTensorBody1 * angularImpulseBody2; // Update the velocities of the body 1 by applying the impulse P mAngularVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].inverseInertiaTensorBody2 * angularImpulseBody2; @@ -428,12 +431,12 @@ void ContactSolver::solve() { Vector3 linearImpulse = mContactPoints[contactPointIndex].normal * deltaLambda; // Update the velocities of the body 1 by applying the impulse P - mLinearVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].massInverseBody1 * (-linearImpulse); - mAngularVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].inverseInertiaTensorBody1 * (-mContactPoints[contactPointIndex].r1CrossN * deltaLambda); + mLinearVelocities[mContactConstraints[c].indexBody1] -= mContactConstraints[c].massInverseBody1 * linearImpulse; + mAngularVelocities[mContactConstraints[c].indexBody1] -= mContactPoints[contactPointIndex].i1TimesR1CrossN * deltaLambda; // Update the velocities of the body 2 by applying the impulse P mLinearVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].massInverseBody2 * linearImpulse; - mAngularVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].inverseInertiaTensorBody2 * (mContactPoints[contactPointIndex].r2CrossN * deltaLambda); + mAngularVelocities[mContactConstraints[c].indexBody2] += mContactPoints[contactPointIndex].i2TimesR2CrossN * deltaLambda; sumPenetrationImpulse += mContactPoints[contactPointIndex].penetrationImpulse; @@ -459,14 +462,12 @@ void ContactSolver::solve() { Vector3 linearImpulse = mContactPoints[contactPointIndex].normal * deltaLambdaSplit; // Update the velocities of the body 1 by applying the impulse P - mSplitLinearVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].massInverseBody1 * (-linearImpulse); - mSplitAngularVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].inverseInertiaTensorBody1 * - (-mContactPoints[contactPointIndex].r1CrossN * deltaLambdaSplit); + mSplitLinearVelocities[mContactConstraints[c].indexBody1] -= mContactConstraints[c].massInverseBody1 * linearImpulse; + mSplitAngularVelocities[mContactConstraints[c].indexBody1] -= mContactPoints[contactPointIndex].i1TimesR1CrossN * deltaLambdaSplit; // Update the velocities of the body 1 by applying the impulse P mSplitLinearVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].massInverseBody2 * linearImpulse; - mSplitAngularVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].inverseInertiaTensorBody2 * - mContactPoints[contactPointIndex].r2CrossN * deltaLambdaSplit; + mSplitAngularVelocities[mContactConstraints[c].indexBody2] += mContactPoints[contactPointIndex].i2TimesR2CrossN * deltaLambdaSplit; } contactPointIndex++; @@ -494,7 +495,7 @@ void ContactSolver::solve() { Vector3 angularImpulseBody2 = mContactConstraints[c].r2CrossT1 * deltaLambda; // Update the velocities of the body 1 by applying the impulse P - mLinearVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].massInverseBody1 * (-linearImpulseBody2); + mLinearVelocities[mContactConstraints[c].indexBody1] -= mContactConstraints[c].massInverseBody1 * linearImpulseBody2; mAngularVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].inverseInertiaTensorBody1 * angularImpulseBody1; // Update the velocities of the body 2 by applying the impulse P @@ -522,7 +523,7 @@ void ContactSolver::solve() { angularImpulseBody2 = mContactConstraints[c].r2CrossT2 * deltaLambda; // Update the velocities of the body 1 by applying the impulse P - mLinearVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].massInverseBody1 * (-linearImpulseBody2); + mLinearVelocities[mContactConstraints[c].indexBody1] -= mContactConstraints[c].massInverseBody1 * linearImpulseBody2; mAngularVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].inverseInertiaTensorBody1 * angularImpulseBody1; // Update the velocities of the body 2 by applying the impulse P @@ -547,7 +548,7 @@ void ContactSolver::solve() { angularImpulseBody2 = mContactConstraints[c].normal * deltaLambda; // Update the velocities of the body 1 by applying the impulse P - mAngularVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].inverseInertiaTensorBody1 * (-angularImpulseBody2); + mAngularVelocities[mContactConstraints[c].indexBody1] -= mContactConstraints[c].inverseInertiaTensorBody1 * angularImpulseBody2; // Update the velocities of the body 1 by applying the impulse P mAngularVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].inverseInertiaTensorBody2 * angularImpulseBody2; @@ -568,7 +569,7 @@ void ContactSolver::solve() { deltaLambdaRolling = mContactConstraints[c].rollingResistanceImpulse - lambdaTempRolling; // Update the velocities of the body 1 by applying the impulse P - mAngularVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].inverseInertiaTensorBody1 * (-deltaLambdaRolling); + mAngularVelocities[mContactConstraints[c].indexBody1] -= mContactConstraints[c].inverseInertiaTensorBody1 * deltaLambdaRolling; // Update the velocities of the body 2 by applying the impulse P mAngularVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].inverseInertiaTensorBody2 * deltaLambdaRolling; diff --git a/src/engine/ContactSolver.h b/src/engine/ContactSolver.h index 089d8b53..40e0721d 100644 --- a/src/engine/ContactSolver.h +++ b/src/engine/ContactSolver.h @@ -147,10 +147,10 @@ class ContactSolver { decimal inversePenetrationMass; /// Cross product of r1 with the contact normal - Vector3 r1CrossN; + Vector3 i1TimesR1CrossN; /// Cross product of r2 with the contact normal - Vector3 r2CrossN; + Vector3 i2TimesR2CrossN; /// True if the contact was existing last time step bool isRestingContact; diff --git a/src/mathematics/Vector3.h b/src/mathematics/Vector3.h index 4f30391d..1ca1adfd 100644 --- a/src/mathematics/Vector3.h +++ b/src/mathematics/Vector3.h @@ -184,7 +184,7 @@ inline void Vector3::setAllValues(decimal newX, decimal newY, decimal newZ) { // Return the length of the vector inline decimal Vector3::length() const { - return sqrt(x*x + y*y + z*z); + return std::sqrt(x*x + y*y + z*z); } // Return the square of the length of the vector From 16d27f40b9369737fbb8bf3b0893f1e6d10a9433 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 3 Nov 2016 18:06:45 +0100 Subject: [PATCH 042/248] Remove bodies pointer from ContactPoint --- src/collision/CollisionDetection.cpp | 2 ++ src/constraint/ContactPoint.cpp | 3 +-- src/constraint/ContactPoint.h | 22 ---------------------- src/engine/ContactSolver.cpp | 4 ++-- 4 files changed, 5 insertions(+), 26 deletions(-) diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index c3caa97a..2fada228 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -433,6 +433,8 @@ void CollisionDetection::notifyContact(OverlappingPair* overlappingPair, const C void CollisionDetection::createContact(OverlappingPair* overlappingPair, const ContactPointInfo& contactInfo) { + PROFILE("CollisionDetection::createContact()"); + // Create a new contact ContactPoint* contact = new (mWorld->mPoolAllocator.allocate(sizeof(ContactPoint))) ContactPoint(contactInfo); diff --git a/src/constraint/ContactPoint.cpp b/src/constraint/ContactPoint.cpp index c0d567ea..7756d68b 100644 --- a/src/constraint/ContactPoint.cpp +++ b/src/constraint/ContactPoint.cpp @@ -32,8 +32,7 @@ using namespace std; // Constructor ContactPoint::ContactPoint(const ContactPointInfo& contactInfo) - : mBody1(contactInfo.shape1->getBody()), mBody2(contactInfo.shape2->getBody()), - mNormal(contactInfo.normal), + : mNormal(contactInfo.normal), mPenetrationDepth(contactInfo.penetrationDepth), mLocalPointOnBody1(contactInfo.localPoint1), mLocalPointOnBody2(contactInfo.localPoint2), diff --git a/src/constraint/ContactPoint.h b/src/constraint/ContactPoint.h index 18be17b0..c15dbafa 100644 --- a/src/constraint/ContactPoint.h +++ b/src/constraint/ContactPoint.h @@ -101,12 +101,6 @@ class ContactPoint { // -------------------- Attributes -------------------- // - /// First rigid body of the contact - CollisionBody* mBody1; - - /// Second rigid body of the contact - CollisionBody* mBody2; - /// Normalized normal vector of the contact (from body1 toward body2) in world space const Vector3 mNormal; @@ -147,12 +141,6 @@ class ContactPoint { /// Deleted assignment operator ContactPoint& operator=(const ContactPoint& contact) = delete; - /// Return the reference to the body 1 - CollisionBody* getBody1() const; - - /// Return the reference to the body 2 - CollisionBody* getBody2() const; - /// Return the normal vector of the contact Vector3 getNormal() const; @@ -196,16 +184,6 @@ class ContactPoint { size_t getSizeInBytes() const; }; -// Return the reference to the body 1 -inline CollisionBody* ContactPoint::getBody1() const { - return mBody1; -} - -// Return the reference to the body 2 -inline CollisionBody* ContactPoint::getBody2() const { - return mBody2; -} - // Return the normal vector of the contact inline Vector3 ContactPoint::getNormal() const { return mNormal; diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index 5d61243a..d5825d5c 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -115,8 +115,8 @@ void ContactSolver::initializeForIsland(Island* island) { assert(externalManifold->getNbContactPoints() > 0); // Get the two bodies of the contact - RigidBody* body1 = static_cast(externalManifold->getContactPoint(0)->getBody1()); - RigidBody* body2 = static_cast(externalManifold->getContactPoint(0)->getBody2()); + RigidBody* body1 = static_cast(externalManifold->getBody1()); + RigidBody* body2 = static_cast(externalManifold->getBody2()); assert(body1 != nullptr); assert(body2 != nullptr); From f82777bd3b50021dc77b5cb9bfe9398b4a795e2c Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sat, 5 Nov 2016 19:20:54 +0100 Subject: [PATCH 043/248] Refactor some methods in ContactPoint --- src/collision/CollisionDetection.cpp | 3 ++ src/collision/ContactManifold.cpp | 9 ++---- src/constraint/ContactPoint.cpp | 6 ---- src/constraint/ContactPoint.h | 43 ++++++++++++---------------- 4 files changed, 25 insertions(+), 36 deletions(-) diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 2fada228..e2599fca 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -439,6 +439,9 @@ void CollisionDetection::createContact(OverlappingPair* overlappingPair, ContactPoint* contact = new (mWorld->mPoolAllocator.allocate(sizeof(ContactPoint))) ContactPoint(contactInfo); + contact->updateWorldContactPoints(overlappingPair->getShape1()->getLocalToWorldTransform(), + overlappingPair->getShape2()->getLocalToWorldTransform()); + // Add the contact to the contact manifold set of the corresponding overlapping pair overlappingPair->addContact(contact); diff --git a/src/collision/ContactManifold.cpp b/src/collision/ContactManifold.cpp index ff15bce6..dc40774b 100644 --- a/src/collision/ContactManifold.cpp +++ b/src/collision/ContactManifold.cpp @@ -110,12 +110,9 @@ void ContactManifold::update(const Transform& transform1, const Transform& trans // Update the world coordinates and penetration depth of the contact points in the manifold for (uint i=0; isetWorldPointOnBody1(transform1 * - mContactPoints[i]->getLocalPointOnBody1()); - mContactPoints[i]->setWorldPointOnBody2(transform2 * - mContactPoints[i]->getLocalPointOnBody2()); - mContactPoints[i]->setPenetrationDepth((mContactPoints[i]->getWorldPointOnBody1() - - mContactPoints[i]->getWorldPointOnBody2()).dot(mContactPoints[i]->getNormal())); + + mContactPoints[i]->updateWorldContactPoints(transform1, transform2); + mContactPoints[i]->updatePenetrationDepth(); } const decimal squarePersistentContactThreshold = PERSISTENT_CONTACT_DIST_THRESHOLD * diff --git a/src/constraint/ContactPoint.cpp b/src/constraint/ContactPoint.cpp index 7756d68b..00ed60d7 100644 --- a/src/constraint/ContactPoint.cpp +++ b/src/constraint/ContactPoint.cpp @@ -36,12 +36,6 @@ ContactPoint::ContactPoint(const ContactPointInfo& contactInfo) mPenetrationDepth(contactInfo.penetrationDepth), mLocalPointOnBody1(contactInfo.localPoint1), mLocalPointOnBody2(contactInfo.localPoint2), - mWorldPointOnBody1(contactInfo.shape1->getBody()->getTransform() * - contactInfo.shape1->getLocalToBodyTransform() * - contactInfo.localPoint1), - mWorldPointOnBody2(contactInfo.shape2->getBody()->getTransform() * - contactInfo.shape2->getLocalToBodyTransform() * - contactInfo.localPoint2), mIsRestingContact(false) { assert(mPenetrationDepth > decimal(0.0)); diff --git a/src/constraint/ContactPoint.h b/src/constraint/ContactPoint.h index c15dbafa..994f5426 100644 --- a/src/constraint/ContactPoint.h +++ b/src/constraint/ContactPoint.h @@ -53,6 +53,8 @@ struct ContactPointInfo { // -------------------- Attributes -------------------- // + // TODO : Check if we really need the shape1, shape2, collisionShape1 and collisionShape2 fields + /// First proxy shape of the contact ProxyShape* shape1; @@ -141,12 +143,15 @@ class ContactPoint { /// Deleted assignment operator ContactPoint& operator=(const ContactPoint& contact) = delete; + /// Update the world contact points + void updateWorldContactPoints(const Transform& body1Transform, const Transform& body2Transform); + + /// Update the penetration depth + void updatePenetrationDepth(); + /// Return the normal vector of the contact Vector3 getNormal() const; - /// Set the penetration depth of the contact - void setPenetrationDepth(decimal penetrationDepth); - /// Return the contact local point on body 1 Vector3 getLocalPointOnBody1() const; @@ -165,12 +170,6 @@ class ContactPoint { /// Set the cached penetration impulse void setPenetrationImpulse(decimal impulse); - /// Set the contact world point on body 1 - void setWorldPointOnBody1(const Vector3& worldPoint); - - /// Set the contact world point on body 2 - void setWorldPointOnBody2(const Vector3& worldPoint); - /// Return true if the contact is a resting contact bool getIsRestingContact() const; @@ -184,16 +183,22 @@ class ContactPoint { size_t getSizeInBytes() const; }; +// Update the world contact points +inline void ContactPoint::updateWorldContactPoints(const Transform& body1Transform, const Transform& body2Transform) { + mWorldPointOnBody1 = body1Transform * mLocalPointOnBody1; + mWorldPointOnBody2 = body2Transform * mLocalPointOnBody2; +} + +// Update the penetration depth +inline void ContactPoint::updatePenetrationDepth() { + mPenetrationDepth = (mWorldPointOnBody1 - mWorldPointOnBody2).dot(mNormal); +} + // Return the normal vector of the contact inline Vector3 ContactPoint::getNormal() const { return mNormal; } -// Set the penetration depth of the contact -inline void ContactPoint::setPenetrationDepth(decimal penetrationDepth) { - this->mPenetrationDepth = penetrationDepth; -} - // Return the contact point on body 1 inline Vector3 ContactPoint::getLocalPointOnBody1() const { return mLocalPointOnBody1; @@ -224,16 +229,6 @@ inline void ContactPoint::setPenetrationImpulse(decimal impulse) { mPenetrationImpulse = impulse; } -// Set the contact world point on body 1 -inline void ContactPoint::setWorldPointOnBody1(const Vector3& worldPoint) { - mWorldPointOnBody1 = worldPoint; -} - -// Set the contact world point on body 2 -inline void ContactPoint::setWorldPointOnBody2(const Vector3& worldPoint) { - mWorldPointOnBody2 = worldPoint; -} - // Return true if the contact is a resting contact inline bool ContactPoint::getIsRestingContact() const { return mIsRestingContact; From 4a97c2ca9732526df3d0dcebd04b241bc604cc91 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 8 Jan 2017 19:56:59 +0100 Subject: [PATCH 044/248] Refactor collision detection --- CMakeLists.txt | 7 +- src/body/CollisionBody.h | 12 + src/collision/CollisionDetection.cpp | 714 +++++++++++++++--- src/collision/CollisionDetection.h | 107 ++- src/collision/ContactManifoldSet.cpp | 2 +- ...CollisionShapeInfo.h => NarrowPhaseInfo.h} | 45 +- src/collision/ProxyShape.h | 27 +- .../broadphase/BroadPhaseAlgorithm.cpp | 76 +- .../broadphase/BroadPhaseAlgorithm.h | 36 +- src/collision/broadphase/DynamicAABBTree.cpp | 2 +- src/collision/narrowphase/CollisionDispatch.h | 5 - .../narrowphase/ConcaveVsConvexAlgorithm.cpp | 236 +++--- .../narrowphase/ConcaveVsConvexAlgorithm.h | 99 +-- .../narrowphase/DefaultCollisionDispatch.cpp | 25 +- .../narrowphase/DefaultCollisionDispatch.h | 7 - .../narrowphase/EPA/EPAAlgorithm.cpp | 32 +- src/collision/narrowphase/EPA/EPAAlgorithm.h | 20 +- .../narrowphase/GJK/GJKAlgorithm.cpp | 86 +-- src/collision/narrowphase/GJK/GJKAlgorithm.h | 25 +- .../narrowphase/NarrowPhaseAlgorithm.h | 28 +- .../narrowphase/SphereVsSphereAlgorithm.cpp | 23 +- .../narrowphase/SphereVsSphereAlgorithm.h | 5 +- src/constraint/ContactPoint.h | 33 +- src/containers/LinkedList.h | 124 +++ src/{memory => containers}/Stack.h | 0 src/engine/CollisionWorld.cpp | 122 +-- src/engine/CollisionWorld.h | 127 +++- src/engine/DynamicsWorld.cpp | 112 --- src/engine/DynamicsWorld.h | 26 - .../Allocator.h} | 36 +- src/memory/PoolAllocator.h | 10 +- src/memory/SingleFrameAllocator.h | 15 +- 32 files changed, 1331 insertions(+), 893 deletions(-) rename src/collision/{CollisionShapeInfo.h => NarrowPhaseInfo.h} (59%) create mode 100644 src/containers/LinkedList.h rename src/{memory => containers}/Stack.h (100%) rename src/{collision/narrowphase/NarrowPhaseAlgorithm.cpp => memory/Allocator.h} (75%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 87a02105..b3d37ed1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -80,7 +80,6 @@ SET (REACTPHYSICS3D_SOURCES "src/collision/narrowphase/GJK/GJKAlgorithm.h" "src/collision/narrowphase/GJK/GJKAlgorithm.cpp" "src/collision/narrowphase/NarrowPhaseAlgorithm.h" - "src/collision/narrowphase/NarrowPhaseAlgorithm.cpp" "src/collision/narrowphase/SphereVsSphereAlgorithm.h" "src/collision/narrowphase/SphereVsSphereAlgorithm.cpp" "src/collision/narrowphase/ConcaveVsConvexAlgorithm.h" @@ -121,7 +120,7 @@ SET (REACTPHYSICS3D_SOURCES "src/collision/TriangleMesh.cpp" "src/collision/CollisionDetection.h" "src/collision/CollisionDetection.cpp" - "src/collision/CollisionShapeInfo.h" + "src/collision/NarrowPhaseInfo.h" "src/collision/ContactManifold.h" "src/collision/ContactManifold.cpp" "src/collision/ContactManifoldSet.h" @@ -173,11 +172,13 @@ SET (REACTPHYSICS3D_SOURCES "src/mathematics/Vector3.h" "src/mathematics/Ray.h" "src/mathematics/Vector3.cpp" + "src/memory/Allocator.h" "src/memory/PoolAllocator.h" "src/memory/PoolAllocator.cpp" "src/memory/SingleFrameAllocator.h" "src/memory/SingleFrameAllocator.cpp" - "src/memory/Stack.h" + "src/containers/Stack.h" + "src/containers/LinkedList.h" ) # Create the library diff --git a/src/body/CollisionBody.h b/src/body/CollisionBody.h index bd5c7818..2d5101b9 100644 --- a/src/body/CollisionBody.h +++ b/src/body/CollisionBody.h @@ -153,6 +153,9 @@ class CollisionBody : public Body { /// Raycast method with feedback information bool raycast(const Ray& ray, RaycastInfo& raycastInfo); + /// Test if the collision body overlaps with a given AABB + bool testAABBOverlap(const AABB& worldAABB) const; + /// Compute and return the AABB of the body by merging all proxy shapes AABBs AABB getAABB() const; @@ -301,6 +304,15 @@ inline Vector3 CollisionBody::getLocalVector(const Vector3& worldVector) const { return mTransform.getOrientation().getInverse() * worldVector; } +/// Test if the collision body overlaps with a given AABB +/** +* @param worldAABB The AABB (in world-space coordinates) that will be used to test overlap +* @return True if the given AABB overlaps with the AABB of the collision body +*/ +inline bool CollisionBody::testAABBOverlap(const AABB& worldAABB) const { + return worldAABB.testCollision(getAABB()); +} + } #endif diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index e2599fca..c199859c 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -35,15 +35,16 @@ #include #include #include +#include // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; using namespace std; // Constructor -CollisionDetection::CollisionDetection(CollisionWorld* world, PoolAllocator& memoryAllocator) - : mMemoryAllocator(memoryAllocator), - mWorld(world), mBroadPhaseAlgorithm(*this), +CollisionDetection::CollisionDetection(CollisionWorld* world, PoolAllocator& memoryAllocator, SingleFrameAllocator& singleFrameAllocator) + : mMemoryAllocator(memoryAllocator), mSingleFrameAllocator(singleFrameAllocator), + mWorld(world), mNarrowPhaseInfoList(nullptr), mBroadPhaseAlgorithm(*this), mIsCollisionShapesAdded(false) { // Set the default collision dispatch configuration @@ -60,27 +61,20 @@ void CollisionDetection::computeCollisionDetection() { // Compute the broad-phase collision detection computeBroadPhase(); + + // Compute the middle-phase collision detection + computeMiddlePhase(); // Compute the narrow-phase collision detection - computeNarrowPhase(); -} - -// Compute the collision detection -void CollisionDetection::testCollisionBetweenShapes(CollisionCallback* callback, - const std::set& shapes1, - const std::set& shapes2) { - - // Compute the broad-phase collision detection - computeBroadPhase(); - - // Delete all the contact points in the currently overlapping pairs - clearContactPoints(); - - // Compute the narrow-phase collision detection among given sets of shapes - computeNarrowPhaseBetweenShapes(callback, shapes1, shapes2); + computeNarrowPhase(); + + // Reset the linked list of narrow-phase info + mNarrowPhaseInfoList = nullptr; } +// TODO : Remove this method // Report collision between two sets of shapes +/* void CollisionDetection::reportCollisionBetweenShapes(CollisionCallback* callback, const std::set& shapes1, const std::set& shapes2) { @@ -126,13 +120,9 @@ void CollisionDetection::reportCollisionBetweenShapes(CollisionCallback* callbac ContactPoint* contactPoint = manifold->getContactPoint(i); // Create the contact info object for the contact - ContactPointInfo contactInfo(manifold->getShape1(), manifold->getShape2(), - manifold->getShape1()->getCollisionShape(), - manifold->getShape2()->getCollisionShape(), - contactPoint->getNormal(), - contactPoint->getPenetrationDepth(), - contactPoint->getLocalPointOnBody1(), - contactPoint->getLocalPointOnBody2()); + ContactPointInfo contactInfo; + contactInfo.init(contactPoint->getNormal(), contactPoint->getPenetrationDepth(), + contactPoint->getLocalPointOnBody1(), contactPoint->getLocalPointOnBody2()); // Notify the collision callback about this new contact if (callback != nullptr) callback->notifyContact(contactInfo); @@ -140,6 +130,7 @@ void CollisionDetection::reportCollisionBetweenShapes(CollisionCallback* callbac } } } +*/ // Compute the broad-phase collision detection void CollisionDetection::computeBroadPhase() { @@ -152,18 +143,18 @@ void CollisionDetection::computeBroadPhase() { // Ask the broad-phase to recompute the overlapping pairs of collision // shapes. This call can only add new overlapping pairs in the collision // detection. - mBroadPhaseAlgorithm.computeOverlappingPairs(); + mBroadPhaseAlgorithm.computeOverlappingPairs(mMemoryAllocator); } } -// Compute the narrow-phase collision detection -void CollisionDetection::computeNarrowPhase() { +// Compute the middle-phase collision detection +void CollisionDetection::computeMiddlePhase() { - PROFILE("CollisionDetection::computeNarrowPhase()"); + PROFILE("CollisionDetection::computeMiddlePhase()"); // Clear the set of overlapping pairs in narrow-phase contact mContactOverlappingPairs.clear(); - + // For each possible collision pair of bodies map::iterator it; for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ) { @@ -199,7 +190,7 @@ void CollisionDetection::computeNarrowPhase() { CollisionBody* const body1 = shape1->getBody(); CollisionBody* const body2 = shape2->getBody(); - + // Update the contact cache of the overlapping pair pair->update(); @@ -211,37 +202,154 @@ void CollisionDetection::computeNarrowPhase() { // Check if the bodies are in the set of bodies that cannot collide between each other bodyindexpair bodiesIndex = OverlappingPair::computeBodiesIndexPair(body1, body2); if (mNoCollisionPairs.count(bodiesIndex) > 0) continue; - - // Select the narrow phase algorithm to use according to the two collision shapes + const CollisionShapeType shape1Type = shape1->getCollisionShape()->getType(); const CollisionShapeType shape2Type = shape2->getCollisionShape()->getType(); + + // If both shapes are convex + if ((CollisionShape::isConvex(shape1Type) && CollisionShape::isConvex(shape2Type))) { + + // No middle-phase is necessary, simply create a narrow phase info + // for the narrow-phase collision detection + NarrowPhaseInfo* firstNarrowPhaseInfo = mNarrowPhaseInfoList; + mNarrowPhaseInfoList = new (mSingleFrameAllocator.allocate(sizeof(NarrowPhaseInfo))) + NarrowPhaseInfo(pair, shape1->getCollisionShape(), + shape2->getCollisionShape(), shape1->getLocalToWorldTransform(), + shape2->getLocalToWorldTransform(), shape1->getCachedCollisionData(), + shape2->getCachedCollisionData()); + mNarrowPhaseInfoList->next = firstNarrowPhaseInfo; + + } + // Concave vs Convex algorithm + else if ((!CollisionShape::isConvex(shape1Type) && CollisionShape::isConvex(shape2Type)) || + (!CollisionShape::isConvex(shape2Type) && CollisionShape::isConvex(shape1Type))) { + + NarrowPhaseInfo* narrowPhaseInfo = nullptr; + computeConvexVsConcaveMiddlePhase(pair, mSingleFrameAllocator, &narrowPhaseInfo); + + // Add all the narrow-phase info object reported by the callback into the + // list of all the narrow-phase info object + while (narrowPhaseInfo != nullptr) { + NarrowPhaseInfo* head = mNarrowPhaseInfoList; + mNarrowPhaseInfoList = narrowPhaseInfo; + mNarrowPhaseInfoList->next = head; + + narrowPhaseInfo = narrowPhaseInfo->next; + } + } + // Concave vs Concave shape + else { + // Not handled + continue; + } + } +} + +// Compute the concave vs convex middle-phase algorithm for a given pair of bodies +void CollisionDetection::computeConvexVsConcaveMiddlePhase(OverlappingPair* pair, Allocator& allocator, + NarrowPhaseInfo** firstNarrowPhaseInfo) { + + ProxyShape* shape1 = pair->getShape1(); + ProxyShape* shape2 = pair->getShape2(); + + ProxyShape* convexProxyShape; + ProxyShape* concaveProxyShape; + const ConvexShape* convexShape; + const ConcaveShape* concaveShape; + + // Collision shape 1 is convex, collision shape 2 is concave + if (shape1->getCollisionShape()->isConvex()) { + convexProxyShape = shape1; + convexShape = static_cast(shape1->getCollisionShape()); + concaveProxyShape = shape2; + concaveShape = static_cast(shape2->getCollisionShape()); + } + else { // Collision shape 2 is convex, collision shape 1 is concave + convexProxyShape = shape2; + convexShape = static_cast(shape2->getCollisionShape()); + concaveProxyShape = shape1; + concaveShape = static_cast(shape1->getCollisionShape()); + } + + // Set the parameters of the callback object + MiddlePhaseTriangleCallback middlePhaseCallback(pair, concaveProxyShape, convexProxyShape, + concaveShape, allocator); + + // Compute the convex shape AABB in the local-space of the convex shape + AABB aabb; + convexShape->computeAABB(aabb, convexProxyShape->getLocalToWorldTransform()); + + // TODO : Implement smooth concave mesh collision somewhere + + // Call the convex vs triangle callback for each triangle of the concave shape + concaveShape->testAllTriangles(middlePhaseCallback, aabb); + + // Add all the narrow-phase info object reported by the callback into the + // list of all the narrow-phase info object + *firstNarrowPhaseInfo = middlePhaseCallback.narrowPhaseInfoList; +} + +// Compute the narrow-phase collision detection +void CollisionDetection::computeNarrowPhase() { + + PROFILE("CollisionDetection::computeNarrowPhase()"); + + const NarrowPhaseInfo* currentNarrowPhaseInfo = mNarrowPhaseInfoList; + while (currentNarrowPhaseInfo != nullptr) { + + // Select the narrow phase algorithm to use according to the two collision shapes + const CollisionShapeType shape1Type = currentNarrowPhaseInfo->collisionShape1->getType(); + const CollisionShapeType shape2Type = currentNarrowPhaseInfo->collisionShape2->getType(); const int shape1Index = static_cast(shape1Type); const int shape2Index = static_cast(shape2Type); NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Index][shape2Index]; - // If there is no collision algorithm between those two kinds of shapes - if (narrowPhaseAlgorithm == nullptr) continue; + // If there is no collision algorithm between those two kinds of shapes, skip it + if (narrowPhaseAlgorithm != nullptr) { - // Notify the narrow-phase algorithm about the overlapping pair we are going to test - narrowPhaseAlgorithm->setCurrentOverlappingPair(pair); + // Use the narrow-phase collision detection algorithm to check + // if there really is a collision. If a collision occurs, the + // notifyContact() callback method will be called. + ContactPointInfo contactPointInfo; + if (narrowPhaseAlgorithm->testCollision(currentNarrowPhaseInfo, contactPointInfo)) { - // Create the CollisionShapeInfo objects - CollisionShapeInfo shape1Info(shape1, shape1->getCollisionShape(), shape1->getLocalToWorldTransform(), - pair, shape1->getCachedCollisionData()); - CollisionShapeInfo shape2Info(shape2, shape2->getCollisionShape(), shape2->getLocalToWorldTransform(), - pair, shape2->getCachedCollisionData()); - - // Use the narrow-phase collision detection algorithm to check - // if there really is a collision. If a collision occurs, the - // notifyContact() callback method will be called. - narrowPhaseAlgorithm->testCollision(shape1Info, shape2Info, this); + // If it is the first contact since the pairs are overlapping + if (currentNarrowPhaseInfo->overlappingPair->getNbContactPoints() == 0) { + + // Trigger a callback event + if (mWorld->mEventListener != nullptr) mWorld->mEventListener->beginContact(contactPointInfo); + } + + // Create a new contact + ContactPoint* contact = new (mWorld->mPoolAllocator.allocate(sizeof(ContactPoint))) + ContactPoint(contactPointInfo); + + contact->updateWorldContactPoints(currentNarrowPhaseInfo->shape1ToWorldTransform, + currentNarrowPhaseInfo->shape2ToWorldTransform); + + // Add the contact to the contact manifold set of the corresponding overlapping pair + currentNarrowPhaseInfo->overlappingPair->addContact(contact); + + // Add the overlapping pair into the set of pairs in contact during narrow-phase + overlappingpairid pairId = OverlappingPair::computeID(currentNarrowPhaseInfo->overlappingPair->getShape1(), + currentNarrowPhaseInfo->overlappingPair->getShape2()); + mContactOverlappingPairs[pairId] = currentNarrowPhaseInfo->overlappingPair; + + // Trigger a callback event for the new contact + if (mWorld->mEventListener != nullptr) mWorld->mEventListener->newContact(contactPointInfo); + } + } + + currentNarrowPhaseInfo = currentNarrowPhaseInfo->next; } // Add all the contact manifolds (between colliding bodies) to the bodies addAllContactManifoldsToBodies(); } +// TODO : Remove this method // Compute the narrow-phase collision detection +/* void CollisionDetection::computeNarrowPhaseBetweenShapes(CollisionCallback* callback, const std::set& shapes1, const std::set& shapes2) { @@ -326,9 +434,6 @@ void CollisionDetection::computeNarrowPhaseBetweenShapes(CollisionCallback* call // If there is no collision algorithm between those two kinds of shapes if (narrowPhaseAlgorithm == nullptr) continue; - // Notify the narrow-phase algorithm about the overlapping pair we are going to test - narrowPhaseAlgorithm->setCurrentOverlappingPair(pair); - // Create the CollisionShapeInfo objects CollisionShapeInfo shape1Info(shape1, shape1->getCollisionShape(), shape1->getLocalToWorldTransform(), pair, shape1->getCachedCollisionData()); @@ -345,6 +450,7 @@ void CollisionDetection::computeNarrowPhaseBetweenShapes(CollisionCallback* call // Add all the contact manifolds (between colliding bodies) to the bodies addAllContactManifoldsToBodies(); } +*/ // Allow the broadphase to notify the collision detection about an overlapping pair. /// This method is called by the broad-phase collision detection algorithm @@ -352,9 +458,6 @@ void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, Pro assert(shape1->mBroadPhaseID != shape2->mBroadPhaseID); - // If the two proxy collision shapes are from the same body, skip it - if (shape1->getBody()->getID() == shape2->getBody()->getID()) return; - // Check if the collision filtering allows collision between the two shapes if ((shape1->getCollideWithMaskBits() & shape2->getCollisionCategoryBits()) == 0 || (shape1->getCollisionCategoryBits() & shape2->getCollideWithMaskBits()) == 0) return; @@ -412,45 +515,6 @@ void CollisionDetection::removeProxyCollisionShape(ProxyShape* proxyShape) { mBroadPhaseAlgorithm.removeProxyCollisionShape(proxyShape); } -// Called by a narrow-phase collision algorithm when a new contact has been found -void CollisionDetection::notifyContact(OverlappingPair* overlappingPair, const ContactPointInfo& contactInfo) { - - // If it is the first contact since the pairs are overlapping - if (overlappingPair->getNbContactPoints() == 0) { - - // Trigger a callback event - if (mWorld->mEventListener != nullptr) mWorld->mEventListener->beginContact(contactInfo); - } - - // Create a new contact - createContact(overlappingPair, contactInfo); - - // Trigger a callback event for the new contact - if (mWorld->mEventListener != nullptr) mWorld->mEventListener->newContact(contactInfo); -} - -// Create a new contact -void CollisionDetection::createContact(OverlappingPair* overlappingPair, - const ContactPointInfo& contactInfo) { - - PROFILE("CollisionDetection::createContact()"); - - // Create a new contact - ContactPoint* contact = new (mWorld->mPoolAllocator.allocate(sizeof(ContactPoint))) - ContactPoint(contactInfo); - - contact->updateWorldContactPoints(overlappingPair->getShape1()->getLocalToWorldTransform(), - overlappingPair->getShape2()->getLocalToWorldTransform()); - - // Add the contact to the contact manifold set of the corresponding overlapping pair - overlappingPair->addContact(contact); - - // Add the overlapping pair into the set of pairs in contact during narrow-phase - overlappingpairid pairId = OverlappingPair::computeID(overlappingPair->getShape1(), - overlappingPair->getShape2()); - mContactOverlappingPairs[pairId] = overlappingPair; -} - void CollisionDetection::addAllContactManifoldsToBodies() { // For each overlapping pairs in contact during the narrow-phase @@ -508,6 +572,464 @@ void CollisionDetection::clearContactPoints() { } } +// Compute the middle-phase collision detection between two proxy shapes +NarrowPhaseInfo* CollisionDetection::computeMiddlePhaseForProxyShapes(ProxyShape* shape1, ProxyShape* shape2) { + + // Create a temporary overlapping pair + OverlappingPair pair(shape1, shape2, 0, mMemoryAllocator); + + // ------------------------------------------------------- + + const CollisionShapeType shape1Type = shape1->getCollisionShape()->getType(); + const CollisionShapeType shape2Type = shape2->getCollisionShape()->getType(); + + NarrowPhaseInfo* narrowPhaseInfo = nullptr; + + // If both shapes are convex + if ((CollisionShape::isConvex(shape1Type) && CollisionShape::isConvex(shape2Type))) { + + // No middle-phase is necessary, simply create a narrow phase info + // for the narrow-phase collision detection + narrowPhaseInfo = new (mMemoryAllocator.allocate(sizeof(NarrowPhaseInfo))) NarrowPhaseInfo(&pair, shape1->getCollisionShape(), + shape2->getCollisionShape(), shape1->getLocalToWorldTransform(), + shape2->getLocalToWorldTransform(), shape1->getCachedCollisionData(), + shape2->getCachedCollisionData()); + + } + // Concave vs Convex algorithm + else if ((!CollisionShape::isConvex(shape1Type) && CollisionShape::isConvex(shape2Type)) || + (!CollisionShape::isConvex(shape2Type) && CollisionShape::isConvex(shape1Type))) { + + // Run the middle-phase collision detection algorithm to find the triangles of the concave + // shape we need to use during the narrow-phase collision detection + computeConvexVsConcaveMiddlePhase(&pair, mMemoryAllocator, &narrowPhaseInfo); + } + + return nullptr; +} + +// Report all the bodies that overlap with the aabb in parameter +void CollisionDetection::testAABBOverlap(const AABB& aabb, OverlapCallback* overlapCallback, + unsigned short categoryMaskBits) { + assert(overlapCallback != nullptr); + + std::unordered_set reportedBodies; + + // Ask the broad-phase to get all the overlapping shapes + LinkedList overlappingNodes(mMemoryAllocator); + mBroadPhaseAlgorithm.reportAllShapesOverlappingWithAABB(aabb, overlappingNodes); + + // For each overlaping proxy shape + LinkedList::ListElement* element = overlappingNodes.getListHead(); + while (element != nullptr) { + + // Get the overlapping proxy shape + int broadPhaseId = element->data; + ProxyShape* proxyShape = mBroadPhaseAlgorithm.getProxyShapeForBroadPhaseId(broadPhaseId); + + CollisionBody* overlapBody = proxyShape->getBody(); + + // If the proxy shape is from a body that we have not already reported collision + if (reportedBodies.find(overlapBody->getID()) == reportedBodies.end()) { + + // Check if the collision filtering allows collision between the two shapes + if ((proxyShape->getCollisionCategoryBits() & categoryMaskBits) != 0) { + + // Add the body into the set of reported bodies + reportedBodies.insert(overlapBody->getID()); + + // Notify the overlap to the user + overlapCallback->notifyOverlap(overlapBody); + } + } + + // Go to the next overlapping proxy shape + element = element->next; + } +} + +// Return true if two bodies overlap +bool CollisionDetection::testOverlap(CollisionBody* body1, CollisionBody* body2) { + + // For each proxy shape proxy shape of the first body + ProxyShape* body1ProxyShape = body1->getProxyShapesList(); + while (body1ProxyShape != nullptr) { + + AABB aabb1 = body1ProxyShape->getWorldAABB(); + + // For each proxy shape of the second body + ProxyShape* body2ProxyShape = body2->getProxyShapesList(); + while (body2ProxyShape != nullptr) { + + AABB aabb2 = body2ProxyShape->getWorldAABB(); + + // Test if the AABBs of the two proxy shapes overlap + if (aabb1.testCollision(aabb2)) { + + const CollisionShapeType shape1Type = body1ProxyShape->getCollisionShape()->getType(); + const CollisionShapeType shape2Type = body2ProxyShape->getCollisionShape()->getType(); + + // Compute the middle-phase collision detection between the two shapes + NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(body1ProxyShape, body2ProxyShape); + + bool isColliding = false; + + // For each narrow-phase info object + while (narrowPhaseInfo != nullptr) { + + // If we have not found a collision yet + if (!isColliding) { + + // Select the narrow phase algorithm to use according to the two collision shapes + const int shape1Index = static_cast(shape1Type); + const int shape2Index = static_cast(shape2Type); + NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Index][shape2Index]; + + // If there is a collision algorithm for those two kinds of shapes + if (narrowPhaseAlgorithm != nullptr) { + + // Use the narrow-phase collision detection algorithm to check + // if there really is a collision. If a collision occurs, the + // notifyContact() callback method will be called. + ContactPointInfo contactPointInfo; + isColliding |= narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactPointInfo); + } + } + + NarrowPhaseInfo* currentNarrowPhaseInfo = narrowPhaseInfo; + narrowPhaseInfo = narrowPhaseInfo->next; + + // Release the allocated memory + mMemoryAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); + } + + // Return if we have found a narrow-phase collision + if (isColliding) return true; + } + + // Go to the next proxy shape + body2ProxyShape = body2ProxyShape->getNext(); + } + + // Go to the next proxy shape + body1ProxyShape = body1ProxyShape->getNext(); + } + + // No overlap has been found + return false; +} + +// Report all the bodies that overlap with the body in parameter +void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overlapCallback, + unsigned short categoryMaskBits) { + + assert(overlapCallback != nullptr); + + std::unordered_set reportedBodies; + + // For each proxy shape proxy shape of the body + ProxyShape* bodyProxyShape = body->getProxyShapesList(); + while (bodyProxyShape != nullptr) { + + // Get the AABB of the shape + const AABB& shapeAABB = mBroadPhaseAlgorithm.getFatAABB(bodyProxyShape->mBroadPhaseID); + + // Ask the broad-phase to get all the overlapping shapes + LinkedList overlappingNodes(mMemoryAllocator); + mBroadPhaseAlgorithm.reportAllShapesOverlappingWithAABB(shapeAABB, overlappingNodes); + + const bodyindex bodyId = body->getID(); + + // For each overlaping proxy shape + LinkedList::ListElement* element = overlappingNodes.getListHead(); + while (element != nullptr) { + + // Get the overlapping proxy shape + int broadPhaseId = element->data; + ProxyShape* proxyShape = mBroadPhaseAlgorithm.getProxyShapeForBroadPhaseId(broadPhaseId); + + // If the proxy shape is from a body that we have not already reported collision and the + // two proxy collision shapes are not from the same body + if (reportedBodies.find(proxyShape->getBody()->getID()) == reportedBodies.end() && + proxyShape->getBody()->getID() != bodyId) { + + // Check if the collision filtering allows collision between the two shapes + if ((proxyShape->getCollisionCategoryBits() & categoryMaskBits) != 0) { + + const CollisionShapeType shape1Type = bodyProxyShape->getCollisionShape()->getType(); + const CollisionShapeType shape2Type = proxyShape->getCollisionShape()->getType(); + + // Compute the middle-phase collision detection between the two shapes + NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(bodyProxyShape, proxyShape); + + bool isColliding = false; + + // For each narrow-phase info object + while (narrowPhaseInfo != nullptr) { + + // If we have not found a collision yet + if (!isColliding) { + + // Select the narrow phase algorithm to use according to the two collision shapes + const int shape1Index = static_cast(shape1Type); + const int shape2Index = static_cast(shape2Type); + NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Index][shape2Index]; + + // If there is a collision algorithm for those two kinds of shapes + if (narrowPhaseAlgorithm != nullptr) { + + // Use the narrow-phase collision detection algorithm to check + // if there really is a collision. If a collision occurs, the + // notifyContact() callback method will be called. + ContactPointInfo contactPointInfo; + isColliding |= narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactPointInfo); + } + } + + NarrowPhaseInfo* currentNarrowPhaseInfo = narrowPhaseInfo; + narrowPhaseInfo = narrowPhaseInfo->next; + + // Release the allocated memory + mMemoryAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); + } + + // Return if we have found a narrow-phase collision + if (isColliding) { + + CollisionBody* overlapBody = proxyShape->getBody(); + + // Add the body into the set of reported bodies + reportedBodies.insert(overlapBody->getID()); + + // Notify the overlap to the user + overlapCallback->notifyOverlap(overlapBody); + } + } + } + + // Go to the next overlapping proxy shape + element = element->next; + } + + // Go to the next proxy shape + bodyProxyShape = bodyProxyShape->getNext(); + } +} + +// Test and report collisions between two bodies +void CollisionDetection::testCollision(CollisionBody* body1, CollisionBody* body2, CollisionCallback* collisionCallback) { + + assert(collisionCallback != nullptr); + + // For each proxy shape proxy shape of the first body + ProxyShape* body1ProxyShape = body1->getProxyShapesList(); + while (body1ProxyShape != nullptr) { + + AABB aabb1 = body1ProxyShape->getWorldAABB(); + + // For each proxy shape of the second body + ProxyShape* body2ProxyShape = body2->getProxyShapesList(); + while (body2ProxyShape != nullptr) { + + AABB aabb2 = body2ProxyShape->getWorldAABB(); + + // Test if the AABBs of the two proxy shapes overlap + if (aabb1.testCollision(aabb2)) { + + // Compute the middle-phase collision detection between the two shapes + NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(body1ProxyShape, body2ProxyShape); + + const CollisionShapeType shape1Type = body1ProxyShape->getCollisionShape()->getType(); + const CollisionShapeType shape2Type = body2ProxyShape->getCollisionShape()->getType(); + + // For each narrow-phase info object + while (narrowPhaseInfo != nullptr) { + + // Select the narrow phase algorithm to use according to the two collision shapes + const int shape1Index = static_cast(shape1Type); + const int shape2Index = static_cast(shape2Type); + NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Index][shape2Index]; + + // If there is a collision algorithm for those two kinds of shapes + if (narrowPhaseAlgorithm != nullptr) { + + // Use the narrow-phase collision detection algorithm to check + // if there really is a collision. If a collision occurs, the + // notifyContact() callback method will be called. + ContactPointInfo contactPointInfo; + if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactPointInfo)) { + + CollisionCallback::CollisionCallbackInfo collisionInfo(contactPointInfo, body1, body2, + body1ProxyShape, body2ProxyShape); + + // Report the contact to the user + collisionCallback->notifyContact(collisionInfo); + } + } + + NarrowPhaseInfo* currentNarrowPhaseInfo = narrowPhaseInfo; + narrowPhaseInfo = narrowPhaseInfo->next; + + // Release the allocated memory + mMemoryAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); + } + } + + // Go to the next proxy shape + body2ProxyShape = body2ProxyShape->getNext(); + } + + // Go to the next proxy shape + body1ProxyShape = body1ProxyShape->getNext(); + } +} + +// Test and report collisions between a body and all the others bodies of the world +void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* callback, unsigned short categoryMaskBits) { + + assert(callback != nullptr); + + // For each proxy shape proxy shape of the body + ProxyShape* bodyProxyShape = body->getProxyShapesList(); + while (bodyProxyShape != nullptr) { + + // Get the AABB of the shape + const AABB& shapeAABB = mBroadPhaseAlgorithm.getFatAABB(bodyProxyShape->mBroadPhaseID); + + // Ask the broad-phase to get all the overlapping shapes + LinkedList overlappingNodes(mMemoryAllocator); + mBroadPhaseAlgorithm.reportAllShapesOverlappingWithAABB(shapeAABB, overlappingNodes); + + const bodyindex bodyId = body->getID(); + + // For each overlaping proxy shape + LinkedList::ListElement* element = overlappingNodes.getListHead(); + while (element != nullptr) { + + // Get the overlapping proxy shape + int broadPhaseId = element->data; + ProxyShape* proxyShape = mBroadPhaseAlgorithm.getProxyShapeForBroadPhaseId(broadPhaseId); + + // If the two proxy collision shapes are not from the same body + if (proxyShape->getBody()->getID() != bodyId) { + + // Check if the collision filtering allows collision between the two shapes + if ((proxyShape->getCollisionCategoryBits() & categoryMaskBits) != 0) { + + const CollisionShapeType shape1Type = bodyProxyShape->getCollisionShape()->getType(); + const CollisionShapeType shape2Type = proxyShape->getCollisionShape()->getType(); + + // Compute the middle-phase collision detection between the two shapes + NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(bodyProxyShape, proxyShape); + + // For each narrow-phase info object + while (narrowPhaseInfo != nullptr) { + + // Select the narrow phase algorithm to use according to the two collision shapes + const int shape1Index = static_cast(shape1Type); + const int shape2Index = static_cast(shape2Type); + NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Index][shape2Index]; + + // If there is a collision algorithm for those two kinds of shapes + if (narrowPhaseAlgorithm != nullptr) { + + // Use the narrow-phase collision detection algorithm to check + // if there really is a collision. If a collision occurs, the + // notifyContact() callback method will be called. + ContactPointInfo contactPointInfo; + if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactPointInfo)) { + + CollisionCallback::CollisionCallbackInfo collisionInfo(contactPointInfo, body, + proxyShape->getBody(), bodyProxyShape, + proxyShape); + + // Report the contact to the user + callback->notifyContact(collisionInfo); + } + } + + NarrowPhaseInfo* currentNarrowPhaseInfo = narrowPhaseInfo; + narrowPhaseInfo = narrowPhaseInfo->next; + + // Release the allocated memory + mMemoryAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); + } + } + } + + // Go to the next overlapping proxy shape + element = element->next; + } + + // Go to the next proxy shape + bodyProxyShape = bodyProxyShape->getNext(); + } +} + +// Test and report collisions between all shapes of the world +void CollisionDetection::testCollision(CollisionCallback* callback) { + + assert(callback != nullptr); + + // Compute the broad-phase collision detection + computeBroadPhase(); + + // For each possible collision pair of bodies + map::iterator it; + for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ) { + + OverlappingPair* pair = it->second; + + ProxyShape* shape1 = pair->getShape1(); + ProxyShape* shape2 = pair->getShape2(); + + // Check if the collision filtering allows collision between the two shapes and + // that the two shapes are still overlapping. + if (((shape1->getCollideWithMaskBits() & shape2->getCollisionCategoryBits()) != 0 && + (shape1->getCollisionCategoryBits() & shape2->getCollideWithMaskBits()) != 0) && + mBroadPhaseAlgorithm.testOverlappingShapes(shape1, shape2)) { + + // Compute the middle-phase collision detection between the two shapes + NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(shape1, shape2); + + const CollisionShapeType shape1Type = shape1->getCollisionShape()->getType(); + const CollisionShapeType shape2Type = shape2->getCollisionShape()->getType(); + + // For each narrow-phase info object + while (narrowPhaseInfo != nullptr) { + + // Select the narrow phase algorithm to use according to the two collision shapes + const int shape1Index = static_cast(shape1Type); + const int shape2Index = static_cast(shape2Type); + NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Index][shape2Index]; + + // If there is a collision algorithm for those two kinds of shapes + if (narrowPhaseAlgorithm != nullptr) { + + // Use the narrow-phase collision detection algorithm to check + // if there really is a collision. If a collision occurs, the + // notifyContact() callback method will be called. + ContactPointInfo contactPointInfo; + if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactPointInfo)) { + + CollisionCallback::CollisionCallbackInfo collisionInfo(contactPointInfo, shape1->getBody(), + shape2->getBody(), shape1, shape2); + + // Report the contact to the user + callback->notifyContact(collisionInfo); + } + } + + NarrowPhaseInfo* currentNarrowPhaseInfo = narrowPhaseInfo; + narrowPhaseInfo = narrowPhaseInfo->next; + + // Release the allocated memory + mMemoryAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); + } + } + } +} + // Fill-in the collision detection matrix void CollisionDetection::fillInCollisionMatrix() { @@ -528,9 +1050,3 @@ EventListener* CollisionDetection::getWorldEventListener() { PoolAllocator& CollisionDetection::getWorldMemoryAllocator() { return mWorld->mPoolAllocator; } - -// Called by a narrow-phase collision algorithm when a new contact has been found -void TestCollisionBetweenShapesCallback::notifyContact(OverlappingPair* overlappingPair, - const ContactPointInfo& contactInfo) { - mCollisionCallback->notifyContact(contactInfo); -} diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index 0fe486c4..3bb27366 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -33,6 +33,7 @@ #include "engine/EventListener.h" #include "narrowphase/DefaultCollisionDispatch.h" #include "memory/PoolAllocator.h" +#include "memory/SingleFrameAllocator.h" #include "constraint/ContactPoint.h" #include #include @@ -46,29 +47,7 @@ namespace reactphysics3d { class BroadPhaseAlgorithm; class CollisionWorld; class CollisionCallback; - -// Class TestCollisionBetweenShapesCallback -class TestCollisionBetweenShapesCallback : public NarrowPhaseCallback { - - private: - - CollisionCallback* mCollisionCallback; - - public: - - // Constructor - TestCollisionBetweenShapesCallback(CollisionCallback* callback) - : mCollisionCallback(callback) { - - } - - // Destructor - virtual ~TestCollisionBetweenShapesCallback() { } - - // Called by a narrow-phase collision algorithm when a new contact has been found - virtual void notifyContact(OverlappingPair* overlappingPair, - const ContactPointInfo& contactInfo) override; -}; +class OverlapCallback; // Class CollisionDetection /** @@ -77,7 +56,7 @@ class TestCollisionBetweenShapesCallback : public NarrowPhaseCallback { * collide and then we run a narrow-phase algorithm to compute the * collision contacts between bodies. */ -class CollisionDetection : public NarrowPhaseCallback { +class CollisionDetection { private : @@ -95,9 +74,15 @@ class CollisionDetection : public NarrowPhaseCallback { /// Reference to the memory allocator PoolAllocator& mMemoryAllocator; + /// Reference to the single frame memory allocator + SingleFrameAllocator& mSingleFrameAllocator; + /// Pointer to the physics world CollisionWorld* mWorld; + /// Pointer to the first narrow-phase info of the linked list + NarrowPhaseInfo* mNarrowPhaseInfoList; + /// Broad-phase overlapping pairs std::map mOverlappingPairs; @@ -111,6 +96,7 @@ class CollisionDetection : public NarrowPhaseCallback { // TODO : Delete this GJKAlgorithm mNarrowPhaseGJKAlgorithm; + // TODO : Maybe delete this set (what is the purpose ?) /// Set of pair of bodies that cannot collide between each other std::set mNoCollisionPairs; @@ -122,6 +108,9 @@ class CollisionDetection : public NarrowPhaseCallback { /// Compute the broad-phase collision detection void computeBroadPhase(); + /// Compute the middle-phase collision detection + void computeMiddlePhase(); + /// Compute the narrow-phase collision detection void computeNarrowPhase(); @@ -137,13 +126,20 @@ class CollisionDetection : public NarrowPhaseCallback { /// Add all the contact manifold of colliding pairs to their bodies void addAllContactManifoldsToBodies(); + + /// Compute the concave vs convex middle-phase algorithm for a given pair of bodies + void computeConvexVsConcaveMiddlePhase(OverlappingPair* pair, Allocator& allocator, + NarrowPhaseInfo** firstNarrowPhaseInfo); + + /// Compute the middle-phase collision detection between two proxy shapes + NarrowPhaseInfo* computeMiddlePhaseForProxyShapes(ProxyShape* shape1, ProxyShape* shape2); public : // -------------------- Methods -------------------- // /// Constructor - CollisionDetection(CollisionWorld* world, PoolAllocator& memoryAllocator); + CollisionDetection(CollisionWorld* world, PoolAllocator& memoryAllocator, SingleFrameAllocator& singleFrameAllocator); /// Destructor ~CollisionDetection() = default; @@ -183,35 +179,42 @@ class CollisionDetection : public NarrowPhaseCallback { /// Compute the collision detection void computeCollisionDetection(); - /// Compute the collision detection - void testCollisionBetweenShapes(CollisionCallback* callback, - const std::set& shapes1, - const std::set& shapes2); - + // TODO : Remove this method /// Report collision between two sets of shapes - void reportCollisionBetweenShapes(CollisionCallback* callback, - const std::set& shapes1, - const std::set& shapes2) ; + //void reportCollisionBetweenShapes(CollisionCallback* callback, + // const std::set& shapes1, + // const std::set& shapes2) ; /// Ray casting method void raycast(RaycastCallback* raycastCallback, const Ray& ray, unsigned short raycastWithCategoryMaskBits) const; - /// Test if the AABBs of two bodies overlap - bool testAABBOverlap(const CollisionBody* body1, - const CollisionBody* body2) const; + /// Report all the bodies that overlap with the aabb in parameter + void testAABBOverlap(const AABB& aabb, OverlapCallback* overlapCallback, unsigned short categoryMaskBits = 0xFFFF); - /// Test if the AABBs of two proxy shapes overlap - bool testAABBOverlap(const ProxyShape* shape1, - const ProxyShape* shape2) const; + /// Return true if two bodies overlap + bool testOverlap(CollisionBody* body1, CollisionBody* body2); + + /// Report all the bodies that overlap with the body in parameter + void testOverlap(CollisionBody* body, OverlapCallback* overlapCallback, unsigned short categoryMaskBits = 0xFFFF); + + /// Test and report collisions between two bodies + void testCollision(CollisionBody* body1, CollisionBody* body2, CollisionCallback* callback); + + /// Test and report collisions between a body and all the others bodies of the world + void testCollision(CollisionBody* body, CollisionCallback* callback, unsigned short categoryMaskBits = 0xFFFF); + + /// Test and report collisions between all shapes of the world + void testCollision(CollisionCallback* callback); /// Allow the broadphase to notify the collision detection about an overlapping pair. void broadPhaseNotifyOverlappingPair(ProxyShape* shape1, ProxyShape* shape2); + // TODO : Remove this method /// Compute the narrow-phase collision detection - void computeNarrowPhaseBetweenShapes(CollisionCallback* callback, - const std::set& shapes1, - const std::set& shapes2); + //void computeNarrowPhaseBetweenShapes(CollisionCallback* callback, + // const std::set& shapes1, + // const std::set& shapes2); /// Return a pointer to the world CollisionWorld* getWorld(); @@ -222,12 +225,6 @@ class CollisionDetection : public NarrowPhaseCallback { /// Return a reference to the world memory allocator PoolAllocator& getWorldMemoryAllocator(); - /// Called by a narrow-phase collision algorithm when a new contact has been found - virtual void notifyContact(OverlappingPair* overlappingPair, const ContactPointInfo& contactInfo) override; - - /// Create a new contact - void createContact(OverlappingPair* overlappingPair, const ContactPointInfo& contactInfo); - // -------------------- Friendship -------------------- // friend class DynamicsWorld; @@ -244,8 +241,6 @@ inline NarrowPhaseAlgorithm* CollisionDetection::getCollisionAlgorithm(Collision inline void CollisionDetection::setCollisionDispatch(CollisionDispatch* collisionDispatch) { mCollisionDispatch = collisionDispatch; - mCollisionDispatch->init(this, &mMemoryAllocator); - // Fill-in the collision matrix with the new algorithms to use fillInCollisionMatrix(); } @@ -299,18 +294,6 @@ inline void CollisionDetection::raycast(RaycastCallback* raycastCallback, mBroadPhaseAlgorithm.raycast(ray, rayCastTest, raycastWithCategoryMaskBits); } -// Test if the AABBs of two proxy shapes overlap -inline bool CollisionDetection::testAABBOverlap(const ProxyShape* shape1, - const ProxyShape* shape2) const { - - // If one of the shape's body is not active, we return no overlap - if (!shape1->getBody()->isActive() || !shape2->getBody()->isActive()) { - return false; - } - - return mBroadPhaseAlgorithm.testOverlappingShapes(shape1, shape2); -} - // Return a pointer to the world inline CollisionWorld* CollisionDetection::getWorld() { return mWorld; diff --git a/src/collision/ContactManifoldSet.cpp b/src/collision/ContactManifoldSet.cpp index 26f3a66f..a7dc9d2e 100644 --- a/src/collision/ContactManifoldSet.cpp +++ b/src/collision/ContactManifoldSet.cpp @@ -33,7 +33,7 @@ ContactManifoldSet::ContactManifoldSet(ProxyShape* shape1, ProxyShape* shape2, PoolAllocator& memoryAllocator, int nbMaxManifolds) : mNbMaxManifolds(nbMaxManifolds), mNbManifolds(0), mShape1(shape1), mShape2(shape2), mMemoryAllocator(memoryAllocator) { - assert(nbMaxManifolds >= 1); + } // Destructor diff --git a/src/collision/CollisionShapeInfo.h b/src/collision/NarrowPhaseInfo.h similarity index 59% rename from src/collision/CollisionShapeInfo.h rename to src/collision/NarrowPhaseInfo.h index 2e1d9504..b97a71be 100644 --- a/src/collision/CollisionShapeInfo.h +++ b/src/collision/NarrowPhaseInfo.h @@ -23,8 +23,8 @@ * * ********************************************************************************/ -#ifndef REACTPHYSICS3D_COLLISION_SHAPE_INFO_H -#define REACTPHYSICS3D_COLLISION_SHAPE_INFO_H +#ifndef REACTPHYSICS3D_NARROW_PHASE_INFO_H +#define REACTPHYSICS3D_NARROW_PHASE_INFO_H // Libraries #include "shapes/CollisionShape.h" @@ -34,37 +34,48 @@ namespace reactphysics3d { class OverlappingPair; -// Class CollisionShapeInfo +// Class NarrowPhaseInfo /** * This structure regroups different things about a collision shape. This is * used to pass information about a collision shape to a collision algorithm. */ -struct CollisionShapeInfo { +struct NarrowPhaseInfo { public: /// Broadphase overlapping pair OverlappingPair* overlappingPair; - /// Proxy shape - ProxyShape* proxyShape; + /// Pointer to the first collision shape to test collision with + const CollisionShape* collisionShape1; - /// Pointer to the collision shape - const CollisionShape* collisionShape; + /// Pointer to the second collision shape to test collision with + const CollisionShape* collisionShape2; - /// Transform that maps from collision shape local-space to world-space - Transform shapeToWorldTransform; + /// Transform that maps from collision shape 1 local-space to world-space + Transform shape1ToWorldTransform; + + /// Transform that maps from collision shape 2 local-space to world-space + Transform shape2ToWorldTransform; /// Cached collision data of the proxy shape - void** cachedCollisionData; + // TODO : Check if we can use separating axis in OverlappingPair instead of cachedCollisionData1 and cachedCollisionData2 + void** cachedCollisionData1; + + /// Cached collision data of the proxy shape + // TODO : Check if we can use separating axis in OverlappingPair instead of cachedCollisionData1 and cachedCollisionData2 + void** cachedCollisionData2; + + /// Pointer to the next element in the linked list + NarrowPhaseInfo* next; /// Constructor - CollisionShapeInfo(ProxyShape* proxyCollisionShape, const CollisionShape* shape, - const Transform& shapeLocalToWorldTransform, OverlappingPair* pair, - void** cachedData) - : overlappingPair(pair), proxyShape(proxyCollisionShape), collisionShape(shape), - shapeToWorldTransform(shapeLocalToWorldTransform), - cachedCollisionData(cachedData) { + NarrowPhaseInfo(OverlappingPair* pair, const CollisionShape* shape1, + const CollisionShape* shape2, const Transform& shape1Transform, + const Transform& shape2Transform, void** cachedData1, void** cachedData2) + : overlappingPair(pair), collisionShape1(shape1), collisionShape2(shape2), + shape1ToWorldTransform(shape1Transform), shape2ToWorldTransform(shape2Transform), + cachedCollisionData1(cachedData1), cachedCollisionData2(cachedData2), next(nullptr) { } }; diff --git a/src/collision/ProxyShape.h b/src/collision/ProxyShape.h index d7c81621..45c0add2 100644 --- a/src/collision/ProxyShape.h +++ b/src/collision/ProxyShape.h @@ -126,6 +126,12 @@ class ProxyShape { /// Return the local to world transform const Transform getLocalToWorldTransform() const; + /// Return the AABB of the proxy shape in world-space + const AABB getWorldAABB() const; + + /// Test if the proxy shape overlaps with a given AABB + bool testAABBOverlap(const AABB& worldAABB) const; + /// Return true if a point is inside the collision shape bool testPointInside(const Vector3& worldPoint); @@ -176,7 +182,7 @@ class ProxyShape { }; // Return the pointer to the cached collision data -inline void** ProxyShape::getCachedCollisionData() { +inline void** ProxyShape::getCachedCollisionData() { return &mCachedCollisionData; } @@ -249,6 +255,16 @@ inline const Transform ProxyShape::getLocalToWorldTransform() const { return mBody->mTransform * mLocalToBodyTransform; } +// Return the AABB of the proxy shape in world-space +/** + * @return The AABB of the proxy shape in world-space + */ +inline const AABB ProxyShape::getWorldAABB() const { + AABB aabb; + mCollisionShape->computeAABB(aabb, getLocalToWorldTransform()); + return aabb; +} + // Return the next proxy shape in the linked list of proxy shapes /** * @return Pointer to the next proxy shape in the linked list of proxy shapes @@ -320,6 +336,15 @@ inline void ProxyShape::setLocalScaling(const Vector3& scaling) { mBody->updateProxyShapeInBroadPhase(this, true); } +/// Test if the proxy shape overlaps with a given AABB +/** +* @param worldAABB The AABB (in world-space coordinates) that will be used to test overlap +* @return True if the given AABB overlaps with the AABB of the collision body +*/ +inline bool ProxyShape::testAABBOverlap(const AABB& worldAABB) const { + return worldAABB.testCollision(getWorldAABB()); +} + } #endif diff --git a/src/collision/broadphase/BroadPhaseAlgorithm.cpp b/src/collision/broadphase/BroadPhaseAlgorithm.cpp index 781273e5..bc03f44d 100644 --- a/src/collision/broadphase/BroadPhaseAlgorithm.cpp +++ b/src/collision/broadphase/BroadPhaseAlgorithm.cpp @@ -162,12 +162,25 @@ void BroadPhaseAlgorithm::updateProxyCollisionShape(ProxyShape* proxyShape, cons } } +void BroadPhaseAlgorithm::reportAllShapesOverlappingWithAABB(const AABB& aabb, + LinkedList& overlappingNodes) const { + + AABBOverlapCallback callback(overlappingNodes); + + // Ask the dynamic AABB tree to report all collision shapes that overlap with this AABB + mDynamicAABBTree.reportAllShapesOverlappingWithAABB(aabb, callback); +} + // Compute all the overlapping pairs of collision shapes -void BroadPhaseAlgorithm::computeOverlappingPairs() { +void BroadPhaseAlgorithm::computeOverlappingPairs(Allocator& allocator) { + + // TODO : Try to see if we can allocate potential pairs in single frame allocator // Reset the potential overlapping pairs mNbPotentialPairs = 0; + LinkedList overlappingNodes(allocator); + // For all collision shapes that have moved (or have been created) during the // last simulation step for (uint i=0; i(mDynamicAABBTree.getNodeDataPointer(pair->collisionShape1ID)); ProxyShape* shape2 = static_cast(mDynamicAABBTree.getNodeDataPointer(pair->collisionShape2ID)); - // Notify the collision detection about the overlapping pair - mCollisionDetection.broadPhaseNotifyOverlappingPair(shape1, shape2); + // If the two proxy collision shapes are from the same body, skip it + if (shape1->getBody()->getID() != shape2->getBody()->getID()) { + + // Notify the collision detection about the overlapping pair + mCollisionDetection.broadPhaseNotifyOverlappingPair(shape1, shape2); + } // Skip the duplicate overlapping pairs while (i < mNbPotentialPairs) { @@ -241,34 +264,41 @@ void BroadPhaseAlgorithm::computeOverlappingPairs() { } // Notify the broad-phase about a potential overlapping pair in the dynamic AABB tree -void BroadPhaseAlgorithm::notifyOverlappingNodes(int node1ID, int node2ID) { +void BroadPhaseAlgorithm::addOverlappingNodes(int referenceNodeId, const LinkedList& overlappingNodes) { - // If both the nodes are the same, we do not create store the overlapping pair - if (node1ID == node2ID) return; + // For each overlapping node in the linked list + LinkedList::ListElement* elem = overlappingNodes.getListHead(); + while (elem != nullptr) { - // If we need to allocate more memory for the array of potential overlapping pairs - if (mNbPotentialPairs == mNbAllocatedPotentialPairs) { + // If both the nodes are the same, we do not create store the overlapping pair + if (referenceNodeId != elem->data) { - // Allocate more memory for the array of potential pairs - BroadPhasePair* oldPairs = mPotentialPairs; - mNbAllocatedPotentialPairs *= 2; - mPotentialPairs = (BroadPhasePair*) malloc(mNbAllocatedPotentialPairs * sizeof(BroadPhasePair)); - assert(mPotentialPairs); - memcpy(mPotentialPairs, oldPairs, mNbPotentialPairs * sizeof(BroadPhasePair)); - free(oldPairs); + // If we need to allocate more memory for the array of potential overlapping pairs + if (mNbPotentialPairs == mNbAllocatedPotentialPairs) { + + // Allocate more memory for the array of potential pairs + BroadPhasePair* oldPairs = mPotentialPairs; + mNbAllocatedPotentialPairs *= 2; + mPotentialPairs = (BroadPhasePair*) malloc(mNbAllocatedPotentialPairs * sizeof(BroadPhasePair)); + assert(mPotentialPairs); + memcpy(mPotentialPairs, oldPairs, mNbPotentialPairs * sizeof(BroadPhasePair)); + free(oldPairs); + } + + // Add the new potential pair into the array of potential overlapping pairs + mPotentialPairs[mNbPotentialPairs].collisionShape1ID = std::min(referenceNodeId, elem->data); + mPotentialPairs[mNbPotentialPairs].collisionShape2ID = std::max(referenceNodeId, elem->data); + mNbPotentialPairs++; + } + + elem = elem->next; } - - // Add the new potential pair into the array of potential overlapping pairs - mPotentialPairs[mNbPotentialPairs].collisionShape1ID = std::min(node1ID, node2ID); - mPotentialPairs[mNbPotentialPairs].collisionShape2ID = std::max(node1ID, node2ID); - mNbPotentialPairs++; } // Called when a overlapping node has been found during the call to // DynamicAABBTree:reportAllShapesOverlappingWithAABB() void AABBOverlapCallback::notifyOverlappingNode(int nodeId) { - - mBroadPhaseAlgorithm.notifyOverlappingNodes(mReferenceNodeId, nodeId); + mOverlappingNodes.insert(nodeId); } // Called for a broad-phase shape that has to be tested for raycast diff --git a/src/collision/broadphase/BroadPhaseAlgorithm.h b/src/collision/broadphase/BroadPhaseAlgorithm.h index 45c8acfb..8d2cda35 100644 --- a/src/collision/broadphase/BroadPhaseAlgorithm.h +++ b/src/collision/broadphase/BroadPhaseAlgorithm.h @@ -32,6 +32,7 @@ #include "collision/ProxyShape.h" #include "DynamicAABBTree.h" #include "engine/Profiler.h" +#include "containers/LinkedList.h" /// Namespace ReactPhysics3D namespace reactphysics3d { @@ -66,15 +67,13 @@ class AABBOverlapCallback : public DynamicAABBTreeOverlapCallback { private: - BroadPhaseAlgorithm& mBroadPhaseAlgorithm; - - int mReferenceNodeId; - public: + LinkedList& mOverlappingNodes; + // Constructor - AABBOverlapCallback(BroadPhaseAlgorithm& broadPhaseAlgo, int referenceNodeId) - : mBroadPhaseAlgorithm(broadPhaseAlgo), mReferenceNodeId(referenceNodeId) { + AABBOverlapCallback(LinkedList& overlappingNodes) + : mOverlappingNodes(overlappingNodes) { } @@ -197,15 +196,24 @@ class BroadPhaseAlgorithm { /// step and that need to be tested again for broad-phase overlapping. void removeMovedCollisionShape(int broadPhaseID); - /// Notify the broad-phase about a potential overlapping pair in the dynamic AABB tree - void notifyOverlappingNodes(int broadPhaseId1, int broadPhaseId2); + /// Add potential overlapping pairs in the dynamic AABB tree + void addOverlappingNodes(int broadPhaseId1, const LinkedList& overlappingNodes); + + /// Report all the shapes that are overlapping with a given AABB + void reportAllShapesOverlappingWithAABB(const AABB& aabb, LinkedList& overlappingNodes) const; /// Compute all the overlapping pairs of collision shapes - void computeOverlappingPairs(); + void computeOverlappingPairs(Allocator& allocator); + + /// Return the proxy shape corresponding to the broad-phase node id in parameter + ProxyShape* getProxyShapeForBroadPhaseId(int broadPhaseId) const; /// Return true if the two broad-phase collision shapes are overlapping bool testOverlappingShapes(const ProxyShape* shape1, const ProxyShape* shape2) const; + /// Return the fat AABB of a given broad-phase shape + const AABB& getFatAABB(int broadPhaseId) const; + /// Ray casting method void raycast(const Ray& ray, RaycastTest& raycastTest, unsigned short raycastWithCategoryMaskBits) const; @@ -232,6 +240,11 @@ inline bool BroadPhaseAlgorithm::testOverlappingShapes(const ProxyShape* shape1, return aabb1.testCollision(aabb2); } +// Return the fat AABB of a given broad-phase shape +inline const AABB& BroadPhaseAlgorithm::getFatAABB(int broadPhaseId) const { + return mDynamicAABBTree.getFatAABB(broadPhaseId); +} + // Ray casting method inline void BroadPhaseAlgorithm::raycast(const Ray& ray, RaycastTest& raycastTest, unsigned short raycastWithCategoryMaskBits) const { @@ -243,6 +256,11 @@ inline void BroadPhaseAlgorithm::raycast(const Ray& ray, RaycastTest& raycastTes mDynamicAABBTree.raycast(ray, broadPhaseRaycastCallback); } +// Return the proxy shape corresponding to the broad-phase node id in parameter +inline ProxyShape* BroadPhaseAlgorithm::getProxyShapeForBroadPhaseId(int broadPhaseId) const { + return static_cast(mDynamicAABBTree.getNodeDataPointer(broadPhaseId)); +} + } #endif diff --git a/src/collision/broadphase/DynamicAABBTree.cpp b/src/collision/broadphase/DynamicAABBTree.cpp index 7efd86ac..f829c000 100644 --- a/src/collision/broadphase/DynamicAABBTree.cpp +++ b/src/collision/broadphase/DynamicAABBTree.cpp @@ -26,7 +26,7 @@ // Libraries #include "DynamicAABBTree.h" #include "BroadPhaseAlgorithm.h" -#include "memory/Stack.h" +#include "containers/Stack.h" #include "engine/Profiler.h" using namespace reactphysics3d; diff --git a/src/collision/narrowphase/CollisionDispatch.h b/src/collision/narrowphase/CollisionDispatch.h index 6e027721..230ebbb3 100644 --- a/src/collision/narrowphase/CollisionDispatch.h +++ b/src/collision/narrowphase/CollisionDispatch.h @@ -49,11 +49,6 @@ class CollisionDispatch { /// Destructor virtual ~CollisionDispatch() = default; - /// Initialize the collision dispatch configuration - virtual void init(CollisionDetection* collisionDetection, - PoolAllocator* memoryAllocator) { - - } /// Select and return the narrow-phase collision detection algorithm to /// use between two types of collision shapes. diff --git a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp index 1e3c86c6..c0da7611 100644 --- a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp +++ b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp @@ -33,94 +33,111 @@ using namespace reactphysics3d; -// Return true and compute a contact info if the two bounding volumes collide -void ConcaveVsConvexAlgorithm::testCollision(const CollisionShapeInfo& shape1Info, - const CollisionShapeInfo& shape2Info, - NarrowPhaseCallback* narrowPhaseCallback) { - - ProxyShape* convexProxyShape; - ProxyShape* concaveProxyShape; - const ConvexShape* convexShape; - const ConcaveShape* concaveShape; - - // Collision shape 1 is convex, collision shape 2 is concave - if (shape1Info.collisionShape->isConvex()) { - convexProxyShape = shape1Info.proxyShape; - convexShape = static_cast(shape1Info.collisionShape); - concaveProxyShape = shape2Info.proxyShape; - concaveShape = static_cast(shape2Info.collisionShape); - } - else { // Collision shape 2 is convex, collision shape 1 is concave - convexProxyShape = shape2Info.proxyShape; - convexShape = static_cast(shape2Info.collisionShape); - concaveProxyShape = shape1Info.proxyShape; - concaveShape = static_cast(shape1Info.collisionShape); - } - - // Set the parameters of the callback object - ConvexVsTriangleCallback convexVsTriangleCallback; - convexVsTriangleCallback.setCollisionDetection(mCollisionDetection); - convexVsTriangleCallback.setConvexShape(convexShape); - convexVsTriangleCallback.setConcaveShape(concaveShape); - convexVsTriangleCallback.setProxyShapes(convexProxyShape, concaveProxyShape); - convexVsTriangleCallback.setOverlappingPair(shape1Info.overlappingPair); - - // Compute the convex shape AABB in the local-space of the convex shape - AABB aabb; - convexShape->computeAABB(aabb, convexProxyShape->getLocalToWorldTransform()); - - // If smooth mesh collision is enabled for the concave mesh - if (concaveShape->getIsSmoothMeshCollisionEnabled()) { - - std::vector contactPoints; - - SmoothCollisionNarrowPhaseCallback smoothNarrowPhaseCallback(contactPoints); - - convexVsTriangleCallback.setNarrowPhaseCallback(&smoothNarrowPhaseCallback); - - // Call the convex vs triangle callback for each triangle of the concave shape - concaveShape->testAllTriangles(convexVsTriangleCallback, aabb); - - // Run the smooth mesh collision algorithm - processSmoothMeshCollision(shape1Info.overlappingPair, contactPoints, narrowPhaseCallback); - } - else { - - convexVsTriangleCallback.setNarrowPhaseCallback(narrowPhaseCallback); - - // Call the convex vs triangle callback for each triangle of the concave shape - concaveShape->testAllTriangles(convexVsTriangleCallback, aabb); - } -} - -// Test collision between a triangle and the convex mesh shape -void ConvexVsTriangleCallback::testTriangle(const Vector3* trianglePoints) { +// Report collision between a triangle of a concave shape and the convex mesh shape (for middle-phase) +void MiddlePhaseTriangleCallback::testTriangle(const Vector3* trianglePoints) { // Create a triangle collision shape decimal margin = mConcaveShape->getTriangleMargin(); - TriangleShape triangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], margin); + TriangleShape* triangleShape = new (mAllocator.allocate(sizeof(TriangleShape))) + TriangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], margin); - // Select the collision algorithm to use between the triangle and the convex shape - NarrowPhaseAlgorithm* algo = mCollisionDetection->getCollisionAlgorithm(triangleShape.getType(), - mConvexShape->getType()); - - // If there is no collision algorithm between those two kinds of shapes - if (algo == nullptr) return; - - // Notify the narrow-phase algorithm about the overlapping pair we are going to test - algo->setCurrentOverlappingPair(mOverlappingPair); - - // Create the CollisionShapeInfo objects - CollisionShapeInfo shapeConvexInfo(mConvexProxyShape, mConvexShape, mConvexProxyShape->getLocalToWorldTransform(), - mOverlappingPair, mConvexProxyShape->getCachedCollisionData()); - CollisionShapeInfo shapeConcaveInfo(mConcaveProxyShape, &triangleShape, - mConcaveProxyShape->getLocalToWorldTransform(), - mOverlappingPair, mConcaveProxyShape->getCachedCollisionData()); - - // Use the collision algorithm to test collision between the triangle and the other convex shape - algo->testCollision(shapeConvexInfo, shapeConcaveInfo, mNarrowPhaseCallback); + // Create a narrow phase info for the narrow-phase collision detection + NarrowPhaseInfo* firstNarrowPhaseInfo = narrowPhaseInfoList; + narrowPhaseInfoList = new (mAllocator.allocate(sizeof(NarrowPhaseInfo))) + NarrowPhaseInfo(mOverlappingPair, mConvexProxyShape->getCollisionShape(), + triangleShape, mConvexProxyShape->getLocalToWorldTransform(), + mConcaveProxyShape->getLocalToWorldTransform(), mConvexProxyShape->getCachedCollisionData(), + mConcaveProxyShape->getCachedCollisionData()); + narrowPhaseInfoList->next = firstNarrowPhaseInfo; } +// Return true and compute a contact info if the two bounding volumes collide +void ConcaveVsConvexAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + NarrowPhaseCallback* narrowPhaseCallback) { + +// ProxyShape* convexProxyShape; +// ProxyShape* concaveProxyShape; +// const ConvexShape* convexShape; +// const ConcaveShape* concaveShape; + +// // Collision shape 1 is convex, collision shape 2 is concave +// if (shape1Info.collisionShape->isConvex()) { +// convexProxyShape = shape1Info.proxyShape; +// convexShape = static_cast(shape1Info.collisionShape); +// concaveProxyShape = shape2Info.proxyShape; +// concaveShape = static_cast(shape2Info.collisionShape); +// } +// else { // Collision shape 2 is convex, collision shape 1 is concave +// convexProxyShape = shape2Info.proxyShape; +// convexShape = static_cast(shape2Info.collisionShape); +// concaveProxyShape = shape1Info.proxyShape; +// concaveShape = static_cast(shape1Info.collisionShape); +// } + +// // Set the parameters of the callback object +// ConvexVsTriangleCallback convexVsTriangleCallback; +// convexVsTriangleCallback.setCollisionDetection(mCollisionDetection); +// convexVsTriangleCallback.setConvexShape(convexShape); +// convexVsTriangleCallback.setConcaveShape(concaveShape); +// convexVsTriangleCallback.setProxyShapes(convexProxyShape, concaveProxyShape); +// convexVsTriangleCallback.setOverlappingPair(shape1Info.overlappingPair); + +// // Compute the convex shape AABB in the local-space of the convex shape +// AABB aabb; +// convexShape->computeAABB(aabb, convexProxyShape->getLocalToWorldTransform()); + +// // If smooth mesh collision is enabled for the concave mesh +// if (concaveShape->getIsSmoothMeshCollisionEnabled()) { + +// std::vector contactPoints; + +// SmoothCollisionNarrowPhaseCallback smoothNarrowPhaseCallback(contactPoints); + +// convexVsTriangleCallback.setNarrowPhaseCallback(&smoothNarrowPhaseCallback); + +// // Call the convex vs triangle callback for each triangle of the concave shape +// concaveShape->testAllTriangles(convexVsTriangleCallback, aabb); + +// // Run the smooth mesh collision algorithm +// processSmoothMeshCollision(shape1Info.overlappingPair, contactPoints, narrowPhaseCallback); +// } +// else { + +// convexVsTriangleCallback.setNarrowPhaseCallback(narrowPhaseCallback); + +// // Call the convex vs triangle callback for each triangle of the concave shape +// concaveShape->testAllTriangles(convexVsTriangleCallback, aabb); +// } +} + +//// Test collision between a triangle and the convex mesh shape +//void ConvexVsTriangleCallback::testTriangle(const Vector3* trianglePoints) { + +// // Create a triangle collision shape +// decimal margin = mConcaveShape->getTriangleMargin(); +// TriangleShape triangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], margin); + +// // Select the collision algorithm to use between the triangle and the convex shape +// NarrowPhaseAlgorithm* algo = mCollisionDetection->getCollisionAlgorithm(triangleShape.getType(), +// mConvexShape->getType()); + +// // If there is no collision algorithm between those two kinds of shapes +// if (algo == nullptr) return; + +// // Notify the narrow-phase algorithm about the overlapping pair we are going to test +// algo->setCurrentOverlappingPair(mOverlappingPair); + +// // Create the CollisionShapeInfo objects +// CollisionShapeInfo shapeConvexInfo(mConvexProxyShape, mConvexShape, mConvexProxyShape->getLocalToWorldTransform(), +// mOverlappingPair, mConvexProxyShape->getCachedCollisionData()); +// CollisionShapeInfo shapeConcaveInfo(mConcaveProxyShape, &triangleShape, +// mConcaveProxyShape->getLocalToWorldTransform(), +// mOverlappingPair, mConcaveProxyShape->getCachedCollisionData()); + +// // Use the collision algorithm to test collision between the triangle and the other convex shape +// algo->testCollision(shapeConvexInfo, shapeConcaveInfo, mNarrowPhaseCallback); +//} + // Process the concave triangle mesh collision using the smooth mesh collision algorithm described // by Pierre Terdiman (http://www.codercorner.com/MeshContacts.pdf). This is used to avoid the collision // issue with some internal edges. @@ -246,36 +263,37 @@ bool ConcaveVsConvexAlgorithm::hasVertexBeenProcessed(const std::unordered_multi return false; } -// Called by a narrow-phase collision algorithm when a new contact has been found -void SmoothCollisionNarrowPhaseCallback::notifyContact(OverlappingPair* overlappingPair, - const ContactPointInfo& contactInfo) { - Vector3 triangleVertices[3]; - bool isFirstShapeTriangle; - // If the collision shape 1 is the triangle - if (contactInfo.collisionShape1->getType() == CollisionShapeType::TRIANGLE) { - assert(contactInfo.collisionShape2->getType() != CollisionShapeType::TRIANGLE); +//// Called by a narrow-phase collision algorithm when a new contact has been found +//void SmoothCollisionNarrowPhaseCallback::notifyContact(OverlappingPair* overlappingPair, +// const ContactPointInfo& contactInfo) { +// Vector3 triangleVertices[3]; +// bool isFirstShapeTriangle; - const TriangleShape* triangleShape = static_cast(contactInfo.collisionShape1); - triangleVertices[0] = triangleShape->getVertex(0); - triangleVertices[1] = triangleShape->getVertex(1); - triangleVertices[2] = triangleShape->getVertex(2); +// // If the collision shape 1 is the triangle +// if (contactInfo.collisionShape1->getType() == CollisionShapeType::TRIANGLE) { +// assert(contactInfo.collisionShape2->getType() != CollisionShapeType::TRIANGLE); - isFirstShapeTriangle = true; - } - else { // If the collision shape 2 is the triangle - assert(contactInfo.collisionShape2->getType() == CollisionShapeType::TRIANGLE); +// const TriangleShape* triangleShape = static_cast(contactInfo.collisionShape1); +// triangleVertices[0] = triangleShape->getVertex(0); +// triangleVertices[1] = triangleShape->getVertex(1); +// triangleVertices[2] = triangleShape->getVertex(2); - const TriangleShape* triangleShape = static_cast(contactInfo.collisionShape2); - triangleVertices[0] = triangleShape->getVertex(0); - triangleVertices[1] = triangleShape->getVertex(1); - triangleVertices[2] = triangleShape->getVertex(2); +// isFirstShapeTriangle = true; +// } +// else { // If the collision shape 2 is the triangle +// assert(contactInfo.collisionShape2->getType() == CollisionShapeType::TRIANGLE); - isFirstShapeTriangle = false; - } - SmoothMeshContactInfo smoothContactInfo(contactInfo, isFirstShapeTriangle, triangleVertices[0], triangleVertices[1], triangleVertices[2]); +// const TriangleShape* triangleShape = static_cast(contactInfo.collisionShape2); +// triangleVertices[0] = triangleShape->getVertex(0); +// triangleVertices[1] = triangleShape->getVertex(1); +// triangleVertices[2] = triangleShape->getVertex(2); - // Add the narrow-phase contact into the list of contact to process for - // smooth mesh collision - mContactPoints.push_back(smoothContactInfo); -} +// isFirstShapeTriangle = false; +// } +// SmoothMeshContactInfo smoothContactInfo(contactInfo, isFirstShapeTriangle, triangleVertices[0], triangleVertices[1], triangleVertices[2]); + +// // Add the narrow-phase contact into the list of contact to process for +// // smooth mesh collision +// mContactPoints.push_back(smoothContactInfo); +//} diff --git a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h index bcd4ef8f..531615da 100644 --- a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h +++ b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h @@ -30,6 +30,7 @@ #include "NarrowPhaseAlgorithm.h" #include "collision/shapes/ConvexShape.h" #include "collision/shapes/ConcaveShape.h" +#include "memory/SingleFrameAllocator.h" #include /// Namespace ReactPhysics3D @@ -37,73 +38,43 @@ namespace reactphysics3d { // Class ConvexVsTriangleCallback /** - * This class is used to encapsulate a callback method for - * collision detection between the triangle of a concave mesh shape - * and a convex shape. + * This class is used to report a collision between the triangle + * of a concave mesh shape and a convex shape during the + * middle-phase algorithm */ -class ConvexVsTriangleCallback : public TriangleCallback { +class MiddlePhaseTriangleCallback : public TriangleCallback { protected: - /// Pointer to the collision detection object - CollisionDetection* mCollisionDetection; - - /// Narrow-phase collision callback - NarrowPhaseCallback* mNarrowPhaseCallback; - - /// Convex collision shape to test collision with - const ConvexShape* mConvexShape; - - /// Concave collision shape - const ConcaveShape* mConcaveShape; - - /// Proxy shape of the convex collision shape - ProxyShape* mConvexProxyShape; - - /// Proxy shape of the concave collision shape - ProxyShape* mConcaveProxyShape; - /// Broadphase overlapping pair OverlappingPair* mOverlappingPair; - /// Used to sort ContactPointInfos according to their penetration depth - static bool contactsDepthCompare(const ContactPointInfo& contact1, - const ContactPointInfo& contact2); + /// Pointer to the concave proxy shape + ProxyShape* mConcaveProxyShape; + + /// Pointer to the convex proxy shape + ProxyShape* mConvexProxyShape; + + /// Pointer to the concave collision shape + const ConcaveShape* mConcaveShape; + + /// Reference to the single-frame memory allocator + Allocator& mAllocator; public: - /// Destructor - virtual ~ConvexVsTriangleCallback() override = default; + /// Pointer to the first element of the linked-list of narrow-phase info + NarrowPhaseInfo* narrowPhaseInfoList; - /// Set the collision detection pointer - void setCollisionDetection(CollisionDetection* collisionDetection) { - mCollisionDetection = collisionDetection; - } + /// Constructor + MiddlePhaseTriangleCallback(OverlappingPair* overlappingPair, + ProxyShape* concaveProxyShape, + ProxyShape* convexProxyShape, const ConcaveShape* concaveShape, + Allocator& allocator) + :mOverlappingPair(overlappingPair), mConcaveProxyShape(concaveProxyShape), + mConvexProxyShape(convexProxyShape), mConcaveShape(concaveShape), + mAllocator(allocator), narrowPhaseInfoList(nullptr) { - /// Set the narrow-phase collision callback - void setNarrowPhaseCallback(NarrowPhaseCallback* callback) { - mNarrowPhaseCallback = callback; - } - - /// Set the convex collision shape to test collision with - void setConvexShape(const ConvexShape* convexShape) { - mConvexShape = convexShape; - } - - /// Set the concave collision shape - void setConcaveShape(const ConcaveShape* concaveShape) { - mConcaveShape = concaveShape; - } - - /// Set the broadphase overlapping pair - void setOverlappingPair(OverlappingPair* overlappingPair) { - mOverlappingPair = overlappingPair; - } - - /// Set the proxy shapes of the two collision shapes - void setProxyShapes(ProxyShape* convexProxyShape, ProxyShape* concaveProxyShape) { - mConvexProxyShape = convexProxyShape; - mConcaveProxyShape = concaveProxyShape; } /// Test collision between a triangle and the convex mesh shape @@ -148,13 +119,14 @@ struct ContactsDepthCompare { // return contact1.contactInfo.penetrationDepth < contact2.contactInfo.penetrationDepth; //} +// TODO : Delete this // Class SmoothCollisionNarrowPhaseCallback /** * This class is used as a narrow-phase callback to get narrow-phase contacts * of the concave triangle mesh to temporary store them in order to be used in * the smooth mesh collision algorithm if this one is enabled. */ -class SmoothCollisionNarrowPhaseCallback : public NarrowPhaseCallback { +class SmoothCollisionNarrowPhaseCallback { private: @@ -169,13 +141,9 @@ class SmoothCollisionNarrowPhaseCallback : public NarrowPhaseCallback { } - - /// Called by a narrow-phase collision algorithm when a new contact has been found - virtual void notifyContact(OverlappingPair* overlappingPair, - const ContactPointInfo& contactInfo) override; - }; +// TODO : Delete this // Class ConcaveVsConvexAlgorithm /** * This class is used to compute the narrow-phase collision detection @@ -183,7 +151,7 @@ class SmoothCollisionNarrowPhaseCallback : public NarrowPhaseCallback { * to use the GJK collision detection algorithm to compute the collision between * the convex shape and each of the triangles in the concave shape. */ -class ConcaveVsConvexAlgorithm : public NarrowPhaseAlgorithm { +class ConcaveVsConvexAlgorithm { protected : @@ -212,7 +180,7 @@ class ConcaveVsConvexAlgorithm : public NarrowPhaseAlgorithm { ConcaveVsConvexAlgorithm() = default; /// Destructor - virtual ~ConcaveVsConvexAlgorithm() override = default; + ~ConcaveVsConvexAlgorithm() = default; /// Private copy-constructor ConcaveVsConvexAlgorithm(const ConcaveVsConvexAlgorithm& algorithm) = delete; @@ -221,9 +189,8 @@ class ConcaveVsConvexAlgorithm : public NarrowPhaseAlgorithm { ConcaveVsConvexAlgorithm& operator=(const ConcaveVsConvexAlgorithm& algorithm) = delete; /// Compute a contact info if the two bounding volume collide - virtual void testCollision(const CollisionShapeInfo& shape1Info, - const CollisionShapeInfo& shape2Info, - NarrowPhaseCallback* narrowPhaseCallback) override; + void testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + NarrowPhaseCallback* narrowPhaseCallback); }; // Add a triangle vertex into the set of processed triangles diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.cpp b/src/collision/narrowphase/DefaultCollisionDispatch.cpp index f6812d74..35b1e50b 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.cpp +++ b/src/collision/narrowphase/DefaultCollisionDispatch.cpp @@ -29,16 +29,6 @@ using namespace reactphysics3d; -/// Initialize the collision dispatch configuration -void DefaultCollisionDispatch::init(CollisionDetection* collisionDetection, - PoolAllocator* memoryAllocator) { - - // Initialize the collision algorithms - mSphereVsSphereAlgorithm.init(collisionDetection, memoryAllocator); - mGJKAlgorithm.init(collisionDetection, memoryAllocator); - mConcaveVsConvexAlgorithm.init(collisionDetection, memoryAllocator); -} - // Select and return the narrow-phase collision detection algorithm to // use between two types of collision shapes. NarrowPhaseAlgorithm* DefaultCollisionDispatch::selectAlgorithm(int type1, int type2) { @@ -46,19 +36,14 @@ NarrowPhaseAlgorithm* DefaultCollisionDispatch::selectAlgorithm(int type1, int t CollisionShapeType shape1Type = static_cast(type1); CollisionShapeType shape2Type = static_cast(type2); - // Sphere vs Sphere algorithm - if (shape1Type == CollisionShapeType::SPHERE && shape2Type == CollisionShapeType::SPHERE) { - return &mSphereVsSphereAlgorithm; - } - // Concave vs Convex algorithm - else if ((!CollisionShape::isConvex(shape1Type) && CollisionShape::isConvex(shape2Type)) || - (!CollisionShape::isConvex(shape2Type) && CollisionShape::isConvex(shape1Type))) { - return &mConcaveVsConvexAlgorithm; - } // Convex vs Convex algorithm (GJK algorithm) - else if (CollisionShape::isConvex(shape1Type) && CollisionShape::isConvex(shape2Type)) { + if (CollisionShape::isConvex(shape1Type) && CollisionShape::isConvex(shape2Type)) { return &mGJKAlgorithm; } + // Sphere vs Sphere algorithm + else if (shape1Type == CollisionShapeType::SPHERE && shape2Type == CollisionShapeType::SPHERE) { + return &mSphereVsSphereAlgorithm; + } else { return nullptr; } diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.h b/src/collision/narrowphase/DefaultCollisionDispatch.h index 5dd07bf2..f62a6564 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.h +++ b/src/collision/narrowphase/DefaultCollisionDispatch.h @@ -47,9 +47,6 @@ class DefaultCollisionDispatch : public CollisionDispatch { /// Sphere vs Sphere collision algorithm SphereVsSphereAlgorithm mSphereVsSphereAlgorithm; - /// Concave vs Convex collision algorithm - ConcaveVsConvexAlgorithm mConcaveVsConvexAlgorithm; - /// GJK Algorithm GJKAlgorithm mGJKAlgorithm; @@ -61,10 +58,6 @@ class DefaultCollisionDispatch : public CollisionDispatch { /// Destructor virtual ~DefaultCollisionDispatch() override = default; - /// Initialize the collision dispatch configuration - virtual void init(CollisionDetection* collisionDetection, - PoolAllocator* memoryAllocator) override; - /// Select and return the narrow-phase collision detection algorithm to /// use between two types of collision shapes. virtual NarrowPhaseAlgorithm* selectAlgorithm(int type1, int type2) override; diff --git a/src/collision/narrowphase/EPA/EPAAlgorithm.cpp b/src/collision/narrowphase/EPA/EPAAlgorithm.cpp index 6fc19680..8779c33e 100644 --- a/src/collision/narrowphase/EPA/EPAAlgorithm.cpp +++ b/src/collision/narrowphase/EPA/EPAAlgorithm.cpp @@ -74,25 +74,22 @@ int EPAAlgorithm::isOriginInTetrahedron(const Vector3& p1, const Vector3& p2, /// the correct penetration depth. This method returns true if the EPA penetration /// depth computation has succeeded and false it has failed. bool EPAAlgorithm::computePenetrationDepthAndContactPoints(const VoronoiSimplex& simplex, - CollisionShapeInfo shape1Info, - const Transform& transform1, - CollisionShapeInfo shape2Info, - const Transform& transform2, + const NarrowPhaseInfo* narrowPhaseInfo, Vector3& v, - NarrowPhaseCallback* narrowPhaseCallback) { + ContactPointInfo& contactPointInfo) { PROFILE("EPAAlgorithm::computePenetrationDepthAndContactPoints()"); decimal gjkPenDepthSquare = v.lengthSquare(); - assert(shape1Info.collisionShape->isConvex()); - assert(shape2Info.collisionShape->isConvex()); + assert(narrowPhaseInfo->collisionShape1->isConvex()); + assert(narrowPhaseInfo->collisionShape2->isConvex()); - const ConvexShape* shape1 = static_cast(shape1Info.collisionShape); - const ConvexShape* shape2 = static_cast(shape2Info.collisionShape); + const ConvexShape* shape1 = static_cast(narrowPhaseInfo->collisionShape1); + const ConvexShape* shape2 = static_cast(narrowPhaseInfo->collisionShape2); - void** shape1CachedCollisionData = shape1Info.cachedCollisionData; - void** shape2CachedCollisionData = shape2Info.cachedCollisionData; + void** shape1CachedCollisionData = narrowPhaseInfo->cachedCollisionData1; + void** shape2CachedCollisionData = narrowPhaseInfo->cachedCollisionData2; Vector3 suppPointsA[MAX_SUPPORT_POINTS]; // Support points of object A in local coordinates Vector3 suppPointsB[MAX_SUPPORT_POINTS]; // Support points of object B in local coordinates @@ -103,12 +100,12 @@ bool EPAAlgorithm::computePenetrationDepthAndContactPoints(const VoronoiSimplex& // Transform a point from local space of body 2 to local // space of body 1 (the GJK algorithm is done in local space of body 1) - Transform body2Tobody1 = transform1.getInverse() * transform2; + Transform body2Tobody1 = narrowPhaseInfo->shape1ToWorldTransform.getInverse() * narrowPhaseInfo->shape2ToWorldTransform; // Matrix that transform a direction from local // space of body 1 into local space of body 2 - Quaternion rotateToBody2 = transform2.getOrientation().getInverse() * - transform1.getOrientation(); + Quaternion rotateToBody2 = narrowPhaseInfo->shape2ToWorldTransform.getOrientation().getInverse() * + narrowPhaseInfo->shape1ToWorldTransform.getOrientation(); // Get the simplex computed previously by the GJK algorithm int nbVertices = simplex.getSimplex(suppPointsA, suppPointsB, points); @@ -416,7 +413,7 @@ bool EPAAlgorithm::computePenetrationDepthAndContactPoints(const VoronoiSimplex& } while(nbTriangles > 0 && triangleHeap[0]->getDistSquare() <= upperBoundSquarePenDepth); // Compute the contact info - v = transform1.getOrientation() * triangle->getClosestPoint(); + v = narrowPhaseInfo->shape1ToWorldTransform.getOrientation() * triangle->getClosestPoint(); Vector3 pALocal = triangle->computeClosestPointOfObject(suppPointsA); Vector3 pBLocal = body2Tobody1.getInverse() * triangle->computeClosestPointOfObject(suppPointsB); Vector3 normal = v.getUnit(); @@ -430,10 +427,7 @@ bool EPAAlgorithm::computePenetrationDepthAndContactPoints(const VoronoiSimplex& if (penetrationDepth * penetrationDepth > gjkPenDepthSquare && penetrationDepth > 0) { // Create the contact info object - ContactPointInfo contactInfo(shape1Info.proxyShape, shape2Info.proxyShape, shape1Info.collisionShape, - shape2Info.collisionShape, normal, penetrationDepth, pALocal, pBLocal); - - narrowPhaseCallback->notifyContact(shape1Info.overlappingPair, contactInfo); + contactPointInfo.init(normal, penetrationDepth, pALocal, pBLocal); return true; } diff --git a/src/collision/narrowphase/EPA/EPAAlgorithm.h b/src/collision/narrowphase/EPA/EPAAlgorithm.h index 05a78eea..1d241540 100644 --- a/src/collision/narrowphase/EPA/EPAAlgorithm.h +++ b/src/collision/narrowphase/EPA/EPAAlgorithm.h @@ -29,7 +29,7 @@ // Libraries #include "collision/narrowphase/GJK/VoronoiSimplex.h" #include "collision/shapes/CollisionShape.h" -#include "collision/CollisionShapeInfo.h" +#include "collision/NarrowPhaseInfo.h" #include "constraint/ContactPoint.h" #include "collision/narrowphase/NarrowPhaseAlgorithm.h" #include "mathematics/mathematics.h" @@ -87,9 +87,6 @@ class EPAAlgorithm { // -------------------- Attributes -------------------- // - /// Reference to the memory allocator - PoolAllocator* mMemoryAllocator; - /// Triangle comparison operator TriangleComparison mTriangleComparison; @@ -119,17 +116,11 @@ class EPAAlgorithm { /// Deleted assignment operator EPAAlgorithm& operator=(const EPAAlgorithm& algorithm) = delete; - /// Initalize the algorithm - void init(PoolAllocator* memoryAllocator); - /// Compute the penetration depth with EPA algorithm. bool computePenetrationDepthAndContactPoints(const VoronoiSimplex& simplex, - CollisionShapeInfo shape1Info, - const Transform& transform1, - CollisionShapeInfo shape2Info, - const Transform& transform2, + const NarrowPhaseInfo* narrowPhaseInfo, Vector3& v, - NarrowPhaseCallback* narrowPhaseCallback); + ContactPointInfo &contactPointInfo); }; // Add a triangle face in the candidate triangle heap in the EPA algorithm @@ -150,11 +141,6 @@ inline void EPAAlgorithm::addFaceCandidate(TriangleEPA* triangle, TriangleEPA** } } -// Initalize the algorithm -inline void EPAAlgorithm::init(PoolAllocator* memoryAllocator) { - mMemoryAllocator = memoryAllocator; -} - } #endif diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp index b7916a53..dec43865 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp @@ -36,11 +36,6 @@ // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; -// Constructor -GJKAlgorithm::GJKAlgorithm() : NarrowPhaseAlgorithm() { - -} - // Compute a contact info if the two collision shapes collide. /// This method implements the Hybrid Technique for computing the penetration depth by /// running the GJK algorithm on original objects (without margin). If the shapes intersect @@ -50,9 +45,8 @@ GJKAlgorithm::GJKAlgorithm() : NarrowPhaseAlgorithm() { /// algorithm on the enlarged object to obtain a simplex polytope that contains the /// origin, they we give that simplex polytope to the EPA algorithm which will compute /// the correct penetration depth and contact points between the enlarged objects. -void GJKAlgorithm::testCollision(const CollisionShapeInfo& shape1Info, - const CollisionShapeInfo& shape2Info, - NarrowPhaseCallback* narrowPhaseCallback) { +bool GJKAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + ContactPointInfo& contactPointInfo) { PROFILE("GJKAlgorithm::testCollision()"); @@ -65,20 +59,20 @@ void GJKAlgorithm::testCollision(const CollisionShapeInfo& shape1Info, decimal prevDistSquare; bool contactFound = false; - assert(shape1Info.collisionShape->isConvex()); - assert(shape2Info.collisionShape->isConvex()); + assert(narrowPhaseInfo->collisionShape1->isConvex()); + assert(narrowPhaseInfo->collisionShape2->isConvex()); - const ConvexShape* shape1 = static_cast(shape1Info.collisionShape); - const ConvexShape* shape2 = static_cast(shape2Info.collisionShape); + const ConvexShape* shape1 = static_cast(narrowPhaseInfo->collisionShape1); + const ConvexShape* shape2 = static_cast(narrowPhaseInfo->collisionShape2); - void** shape1CachedCollisionData = shape1Info.cachedCollisionData; - void** shape2CachedCollisionData = shape2Info.cachedCollisionData; + void** shape1CachedCollisionData = narrowPhaseInfo->cachedCollisionData1; + void** shape2CachedCollisionData = narrowPhaseInfo->cachedCollisionData2; bool isPolytopeShape = shape1->isPolyhedron() && shape2->isPolyhedron(); // Get the local-space to world-space transforms - const Transform transform1 = shape1Info.shapeToWorldTransform; - const Transform transform2 = shape2Info.shapeToWorldTransform; + const Transform& transform1 = narrowPhaseInfo->shape1ToWorldTransform; + const Transform& transform2 = narrowPhaseInfo->shape2ToWorldTransform; // Transform a point from local space of body 2 to local // space of body 1 (the GJK algorithm is done in local space of body 1) @@ -92,13 +86,13 @@ void GJKAlgorithm::testCollision(const CollisionShapeInfo& shape1Info, // Initialize the margin (sum of margins of both objects) decimal margin = shape1->getMargin() + shape2->getMargin(); decimal marginSquare = margin * margin; - assert(margin > 0.0); + assert(margin > decimal(0.0)); // Create a simplex set VoronoiSimplex simplex; // Get the previous point V (last cached separating axis) - Vector3 v = mCurrentOverlappingPair->getCachedSeparatingAxis(); + Vector3 v = narrowPhaseInfo->overlappingPair->getCachedSeparatingAxis(); // Initialize the upper bound for the square distance decimal distSquare = DECIMAL_LARGEST; @@ -116,13 +110,13 @@ void GJKAlgorithm::testCollision(const CollisionShapeInfo& shape1Info, vDotw = v.dot(w); // If the enlarge objects (with margins) do not intersect - if (vDotw > 0.0 && vDotw * vDotw > distSquare * marginSquare) { + if (vDotw > decimal(0.0) && vDotw * vDotw > distSquare * marginSquare) { // Cache the current separating axis for frame coherence - mCurrentOverlappingPair->setCachedSeparatingAxis(v); + narrowPhaseInfo->overlappingPair->setCachedSeparatingAxis(v); // No intersection, we return - return; + return false; } // If the objects intersect only in the margins @@ -188,8 +182,7 @@ void GJKAlgorithm::testCollision(const CollisionShapeInfo& shape1Info, // again but on the enlarged objects to compute a simplex polytope that contains // the origin. Then, we give that simplex polytope to the EPA algorithm to compute // the correct penetration depth and contact points between the enlarged objects. - isEPAResultValid = computePenetrationDepthForEnlargedObjects(shape1Info, transform1, shape2Info, - transform2, narrowPhaseCallback, v); + isEPAResultValid = computePenetrationDepthForEnlargedObjects(narrowPhaseInfo, contactPointInfo, v); } if ((contactFound || !isEPAResultValid) && distSquare > MACHINE_EPSILON) { @@ -200,7 +193,7 @@ void GJKAlgorithm::testCollision(const CollisionShapeInfo& shape1Info, // Project those two points on the margins to have the closest points of both // object with the margins decimal dist = std::sqrt(distSquare); - assert(dist > 0.0); + assert(dist > decimal(0.0)); pA = (pA - (shape1->getMargin() / dist) * v); pB = body2Tobody1.getInverse() * (pB + (shape2->getMargin() / dist) * v); @@ -209,21 +202,22 @@ void GJKAlgorithm::testCollision(const CollisionShapeInfo& shape1Info, decimal penetrationDepth = margin - dist; // If the penetration depth is negative (due too numerical errors), there is no contact - if (penetrationDepth <= 0.0) { - return; + if (penetrationDepth <= decimal(0.0)) { + return false; } // Do not generate a contact point with zero normal length if (normal.lengthSquare() < MACHINE_EPSILON) { - return; + return false; } // Create the contact info object - ContactPointInfo contactInfo(shape1Info.proxyShape, shape2Info.proxyShape, shape1Info.collisionShape, - shape2Info.collisionShape, normal, penetrationDepth, pA, pB); + contactPointInfo.init(normal, penetrationDepth, pA, pB); - narrowPhaseCallback->notifyContact(shape1Info.overlappingPair, contactInfo); + return true; } + + return false; } /// This method runs the GJK algorithm on the two enlarged objects (with margin) @@ -231,11 +225,8 @@ void GJKAlgorithm::testCollision(const CollisionShapeInfo& shape1Info, /// assumed to intersect in the original objects (without margin). Therefore such /// a polytope must exist. Then, we give that polytope to the EPA algorithm to /// compute the correct penetration depth and contact points of the enlarged objects. -bool GJKAlgorithm::computePenetrationDepthForEnlargedObjects(const CollisionShapeInfo& shape1Info, - const Transform& transform1, - const CollisionShapeInfo& shape2Info, - const Transform& transform2, - NarrowPhaseCallback* narrowPhaseCallback, +bool GJKAlgorithm::computePenetrationDepthForEnlargedObjects(const NarrowPhaseInfo* narrowPhaseInfo, + ContactPointInfo& contactPointInfo, Vector3& v) { PROFILE("GJKAlgorithm::computePenetrationDepthForEnlargedObjects()"); @@ -247,24 +238,24 @@ bool GJKAlgorithm::computePenetrationDepthForEnlargedObjects(const CollisionShap decimal distSquare = DECIMAL_LARGEST; decimal prevDistSquare; - assert(shape1Info.collisionShape->isConvex()); - assert(shape2Info.collisionShape->isConvex()); + assert(narrowPhaseInfo->collisionShape1->isConvex()); + assert(narrowPhaseInfo->collisionShape2->isConvex()); - const ConvexShape* shape1 = static_cast(shape1Info.collisionShape); - const ConvexShape* shape2 = static_cast(shape2Info.collisionShape); + const ConvexShape* shape1 = static_cast(narrowPhaseInfo->collisionShape1); + const ConvexShape* shape2 = static_cast(narrowPhaseInfo->collisionShape2); bool isPolytopeShape = shape1->isPolyhedron() && shape2->isPolyhedron(); - void** shape1CachedCollisionData = shape1Info.cachedCollisionData; - void** shape2CachedCollisionData = shape2Info.cachedCollisionData; + void** shape1CachedCollisionData = narrowPhaseInfo->cachedCollisionData1; + void** shape2CachedCollisionData = narrowPhaseInfo->cachedCollisionData2; // Transform a point from local space of body 2 to local space // of body 1 (the GJK algorithm is done in local space of body 1) - Transform body2ToBody1 = transform1.getInverse() * transform2; + Transform body2ToBody1 = narrowPhaseInfo->shape1ToWorldTransform.getInverse() * narrowPhaseInfo->shape2ToWorldTransform; // Matrix that transform a direction from local space of body 1 into local space of body 2 - Matrix3x3 rotateToBody2 = transform2.getOrientation().getMatrix().getTranspose() * - transform1.getOrientation().getMatrix(); + Matrix3x3 rotateToBody2 = narrowPhaseInfo->shape2ToWorldTransform.getOrientation().getMatrix().getTranspose() * + narrowPhaseInfo->shape1ToWorldTransform.getOrientation().getMatrix(); do { // Compute the support points for the enlarged object A and B @@ -277,7 +268,7 @@ bool GJKAlgorithm::computePenetrationDepthForEnlargedObjects(const CollisionShap vDotw = v.dot(w); // If the enlarge objects do not intersect - if (vDotw > 0.0) { + if (vDotw > decimal(0.0)) { // No intersection, we return return false; @@ -308,9 +299,7 @@ bool GJKAlgorithm::computePenetrationDepthForEnlargedObjects(const CollisionShap // Give the simplex computed with GJK algorithm to the EPA algorithm // which will compute the correct penetration depth and contact points // between the two enlarged objects - return mAlgoEPA.computePenetrationDepthAndContactPoints(simplex, shape1Info, - transform1, shape2Info, transform2, - v, narrowPhaseCallback); + return mAlgoEPA.computePenetrationDepthAndContactPoints(simplex, narrowPhaseInfo, v, contactPointInfo); } // Use the GJK Algorithm to find if a point is inside a convex collision shape @@ -378,7 +367,6 @@ bool GJKAlgorithm::testPointInside(const Vector3& localPoint, ProxyShape* proxyS return true; } - // Ray casting algorithm agains a convex collision shape using the GJK Algorithm /// This method implements the GJK ray casting algorithm described by Gino Van Den Bergen in /// "Ray Casting against General Convex Objects with Application to Continuous Collision Detection". diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.h b/src/collision/narrowphase/GJK/GJKAlgorithm.h index b6cce5c2..e0dad891 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.h +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.h @@ -69,11 +69,8 @@ class GJKAlgorithm : public NarrowPhaseAlgorithm { // -------------------- Methods -------------------- // /// Compute the penetration depth for enlarged objects. - bool computePenetrationDepthForEnlargedObjects(const CollisionShapeInfo& shape1Info, - const Transform& transform1, - const CollisionShapeInfo& shape2Info, - const Transform& transform2, - NarrowPhaseCallback* narrowPhaseCallback, + bool computePenetrationDepthForEnlargedObjects(const NarrowPhaseInfo* narrowPhaseInfo, + ContactPointInfo& contactPointInfo, Vector3& v); public : @@ -81,7 +78,7 @@ class GJKAlgorithm : public NarrowPhaseAlgorithm { // -------------------- Methods -------------------- // /// Constructor - GJKAlgorithm(); + GJKAlgorithm() = default; /// Destructor ~GJKAlgorithm() = default; @@ -92,14 +89,9 @@ class GJKAlgorithm : public NarrowPhaseAlgorithm { /// Deleted assignment operator GJKAlgorithm& operator=(const GJKAlgorithm& algorithm) = delete; - /// Initalize the algorithm - virtual void init(CollisionDetection* collisionDetection, - PoolAllocator* memoryAllocator) override; - /// Compute a contact info if the two bounding volumes collide. - virtual void testCollision(const CollisionShapeInfo& shape1Info, - const CollisionShapeInfo& shape2Info, - NarrowPhaseCallback* narrowPhaseCallback) override; + virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + ContactPointInfo& contactPointInfo) override; /// Use the GJK Algorithm to find if a point is inside a convex collision shape bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape); @@ -108,13 +100,6 @@ class GJKAlgorithm : public NarrowPhaseAlgorithm { bool raycast(const Ray& ray, ProxyShape* proxyShape, RaycastInfo& raycastInfo); }; -// Initalize the algorithm -inline void GJKAlgorithm::init(CollisionDetection* collisionDetection, - PoolAllocator* memoryAllocator) { - NarrowPhaseAlgorithm::init(collisionDetection, memoryAllocator); - mAlgoEPA.init(memoryAllocator); -} - } #endif diff --git a/src/collision/narrowphase/NarrowPhaseAlgorithm.h b/src/collision/narrowphase/NarrowPhaseAlgorithm.h index 0759d138..f7f68907 100644 --- a/src/collision/narrowphase/NarrowPhaseAlgorithm.h +++ b/src/collision/narrowphase/NarrowPhaseAlgorithm.h @@ -31,7 +31,7 @@ #include "constraint/ContactPoint.h" #include "memory/PoolAllocator.h" #include "engine/OverlappingPair.h" -#include "collision/CollisionShapeInfo.h" +#include "collision/NarrowPhaseInfo.h" /// Namespace ReactPhysics3D namespace reactphysics3d { @@ -67,21 +67,12 @@ class NarrowPhaseAlgorithm { // -------------------- Attributes -------------------- // - /// Pointer to the collision detection object - CollisionDetection* mCollisionDetection; - - /// Pointer to the memory allocator - PoolAllocator* mMemoryAllocator; - - /// Overlapping pair of the bodies currently tested for collision - OverlappingPair* mCurrentOverlappingPair; - public : // -------------------- Methods -------------------- // /// Constructor - NarrowPhaseAlgorithm(); + NarrowPhaseAlgorithm() = default; /// Destructor virtual ~NarrowPhaseAlgorithm() = default; @@ -92,23 +83,10 @@ class NarrowPhaseAlgorithm { /// Deleted assignment operator NarrowPhaseAlgorithm& operator=(const NarrowPhaseAlgorithm& algorithm) = delete; - /// Initalize the algorithm - virtual void init(CollisionDetection* collisionDetection, PoolAllocator* memoryAllocator); - - /// Set the current overlapping pair of bodies - void setCurrentOverlappingPair(OverlappingPair* overlappingPair); - /// Compute a contact info if the two bounding volume collide - virtual void testCollision(const CollisionShapeInfo& shape1Info, - const CollisionShapeInfo& shape2Info, - NarrowPhaseCallback* narrowPhaseCallback)=0; + virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactPointInfo& contactPointInfo)=0; }; -// Set the current overlapping pair of bodies -inline void NarrowPhaseAlgorithm::setCurrentOverlappingPair(OverlappingPair* overlappingPair) { - mCurrentOverlappingPair = overlappingPair; -} - } #endif diff --git a/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp b/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp index 9d2c4baa..6b28372d 100644 --- a/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp @@ -30,17 +30,16 @@ // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; -void SphereVsSphereAlgorithm::testCollision(const CollisionShapeInfo& shape1Info, - const CollisionShapeInfo& shape2Info, - NarrowPhaseCallback* narrowPhaseCallback) { +bool SphereVsSphereAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + ContactPointInfo& contactPointInfo) { // Get the sphere collision shapes - const SphereShape* sphereShape1 = static_cast(shape1Info.collisionShape); - const SphereShape* sphereShape2 = static_cast(shape2Info.collisionShape); + const SphereShape* sphereShape1 = static_cast(narrowPhaseInfo->collisionShape1); + const SphereShape* sphereShape2 = static_cast(narrowPhaseInfo->collisionShape2); // Get the local-space to world-space transforms - const Transform& transform1 = shape1Info.shapeToWorldTransform; - const Transform& transform2 = shape2Info.shapeToWorldTransform; + const Transform& transform1 = narrowPhaseInfo->shape1ToWorldTransform; + const Transform& transform2 = narrowPhaseInfo->shape2ToWorldTransform; // Compute the distance between the centers Vector3 vectorBetweenCenters = transform2.getPosition() - transform1.getPosition(); @@ -60,11 +59,11 @@ void SphereVsSphereAlgorithm::testCollision(const CollisionShapeInfo& shape1Info decimal penetrationDepth = sumRadius - std::sqrt(squaredDistanceBetweenCenters); // Create the contact info object - ContactPointInfo contactInfo(shape1Info.proxyShape, shape2Info.proxyShape, shape1Info.collisionShape, - shape2Info.collisionShape, vectorBetweenCenters.getUnit(), penetrationDepth, - intersectionOnBody1, intersectionOnBody2); + contactPointInfo.init(vectorBetweenCenters.getUnit(), penetrationDepth, + intersectionOnBody1, intersectionOnBody2); - // Notify about the new contact - narrowPhaseCallback->notifyContact(shape1Info.overlappingPair, contactInfo); + return true; } + + return false; } diff --git a/src/collision/narrowphase/SphereVsSphereAlgorithm.h b/src/collision/narrowphase/SphereVsSphereAlgorithm.h index 525c55d5..24886f7f 100644 --- a/src/collision/narrowphase/SphereVsSphereAlgorithm.h +++ b/src/collision/narrowphase/SphereVsSphereAlgorithm.h @@ -61,9 +61,8 @@ class SphereVsSphereAlgorithm : public NarrowPhaseAlgorithm { SphereVsSphereAlgorithm& operator=(const SphereVsSphereAlgorithm& algorithm) = delete; /// Compute a contact info if the two bounding volume collide - virtual void testCollision(const CollisionShapeInfo& shape1Info, - const CollisionShapeInfo& shape2Info, - NarrowPhaseCallback* narrowPhaseCallback) override; + virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + ContactPointInfo& contactPointInfo) override; }; } diff --git a/src/constraint/ContactPoint.h b/src/constraint/ContactPoint.h index 994f5426..4028ed8f 100644 --- a/src/constraint/ContactPoint.h +++ b/src/constraint/ContactPoint.h @@ -28,7 +28,7 @@ // Libraries #include "body/CollisionBody.h" -#include "collision/CollisionShapeInfo.h" +#include "collision/NarrowPhaseInfo.h" #include "configuration.h" #include "mathematics/mathematics.h" #include "configuration.h" @@ -53,20 +53,6 @@ struct ContactPointInfo { // -------------------- Attributes -------------------- // - // TODO : Check if we really need the shape1, shape2, collisionShape1 and collisionShape2 fields - - /// First proxy shape of the contact - ProxyShape* shape1; - - /// Second proxy shape of the contact - ProxyShape* shape2; - - /// First collision shape - const CollisionShape* collisionShape1; - - /// Second collision shape - const CollisionShape* collisionShape2; - /// Normalized normal vector of the collision contact in world space Vector3 normal; @@ -82,13 +68,18 @@ struct ContactPointInfo { // -------------------- Methods -------------------- // /// Constructor - ContactPointInfo(ProxyShape* proxyShape1, ProxyShape* proxyShape2, const CollisionShape* collShape1, - const CollisionShape* collShape2, const Vector3& normal, decimal penetrationDepth, - const Vector3& localPoint1, const Vector3& localPoint2) - : shape1(proxyShape1), shape2(proxyShape2), collisionShape1(collShape1), collisionShape2(collShape2), - normal(normal), penetrationDepth(penetrationDepth), localPoint1(localPoint1), - localPoint2(localPoint2) { + ContactPointInfo() = default; + /// Destructor + ~ContactPointInfo() = default; + + /// Initialize the contact point info + void init(const Vector3& contactNormal, decimal penDepth, + const Vector3& localPt1, const Vector3& localPt2) { + normal = contactNormal; + penetrationDepth = penDepth; + localPoint1 = localPt1; + localPoint2 = localPt2; } }; diff --git a/src/containers/LinkedList.h b/src/containers/LinkedList.h new file mode 100644 index 00000000..281c134c --- /dev/null +++ b/src/containers/LinkedList.h @@ -0,0 +1,124 @@ +/******************************************************************************** +* 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_LINKED_LIST_H +#define REACTPHYSICS3D_LINKED_LIST_H + +// Libraries +#include "memory/Allocator.h" + +namespace reactphysics3d { + +// Class LinkedList +/** + * This class represents a simple generic linked list. + */ +template +class LinkedList { + + public: + + /// Element of the linked list + struct ListElement { + + /// Data of the list element + T data; + + /// Pointer to the next element of the list + ListElement* next; + + /// Constructor + ListElement(T elementData, ListElement* nextElement) + : data(elementData), next(nextElement) { + + } + }; + + private: + + // -------------------- Attributes -------------------- // + + /// Pointer to the first element of the list + ListElement* mListHead; + + /// Memory allocator used to allocate the list elements + Allocator& mAllocator; + + public: + + // -------------------- Methods -------------------- // + + /// Constructor + LinkedList(Allocator& allocator) : mListHead(nullptr), mAllocator(allocator) { + + } + + /// Destructor + ~LinkedList() { + reset(); + } + + /// Return the first element of the list + ListElement* getListHead() const; + + /// Insert an element at the beginning of the linked list + void insert(const T& data); + + /// Remove all the elements of the list + void reset(); + +}; + +// Return the first element of the list +template +inline typename LinkedList::ListElement* LinkedList::getListHead() const { + return mListHead; +} + +// Insert an element at the beginning of the linked list +template +inline void LinkedList::insert(const T& data) { + ListElement* element = new (mAllocator.allocate(sizeof(ListElement))) ListElement(data, mListHead); + mListHead = element; +} + +// Remove all the elements of the list +template +inline void LinkedList::reset() { + + // Release all the list elements + ListElement* element = mListHead; + while (element != nullptr) { + ListElement* nextElement = element->next; + mAllocator.release(element, sizeof(ListElement)); + element = nextElement; + } + + mListHead = nullptr; +} + +} + +#endif diff --git a/src/memory/Stack.h b/src/containers/Stack.h similarity index 100% rename from src/memory/Stack.h rename to src/containers/Stack.h diff --git a/src/engine/CollisionWorld.cpp b/src/engine/CollisionWorld.cpp index b1b004ec..d160021c 100644 --- a/src/engine/CollisionWorld.cpp +++ b/src/engine/CollisionWorld.cpp @@ -33,7 +33,8 @@ using namespace std; // Constructor CollisionWorld::CollisionWorld() - : mCollisionDetection(this, mPoolAllocator), mCurrentBodyID(0), + : mSingleFrameAllocator(SIZE_SINGLE_FRAME_ALLOCATOR_BYTES), + mCollisionDetection(this, mPoolAllocator, mSingleFrameAllocator), mCurrentBodyID(0), mEventListener(nullptr) { } @@ -148,119 +149,18 @@ bool CollisionWorld::testAABBOverlap(const CollisionBody* body1, return body1AABB.testCollision(body2AABB); } -// Test and report collisions between a given shape and all the others -// shapes of the world. +// Report all the bodies that overlap with the aabb in parameter /** - * @param shape Pointer to the proxy shape to test - * @param callback Pointer to the object with the callback method + * @param aabb AABB used to test for overlap + * @param overlapCallback Pointer to the callback class to report overlap + * @param categoryMaskBits bits mask used to filter the bodies to test overlap with */ -void CollisionWorld::testCollision(const ProxyShape* shape, - CollisionCallback* callback) { - - // Reset all the contact manifolds lists of each body - resetContactManifoldListsOfBodies(); - - // Create the sets of shapes - std::set shapes; - shapes.insert(shape->mBroadPhaseID); - std::set emptySet; - - // Perform the collision detection and report contacts - mCollisionDetection.testCollisionBetweenShapes(callback, shapes, emptySet); +inline void CollisionWorld::testAABBOverlap(const AABB& aabb, OverlapCallback* overlapCallback, unsigned short categoryMaskBits) { + mCollisionDetection.testAABBOverlap(aabb, overlapCallback, categoryMaskBits); } -// Test and report collisions between two given shapes -/** - * @param shape1 Pointer to the first proxy shape to test - * @param shape2 Pointer to the second proxy shape to test - * @param callback Pointer to the object with the callback method - */ -void CollisionWorld::testCollision(const ProxyShape* shape1, - const ProxyShape* shape2, - CollisionCallback* callback) { - - // Reset all the contact manifolds lists of each body - resetContactManifoldListsOfBodies(); - - // Create the sets of shapes - std::set shapes1; - shapes1.insert(shape1->mBroadPhaseID); - std::set shapes2; - shapes2.insert(shape2->mBroadPhaseID); - - // Perform the collision detection and report contacts - mCollisionDetection.testCollisionBetweenShapes(callback, shapes1, shapes2); -} - -// Test and report collisions between a body and all the others bodies of the -// world -/** - * @param body Pointer to the first body to test - * @param callback Pointer to the object with the callback method - */ -void CollisionWorld::testCollision(const CollisionBody* body, - CollisionCallback* callback) { - - // Reset all the contact manifolds lists of each body - resetContactManifoldListsOfBodies(); - - // Create the sets of shapes - std::set shapes1; - - // For each shape of the body - for (const ProxyShape* shape=body->getProxyShapesList(); shape != nullptr; - shape = shape->getNext()) { - shapes1.insert(shape->mBroadPhaseID); - } - - std::set emptySet; - - // Perform the collision detection and report contacts - mCollisionDetection.testCollisionBetweenShapes(callback, shapes1, emptySet); -} - -// Test and report collisions between two bodies -/** - * @param body1 Pointer to the first body to test - * @param body2 Pointer to the second body to test - * @param callback Pointer to the object with the callback method - */ -void CollisionWorld::testCollision(const CollisionBody* body1, - const CollisionBody* body2, - CollisionCallback* callback) { - - // Reset all the contact manifolds lists of each body - resetContactManifoldListsOfBodies(); - - // Create the sets of shapes - std::set shapes1; - for (const ProxyShape* shape=body1->getProxyShapesList(); shape != nullptr; - shape = shape->getNext()) { - shapes1.insert(shape->mBroadPhaseID); - } - - std::set shapes2; - for (const ProxyShape* shape=body2->getProxyShapesList(); shape != nullptr; - shape = shape->getNext()) { - shapes2.insert(shape->mBroadPhaseID); - } - - // Perform the collision detection and report contacts - mCollisionDetection.testCollisionBetweenShapes(callback, shapes1, shapes2); -} - -// Test and report collisions between all shapes of the world -/** - * @param callback Pointer to the object with the callback method - */ -void CollisionWorld::testCollision(CollisionCallback* callback) { - - // Reset all the contact manifolds lists of each body - resetContactManifoldListsOfBodies(); - - std::set emptySet; - - // Perform the collision detection and report contacts - mCollisionDetection.testCollisionBetweenShapes(callback, emptySet, emptySet); +// Return true if two bodies overlap +bool CollisionWorld::testOverlap(CollisionBody* body1, CollisionBody* body2) { + return mCollisionDetection.testOverlap(body1, body2); } diff --git a/src/engine/CollisionWorld.h b/src/engine/CollisionWorld.h index d04acb4e..dc162716 100644 --- a/src/engine/CollisionWorld.h +++ b/src/engine/CollisionWorld.h @@ -47,6 +47,7 @@ namespace reactphysics3d { // Declarations class CollisionCallback; +class OverlapCallback; // Class CollisionWorld /** @@ -60,6 +61,12 @@ class CollisionWorld { // -------------------- Attributes -------------------- // + /// Pool Memory allocator + PoolAllocator mPoolAllocator; + + /// Single frame Memory allocator + SingleFrameAllocator mSingleFrameAllocator; + /// Reference to the collision detection CollisionDetection mCollisionDetection; @@ -72,9 +79,6 @@ class CollisionWorld { /// List of free ID for rigid bodies std::vector mFreeBodiesIDs; - /// Pool Memory allocator - PoolAllocator mPoolAllocator; - /// Pointer to an event listener object EventListener* mEventListener; @@ -125,32 +129,23 @@ class CollisionWorld { bool testAABBOverlap(const CollisionBody* body1, const CollisionBody* body2) const; - /// Test if the AABBs of two proxy shapes overlap - bool testAABBOverlap(const ProxyShape* shape1, - const ProxyShape* shape2) const; + /// Report all the bodies that overlap with the AABB in parameter + void testAABBOverlap(const AABB& aabb, OverlapCallback* overlapCallback, unsigned short categoryMaskBits = 0xFFFF); - /// Test and report collisions between a given shape and all the others - /// shapes of the world - virtual void testCollision(const ProxyShape* shape, - CollisionCallback* callback); + /// Return true if two bodies overlap + bool testOverlap(CollisionBody* body1, CollisionBody* body2); - /// Test and report collisions between two given shapes - virtual void testCollision(const ProxyShape* shape1, - const ProxyShape* shape2, - CollisionCallback* callback); - - /// Test and report collisions between a body and all the others bodies of the - /// world - virtual void testCollision(const CollisionBody* body, - CollisionCallback* callback); + /// Report all the bodies that overlap with the body in parameter + void testOverlap(CollisionBody* body, OverlapCallback* overlapCallback, unsigned short categoryMaskBits = 0xFFFF); /// Test and report collisions between two bodies - virtual void testCollision(const CollisionBody* body1, - const CollisionBody* body2, - CollisionCallback* callback); + void testCollision(CollisionBody* body1, CollisionBody* body2, CollisionCallback* callback); + + /// Test and report collisions between a body and all the others bodies of the world + void testCollision(CollisionBody* body, CollisionCallback* callback, unsigned short categoryMaskBits = 0xFFFF); /// Test and report collisions between all shapes of the world - virtual void testCollision(CollisionCallback* callback); + void testCollision(CollisionCallback* callback); // -------------------- Friendship -------------------- // @@ -200,36 +195,100 @@ inline void CollisionWorld::raycast(const Ray& ray, mCollisionDetection.raycast(raycastCallback, ray, raycastWithCategoryMaskBits); } -// Test if the AABBs of two proxy shapes overlap +// Test and report collisions between two bodies /** - * @param shape1 Pointer to the first proxy shape to test - * @param shape2 Pointer to the second proxy shape to test - * @return + * @param body1 Pointer to the first body to test + * @param body2 Pointer to the second body to test + * @param callback Pointer to the object with the callback method */ -inline bool CollisionWorld::testAABBOverlap(const ProxyShape* shape1, - const ProxyShape* shape2) const { +inline void CollisionWorld::testCollision(CollisionBody* body1, CollisionBody* body2, CollisionCallback* callback) { + mCollisionDetection.testCollision(body1, body2, callback); +} - return mCollisionDetection.testAABBOverlap(shape1, shape2); +// Test and report collisions between a body and all the others bodies of the world +/** + * @param body Pointer to the body against which we need to test collision + * @param callback Pointer to the object with the callback method to report contacts + * @param categoryMaskBits Bits mask corresponding to the category of bodies we need to test collision with + */ +inline void CollisionWorld::testCollision(CollisionBody* body, CollisionCallback* callback, unsigned short categoryMaskBits) { + mCollisionDetection.testCollision(body, callback, categoryMaskBits); +} + +// Test and report collisions between all bodies of the world +/** + * @param callback Pointer to the object with the callback method to report contacts + */ +inline void CollisionWorld::testCollision(CollisionCallback* callback) { + mCollisionDetection.testCollision(callback); +} + +// Report all the bodies that overlap with the body in parameter +/** + * @param body Pointer to the collision body to test overlap with + * @param overlapCallback Pointer to the callback class to report overlap + * @param categoryMaskBits bits mask used to filter the bodies to test overlap with + */ +inline void CollisionWorld::testOverlap(CollisionBody* body, OverlapCallback* overlapCallback, unsigned short categoryMaskBits) { + mCollisionDetection.testOverlap(body, overlapCallback, categoryMaskBits); } // Class CollisionCallback /** * This class can be used to register a callback for collision test queries. * You should implement your own class inherited from this one and implement - * the notifyRaycastHit() method. This method will be called for each ProxyShape - * that is hit by the ray. + * the notifyContact() method. This method will called each time a contact + * point is reported. */ class CollisionCallback { public: + struct CollisionCallbackInfo { + + public: + const ContactPointInfo& contactPoint; + CollisionBody* body1; + CollisionBody* body2; + const ProxyShape* proxyShape1; + const ProxyShape* proxyShape2; + + // Constructor + CollisionCallbackInfo(const ContactPointInfo& point, CollisionBody* b1, CollisionBody* b2, + const ProxyShape* proxShape1, const ProxyShape* proxShape2) : + contactPoint(point), body1(b1), body2(b2), + proxyShape1(proxShape1), proxyShape2(proxShape2) { + + } + }; + /// Destructor virtual ~CollisionCallback() { } - /// This method will be called for contact - virtual void notifyContact(const ContactPointInfo& contactPointInfo)=0; + /// This method will be called for each reported contact point + virtual void notifyContact(const CollisionCallbackInfo& collisionCallbackInfo)=0; +}; + +// Class OverlapCallback +/** + * This class can be used to register a callback for collision overlap queries. + * You should implement your own class inherited from this one and implement + * the notifyOverlap() method. This method will called each time a contact + * point is reported. + */ +class OverlapCallback { + + public: + + /// Destructor + virtual ~OverlapCallback() { + + } + + /// This method will be called for each reported overlapping bodies + virtual void notifyOverlap(CollisionBody* collisionBody)=0; }; } diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index d52348f8..4f7bd15a 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -40,7 +40,6 @@ using namespace std; */ DynamicsWorld::DynamicsWorld(const Vector3 &gravity) : CollisionWorld(), - mSingleFrameAllocator(SIZE_SINGLE_FRAME_ALLOCATOR_BYTES), mContactSolver(mMapBodyToConstrainedVelocityIndex, mSingleFrameAllocator), mConstraintSolver(mMapBodyToConstrainedVelocityIndex), mNbVelocitySolverIterations(DEFAULT_VELOCITY_SOLVER_NB_ITERATIONS), @@ -829,117 +828,6 @@ void DynamicsWorld::enableSleeping(bool isSleepingEnabled) { } } -// Test and report collisions between a given shape and all the others -// shapes of the world. -/// This method should be called after calling the -/// DynamicsWorld::update() method that will compute the collisions. -/** - * @param shape Pointer to the proxy shape to test - * @param callback Pointer to the object with the callback method - */ -void DynamicsWorld::testCollision(const ProxyShape* shape, - CollisionCallback* callback) { - - // Create the sets of shapes - std::set shapes; - shapes.insert(shape->mBroadPhaseID); - std::set emptySet; - - // Perform the collision detection and report contacts - mCollisionDetection.reportCollisionBetweenShapes(callback, shapes, emptySet); -} - -// Test and report collisions between two given shapes. -/// This method should be called after calling the -/// DynamicsWorld::update() method that will compute the collisions. -/** - * @param shape1 Pointer to the first proxy shape to test - * @param shape2 Pointer to the second proxy shape to test - * @param callback Pointer to the object with the callback method - */ -void DynamicsWorld::testCollision(const ProxyShape* shape1, - const ProxyShape* shape2, - CollisionCallback* callback) { - - // Create the sets of shapes - std::set shapes1; - shapes1.insert(shape1->mBroadPhaseID); - std::set shapes2; - shapes2.insert(shape2->mBroadPhaseID); - - // Perform the collision detection and report contacts - mCollisionDetection.reportCollisionBetweenShapes(callback, shapes1, shapes2); -} - -// Test and report collisions between a body and all the others bodies of the -// world. -/// This method should be called after calling the -/// DynamicsWorld::update() method that will compute the collisions. -/** - * @param body Pointer to the first body to test - * @param callback Pointer to the object with the callback method - */ -void DynamicsWorld::testCollision(const CollisionBody* body, - CollisionCallback* callback) { - - // Create the sets of shapes - std::set shapes1; - - // For each shape of the body - for (const ProxyShape* shape=body->getProxyShapesList(); shape != nullptr; - shape = shape->getNext()) { - shapes1.insert(shape->mBroadPhaseID); - } - - std::set emptySet; - - // Perform the collision detection and report contacts - mCollisionDetection.reportCollisionBetweenShapes(callback, shapes1, emptySet); -} - -// Test and report collisions between two bodies. -/// This method should be called after calling the -/// DynamicsWorld::update() method that will compute the collisions. -/** - * @param body1 Pointer to the first body to test - * @param body2 Pointer to the second body to test - * @param callback Pointer to the object with the callback method - */ -void DynamicsWorld::testCollision(const CollisionBody* body1, - const CollisionBody* body2, - CollisionCallback* callback) { - - // Create the sets of shapes - std::set shapes1; - for (const ProxyShape* shape=body1->getProxyShapesList(); shape != nullptr; - shape = shape->getNext()) { - shapes1.insert(shape->mBroadPhaseID); - } - - std::set shapes2; - for (const ProxyShape* shape=body2->getProxyShapesList(); shape != nullptr; - shape = shape->getNext()) { - shapes2.insert(shape->mBroadPhaseID); - } - - // Perform the collision detection and report contacts - mCollisionDetection.reportCollisionBetweenShapes(callback, shapes1, shapes2); -} - -// Test and report collisions between all shapes of the world. -/// This method should be called after calling the -/// DynamicsWorld::update() method that will compute the collisions. -/** - * @param callback Pointer to the object with the callback method - */ -void DynamicsWorld::testCollision(CollisionCallback* callback) { - - std::set emptySet; - - // Perform the collision detection and report contacts - mCollisionDetection.reportCollisionBetweenShapes(callback, emptySet, emptySet); -} - /// Return the list of all contacts of the world std::vector DynamicsWorld::getContactsList() const { diff --git a/src/engine/DynamicsWorld.h b/src/engine/DynamicsWorld.h index 746e8255..b632dcf2 100644 --- a/src/engine/DynamicsWorld.h +++ b/src/engine/DynamicsWorld.h @@ -50,9 +50,6 @@ class DynamicsWorld : public CollisionWorld { // -------------------- Attributes -------------------- // - /// Single frame Memory allocator - SingleFrameAllocator mSingleFrameAllocator; - /// Contact solver ContactSolver mContactSolver; @@ -267,29 +264,6 @@ class DynamicsWorld : public CollisionWorld { /// Set an event listener object to receive events callbacks. void setEventListener(EventListener* eventListener); - /// Test and report collisions between a given shape and all the others - /// shapes of the world - virtual void testCollision(const ProxyShape* shape, - CollisionCallback* callback) override; - - /// Test and report collisions between two given shapes - virtual void testCollision(const ProxyShape* shape1, - const ProxyShape* shape2, - CollisionCallback* callback) override; - - /// Test and report collisions between a body and all - /// the others bodies of the world - virtual void testCollision(const CollisionBody* body, - CollisionCallback* callback) override; - - /// Test and report collisions between two bodies - virtual void testCollision(const CollisionBody* body1, - const CollisionBody* body2, - CollisionCallback* callback) override; - - /// Test and report collisions between all shapes of the world - virtual void testCollision(CollisionCallback* callback) override; - /// Return the list of all contacts of the world std::vector getContactsList() const; diff --git a/src/collision/narrowphase/NarrowPhaseAlgorithm.cpp b/src/memory/Allocator.h similarity index 75% rename from src/collision/narrowphase/NarrowPhaseAlgorithm.cpp rename to src/memory/Allocator.h index 782f8d6f..f7b9ac73 100644 --- a/src/collision/narrowphase/NarrowPhaseAlgorithm.cpp +++ b/src/memory/Allocator.h @@ -23,20 +23,34 @@ * * ********************************************************************************/ +#ifndef REACTPHYSICS3D_ALLOCATOR_H +#define REACTPHYSICS3D_ALLOCATOR_H + // Libraries -#include "NarrowPhaseAlgorithm.h" +#include -// We want to use the ReactPhysics3D namespace -using namespace reactphysics3d; +/// ReactPhysics3D namespace +namespace reactphysics3d { -// Constructor -NarrowPhaseAlgorithm::NarrowPhaseAlgorithm() - : mMemoryAllocator(nullptr), mCurrentOverlappingPair(nullptr) { +// Class Allocator +/** + * Abstract class with the basic interface of all the derived memory allocators + */ +class Allocator { + + public: + + /// Destructor + virtual ~Allocator() = default; + + /// Allocate memory of a given size (in bytes) and return a pointer to the + /// allocated memory. + virtual void* allocate(size_t size)=0; + + /// Release previously allocated memory. + virtual void release(void* pointer, size_t size)=0; +}; } -// Initalize the algorithm -void NarrowPhaseAlgorithm::init(CollisionDetection* collisionDetection, PoolAllocator* memoryAllocator) { - mCollisionDetection = collisionDetection; - mMemoryAllocator = memoryAllocator; -} +#endif diff --git a/src/memory/PoolAllocator.h b/src/memory/PoolAllocator.h index 2af762ca..71e11714 100644 --- a/src/memory/PoolAllocator.h +++ b/src/memory/PoolAllocator.h @@ -27,8 +27,8 @@ #define REACTPHYSICS3D_POOL_ALLOCATOR_H // Libraries -#include #include "configuration.h" +#include "Allocator.h" /// ReactPhysics3D namespace namespace reactphysics3d { @@ -40,7 +40,7 @@ namespace reactphysics3d { * efficiently. This implementation is inspired by the small block allocator * described here : http://www.codeproject.com/useritems/Small_Block_Allocator.asp */ -class PoolAllocator { +class PoolAllocator : public Allocator { private : @@ -129,14 +129,14 @@ class PoolAllocator { PoolAllocator(); /// Destructor - ~PoolAllocator(); + virtual ~PoolAllocator() override; /// Allocate memory of a given size (in bytes) and return a pointer to the /// allocated memory. - void* allocate(size_t size); + virtual void* allocate(size_t size) override; /// Release previously allocated memory. - void release(void* pointer, size_t size); + virtual void release(void* pointer, size_t size) override; }; diff --git a/src/memory/SingleFrameAllocator.h b/src/memory/SingleFrameAllocator.h index e3151f0a..cc030daa 100644 --- a/src/memory/SingleFrameAllocator.h +++ b/src/memory/SingleFrameAllocator.h @@ -27,7 +27,7 @@ #define REACTPHYSICS3D_SINGLE_FRAME_ALLOCATOR_H // Libraries -#include +#include "Allocator.h" #include "configuration.h" /// ReactPhysics3D namespace @@ -38,7 +38,7 @@ namespace reactphysics3d { * This class represent a memory allocator used to efficiently allocate * memory on the heap that is used during a single frame. */ -class SingleFrameAllocator { +class SingleFrameAllocator : public Allocator { private : @@ -61,13 +61,18 @@ class SingleFrameAllocator { SingleFrameAllocator(size_t totalSizeBytes); /// Destructor - ~SingleFrameAllocator(); + virtual ~SingleFrameAllocator() override; /// Allocate memory of a given size (in bytes) - void* allocate(size_t size); + virtual void* allocate(size_t size) override; + + /// Release previously allocated memory. + virtual void release(void* pointer, size_t size) override { } /// Reset the marker of the current allocated memory - void reset(); + virtual void reset(); + + }; From c7e977250d1eab8d64ee35d7811f346a1b7f197d Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 9 Jan 2017 21:34:31 +0100 Subject: [PATCH 045/248] Update tests of collision world according to changes in collision detection --- test/tests/collision/TestCollisionWorld.h | 51 ++++++++-------------- test/tests/collision/TestDynamicAABBTree.h | 6 +-- 2 files changed, 21 insertions(+), 36 deletions(-) diff --git a/test/tests/collision/TestCollisionWorld.h b/test/tests/collision/TestCollisionWorld.h index d778bcd5..94d44a98 100644 --- a/test/tests/collision/TestCollisionWorld.h +++ b/test/tests/collision/TestCollisionWorld.h @@ -28,6 +28,7 @@ // Libraries #include "reactphysics3d.h" +#include "Test.h" /// Reactphysics3D namespace namespace reactphysics3d { @@ -70,28 +71,28 @@ class WorldCollisionCallback : public CollisionCallback } // This method will be called for contact - virtual void notifyContact(const ContactPointInfo& contactPointInfo) override { + virtual void notifyContact(const CollisionCallbackInfo& collisionCallbackInfo) override { - if (isContactBetweenBodies(boxBody, sphere1Body, contactPointInfo)) { + if (isContactBetweenBodies(boxBody, sphere1Body, collisionCallbackInfo)) { boxCollideWithSphere1 = true; } - else if (isContactBetweenBodies(boxBody, cylinderBody, contactPointInfo)) { + else if (isContactBetweenBodies(boxBody, cylinderBody, collisionCallbackInfo)) { boxCollideWithCylinder = true; } - else if (isContactBetweenBodies(sphere1Body, cylinderBody, contactPointInfo)) { + else if (isContactBetweenBodies(sphere1Body, cylinderBody, collisionCallbackInfo)) { sphere1CollideWithCylinder = true; } - else if (isContactBetweenBodies(sphere1Body, sphere2Body, contactPointInfo)) { + else if (isContactBetweenBodies(sphere1Body, sphere2Body, collisionCallbackInfo)) { sphere1CollideWithSphere2 = true; } } bool isContactBetweenBodies(const CollisionBody* body1, const CollisionBody* body2, - const ContactPointInfo& contactPointInfo) { - return (contactPointInfo.shape1->getBody()->getID() == body1->getID() && - contactPointInfo.shape2->getBody()->getID() == body2->getID()) || - (contactPointInfo.shape2->getBody()->getID() == body1->getID() && - contactPointInfo.shape1->getBody()->getID() == body2->getID()); + const CollisionCallbackInfo& collisionCallbackInfo) { + return (collisionCallbackInfo.body1->getID() == body1->getID() && + collisionCallbackInfo.body2->getID() == body2->getID()) || + (collisionCallbackInfo.body2->getID() == body1->getID() && + collisionCallbackInfo.body1->getID() == body2->getID()); } }; @@ -197,10 +198,10 @@ class TestCollisionWorld : public Test { test(!mWorld->testAABBOverlap(mSphere1Body, mCylinderBody)); test(!mWorld->testAABBOverlap(mSphere1Body, mSphere2Body)); - test(mWorld->testAABBOverlap(mBoxProxyShape, mSphere1ProxyShape)); - test(mWorld->testAABBOverlap(mBoxProxyShape, mCylinderProxyShape)); - test(!mWorld->testAABBOverlap(mSphere1ProxyShape, mCylinderProxyShape)); - test(!mWorld->testAABBOverlap(mSphere1ProxyShape, mSphere2ProxyShape)); + test(mBoxProxyShape->testAABBOverlap(mSphere1ProxyShape->getWorldAABB())); + test(mBoxProxyShape->testAABBOverlap(mCylinderProxyShape->getWorldAABB())); + test(!mSphere1ProxyShape->testAABBOverlap(mCylinderProxyShape->getWorldAABB())); + test(!mSphere1ProxyShape->testAABBOverlap(mSphere2ProxyShape->getWorldAABB())); mCollisionCallback.reset(); mWorld->testCollision(mCylinderBody, &mCollisionCallback); @@ -223,20 +224,6 @@ class TestCollisionWorld : public Test { test(!mCollisionCallback.sphere1CollideWithCylinder); test(!mCollisionCallback.sphere1CollideWithSphere2); - mCollisionCallback.reset(); - mWorld->testCollision(mCylinderProxyShape, &mCollisionCallback); - test(!mCollisionCallback.boxCollideWithSphere1); - test(mCollisionCallback.boxCollideWithCylinder); - test(!mCollisionCallback.sphere1CollideWithCylinder); - test(!mCollisionCallback.sphere1CollideWithSphere2); - - mCollisionCallback.reset(); - mWorld->testCollision(mBoxProxyShape, mCylinderProxyShape, &mCollisionCallback); - test(!mCollisionCallback.boxCollideWithSphere1); - test(mCollisionCallback.boxCollideWithCylinder); - test(!mCollisionCallback.sphere1CollideWithCylinder); - test(!mCollisionCallback.sphere1CollideWithSphere2); - // Move sphere 1 to collide with sphere 2 mSphere1Body->setTransform(Transform(Vector3(30, 15, 10), Quaternion::identity())); @@ -282,10 +269,10 @@ class TestCollisionWorld : public Test { test(!mWorld->testAABBOverlap(mSphere1Body, mCylinderBody)); test(!mWorld->testAABBOverlap(mSphere1Body, mSphere2Body)); - test(!mWorld->testAABBOverlap(mBoxProxyShape, mSphere1ProxyShape)); - test(!mWorld->testAABBOverlap(mBoxProxyShape, mCylinderProxyShape)); - test(!mWorld->testAABBOverlap(mSphere1ProxyShape, mCylinderProxyShape)); - test(!mWorld->testAABBOverlap(mSphere1ProxyShape, mSphere2ProxyShape)); + test(!mBoxProxyShape->testAABBOverlap(mSphere1ProxyShape->getWorldAABB())); + test(!mBoxProxyShape->testAABBOverlap(mCylinderProxyShape->getWorldAABB())); + test(!mSphere1ProxyShape->testAABBOverlap(mCylinderProxyShape->getWorldAABB())); + test(!mSphere1ProxyShape->testAABBOverlap(mSphere2ProxyShape->getWorldAABB())); mBoxBody->setIsActive(true); mCylinderBody->setIsActive(true); diff --git a/test/tests/collision/TestDynamicAABBTree.h b/test/tests/collision/TestDynamicAABBTree.h index cb407738..7ab3202b 100644 --- a/test/tests/collision/TestDynamicAABBTree.h +++ b/test/tests/collision/TestDynamicAABBTree.h @@ -34,7 +34,7 @@ /// Reactphysics3D namespace namespace reactphysics3d { -class OverlapCallback : public DynamicAABBTreeOverlapCallback { +class TestOverlapCallback : public DynamicAABBTreeOverlapCallback { public : @@ -86,11 +86,9 @@ class TestDynamicAABBTree : public Test { // ---------- Atributes ---------- // - OverlapCallback mOverlapCallback; + TestOverlapCallback mOverlapCallback; DynamicTreeRaycastCallback mRaycastCallback; - - public : // ---------- Methods ---------- // From f2a6dde9132b3f860d7e110eb95a4313be7b5110 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 18 Jan 2017 23:05:43 +0100 Subject: [PATCH 046/248] Fix return value in EPA Algorithm --- src/collision/narrowphase/EPA/EPAAlgorithm.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/collision/narrowphase/EPA/EPAAlgorithm.cpp b/src/collision/narrowphase/EPA/EPAAlgorithm.cpp index 8779c33e..6afa7a10 100644 --- a/src/collision/narrowphase/EPA/EPAAlgorithm.cpp +++ b/src/collision/narrowphase/EPA/EPAAlgorithm.cpp @@ -127,7 +127,7 @@ bool EPAAlgorithm::computePenetrationDepthAndContactPoints(const VoronoiSimplex& // Only one point in the simplex (which should be the origin). // We have a touching contact with zero penetration depth. // We drop that kind of contact. Therefore, we return false - return true; + return false; case 2: { // The simplex returned by GJK is a line segment d containing the origin. From a50ae736637960d427d4286e7e327b0041660dda Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 19 Jan 2017 20:29:40 +0100 Subject: [PATCH 047/248] Fix issue in GJK algorithm --- src/collision/narrowphase/GJK/GJKAlgorithm.cpp | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp index dec43865..e1649af0 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp @@ -173,8 +173,6 @@ bool GJKAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, } while((isPolytopeShape && !simplex.isFull()) || (!isPolytopeShape && !simplex.isFull() && distSquare > MACHINE_EPSILON * simplex.getMaxLengthSquareOfAPoint())); - bool isEPAResultValid = false; - // If no contact has been found (penetration case) if (!contactFound) { @@ -182,10 +180,14 @@ bool GJKAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, // again but on the enlarged objects to compute a simplex polytope that contains // the origin. Then, we give that simplex polytope to the EPA algorithm to compute // the correct penetration depth and contact points between the enlarged objects. - isEPAResultValid = computePenetrationDepthForEnlargedObjects(narrowPhaseInfo, contactPointInfo, v); + if(computePenetrationDepthForEnlargedObjects(narrowPhaseInfo, contactPointInfo, v)) { + + // A contact has been found with EPA algorithm, we return true + return true; + } } - if ((contactFound || !isEPAResultValid) && distSquare > MACHINE_EPSILON) { + if (contactFound && distSquare > MACHINE_EPSILON) { // Compute the closet points of both objects (without the margins) simplex.computeClosestPointsOfAandB(pA, pB); From 99eb7cf82cc247b187c7ab051a08ec094553536e Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 19 Jan 2017 21:27:58 +0100 Subject: [PATCH 048/248] Fix issue in collision detection --- src/collision/CollisionDetection.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index c199859c..345c46bb 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -230,11 +230,11 @@ void CollisionDetection::computeMiddlePhase() { // Add all the narrow-phase info object reported by the callback into the // list of all the narrow-phase info object while (narrowPhaseInfo != nullptr) { - NarrowPhaseInfo* head = mNarrowPhaseInfoList; + NarrowPhaseInfo* next = narrowPhaseInfo->next; + narrowPhaseInfo->next = mNarrowPhaseInfoList; mNarrowPhaseInfoList = narrowPhaseInfo; - mNarrowPhaseInfoList->next = head; - narrowPhaseInfo = narrowPhaseInfo->next; + narrowPhaseInfo = next; } } // Concave vs Concave shape From e491e3814630d4371e411271812340653c3c18d6 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Fri, 27 Jan 2017 20:26:56 +0100 Subject: [PATCH 049/248] Fix issue in collision detection --- src/collision/CollisionDetection.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 345c46bb..be17e4f7 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -605,7 +605,7 @@ NarrowPhaseInfo* CollisionDetection::computeMiddlePhaseForProxyShapes(ProxyShape computeConvexVsConcaveMiddlePhase(&pair, mMemoryAllocator, &narrowPhaseInfo); } - return nullptr; + return narrowPhaseInfo; } // Report all the bodies that overlap with the aabb in parameter @@ -976,7 +976,7 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { // For each possible collision pair of bodies map::iterator it; - for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ) { + for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ++it) { OverlappingPair* pair = it->second; From bccdfa9b5803adfc81fccf725acf0b693d49239a Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Fri, 27 Jan 2017 20:26:56 +0100 Subject: [PATCH 050/248] Fix issue in collision detection --- src/collision/CollisionDetection.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 345c46bb..be17e4f7 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -605,7 +605,7 @@ NarrowPhaseInfo* CollisionDetection::computeMiddlePhaseForProxyShapes(ProxyShape computeConvexVsConcaveMiddlePhase(&pair, mMemoryAllocator, &narrowPhaseInfo); } - return nullptr; + return narrowPhaseInfo; } // Report all the bodies that overlap with the aabb in parameter @@ -976,7 +976,7 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { // For each possible collision pair of bodies map::iterator it; - for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ) { + for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ++it) { OverlappingPair* pair = it->second; From d1cb0d92756963afcb8b27fd8c39658c95cc03cb Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sat, 28 Jan 2017 00:22:22 +0100 Subject: [PATCH 051/248] Refactor testbed application, Add collision detection scene --- testbed/CMakeLists.txt | 2 + testbed/common/Box.cpp | 161 +++---- testbed/common/Box.h | 30 +- testbed/common/Capsule.cpp | 10 +- testbed/common/Capsule.h | 2 +- testbed/common/ConcaveMesh.cpp | 10 +- testbed/common/ConcaveMesh.h | 2 +- testbed/common/Cone.cpp | 10 +- testbed/common/Cone.h | 2 +- testbed/common/ConvexMesh.cpp | 10 +- testbed/common/ConvexMesh.h | 2 +- testbed/common/Cylinder.cpp | 10 +- testbed/common/Cylinder.h | 2 +- testbed/common/Dumbbell.cpp | 10 +- testbed/common/Dumbbell.h | 2 +- testbed/common/HeightField.cpp | 10 +- testbed/common/HeightField.h | 2 +- testbed/common/Sphere.cpp | 11 +- testbed/common/Sphere.h | 2 +- testbed/meshes/cube.obj | 17 + .../CollisionDetectionScene.cpp | 359 +++++++++++++++ .../CollisionDetectionScene.h | 235 ++++++++++ .../collisionshapes/CollisionShapesScene.cpp | 20 +- .../scenes/concavemesh/ConcaveMeshScene.cpp | 6 +- testbed/scenes/cubes/CubesScene.cpp | 408 +++++++++--------- testbed/scenes/cubes/CubesScene.h | 192 ++++----- .../scenes/heightfield/HeightFieldScene.cpp | 6 +- testbed/scenes/joints/JointsScene.cpp | 28 +- testbed/scenes/raycast/RaycastScene.cpp | 20 +- testbed/src/Gui.cpp | 7 + testbed/src/Scene.cpp | 2 +- testbed/src/Scene.h | 19 + testbed/src/TestbedApplication.cpp | 12 +- testbed/src/TestbedApplication.h | 3 + 34 files changed, 1166 insertions(+), 458 deletions(-) create mode 100644 testbed/meshes/cube.obj create mode 100644 testbed/scenes/collisiondetection/CollisionDetectionScene.cpp create mode 100644 testbed/scenes/collisiondetection/CollisionDetectionScene.h diff --git a/testbed/CMakeLists.txt b/testbed/CMakeLists.txt index 808ded2f..8d402ad3 100644 --- a/testbed/CMakeLists.txt +++ b/testbed/CMakeLists.txt @@ -110,6 +110,8 @@ SET(SCENES_SOURCES scenes/raycast/RaycastScene.cpp scenes/collisionshapes/CollisionShapesScene.h scenes/collisionshapes/CollisionShapesScene.cpp + scenes/collisiondetection/CollisionDetectionScene.h + scenes/collisiondetection/CollisionDetectionScene.cpp scenes/concavemesh/ConcaveMeshScene.h scenes/concavemesh/ConcaveMeshScene.cpp scenes/heightfield/HeightFieldScene.h diff --git a/testbed/common/Box.cpp b/testbed/common/Box.cpp index 549b86bb..6c8f052d 100644 --- a/testbed/common/Box.cpp +++ b/testbed/common/Box.cpp @@ -32,88 +32,21 @@ // Initialize static variables openglframework::VertexBufferObject Box::mVBOVertices(GL_ARRAY_BUFFER); openglframework::VertexBufferObject Box::mVBONormals(GL_ARRAY_BUFFER); +openglframework::VertexBufferObject Box::mVBOTextureCoords(GL_ARRAY_BUFFER); +openglframework::VertexBufferObject Box::mVBOIndices(GL_ELEMENT_ARRAY_BUFFER); openglframework::VertexArrayObject Box::mVAO; int Box::totalNbBoxes = 0; -GLfloat Box::mCubeVertices[108] = { - -1.0f,-1.0f,-1.0f, // triangle 1 : begin - -1.0f,-1.0f, 1.0f, - -1.0f, 1.0f, 1.0f, // triangle 1 : end - 1.0f, 1.0f,-1.0f, // triangle 2 : begin - -1.0f,-1.0f,-1.0f, - -1.0f, 1.0f,-1.0f, // triangle 2 : end - 1.0f,-1.0f, 1.0f, - -1.0f,-1.0f,-1.0f, - 1.0f,-1.0f,-1.0f, - 1.0f, 1.0f,-1.0f, - 1.0f,-1.0f,-1.0f, - -1.0f,-1.0f,-1.0f, - -1.0f,-1.0f,-1.0f, - -1.0f, 1.0f, 1.0f, - -1.0f, 1.0f,-1.0f, - 1.0f,-1.0f, 1.0f, - -1.0f,-1.0f, 1.0f, - -1.0f,-1.0f,-1.0f, - -1.0f, 1.0f, 1.0f, - -1.0f,-1.0f, 1.0f, - 1.0f,-1.0f, 1.0f, - 1.0f, 1.0f, 1.0f, - 1.0f,-1.0f,-1.0f, - 1.0f, 1.0f,-1.0f, - 1.0f,-1.0f,-1.0f, - 1.0f, 1.0f, 1.0f, - 1.0f,-1.0f, 1.0f, - 1.0f, 1.0f, 1.0f, - 1.0f, 1.0f,-1.0f, - -1.0f, 1.0f,-1.0f, - 1.0f, 1.0f, 1.0f, - -1.0f, 1.0f,-1.0f, - -1.0f, 1.0f, 1.0f, - 1.0f, 1.0f, 1.0f, - -1.0f, 1.0f, 1.0f, - 1.0f,-1.0f, 1.0f -}; -GLfloat Box::mCubeNormals[108] = { - -1.0f, 0.0f, 0.0f, // triangle 1 : begin - -1.0f, 0.0f, 0.0f, - -1.0f, 0.0f, 0.0f, // triangle 1 : end - 0.0f, 0.0f,-1.0f, // triangle 2 : begin - 0.0f, 0.0f,-1.0f, - 0.0f, 0.0f,-1.0f, // triangle 2 : end - 0.0f,-1.0f, 0.0f, - 0.0f,-1.0f, 0.0f, - 0.0f,-1.0f, 0.0f,// - 0.0f, 0.0f,-1.0f, - 0.0f, 0.0f,-1.0f, - 0.0f, 0.0f,-1.0f,// - -1.0f, 0.0f, 0.0f, - -1.0f, 0.0f, 0.0f, - -1.0f, 0.0f,0.0f,// - 0.0f,-1.0f, 0.0f, - 0.0f,-1.0f, 0.0f, - 0.0f,-1.0f, 0.0f,// - 0.0f, 0.0f, 1.0f, - 0.0f, 0.0f, 1.0f, - 0.0f, 0.0f, 1.0f,// - 1.0f, 0.0f, 0.0f, - 1.0f, 0.0f, 0.0f, - 1.0f, 0.0f, 0.0f,// - 1.0f, 0.0f, 0.0f, - 1.0f, 0.0f, 0.0f, - 1.0f, 0.0f, 0.0f,// - 0.0f, 1.0f, 0.0f, - 0.0f, 1.0f, 0.0f, - 0.0f, 1.0f, 0.0f,// - 0.0f, 1.0f, 0.0f, - 0.0f, 1.0f, 0.0f, - 0.0f, 1.0f, 0.0f,// - 0.0f, 0.0f, 1.0f, - 0.0f, 0.0f, 1.0f, - 0.0f, 0.0f, 1.0f// -}; + // Constructor Box::Box(const openglframework::Vector3& size, const openglframework::Vector3 &position, - reactphysics3d::CollisionWorld* world) - : openglframework::Object3D() { + reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath) + : openglframework::Mesh() { + + // Load the mesh from a file + openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "cube.obj", *this); + + // Calculate the normals of the mesh + calculateNormals(); // Initialize the size of the box mSize[0] = size.x * 0.5f; @@ -161,8 +94,14 @@ Box::Box(const openglframework::Vector3& size, const openglframework::Vector3 &p // Constructor Box::Box(const openglframework::Vector3& size, const openglframework::Vector3& position, - float mass, reactphysics3d::DynamicsWorld* world) - : openglframework::Object3D() { + float mass, reactphysics3d::DynamicsWorld* world, const std::string& meshFolderPath) + : openglframework::Mesh() { + + // Load the mesh from a file + openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "cube.obj", *this); + + // Calculate the normals of the mesh + calculateNormals(); // Initialize the size of the box mSize[0] = size.x * 0.5f; @@ -226,16 +165,15 @@ Box::~Box() { // Render the cube at the correct position and with the correct orientation void Box::render(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix) { + const openglframework::Matrix4& worldToCameraMatrix, bool wireframe) { - // Bind the VAO - mVAO.bind(); + if (wireframe) { + glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); + } // Bind the shader shader.bind(); - mVBOVertices.bind(); - // Set the model to camera matrix shader.setMatrix4x4Uniform("localToWorldMatrix", mTransformMatrix); shader.setMatrix4x4Uniform("worldToCameraMatrix", worldToCameraMatrix); @@ -252,20 +190,27 @@ void Box::render(openglframework::Shader& shader, openglframework::Vector4 color(currentColor.r, currentColor.g, currentColor.b, currentColor.a); shader.setVector4Uniform("vertexColor", color, false); + // Bind the VAO + mVAO.bind(); + + mVBOVertices.bind(); + // Get the location of shader attribute variables GLint vertexPositionLoc = shader.getAttribLocation("vertexPosition"); GLint vertexNormalLoc = shader.getAttribLocation("vertexNormal", false); glEnableVertexAttribArray(vertexPositionLoc); - glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, nullptr); + glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)nullptr); mVBONormals.bind(); + if (vertexNormalLoc != -1) glVertexAttribPointer(vertexNormalLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)nullptr); if (vertexNormalLoc != -1) glEnableVertexAttribArray(vertexNormalLoc); - if (vertexNormalLoc != -1) glVertexAttribPointer(vertexNormalLoc, 3, GL_FLOAT, GL_FALSE, 0, nullptr); - // Draw the geometry of the box - glDrawArrays(GL_TRIANGLES, 0, 36); + // For each part of the mesh + for (unsigned int i=0; isetColor(mGreyColorDemo); + mSphere1->setSleepingColor(mRedColorDemo); + + // ---------- Sphere 2 ---------- // + openglframework::Vector3 position2(4, 0, 0); + + // Create a sphere and a corresponding collision body in the dynamics world + mSphere2 = new Sphere(4, position2, mCollisionWorld, mMeshFolderPath); + mAllShapesObjects.push_back(mSphere2); + mAllShapesPhysicsObjects.push_back(mSphere2); + + // Set the color + mSphere2->setColor(mGreyColorDemo); + mSphere2->setSleepingColor(mRedColorDemo); + + // ---------- Cone ---------- // + //openglframework::Vector3 position4(0, 0, 0); + + // Create a cone and a corresponding collision body in the dynamics world + //mCone = new Cone(CONE_RADIUS, CONE_HEIGHT, position4, mCollisionWorld, + // mMeshFolderPath); + + // Set the color + //mCone->setColor(mGreyColorDemo); + //mCone->setSleepingColor(mRedColorDemo); + + // ---------- Cylinder ---------- // + //openglframework::Vector3 position5(0, 0, 0); + + // Create a cylinder and a corresponding collision body in the dynamics world + //mCylinder = new Cylinder(CYLINDER_RADIUS, CYLINDER_HEIGHT, position5, + // mCollisionWorld, mMeshFolderPath); + + // Set the color + //mCylinder->setColor(mGreyColorDemo); + //mCylinder->setSleepingColor(mRedColorDemo); + + // ---------- Capsule ---------- // + //openglframework::Vector3 position6(0, 0, 0); + + // Create a cylinder and a corresponding collision body in the dynamics world + //mCapsule = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, position6 , + // mCollisionWorld, mMeshFolderPath); + + // Set the color + //mCapsule->setColor(mGreyColorDemo); + //mCapsule->setSleepingColor(mRedColorDemo); + + // ---------- Convex Mesh ---------- // + //openglframework::Vector3 position7(0, 0, 0); + + // Create a convex mesh and a corresponding collision body in the dynamics world + //mConvexMesh = new ConvexMesh(position7, mCollisionWorld, mMeshFolderPath + "convexmesh.obj"); + + // Set the color + //mConvexMesh->setColor(mGreyColorDemo); + //mConvexMesh->setSleepingColor(mRedColorDemo); + + // ---------- Concave Mesh ---------- // + //openglframework::Vector3 position8(0, 0, 0); + + // Create a convex mesh and a corresponding collision body in the dynamics world + //mConcaveMesh = new ConcaveMesh(position8, mCollisionWorld, mMeshFolderPath + "city.obj"); + + // Set the color + //mConcaveMesh->setColor(mGreyColorDemo); + //mConcaveMesh->setSleepingColor(mRedColorDemo); + + // ---------- Heightfield ---------- // + //openglframework::Vector3 position9(0, 0, 0); + + // Create a convex mesh and a corresponding collision body in the dynamics world + //mHeightField = new HeightField(position9, mCollisionWorld); + + // Set the color + //mHeightField->setColor(mGreyColorDemo); + //mHeightField->setSleepingColor(mRedColorDemo); + + // Create the VBO and VAO to render the lines + createVBOAndVAO(mPhongShader); + + mAllShapesPhysicsObjects[mSelectedShapeIndex]->setColor(mBlueColorDemo); +} + +// Reset the scene +void CollisionDetectionScene::reset() { + +} + +// Destructor +CollisionDetectionScene::~CollisionDetectionScene() { + + // Destroy the shader + mPhongShader.destroy(); + + // Destroy the box rigid body from the dynamics world + //mCollisionWorld->destroyCollisionBody(mBox->getCollisionBody()); + //delete mBox; + + // Destroy the spheres + mCollisionWorld->destroyCollisionBody(mSphere1->getCollisionBody()); + delete mSphere1; + + mCollisionWorld->destroyCollisionBody(mSphere2->getCollisionBody()); + delete mSphere2; + + /* + // Destroy the corresponding rigid body from the dynamics world + mCollisionWorld->destroyCollisionBody(mCone->getCollisionBody()); + delete mCone; + + // Destroy the corresponding rigid body from the dynamics world + mCollisionWorld->destroyCollisionBody(mCylinder->getCollisionBody()); + + // Destroy the sphere + delete mCylinder; + + // Destroy the corresponding rigid body from the dynamics world + mCollisionWorld->destroyCollisionBody(mCapsule->getCollisionBody()); + + // Destroy the sphere + delete mCapsule; + + // Destroy the corresponding rigid body from the dynamics world + mCollisionWorld->destroyCollisionBody(mConvexMesh->getCollisionBody()); + + // Destroy the convex mesh + delete mConvexMesh; + + // Destroy the corresponding rigid body from the dynamics world + mCollisionWorld->destroyCollisionBody(mDumbbell->getCollisionBody()); + + // Destroy the dumbbell + delete mDumbbell; + + // Destroy the corresponding rigid body from the dynamics world + mCollisionWorld->destroyCollisionBody(mConcaveMesh->getCollisionBody()); + + // Destroy the convex mesh + delete mConcaveMesh; + + // Destroy the corresponding rigid body from the dynamics world + mCollisionWorld->destroyCollisionBody(mHeightField->getCollisionBody()); + + // Destroy the convex mesh + delete mHeightField; + */ + + mContactManager.resetPoints(); + + // Destroy the static data for the visual contact points + VisualContactPoint::destroyStaticData(); + + // Destroy the collision world + delete mCollisionWorld; + + // Destroy the VBOs and VAO + mVBOVertices.destroy(); + mVAO.destroy(); +} + +// Update the physics world (take a simulation step) +void CollisionDetectionScene::updatePhysics() { + + +} + +// Take a step for the simulation +void CollisionDetectionScene::update() { + + mContactManager.resetPoints(); + + mCollisionWorld->testCollision(&mContactManager); + + SceneDemo::update(); +} + +// Render the scene +void CollisionDetectionScene::renderSinglePass(openglframework::Shader& shader, + const openglframework::Matrix4& worldToCameraMatrix) { + + /* + // Bind the VAO + mVAO.bind(); + + // Bind the shader + shader.bind(); + + mVBOVertices.bind(); + + // Set the model to camera matrix + const Matrix4 localToCameraMatrix = Matrix4::identity(); + shader.setMatrix4x4Uniform("localToWorldMatrix", localToCameraMatrix); + shader.setMatrix4x4Uniform("worldToCameraMatrix", worldToCameraMatrix); + + // Set the normal matrix (inverse transpose of the 3x3 upper-left sub matrix of the + // model-view matrix) + const openglframework::Matrix3 normalMatrix = + localToCameraMatrix.getUpperLeft3x3Matrix().getInverse().getTranspose(); + shader.setMatrix3x3Uniform("normalMatrix", normalMatrix, false); + + // Set the vertex color + openglframework::Vector4 color(1, 0, 0, 1); + shader.setVector4Uniform("vertexColor", color, false); + + // Get the location of shader attribute variables + GLint vertexPositionLoc = shader.getAttribLocation("vertexPosition"); + + glEnableVertexAttribArray(vertexPositionLoc); + glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)NULL); + + // Draw the lines + glDrawArrays(GL_LINES, 0, NB_RAYS); + + glDisableVertexAttribArray(vertexPositionLoc); + + mVBOVertices.unbind(); + + // Unbind the VAO + mVAO.unbind(); + + shader.unbind(); + */ + + // Render the shapes + if (mSphere1->getCollisionBody()->isActive()) mSphere1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + if (mSphere2->getCollisionBody()->isActive()) mSphere2->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + + /* + if (mBox->getCollisionBody()->isActive()) mBox->render(shader, worldToCameraMatrix); + if (mCone->getCollisionBody()->isActive()) mCone->render(shader, worldToCameraMatrix); + if (mCylinder->getCollisionBody()->isActive()) mCylinder->render(shader, worldToCameraMatrix); + if (mCapsule->getCollisionBody()->isActive()) mCapsule->render(shader, worldToCameraMatrix); + if (mConvexMesh->getCollisionBody()->isActive()) mConvexMesh->render(shader, worldToCameraMatrix); + if (mDumbbell->getCollisionBody()->isActive()) mDumbbell->render(shader, worldToCameraMatrix); + if (mConcaveMesh->getCollisionBody()->isActive()) mConcaveMesh->render(shader, worldToCameraMatrix); + if (mHeightField->getCollisionBody()->isActive()) mHeightField->render(shader, worldToCameraMatrix); + */ + + shader.unbind(); +} + +// Create the Vertex Buffer Objects used to render with OpenGL. +/// We create two VBOs (one for vertices and one for indices) +void CollisionDetectionScene::createVBOAndVAO(openglframework::Shader& shader) { + + // Bind the shader + shader.bind(); + + // Create the VBO for the vertices data + mVBOVertices.create(); + mVBOVertices.bind(); + size_t sizeVertices = mLinePoints.size() * sizeof(openglframework::Vector3); + mVBOVertices.copyDataIntoVBO(sizeVertices, &mLinePoints[0], GL_STATIC_DRAW); + mVBOVertices.unbind(); + + // Create the VAO for both VBOs + mVAO.create(); + mVAO.bind(); + + // Bind the VBO of vertices + mVBOVertices.bind(); + + // Unbind the VAO + mVAO.unbind(); + + // Unbind the shader + shader.unbind(); +} + +void CollisionDetectionScene::selectNextShape() { + + int previousIndex = mSelectedShapeIndex; + mSelectedShapeIndex++; + if (mSelectedShapeIndex >= mAllShapesPhysicsObjects.size()) { + mSelectedShapeIndex = 0; + } + + mAllShapesPhysicsObjects[previousIndex]->setColor(mGreyColorDemo); + mAllShapesPhysicsObjects[mSelectedShapeIndex]->setColor(mBlueColorDemo); +} + +// Called when a keyboard event occurs +bool CollisionDetectionScene::keyboardEvent(int key, int scancode, int action, int mods) { + + // If the space key has been pressed + if (key == GLFW_KEY_SPACE && action == GLFW_PRESS) { + selectNextShape(); + return true; + } + + if (key == GLFW_KEY_RIGHT && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapesPhysicsObjects[mSelectedShapeIndex]->getCollisionBody()->getTransform(); + transform.setPosition(transform.getPosition() + rp3d::Vector3(1, 0, 0)); + mAllShapesObjects[mSelectedShapeIndex]->translateWorld(openglframework::Vector3(1, 0, 0)); + } + + return false; +} diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.h b/testbed/scenes/collisiondetection/CollisionDetectionScene.h new file mode 100644 index 00000000..d77cee7f --- /dev/null +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.h @@ -0,0 +1,235 @@ +/******************************************************************************** +* 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 COLLISION_DETECTION_SCENE_H +#define COLLISION_DETECTION_SCENE_H + +// Libraries +#define _USE_MATH_DEFINES +#include +#include "openglframework.h" +#include "reactphysics3d.h" +#include "SceneDemo.h" +#include "Sphere.h" +#include "Box.h" +#include "Cone.h" +#include "Cylinder.h" +#include "Capsule.h" +#include "Line.h" +#include "ConvexMesh.h" +#include "ConcaveMesh.h" +#include "HeightField.h" +#include "Dumbbell.h" +#include "VisualContactPoint.h" + +namespace collisiondetectionscene { + +// Constants +const float SCENE_RADIUS = 30.0f; +const openglframework::Vector3 BOX_SIZE(4, 2, 1); +const float SPHERE_RADIUS = 3.0f; +const float CONE_RADIUS = 3.0f; +const float CONE_HEIGHT = 5.0f; +const float CYLINDER_RADIUS = 3.0f; +const float CYLINDER_HEIGHT = 5.0f; +const float CAPSULE_RADIUS = 3.0f; +const float CAPSULE_HEIGHT = 5.0f; +const float DUMBBELL_HEIGHT = 5.0f; +const int NB_RAYS = 100; +const float RAY_LENGTH = 30.0f; +const int NB_BODIES = 9; + +// Raycast manager +class ContactManager : public rp3d::CollisionCallback { + + private: + + /// All the visual contact points + std::vector mContactPoints; + + /// All the normals at contact points + std::vector mNormals; + + /// Contact point mesh folder path + std::string mMeshFolderPath; + + public: + + ContactManager(openglframework::Shader& shader, + const std::string& meshFolderPath) + : mMeshFolderPath(meshFolderPath) { + + } + + /// This method will be called for each reported contact point + virtual void notifyContact(const CollisionCallbackInfo& collisionCallbackInfo) override { + + rp3d::Vector3 point1 = collisionCallbackInfo.contactPoint.localPoint1; + point1 = collisionCallbackInfo.proxyShape1->getLocalToWorldTransform() * point1; + openglframework::Vector3 position1(point1.x, point1.y, point1.z); + mContactPoints.push_back(ContactPoint(position1)); + + rp3d::Vector3 point2 = collisionCallbackInfo.contactPoint.localPoint2; + point2 = collisionCallbackInfo.proxyShape2->getLocalToWorldTransform() * point2; + openglframework::Vector3 position2(point2.x, point2.y, point2.z); + mContactPoints.push_back(ContactPoint(position2)); + + // Create a line to display the normal at hit point + rp3d::Vector3 n = collisionCallbackInfo.contactPoint.normal; + openglframework::Vector3 normal(n.x, n.y, n.z); + Line* normalLine = new Line(position1, position1 + normal); + mNormals.push_back(normalLine); + } + + void resetPoints() { + + mContactPoints.clear(); + + // Destroy all the normals + for (std::vector::iterator it = mNormals.begin(); + it != mNormals.end(); ++it) { + delete (*it); + } + mNormals.clear(); + } + + std::vector getContactPoints() const { + return mContactPoints; + } +}; + +// Class CollisionDetectionScene +class CollisionDetectionScene : public SceneDemo { + + private : + + // -------------------- Attributes -------------------- // + + /// Contact point mesh folder path + std::string mMeshFolderPath; + + /// Contact manager + ContactManager mContactManager; + + bool mAreNormalsDisplayed; + + /// All objects on the scene + //Box* mBox; + Sphere* mSphere1; + Sphere* mSphere2; + //Cone* mCone; + //Cylinder* mCylinder; + //Capsule* mCapsule; + //ConvexMesh* mConvexMesh; + //Dumbbell* mDumbbell; + //ConcaveMesh* mConcaveMesh; + //HeightField* mHeightField; + + std::vector mAllShapesObjects; + std::vector mAllShapesPhysicsObjects; + + int mSelectedShapeIndex; + + /// Collision world used for the physics simulation + rp3d::CollisionWorld* mCollisionWorld; + + /// All the points to render the lines + std::vector mLinePoints; + + /// Vertex Buffer Object for the vertices data + openglframework::VertexBufferObject mVBOVertices; + + /// Vertex Array Object for the vertex data + openglframework::VertexArrayObject mVAO; + + /// Create the Vertex Buffer Objects used to render with OpenGL. + void createVBOAndVAO(openglframework::Shader& shader); + + /// Select the next shape + void selectNextShape(); + + public: + + // -------------------- Methods -------------------- // + + /// Constructor + CollisionDetectionScene(const std::string& name); + + /// Destructor + virtual ~CollisionDetectionScene() override; + + /// Update the physics world (take a simulation step) + /// Can be called several times per frame + virtual void updatePhysics() override; + + /// Take a step for the simulation + virtual void update() override; + + /// Render the scene in a single pass + virtual void renderSinglePass(openglframework::Shader& shader, + const openglframework::Matrix4& worldToCameraMatrix) override; + + /// Reset the scene + virtual void reset() override; + + /// Display or not the surface normals at hit points + void showHideNormals(); + + /// Called when a keyboard event occurs + virtual bool keyboardEvent(int key, int scancode, int action, int mods) override; + + /// Enabled/Disable the shadow mapping + virtual void setIsShadowMappingEnabled(bool isShadowMappingEnabled) override; + + /// Display/Hide the contact points + virtual void setIsContactPointsDisplayed(bool display) override; + + /// Return all the contact points of the scene + virtual std::vector getContactPoints() const override; +}; + +// Display or not the surface normals at hit points +inline void CollisionDetectionScene::showHideNormals() { + mAreNormalsDisplayed = !mAreNormalsDisplayed; +} + +// Enabled/Disable the shadow mapping +inline void CollisionDetectionScene::setIsShadowMappingEnabled(bool isShadowMappingEnabled) { + SceneDemo::setIsShadowMappingEnabled(false); +} + +// Display/Hide the contact points +inline void CollisionDetectionScene::setIsContactPointsDisplayed(bool display) { + SceneDemo::setIsContactPointsDisplayed(true); +} + +// Return all the contact points of the scene +inline std::vector CollisionDetectionScene::getContactPoints() const { + return mContactManager.getContactPoints(); +} + +} + +#endif diff --git a/testbed/scenes/collisionshapes/CollisionShapesScene.cpp b/testbed/scenes/collisionshapes/CollisionShapesScene.cpp index 5078cd14..e146bd6b 100644 --- a/testbed/scenes/collisionshapes/CollisionShapesScene.cpp +++ b/testbed/scenes/collisionshapes/CollisionShapesScene.cpp @@ -83,7 +83,7 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name) radius * sin(angle)); // Create a sphere and a corresponding rigid in the dynamics world - Box* box = new Box(BOX_SIZE, position , BOX_MASS, mDynamicsWorld); + Box* box = new Box(BOX_SIZE, position , BOX_MASS, mDynamicsWorld, mMeshFolderPath); // Set the box color box->setColor(mDemoColors[i % mNbDemoColors]); @@ -235,7 +235,7 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name) // ---------- Create the floor --------- openglframework::Vector3 floorPosition(0, 0, 0); - mFloor = new Box(FLOOR_SIZE, floorPosition, FLOOR_MASS, mDynamicsWorld); + mFloor = new Box(FLOOR_SIZE, floorPosition, FLOOR_MASS, mDynamicsWorld, mMeshFolderPath); // Set the box color mFloor->setColor(mGreyColorDemo); @@ -461,43 +461,43 @@ void CollisionShapesScene::renderSinglePass(openglframework::Shader& shader, // Render all the boxes of the scene for (std::vector::iterator it = mBoxes.begin(); it != mBoxes.end(); ++it) { - (*it)->render(shader, worldToCameraMatrix); + (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); } // Render all the sphere of the scene for (std::vector::iterator it = mSpheres.begin(); it != mSpheres.end(); ++it) { - (*it)->render(shader, worldToCameraMatrix); + (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); } // Render all the cones of the scene for (std::vector::iterator it = mCones.begin(); it != mCones.end(); ++it) { - (*it)->render(shader, worldToCameraMatrix); + (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); } // Render all the cylinders of the scene for (std::vector::iterator it = mCylinders.begin(); it != mCylinders.end(); ++it) { - (*it)->render(shader, worldToCameraMatrix); + (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); } // Render all the capsules of the scene for (std::vector::iterator it = mCapsules.begin(); it != mCapsules.end(); ++it) { - (*it)->render(shader, worldToCameraMatrix); + (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); } // Render all the convex meshes of the scene for (std::vector::iterator it = mConvexMeshes.begin(); it != mConvexMeshes.end(); ++it) { - (*it)->render(shader, worldToCameraMatrix); + (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); } // Render all the dumbbells of the scene for (std::vector::iterator it = mDumbbells.begin(); it != mDumbbells.end(); ++it) { - (*it)->render(shader, worldToCameraMatrix); + (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); } // Render the floor - mFloor->render(shader, worldToCameraMatrix); + mFloor->render(shader, worldToCameraMatrix, mIsWireframeEnabled); //mConcaveMesh->render(shader, worldToCameraMatrix); diff --git a/testbed/scenes/concavemesh/ConcaveMeshScene.cpp b/testbed/scenes/concavemesh/ConcaveMeshScene.cpp index 41234f3f..9b65893e 100644 --- a/testbed/scenes/concavemesh/ConcaveMeshScene.cpp +++ b/testbed/scenes/concavemesh/ConcaveMeshScene.cpp @@ -58,7 +58,7 @@ ConcaveMeshScene::ConcaveMeshScene(const std::string& name) openglframework::Vector3 boxPosition(-NB_BOXES_X * BOX_SIZE * BOXES_SPACE / 2 + i * BOX_SIZE * BOXES_SPACE, 30, -NB_BOXES_Z * BOX_SIZE * BOXES_SPACE / 2 + j * BOX_SIZE * BOXES_SPACE); // Create a sphere and a corresponding rigid in the dynamics world - mBoxes[i * NB_BOXES_Z + j] = new Box(Vector3(BOX_SIZE, BOX_SIZE, BOX_SIZE) * 0.5f, boxPosition, 80.1, mDynamicsWorld); + mBoxes[i * NB_BOXES_Z + j] = new Box(Vector3(BOX_SIZE, BOX_SIZE, BOX_SIZE) * 0.5f, boxPosition, 80.1, mDynamicsWorld, mMeshFolderPath); // Set the sphere color mBoxes[i * NB_BOXES_Z + j]->setColor(mDemoColors[0]); @@ -160,10 +160,10 @@ void ConcaveMeshScene::renderSinglePass(Shader& shader, const openglframework::M // Bind the shader shader.bind(); - mConcaveMesh->render(shader, worldToCameraMatrix); + mConcaveMesh->render(shader, worldToCameraMatrix, mIsWireframeEnabled); for (int i=0; irender(shader, worldToCameraMatrix); + mBoxes[i]->render(shader, worldToCameraMatrix, mIsWireframeEnabled); } // Unbind the shader diff --git a/testbed/scenes/cubes/CubesScene.cpp b/testbed/scenes/cubes/CubesScene.cpp index f9c8ad77..17af45c1 100644 --- a/testbed/scenes/cubes/CubesScene.cpp +++ b/testbed/scenes/cubes/CubesScene.cpp @@ -1,195 +1,213 @@ -/******************************************************************************** -* 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. * -* * -********************************************************************************/ - -// Libraries -#include "CubesScene.h" - -// Namespaces -using namespace openglframework; -using namespace cubesscene; - -// Constructor -CubesScene::CubesScene(const std::string& name) - : SceneDemo(name, SCENE_RADIUS) { - - // Compute the radius and the center of the scene - openglframework::Vector3 center(0, 5, 0); - - // Set the center of the scene - setScenePosition(center, SCENE_RADIUS); - - // Gravity vector in the dynamics world - rp3d::Vector3 gravity(0, rp3d::decimal(-9.81), 0); - - // Create the dynamics world for the physics simulation - mDynamicsWorld = new rp3d::DynamicsWorld(gravity); - - float radius = 2.0f; - - // Create all the cubes of the scene - for (int i=0; isetColor(mDemoColors[i % mNbDemoColors]); - cube->setSleepingColor(mRedColorDemo); - - // Change the material properties of the rigid body - rp3d::Material& material = cube->getRigidBody()->getMaterial(); - material.setBounciness(rp3d::decimal(0.4)); - - // Add the box the list of box in the scene - mBoxes.push_back(cube); - } - - // Create the floor - openglframework::Vector3 floorPosition(0, 0, 0); - mFloor = new Box(FLOOR_SIZE, floorPosition, FLOOR_MASS, mDynamicsWorld); - mFloor->setColor(mGreyColorDemo); - mFloor->setSleepingColor(mGreyColorDemo); - - // The floor must be a static rigid body - mFloor->getRigidBody()->setType(rp3d::BodyType::STATIC); - - // Change the material properties of the floor rigid body - rp3d::Material& material = mFloor->getRigidBody()->getMaterial(); - material.setBounciness(rp3d::decimal(0.3)); - - // Get the physics engine parameters - mEngineSettings.isGravityEnabled = mDynamicsWorld->isGravityEnabled(); - rp3d::Vector3 gravityVector = mDynamicsWorld->getGravity(); - mEngineSettings.gravity = openglframework::Vector3(gravityVector.x, gravityVector.y, gravityVector.z); - mEngineSettings.isSleepingEnabled = mDynamicsWorld->isSleepingEnabled(); - mEngineSettings.sleepLinearVelocity = mDynamicsWorld->getSleepLinearVelocity(); - mEngineSettings.sleepAngularVelocity = mDynamicsWorld->getSleepAngularVelocity(); - mEngineSettings.nbPositionSolverIterations = mDynamicsWorld->getNbIterationsPositionSolver(); - mEngineSettings.nbVelocitySolverIterations = mDynamicsWorld->getNbIterationsVelocitySolver(); - mEngineSettings.timeBeforeSleep = mDynamicsWorld->getTimeBeforeSleep(); -} - -// Destructor -CubesScene::~CubesScene() { - - // Destroy all the cubes of the scene - for (std::vector::iterator it = mBoxes.begin(); it != mBoxes.end(); ++it) { - - // Destroy the corresponding rigid body from the dynamics world - mDynamicsWorld->destroyRigidBody((*it)->getRigidBody()); - - // Destroy the cube - delete (*it); - } - - // Destroy the rigid body of the floor - mDynamicsWorld->destroyRigidBody(mFloor->getRigidBody()); - - // Destroy the floor - delete mFloor; - - // Destroy the dynamics world - delete mDynamicsWorld; -} - -// Update the physics world (take a simulation step) -void CubesScene::updatePhysics() { - - // Update the physics engine parameters - mDynamicsWorld->setIsGratityEnabled(mEngineSettings.isGravityEnabled); - rp3d::Vector3 gravity(mEngineSettings.gravity.x, mEngineSettings.gravity.y, - mEngineSettings.gravity.z); - mDynamicsWorld->setGravity(gravity); - mDynamicsWorld->enableSleeping(mEngineSettings.isSleepingEnabled); - mDynamicsWorld->setSleepLinearVelocity(mEngineSettings.sleepLinearVelocity); - mDynamicsWorld->setSleepAngularVelocity(mEngineSettings.sleepAngularVelocity); - mDynamicsWorld->setNbIterationsPositionSolver(mEngineSettings.nbPositionSolverIterations); - mDynamicsWorld->setNbIterationsVelocitySolver(mEngineSettings.nbVelocitySolverIterations); - mDynamicsWorld->setTimeBeforeSleep(mEngineSettings.timeBeforeSleep); - - // Take a simulation step - mDynamicsWorld->update(mEngineSettings.timeStep); -} - -// Update the scene -void CubesScene::update() { - - SceneDemo::update(); - - // Update the position and orientation of the boxes - for (std::vector::iterator it = mBoxes.begin(); it != mBoxes.end(); ++it) { - - // Update the transform used for the rendering - (*it)->updateTransform(mInterpolationFactor); - } - - mFloor->updateTransform(mInterpolationFactor); -} - -// Render the scene in a single pass -void CubesScene::renderSinglePass(Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) { - - // Bind the shader - shader.bind(); - - // Render all the cubes of the scene - for (std::vector::iterator it = mBoxes.begin(); it != mBoxes.end(); ++it) { - (*it)->render(shader, worldToCameraMatrix); - } - - // Render the floor - mFloor->render(shader, worldToCameraMatrix); - - // Unbind the shader - shader.unbind(); -} - -// Reset the scene -void CubesScene::reset() { - - float radius = 2.0f; - - for (int i=0; iresetTransform(transform); - } -} +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "CubesScene.h" + +// Namespaces +using namespace openglframework; +using namespace cubesscene; + +// Constructor +CubesScene::CubesScene(const std::string& name) + : SceneDemo(name, SCENE_RADIUS) { + + // Compute the radius and the center of the scene + openglframework::Vector3 center(0, 5, 0); + + // Set the center of the scene + setScenePosition(center, SCENE_RADIUS); + + // Gravity vector in the dynamics world + rp3d::Vector3 gravity(0, rp3d::decimal(-9.81), 0); + + // Create the dynamics world for the physics simulation + mDynamicsWorld = new rp3d::DynamicsWorld(gravity); + + float radius = 2.0f; + + //// Create all the cubes of the scene + //for (int i=0; isetColor(mDemoColors[i % mNbDemoColors]); + // cube->setSleepingColor(mRedColorDemo); + + // // Change the material properties of the rigid body + // rp3d::Material& material = cube->getRigidBody()->getMaterial(); + // material.setBounciness(rp3d::decimal(0.4)); + + // // Add the box the list of box in the scene + // mBoxes.push_back(cube); + //} + + // ------------------------- FLOOR ----------------------- // + + // Create the floor + openglframework::Vector3 floorPosition(0, 0, 0); + mFloor = new Box(FLOOR_SIZE, floorPosition, FLOOR_MASS, mDynamicsWorld, mMeshFolderPath); + mFloor->setColor(mGreyColorDemo); + mFloor->setSleepingColor(mGreyColorDemo); + + // The floor must be a static rigid body + mFloor->getRigidBody()->setType(rp3d::BodyType::STATIC); + + // Change the material properties of the floor rigid body + //rp3d::Material& material = mFloor->getRigidBody()->getMaterial(); + //material.setBounciness(rp3d::decimal(0.3)); + + // ------------------------- BOX ----------------------- // + + // Create a cube and a corresponding rigid in the dynamics world + Box* cube = new Box(BOX_SIZE, Vector3(0, 10, 0), BOX_MASS, mDynamicsWorld, mMeshFolderPath); + + // Set the box color + cube->setColor(mDemoColors[0]); + cube->setSleepingColor(mRedColorDemo); + + // Change the material properties of the rigid body + //rp3d::Material& material = cube->getRigidBody()->getMaterial(); + //material.setBounciness(rp3d::decimal(0.4)); + + // Add the box the list of box in the scene + mBoxes.push_back(cube); + + // Get the physics engine parameters + mEngineSettings.isGravityEnabled = mDynamicsWorld->isGravityEnabled(); + rp3d::Vector3 gravityVector = mDynamicsWorld->getGravity(); + mEngineSettings.gravity = openglframework::Vector3(gravityVector.x, gravityVector.y, gravityVector.z); + mEngineSettings.isSleepingEnabled = mDynamicsWorld->isSleepingEnabled(); + mEngineSettings.sleepLinearVelocity = mDynamicsWorld->getSleepLinearVelocity(); + mEngineSettings.sleepAngularVelocity = mDynamicsWorld->getSleepAngularVelocity(); + mEngineSettings.nbPositionSolverIterations = mDynamicsWorld->getNbIterationsPositionSolver(); + mEngineSettings.nbVelocitySolverIterations = mDynamicsWorld->getNbIterationsVelocitySolver(); + mEngineSettings.timeBeforeSleep = mDynamicsWorld->getTimeBeforeSleep(); +} + +// Destructor +CubesScene::~CubesScene() { + + // Destroy all the cubes of the scene + for (std::vector::iterator it = mBoxes.begin(); it != mBoxes.end(); ++it) { + + // Destroy the corresponding rigid body from the dynamics world + mDynamicsWorld->destroyRigidBody((*it)->getRigidBody()); + + // Destroy the cube + delete (*it); + } + + // Destroy the rigid body of the floor + mDynamicsWorld->destroyRigidBody(mFloor->getRigidBody()); + + // Destroy the floor + delete mFloor; + + // Destroy the dynamics world + delete mDynamicsWorld; +} + +// Update the physics world (take a simulation step) +void CubesScene::updatePhysics() { + + // Update the physics engine parameters + mDynamicsWorld->setIsGratityEnabled(mEngineSettings.isGravityEnabled); + rp3d::Vector3 gravity(mEngineSettings.gravity.x, mEngineSettings.gravity.y, + mEngineSettings.gravity.z); + mDynamicsWorld->setGravity(gravity); + mDynamicsWorld->enableSleeping(mEngineSettings.isSleepingEnabled); + mDynamicsWorld->setSleepLinearVelocity(mEngineSettings.sleepLinearVelocity); + mDynamicsWorld->setSleepAngularVelocity(mEngineSettings.sleepAngularVelocity); + mDynamicsWorld->setNbIterationsPositionSolver(mEngineSettings.nbPositionSolverIterations); + mDynamicsWorld->setNbIterationsVelocitySolver(mEngineSettings.nbVelocitySolverIterations); + mDynamicsWorld->setTimeBeforeSleep(mEngineSettings.timeBeforeSleep); + + // Take a simulation step + mDynamicsWorld->update(mEngineSettings.timeStep); +} + +// Update the scene +void CubesScene::update() { + + SceneDemo::update(); + + // Update the position and orientation of the boxes + for (std::vector::iterator it = mBoxes.begin(); it != mBoxes.end(); ++it) { + + // Update the transform used for the rendering + (*it)->updateTransform(mInterpolationFactor); + } + + mFloor->updateTransform(mInterpolationFactor); +} + +// Render the scene in a single pass +void CubesScene::renderSinglePass(Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) { + + // Bind the shader + shader.bind(); + + // Render all the cubes of the scene + for (std::vector::iterator it = mBoxes.begin(); it != mBoxes.end(); ++it) { + (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + } + + // Render the floor + mFloor->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + + // Unbind the shader + shader.unbind(); +} + +// Reset the scene +void CubesScene::reset() { + + float radius = 2.0f; + + for (int i=0; iresetTransform(transform); + } +} diff --git a/testbed/scenes/cubes/CubesScene.h b/testbed/scenes/cubes/CubesScene.h index a07c74d2..4ad57f77 100644 --- a/testbed/scenes/cubes/CubesScene.h +++ b/testbed/scenes/cubes/CubesScene.h @@ -1,96 +1,96 @@ -/******************************************************************************** -* 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 CUBES_SCENE_H -#define CUBES_SCENE_H - -// Libraries -#include "openglframework.h" -#include "reactphysics3d.h" -#include "Box.h" -#include "SceneDemo.h" - -namespace cubesscene { - -// Constants -const float SCENE_RADIUS = 30.0f; // Radius of the scene in meters -const int NB_CUBES = 30; // Number of boxes in the scene -const openglframework::Vector3 BOX_SIZE(2, 2, 2); // Box dimensions in meters -const openglframework::Vector3 FLOOR_SIZE(50, 0.5f, 50); // Floor dimensions in meters -const float BOX_MASS = 1.0f; // Box mass in kilograms -const float FLOOR_MASS = 100.0f; // Floor mass in kilograms - -// Class CubesScene -class CubesScene : public SceneDemo { - - protected : - - // -------------------- Attributes -------------------- // - - /// All the boxes of the scene - std::vector mBoxes; - - /// Box for the floor - Box* mFloor; - - /// Dynamics world used for the physics simulation - rp3d::DynamicsWorld* mDynamicsWorld; - - public: - - // -------------------- Methods -------------------- // - - /// Constructor - CubesScene(const std::string& name); - - /// Destructor - virtual ~CubesScene() override; - - /// Update the physics world (take a simulation step) - /// Can be called several times per frame - virtual void updatePhysics() override; - - /// Update the scene (take a simulation step) - virtual void update() override; - - /// Render the scene in a single pass - virtual void renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix) override; - - /// Reset the scene - virtual void reset() override; - - /// Return all the contact points of the scene - virtual std::vector getContactPoints() const override; -}; - -// Return all the contact points of the scene -inline std::vector CubesScene::getContactPoints() const { - return computeContactPointsOfWorld(mDynamicsWorld); -} - -} - -#endif +/******************************************************************************** +* 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 CUBES_SCENE_H +#define CUBES_SCENE_H + +// Libraries +#include "openglframework.h" +#include "reactphysics3d.h" +#include "Box.h" +#include "SceneDemo.h" + +namespace cubesscene { + +// Constants +const float SCENE_RADIUS = 30.0f; // Radius of the scene in meters +const int NB_CUBES = 30; // Number of boxes in the scene +const openglframework::Vector3 BOX_SIZE(2, 2, 2); // Box dimensions in meters +const openglframework::Vector3 FLOOR_SIZE(5, 5.0, 5); // Floor dimensions in meters +const float BOX_MASS = 1.0f; // Box mass in kilograms +const float FLOOR_MASS = 100.0f; // Floor mass in kilograms + +// Class CubesScene +class CubesScene : public SceneDemo { + + protected : + + // -------------------- Attributes -------------------- // + + /// All the boxes of the scene + std::vector mBoxes; + + /// Box for the floor + Box* mFloor; + + /// Dynamics world used for the physics simulation + rp3d::DynamicsWorld* mDynamicsWorld; + + public: + + // -------------------- Methods -------------------- // + + /// Constructor + CubesScene(const std::string& name); + + /// Destructor + virtual ~CubesScene() override; + + /// Update the physics world (take a simulation step) + /// Can be called several times per frame + virtual void updatePhysics() override; + + /// Update the scene (take a simulation step) + virtual void update() override; + + /// Render the scene in a single pass + virtual void renderSinglePass(openglframework::Shader& shader, + const openglframework::Matrix4& worldToCameraMatrix) override; + + /// Reset the scene + virtual void reset() override; + + /// Return all the contact points of the scene + virtual std::vector getContactPoints() const override; +}; + +// Return all the contact points of the scene +inline std::vector CubesScene::getContactPoints() const { + return computeContactPointsOfWorld(mDynamicsWorld); +} + +} + +#endif diff --git a/testbed/scenes/heightfield/HeightFieldScene.cpp b/testbed/scenes/heightfield/HeightFieldScene.cpp index 3395ac17..5b62f614 100644 --- a/testbed/scenes/heightfield/HeightFieldScene.cpp +++ b/testbed/scenes/heightfield/HeightFieldScene.cpp @@ -54,7 +54,7 @@ HeightFieldScene::HeightFieldScene(const std::string& name) : SceneDemo(name, SC openglframework::Vector3 position(15, 10 + 6 * i, 0); // Create a box and a corresponding rigid in the dynamics world - mBoxes[i] = new Box(Vector3(3, 3, 3), position, 80.1, mDynamicsWorld); + mBoxes[i] = new Box(Vector3(3, 3, 3), position, 80.1, mDynamicsWorld, mMeshFolderPath); // Set the box color mBoxes[i]->setColor(mDemoColors[2]); @@ -156,10 +156,10 @@ void HeightFieldScene::renderSinglePass(Shader& shader, const openglframework::M // Bind the shader shader.bind(); - mHeightField->render(shader, worldToCameraMatrix); + mHeightField->render(shader, worldToCameraMatrix, mIsWireframeEnabled); for (int i=0; irender(shader, worldToCameraMatrix); + mBoxes[i]->render(shader, worldToCameraMatrix, mIsWireframeEnabled); } // Unbind the shader diff --git a/testbed/scenes/joints/JointsScene.cpp b/testbed/scenes/joints/JointsScene.cpp index b1891627..34bb1503 100644 --- a/testbed/scenes/joints/JointsScene.cpp +++ b/testbed/scenes/joints/JointsScene.cpp @@ -163,17 +163,17 @@ void JointsScene::renderSinglePass(openglframework::Shader& shader, shader.bind(); // Render all the boxes - mSliderJointBottomBox->render(shader, worldToCameraMatrix); - mSliderJointTopBox->render(shader, worldToCameraMatrix); - mPropellerBox->render(shader, worldToCameraMatrix); - mFixedJointBox1->render(shader, worldToCameraMatrix); - mFixedJointBox2->render(shader, worldToCameraMatrix); + mSliderJointBottomBox->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + mSliderJointTopBox->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + mPropellerBox->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + mFixedJointBox1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + mFixedJointBox2->render(shader, worldToCameraMatrix, mIsWireframeEnabled); for (int i=0; irender(shader, worldToCameraMatrix); + mBallAndSocketJointChainBoxes[i]->render(shader, worldToCameraMatrix, mIsWireframeEnabled); } // Render the floor - mFloor->render(shader, worldToCameraMatrix); + mFloor->render(shader, worldToCameraMatrix, mIsWireframeEnabled); // Unbind the shader shader.unbind(); @@ -263,7 +263,7 @@ void JointsScene::createBallAndSocketJoints() { // Create a box and a corresponding rigid in the dynamics world mBallAndSocketJointChainBoxes[i] = new Box(boxDimension, positionBox , boxMass, - mDynamicsWorld); + mDynamicsWorld, mMeshFolderPath); // Set the box color mBallAndSocketJointChainBoxes[i]->setColor(mDemoColors[i % mNbDemoColors]); @@ -312,7 +312,7 @@ void JointsScene::createSliderJoint() { // Create a box and a corresponding rigid in the dynamics world openglframework::Vector3 box1Dimension(2, 4, 2); - mSliderJointBottomBox = new Box(box1Dimension, positionBox1 , BOX_MASS, mDynamicsWorld); + mSliderJointBottomBox = new Box(box1Dimension, positionBox1 , BOX_MASS, mDynamicsWorld, mMeshFolderPath); // Set the box color mSliderJointBottomBox->setColor(mBlueColorDemo); @@ -332,7 +332,7 @@ void JointsScene::createSliderJoint() { // Create a box and a corresponding rigid in the dynamics world openglframework::Vector3 box2Dimension(1.5f, 4, 1.5f); - mSliderJointTopBox = new Box(box2Dimension, positionBox2, BOX_MASS, mDynamicsWorld); + mSliderJointTopBox = new Box(box2Dimension, positionBox2, BOX_MASS, mDynamicsWorld, mMeshFolderPath); // Set the box color mSliderJointTopBox->setColor(mOrangeColorDemo); @@ -372,7 +372,7 @@ void JointsScene::createPropellerHingeJoint() { // Create a box and a corresponding rigid in the dynamics world openglframework::Vector3 boxDimension(10, 1, 1); - mPropellerBox = new Box(boxDimension, positionBox1 , BOX_MASS, mDynamicsWorld); + mPropellerBox = new Box(boxDimension, positionBox1 , BOX_MASS, mDynamicsWorld, mMeshFolderPath); // Set the box color mPropellerBox->setColor(mYellowColorDemo); @@ -411,7 +411,7 @@ void JointsScene::createFixedJoints() { // Create a box and a corresponding rigid in the dynamics world openglframework::Vector3 boxDimension(1.5, 1.5, 1.5); - mFixedJointBox1 = new Box(boxDimension, positionBox1 , BOX_MASS, mDynamicsWorld); + mFixedJointBox1 = new Box(boxDimension, positionBox1 , BOX_MASS, mDynamicsWorld, mMeshFolderPath); // Set the box color mFixedJointBox1->setColor(mPinkColorDemo); @@ -427,7 +427,7 @@ void JointsScene::createFixedJoints() { openglframework::Vector3 positionBox2(-5, 7, 0); // Create a box and a corresponding rigid in the dynamics world - mFixedJointBox2 = new Box(boxDimension, positionBox2 , BOX_MASS, mDynamicsWorld); + mFixedJointBox2 = new Box(boxDimension, positionBox2 , BOX_MASS, mDynamicsWorld, mMeshFolderPath); // Set the box color mFixedJointBox2->setColor(mBlueColorDemo); @@ -466,7 +466,7 @@ void JointsScene::createFloor() { // Create the floor openglframework::Vector3 floorPosition(0, 0, 0); - mFloor = new Box(FLOOR_SIZE, floorPosition, FLOOR_MASS, mDynamicsWorld); + mFloor = new Box(FLOOR_SIZE, floorPosition, FLOOR_MASS, mDynamicsWorld, mMeshFolderPath); // Set the box color mFloor->setColor(mGreyColorDemo); diff --git a/testbed/scenes/raycast/RaycastScene.cpp b/testbed/scenes/raycast/RaycastScene.cpp index 479e0915..58b19055 100644 --- a/testbed/scenes/raycast/RaycastScene.cpp +++ b/testbed/scenes/raycast/RaycastScene.cpp @@ -61,7 +61,7 @@ RaycastScene::RaycastScene(const std::string& name) openglframework::Vector3 position2(0, 0, 0); // Create a box and a corresponding collision body in the dynamics world - mBox = new Box(BOX_SIZE, position2, mCollisionWorld); + mBox = new Box(BOX_SIZE, position2, mCollisionWorld, mMeshFolderPath); mBox->getCollisionBody()->setIsActive(false); // Set the box color @@ -376,15 +376,15 @@ void RaycastScene::renderSinglePass(openglframework::Shader& shader, shader.unbind(); // Render the shapes - if (mBox->getCollisionBody()->isActive()) mBox->render(shader, worldToCameraMatrix); - if (mSphere->getCollisionBody()->isActive()) mSphere->render(shader, worldToCameraMatrix); - if (mCone->getCollisionBody()->isActive()) mCone->render(shader, worldToCameraMatrix); - if (mCylinder->getCollisionBody()->isActive()) mCylinder->render(shader, worldToCameraMatrix); - if (mCapsule->getCollisionBody()->isActive()) mCapsule->render(shader, worldToCameraMatrix); - if (mConvexMesh->getCollisionBody()->isActive()) mConvexMesh->render(shader, worldToCameraMatrix); - if (mDumbbell->getCollisionBody()->isActive()) mDumbbell->render(shader, worldToCameraMatrix); - if (mConcaveMesh->getCollisionBody()->isActive()) mConcaveMesh->render(shader, worldToCameraMatrix); - if (mHeightField->getCollisionBody()->isActive()) mHeightField->render(shader, worldToCameraMatrix); + if (mBox->getCollisionBody()->isActive()) mBox->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + if (mSphere->getCollisionBody()->isActive()) mSphere->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + if (mCone->getCollisionBody()->isActive()) mCone->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + if (mCylinder->getCollisionBody()->isActive()) mCylinder->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + if (mCapsule->getCollisionBody()->isActive()) mCapsule->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + if (mConvexMesh->getCollisionBody()->isActive()) mConvexMesh->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + if (mDumbbell->getCollisionBody()->isActive()) mDumbbell->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + if (mConcaveMesh->getCollisionBody()->isActive()) mConcaveMesh->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + if (mHeightField->getCollisionBody()->isActive()) mHeightField->render(shader, worldToCameraMatrix, mIsWireframeEnabled); shader.unbind(); } diff --git a/testbed/src/Gui.cpp b/testbed/src/Gui.cpp index 499f1fb3..cd9f8f4e 100644 --- a/testbed/src/Gui.cpp +++ b/testbed/src/Gui.cpp @@ -402,6 +402,13 @@ void Gui::createSettingsPanel() { mApp->mIsShadowMappingEnabled = value; }); + // Enable/Disable wireframe mode + CheckBox* checkboxWireframe = new CheckBox(mRenderingPanel, "Wireframe"); + checkboxWireframe->setChecked(mApp->mIsWireframeEnabled); + checkboxWireframe->setCallback([&](bool value) { + mApp->mIsWireframeEnabled = value; + }); + mPhysicsPanel->setVisible(true); mRenderingPanel->setVisible(false); } diff --git a/testbed/src/Scene.cpp b/testbed/src/Scene.cpp index 8031c1f8..e872b3bc 100644 --- a/testbed/src/Scene.cpp +++ b/testbed/src/Scene.cpp @@ -33,7 +33,7 @@ using namespace openglframework; Scene::Scene(const std::string& name, bool isShadowMappingEnabled) : mName(name), mInterpolationFactor(0.0f), mViewportX(0), mViewportY(0), mViewportWidth(0), mViewportHeight(0), mIsShadowMappingEnabled(isShadowMappingEnabled), - mIsContactPointsDisplayed(true) { + mIsContactPointsDisplayed(true), mIsWireframeEnabled(false) { } diff --git a/testbed/src/Scene.h b/testbed/src/Scene.h index bfac3ecb..d51ffec1 100644 --- a/testbed/src/Scene.h +++ b/testbed/src/Scene.h @@ -108,6 +108,9 @@ class Scene { /// True if contact points are displayed bool mIsContactPointsDisplayed; + /// True if we render shapes in wireframe mode + bool mIsWireframeEnabled; + // -------------------- Methods -------------------- // /// Set the scene position (where the camera needs to look at) @@ -199,6 +202,12 @@ class Scene { /// Display/Hide the contact points void virtual setIsContactPointsDisplayed(bool display); + /// Return true if wireframe rendering is enabled + bool getIsWireframeEnabled() const; + + /// Enable/disbale wireframe rendering + void setIsWireframeEnabled(bool isEnabled); + /// Return all the contact points of the scene std::vector virtual getContactPoints() const; }; @@ -267,6 +276,16 @@ inline void Scene::setIsContactPointsDisplayed(bool display) { mIsContactPointsDisplayed = display; } +// Return true if wireframe rendering is enabled +inline bool Scene::getIsWireframeEnabled() const { + return mIsWireframeEnabled; +} + +// Enable/disbale wireframe rendering +inline void Scene::setIsWireframeEnabled(bool isEnabled) { + mIsWireframeEnabled = isEnabled; +} + // Return all the contact points of the scene inline std::vector Scene::getContactPoints() const { diff --git a/testbed/src/TestbedApplication.cpp b/testbed/src/TestbedApplication.cpp index f57aa829..09f464f3 100644 --- a/testbed/src/TestbedApplication.cpp +++ b/testbed/src/TestbedApplication.cpp @@ -30,6 +30,7 @@ #include #include #include "cubes/CubesScene.h" +#include "collisiondetection/CollisionDetectionScene.h" #include "joints/JointsScene.h" #include "collisionshapes/CollisionShapesScene.h" #include "heightfield/HeightFieldScene.h" @@ -43,6 +44,7 @@ using namespace raycastscene; using namespace collisionshapesscene; using namespace trianglemeshscene; using namespace heightfieldscene; +using namespace collisiondetectionscene; // Initialization of static variables const float TestbedApplication::SCROLL_SENSITIVITY = 0.08f; @@ -63,6 +65,7 @@ TestbedApplication::TestbedApplication(bool isFullscreen) mIsShadowMappingEnabled = true; mIsVSyncEnabled = false; mIsContactPointsDisplayed = false; + mIsWireframeEnabled = false; init(); @@ -113,7 +116,11 @@ void TestbedApplication::createScenes() { RaycastScene* raycastScene = new RaycastScene("Raycast"); mScenes.push_back(raycastScene); - // Raycast scene + // Collision Detection scene + CollisionDetectionScene* collisionDetectionScene = new CollisionDetectionScene("Collision Detection"); + mScenes.push_back(collisionDetectionScene); + + // Concave Mesh scene ConcaveMeshScene* concaveMeshScene = new ConcaveMeshScene("Concave Mesh"); mScenes.push_back(concaveMeshScene); @@ -195,6 +202,9 @@ void TestbedApplication::update() { // Display/Hide contact points mCurrentScene->setIsContactPointsDisplayed(mIsContactPointsDisplayed); + // Enable/Disable wireframe mode + mCurrentScene->setIsWireframeEnabled(mIsWireframeEnabled); + // Update the scene mCurrentScene->update(); } diff --git a/testbed/src/TestbedApplication.h b/testbed/src/TestbedApplication.h index dcff0598..93d85ea7 100644 --- a/testbed/src/TestbedApplication.h +++ b/testbed/src/TestbedApplication.h @@ -109,6 +109,9 @@ class TestbedApplication : public Screen { /// True if contact points are displayed bool mIsContactPointsDisplayed; + /// True if the wireframe rendering is enabled + bool mIsWireframeEnabled; + /// True if vsync is enabled bool mIsVSyncEnabled; From a9da0d6d3c7a68136864ebaf88c23e58230c194d Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sat, 28 Jan 2017 00:59:04 +0100 Subject: [PATCH 052/248] Refactor testbed application --- testbed/common/Box.cpp | 6 ++---- testbed/common/Box.h | 2 +- testbed/common/Capsule.cpp | 4 ++-- testbed/common/Capsule.h | 2 +- testbed/common/ConcaveMesh.cpp | 4 ++-- testbed/common/ConcaveMesh.h | 2 +- testbed/common/Cone.cpp | 4 ++-- testbed/common/Cone.h | 2 +- testbed/common/ConvexMesh.cpp | 4 ++-- testbed/common/ConvexMesh.h | 2 +- testbed/common/Cylinder.cpp | 4 ++-- testbed/common/Cylinder.h | 2 +- testbed/common/Dumbbell.cpp | 6 ++---- testbed/common/Dumbbell.h | 2 +- testbed/common/HeightField.cpp | 4 ++-- testbed/common/HeightField.h | 2 +- testbed/common/PhysicsObject.cpp | 2 +- testbed/common/PhysicsObject.h | 2 +- testbed/common/Sphere.cpp | 4 ++-- testbed/common/Sphere.h | 2 +- testbed/scenes/cubes/CubesScene.cpp | 24 ++++++++++++------------ 21 files changed, 41 insertions(+), 45 deletions(-) diff --git a/testbed/common/Box.cpp b/testbed/common/Box.cpp index 6c8f052d..0720799e 100644 --- a/testbed/common/Box.cpp +++ b/testbed/common/Box.cpp @@ -39,8 +39,7 @@ int Box::totalNbBoxes = 0; // Constructor Box::Box(const openglframework::Vector3& size, const openglframework::Vector3 &position, - reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath) - : openglframework::Mesh() { + reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath) { // Load the mesh from a file openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "cube.obj", *this); @@ -94,8 +93,7 @@ Box::Box(const openglframework::Vector3& size, const openglframework::Vector3 &p // Constructor Box::Box(const openglframework::Vector3& size, const openglframework::Vector3& position, - float mass, reactphysics3d::DynamicsWorld* world, const std::string& meshFolderPath) - : openglframework::Mesh() { + float mass, reactphysics3d::DynamicsWorld* world, const std::string& meshFolderPath) { // Load the mesh from a file openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "cube.obj", *this); diff --git a/testbed/common/Box.h b/testbed/common/Box.h index 53da204e..0c21be36 100644 --- a/testbed/common/Box.h +++ b/testbed/common/Box.h @@ -32,7 +32,7 @@ #include "PhysicsObject.h" // Class Box -class Box : public openglframework::Mesh, public PhysicsObject { +class Box : public PhysicsObject { private : diff --git a/testbed/common/Capsule.cpp b/testbed/common/Capsule.cpp index ba6a45b4..e9ae2b40 100644 --- a/testbed/common/Capsule.cpp +++ b/testbed/common/Capsule.cpp @@ -37,7 +37,7 @@ int Capsule::totalNbCapsules = 0; Capsule::Capsule(float radius, float height, const openglframework::Vector3& position, reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath) - : openglframework::Mesh(), mRadius(radius), mHeight(height) { + : mRadius(radius), mHeight(height) { // Load the mesh from a file openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "capsule.obj", *this); @@ -86,7 +86,7 @@ Capsule::Capsule(float radius, float height, const openglframework::Vector3& pos Capsule::Capsule(float radius, float height, const openglframework::Vector3& position, float mass, reactphysics3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath) - : openglframework::Mesh(), mRadius(radius), mHeight(height) { + : mRadius(radius), mHeight(height) { // Load the mesh from a file openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "capsule.obj", *this); diff --git a/testbed/common/Capsule.h b/testbed/common/Capsule.h index 748fa46b..2a97b14b 100644 --- a/testbed/common/Capsule.h +++ b/testbed/common/Capsule.h @@ -32,7 +32,7 @@ #include "PhysicsObject.h" // Class Sphere -class Capsule : public openglframework::Mesh, public PhysicsObject { +class Capsule : public PhysicsObject { private : diff --git a/testbed/common/ConcaveMesh.cpp b/testbed/common/ConcaveMesh.cpp index c21732f8..2f0360ba 100644 --- a/testbed/common/ConcaveMesh.cpp +++ b/testbed/common/ConcaveMesh.cpp @@ -30,7 +30,7 @@ ConcaveMesh::ConcaveMesh(const openglframework::Vector3 &position, reactphysics3d::CollisionWorld* world, const std::string& meshPath) - : openglframework::Mesh(), mVBOVertices(GL_ARRAY_BUFFER), + : mVBOVertices(GL_ARRAY_BUFFER), mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER), mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) { @@ -87,7 +87,7 @@ ConcaveMesh::ConcaveMesh(const openglframework::Vector3 &position, ConcaveMesh::ConcaveMesh(const openglframework::Vector3 &position, float mass, reactphysics3d::DynamicsWorld* dynamicsWorld, const std::string& meshPath) - : openglframework::Mesh(), mVBOVertices(GL_ARRAY_BUFFER), + : mVBOVertices(GL_ARRAY_BUFFER), mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER), mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) { diff --git a/testbed/common/ConcaveMesh.h b/testbed/common/ConcaveMesh.h index 3c645ec8..e4b33308 100644 --- a/testbed/common/ConcaveMesh.h +++ b/testbed/common/ConcaveMesh.h @@ -32,7 +32,7 @@ #include "PhysicsObject.h" // Class ConcaveMesh -class ConcaveMesh : public openglframework::Mesh, public PhysicsObject { +class ConcaveMesh : public PhysicsObject { private : diff --git a/testbed/common/Cone.cpp b/testbed/common/Cone.cpp index 07a825a8..96f52c54 100644 --- a/testbed/common/Cone.cpp +++ b/testbed/common/Cone.cpp @@ -37,7 +37,7 @@ int Cone::totalNbCones = 0; Cone::Cone(float radius, float height, const openglframework::Vector3 &position, reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath) - : openglframework::Mesh(), mRadius(radius), mHeight(height) { + : mRadius(radius), mHeight(height) { // Load the mesh from a file openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "cone.obj", *this); @@ -85,7 +85,7 @@ Cone::Cone(float radius, float height, const openglframework::Vector3 &position, Cone::Cone(float radius, float height, const openglframework::Vector3 &position, float mass, reactphysics3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath) - : openglframework::Mesh(), mRadius(radius), mHeight(height) { + : mRadius(radius), mHeight(height) { // Load the mesh from a file openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "cone.obj", *this); diff --git a/testbed/common/Cone.h b/testbed/common/Cone.h index e4f7face..6fc35182 100644 --- a/testbed/common/Cone.h +++ b/testbed/common/Cone.h @@ -32,7 +32,7 @@ #include "PhysicsObject.h" // Class Cone -class Cone : public openglframework::Mesh, public PhysicsObject { +class Cone : public PhysicsObject { private : diff --git a/testbed/common/ConvexMesh.cpp b/testbed/common/ConvexMesh.cpp index ca372a1f..c107724f 100644 --- a/testbed/common/ConvexMesh.cpp +++ b/testbed/common/ConvexMesh.cpp @@ -30,7 +30,7 @@ ConvexMesh::ConvexMesh(const openglframework::Vector3 &position, reactphysics3d::CollisionWorld* world, const std::string& meshPath) - : openglframework::Mesh(), mVBOVertices(GL_ARRAY_BUFFER), + : mVBOVertices(GL_ARRAY_BUFFER), mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER), mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) { @@ -81,7 +81,7 @@ ConvexMesh::ConvexMesh(const openglframework::Vector3 &position, ConvexMesh::ConvexMesh(const openglframework::Vector3 &position, float mass, reactphysics3d::DynamicsWorld* dynamicsWorld, const std::string& meshPath) - : openglframework::Mesh(), mVBOVertices(GL_ARRAY_BUFFER), + : mVBOVertices(GL_ARRAY_BUFFER), mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER), mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) { diff --git a/testbed/common/ConvexMesh.h b/testbed/common/ConvexMesh.h index a4a2ffab..19b39220 100644 --- a/testbed/common/ConvexMesh.h +++ b/testbed/common/ConvexMesh.h @@ -32,7 +32,7 @@ #include "PhysicsObject.h" // Class ConvexMesh -class ConvexMesh : public openglframework::Mesh, public PhysicsObject { +class ConvexMesh : public PhysicsObject { private : diff --git a/testbed/common/Cylinder.cpp b/testbed/common/Cylinder.cpp index d5ec1964..9b520d5c 100644 --- a/testbed/common/Cylinder.cpp +++ b/testbed/common/Cylinder.cpp @@ -37,7 +37,7 @@ int Cylinder::totalNbCylinders = 0; Cylinder::Cylinder(float radius, float height, const openglframework::Vector3& position, reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath) - : openglframework::Mesh(), mRadius(radius), mHeight(height) { + : mRadius(radius), mHeight(height) { // Load the mesh from a file openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "cylinder.obj", *this); @@ -85,7 +85,7 @@ Cylinder::Cylinder(float radius, float height, const openglframework::Vector3& p Cylinder::Cylinder(float radius, float height, const openglframework::Vector3& position, float mass, reactphysics3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath) - : openglframework::Mesh(), mRadius(radius), mHeight(height) { + : mRadius(radius), mHeight(height) { // Load the mesh from a file openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "cylinder.obj", *this); diff --git a/testbed/common/Cylinder.h b/testbed/common/Cylinder.h index eb7ba72d..4aab2dc9 100644 --- a/testbed/common/Cylinder.h +++ b/testbed/common/Cylinder.h @@ -32,7 +32,7 @@ #include "PhysicsObject.h" // Class Cylinder -class Cylinder : public openglframework::Mesh, public PhysicsObject { +class Cylinder : public PhysicsObject { private : diff --git a/testbed/common/Dumbbell.cpp b/testbed/common/Dumbbell.cpp index e590d033..770f8ec1 100644 --- a/testbed/common/Dumbbell.cpp +++ b/testbed/common/Dumbbell.cpp @@ -35,8 +35,7 @@ int Dumbbell::totalNbDumbbells = 0; // Constructor Dumbbell::Dumbbell(const openglframework::Vector3 &position, - reactphysics3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath) - : openglframework::Mesh() { + reactphysics3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath) { // Load the mesh from a file openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "dumbbell.obj", *this); @@ -106,8 +105,7 @@ Dumbbell::Dumbbell(const openglframework::Vector3 &position, // Constructor Dumbbell::Dumbbell(const openglframework::Vector3 &position, - reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath) - : openglframework::Mesh() { + reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath) { // Load the mesh from a file openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "dumbbell.obj", *this); diff --git a/testbed/common/Dumbbell.h b/testbed/common/Dumbbell.h index 4d44a38b..5ce3ec95 100644 --- a/testbed/common/Dumbbell.h +++ b/testbed/common/Dumbbell.h @@ -32,7 +32,7 @@ #include "PhysicsObject.h" // Class Sphere -class Dumbbell : public openglframework::Mesh, public PhysicsObject { +class Dumbbell : public PhysicsObject { private : diff --git a/testbed/common/HeightField.cpp b/testbed/common/HeightField.cpp index 38eda261..55da4e1d 100644 --- a/testbed/common/HeightField.cpp +++ b/testbed/common/HeightField.cpp @@ -30,7 +30,7 @@ // Constructor HeightField::HeightField(const openglframework::Vector3 &position, reactphysics3d::CollisionWorld* world) - : openglframework::Mesh(), mVBOVertices(GL_ARRAY_BUFFER), + : mVBOVertices(GL_ARRAY_BUFFER), mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER), mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) { @@ -73,7 +73,7 @@ HeightField::HeightField(const openglframework::Vector3 &position, // Constructor HeightField::HeightField(const openglframework::Vector3 &position, float mass, reactphysics3d::DynamicsWorld* dynamicsWorld) - : openglframework::Mesh(), mVBOVertices(GL_ARRAY_BUFFER), + : mVBOVertices(GL_ARRAY_BUFFER), mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER), mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) { diff --git a/testbed/common/HeightField.h b/testbed/common/HeightField.h index d4a4895d..d9851992 100644 --- a/testbed/common/HeightField.h +++ b/testbed/common/HeightField.h @@ -33,7 +33,7 @@ // Class HeightField -class HeightField : public openglframework::Mesh, public PhysicsObject { +class HeightField : public PhysicsObject { private : diff --git a/testbed/common/PhysicsObject.cpp b/testbed/common/PhysicsObject.cpp index c176bb5d..c69f9485 100644 --- a/testbed/common/PhysicsObject.cpp +++ b/testbed/common/PhysicsObject.cpp @@ -27,7 +27,7 @@ #include "PhysicsObject.h" /// Constructor -PhysicsObject::PhysicsObject() { +PhysicsObject::PhysicsObject() : openglframework::Mesh() { mColor = openglframework::Color(1, 1, 1, 1); mSleepingColor = openglframework::Color(1, 0, 0, 1); diff --git a/testbed/common/PhysicsObject.h b/testbed/common/PhysicsObject.h index 5a54d6d0..bc470091 100644 --- a/testbed/common/PhysicsObject.h +++ b/testbed/common/PhysicsObject.h @@ -31,7 +31,7 @@ #include "reactphysics3d.h" // Class PhysicsObject -class PhysicsObject { +class PhysicsObject : public openglframework::Mesh { protected: diff --git a/testbed/common/Sphere.cpp b/testbed/common/Sphere.cpp index 236a81ad..93c48af2 100644 --- a/testbed/common/Sphere.cpp +++ b/testbed/common/Sphere.cpp @@ -37,7 +37,7 @@ int Sphere::totalNbSpheres = 0; Sphere::Sphere(float radius, const openglframework::Vector3 &position, reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath) - : openglframework::Mesh(), mRadius(radius) { + : mRadius(radius) { // Load the mesh from a file openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "sphere.obj", *this); @@ -86,7 +86,7 @@ Sphere::Sphere(float radius, const openglframework::Vector3 &position, Sphere::Sphere(float radius, const openglframework::Vector3 &position, float mass, reactphysics3d::DynamicsWorld* world, const std::string& meshFolderPath) - : openglframework::Mesh(), mRadius(radius) { + : mRadius(radius) { // Load the mesh from a file openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "sphere.obj", *this); diff --git a/testbed/common/Sphere.h b/testbed/common/Sphere.h index 5fdfcfe9..d941d984 100644 --- a/testbed/common/Sphere.h +++ b/testbed/common/Sphere.h @@ -32,7 +32,7 @@ #include "PhysicsObject.h" // Class Sphere -class Sphere : public openglframework::Mesh, public PhysicsObject { +class Sphere : public PhysicsObject { private : diff --git a/testbed/scenes/cubes/CubesScene.cpp b/testbed/scenes/cubes/CubesScene.cpp index 17af45c1..81929e58 100644 --- a/testbed/scenes/cubes/CubesScene.cpp +++ b/testbed/scenes/cubes/CubesScene.cpp @@ -195,19 +195,19 @@ void CubesScene::reset() { float radius = 2.0f; - for (int i=0; iresetTransform(transform); - } +// mBoxes[i]->resetTransform(transform); +// } } From 0b0975769b1a408266cf3f23e1175709e48cfe77 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sat, 28 Jan 2017 11:38:48 +0100 Subject: [PATCH 053/248] Refactor testbed application --- testbed/common/Box.cpp | 30 +++------------- testbed/common/Box.h | 3 -- testbed/common/Capsule.cpp | 34 ++---------------- testbed/common/Capsule.h | 3 -- testbed/common/ConcaveMesh.cpp | 34 ++---------------- testbed/common/ConcaveMesh.h | 3 -- testbed/common/Cone.cpp | 34 ++---------------- testbed/common/Cone.h | 3 -- testbed/common/ConvexMesh.cpp | 34 ++---------------- testbed/common/ConvexMesh.h | 3 -- testbed/common/Cylinder.cpp | 34 ++---------------- testbed/common/Cylinder.h | 3 -- testbed/common/Dumbbell.cpp | 36 +++---------------- testbed/common/Dumbbell.h | 3 -- testbed/common/HeightField.cpp | 18 ---------- testbed/common/HeightField.h | 3 -- testbed/common/PhysicsObject.cpp | 28 +++++++++++++++ testbed/common/PhysicsObject.h | 6 ++++ testbed/common/Sphere.cpp | 34 ++---------------- testbed/common/Sphere.h | 3 -- .../CollisionDetectionScene.h | 1 - 21 files changed, 54 insertions(+), 296 deletions(-) diff --git a/testbed/common/Box.cpp b/testbed/common/Box.cpp index 0720799e..09dc388e 100644 --- a/testbed/common/Box.cpp +++ b/testbed/common/Box.cpp @@ -39,13 +39,8 @@ int Box::totalNbBoxes = 0; // Constructor Box::Box(const openglframework::Vector3& size, const openglframework::Vector3 &position, - reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath) { - - // Load the mesh from a file - openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "cube.obj", *this); - - // Calculate the normals of the mesh - calculateNormals(); + reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath) + : PhysicsObject(meshFolderPath + "cube.obj") { // Initialize the size of the box mSize[0] = size.x * 0.5f; @@ -93,7 +88,8 @@ Box::Box(const openglframework::Vector3& size, const openglframework::Vector3 &p // Constructor Box::Box(const openglframework::Vector3& size, const openglframework::Vector3& position, - float mass, reactphysics3d::DynamicsWorld* world, const std::string& meshFolderPath) { + float mass, reactphysics3d::DynamicsWorld* world, const std::string& meshFolderPath) + : PhysicsObject(meshFolderPath + "cube.obj") { // Load the mesh from a file openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "cube.obj", *this); @@ -284,24 +280,6 @@ void Box::createVBOAndVAO() { mVAO.unbind(); } -// Reset the transform -void Box::resetTransform(const rp3d::Transform& transform) { - - // Reset the transform - mBody->setTransform(transform); - - mBody->setIsSleeping(false); - - // Reset the velocity of the rigid body - rp3d::RigidBody* rigidBody = dynamic_cast(mBody); - if (rigidBody != nullptr) { - rigidBody->setLinearVelocity(rp3d::Vector3(0, 0, 0)); - rigidBody->setAngularVelocity(rp3d::Vector3(0, 0, 0)); - } - - updateTransform(1.0f); -} - // Set the scaling of the object void Box::setScaling(const openglframework::Vector3& scaling) { diff --git a/testbed/common/Box.h b/testbed/common/Box.h index 0c21be36..a1f05d5e 100644 --- a/testbed/common/Box.h +++ b/testbed/common/Box.h @@ -88,9 +88,6 @@ class Box : public PhysicsObject { /// Render the cube at the correct position and with the correct orientation void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe); - /// Set the position of the box - void resetTransform(const rp3d::Transform& transform); - /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; diff --git a/testbed/common/Capsule.cpp b/testbed/common/Capsule.cpp index e9ae2b40..413d6eb2 100644 --- a/testbed/common/Capsule.cpp +++ b/testbed/common/Capsule.cpp @@ -37,13 +37,7 @@ int Capsule::totalNbCapsules = 0; Capsule::Capsule(float radius, float height, const openglframework::Vector3& position, reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath) - : mRadius(radius), mHeight(height) { - - // Load the mesh from a file - openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "capsule.obj", *this); - - // Calculate the normals of the mesh - calculateNormals(); + : PhysicsObject(meshFolderPath + "capsule.obj"), mRadius(radius), mHeight(height) { // Compute the scaling matrix mScalingMatrix = openglframework::Matrix4(mRadius, 0, 0, 0, @@ -86,13 +80,7 @@ Capsule::Capsule(float radius, float height, const openglframework::Vector3& pos Capsule::Capsule(float radius, float height, const openglframework::Vector3& position, float mass, reactphysics3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath) - : mRadius(radius), mHeight(height) { - - // Load the mesh from a file - openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "capsule.obj", *this); - - // Calculate the normals of the mesh - calculateNormals(); + : PhysicsObject(meshFolderPath + "capsule.obj"), mRadius(radius), mHeight(height) { // Compute the scaling matrix mScalingMatrix = openglframework::Matrix4(mRadius, 0, 0, 0, @@ -272,24 +260,6 @@ void Capsule::createVBOAndVAO() { mVAO.unbind(); } -// Reset the transform -void Capsule::resetTransform(const rp3d::Transform& transform) { - - // Reset the transform - mBody->setTransform(transform); - - mBody->setIsSleeping(false); - - // Reset the velocity of the rigid body - rp3d::RigidBody* rigidBody = dynamic_cast(mBody); - if (rigidBody != nullptr) { - rigidBody->setLinearVelocity(rp3d::Vector3(0, 0, 0)); - rigidBody->setAngularVelocity(rp3d::Vector3(0, 0, 0)); - } - - updateTransform(1.0f); -} - // Set the scaling of the object void Capsule::setScaling(const openglframework::Vector3& scaling) { diff --git a/testbed/common/Capsule.h b/testbed/common/Capsule.h index 2a97b14b..f117984f 100644 --- a/testbed/common/Capsule.h +++ b/testbed/common/Capsule.h @@ -97,9 +97,6 @@ class Capsule : public PhysicsObject { void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe); - /// Set the position of the box - void resetTransform(const rp3d::Transform& transform); - /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; diff --git a/testbed/common/ConcaveMesh.cpp b/testbed/common/ConcaveMesh.cpp index 2f0360ba..608e0020 100644 --- a/testbed/common/ConcaveMesh.cpp +++ b/testbed/common/ConcaveMesh.cpp @@ -30,16 +30,10 @@ ConcaveMesh::ConcaveMesh(const openglframework::Vector3 &position, reactphysics3d::CollisionWorld* world, const std::string& meshPath) - : mVBOVertices(GL_ARRAY_BUFFER), + : PhysicsObject(meshPath), mVBOVertices(GL_ARRAY_BUFFER), mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER), mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) { - // Load the mesh from a file - openglframework::MeshReaderWriter::loadMeshFromFile(meshPath, *this); - - // Calculate the normals of the mesh - calculateNormals(); - // Initialize the position where the sphere will be rendered translateWorld(position); @@ -87,16 +81,10 @@ ConcaveMesh::ConcaveMesh(const openglframework::Vector3 &position, ConcaveMesh::ConcaveMesh(const openglframework::Vector3 &position, float mass, reactphysics3d::DynamicsWorld* dynamicsWorld, const std::string& meshPath) - : mVBOVertices(GL_ARRAY_BUFFER), + : PhysicsObject(meshPath), mVBOVertices(GL_ARRAY_BUFFER), mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER), mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) { - // Load the mesh from a file - openglframework::MeshReaderWriter::loadMeshFromFile(meshPath, *this); - - // Calculate the normals of the mesh - calculateNormals(); - // Initialize the position where the sphere will be rendered translateWorld(position); @@ -285,24 +273,6 @@ void ConcaveMesh::createVBOAndVAO() { mVAO.unbind(); } -// Reset the transform -void ConcaveMesh::resetTransform(const rp3d::Transform& transform) { - - // Reset the transform - mBody->setTransform(transform); - - mBody->setIsSleeping(false); - - // Reset the velocity of the rigid body - rp3d::RigidBody* rigidBody = dynamic_cast(mBody); - if (rigidBody != nullptr) { - rigidBody->setLinearVelocity(rp3d::Vector3(0, 0, 0)); - rigidBody->setAngularVelocity(rp3d::Vector3(0, 0, 0)); - } - - updateTransform(1.0f); -} - // Set the scaling of the object void ConcaveMesh::setScaling(const openglframework::Vector3& scaling) { diff --git a/testbed/common/ConcaveMesh.h b/testbed/common/ConcaveMesh.h index e4b33308..afda3d45 100644 --- a/testbed/common/ConcaveMesh.h +++ b/testbed/common/ConcaveMesh.h @@ -90,9 +90,6 @@ class ConcaveMesh : public PhysicsObject { void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe); - /// Set the position of the box - void resetTransform(const rp3d::Transform& transform); - /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; diff --git a/testbed/common/Cone.cpp b/testbed/common/Cone.cpp index 96f52c54..bbd32ed9 100644 --- a/testbed/common/Cone.cpp +++ b/testbed/common/Cone.cpp @@ -37,13 +37,7 @@ int Cone::totalNbCones = 0; Cone::Cone(float radius, float height, const openglframework::Vector3 &position, reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath) - : mRadius(radius), mHeight(height) { - - // Load the mesh from a file - openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "cone.obj", *this); - - // Calculate the normals of the mesh - calculateNormals(); + : PhysicsObject(meshFolderPath + "cone.obj"), mRadius(radius), mHeight(height) { // Compute the scaling matrix mScalingMatrix = openglframework::Matrix4(mRadius, 0, 0, 0, @@ -85,13 +79,7 @@ Cone::Cone(float radius, float height, const openglframework::Vector3 &position, Cone::Cone(float radius, float height, const openglframework::Vector3 &position, float mass, reactphysics3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath) - : mRadius(radius), mHeight(height) { - - // Load the mesh from a file - openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "cone.obj", *this); - - // Calculate the normals of the mesh - calculateNormals(); + : PhysicsObject(meshFolderPath + "cone.obj"), mRadius(radius), mHeight(height) { // Compute the scaling matrix mScalingMatrix = openglframework::Matrix4(mRadius, 0, 0, 0, @@ -269,24 +257,6 @@ void Cone::createVBOAndVAO() { mVAO.unbind(); } -// Reset the transform -void Cone::resetTransform(const rp3d::Transform& transform) { - - // Reset the transform - mBody->setTransform(transform); - - mBody->setIsSleeping(false); - - // Reset the velocity of the rigid body - rp3d::RigidBody* rigidBody = dynamic_cast(mBody); - if (rigidBody != nullptr) { - rigidBody->setLinearVelocity(rp3d::Vector3(0, 0, 0)); - rigidBody->setAngularVelocity(rp3d::Vector3(0, 0, 0)); - } - - updateTransform(1.0f); -} - // Set the scaling of the object void Cone::setScaling(const openglframework::Vector3& scaling) { diff --git a/testbed/common/Cone.h b/testbed/common/Cone.h index 6fc35182..8f71493c 100644 --- a/testbed/common/Cone.h +++ b/testbed/common/Cone.h @@ -96,9 +96,6 @@ class Cone : public PhysicsObject { void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe); - /// Set the position of the box - void resetTransform(const rp3d::Transform& transform); - /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; diff --git a/testbed/common/ConvexMesh.cpp b/testbed/common/ConvexMesh.cpp index c107724f..7842c529 100644 --- a/testbed/common/ConvexMesh.cpp +++ b/testbed/common/ConvexMesh.cpp @@ -30,16 +30,10 @@ ConvexMesh::ConvexMesh(const openglframework::Vector3 &position, reactphysics3d::CollisionWorld* world, const std::string& meshPath) - : mVBOVertices(GL_ARRAY_BUFFER), + : PhysicsObject(meshPath), mVBOVertices(GL_ARRAY_BUFFER), mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER), mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) { - // Load the mesh from a file - openglframework::MeshReaderWriter::loadMeshFromFile(meshPath, *this); - - // Calculate the normals of the mesh - calculateNormals(); - // Initialize the position where the sphere will be rendered translateWorld(position); @@ -81,16 +75,10 @@ ConvexMesh::ConvexMesh(const openglframework::Vector3 &position, ConvexMesh::ConvexMesh(const openglframework::Vector3 &position, float mass, reactphysics3d::DynamicsWorld* dynamicsWorld, const std::string& meshPath) - : mVBOVertices(GL_ARRAY_BUFFER), + : PhysicsObject(meshPath), mVBOVertices(GL_ARRAY_BUFFER), mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER), mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) { - // Load the mesh from a file - openglframework::MeshReaderWriter::loadMeshFromFile(meshPath, *this); - - // Calculate the normals of the mesh - calculateNormals(); - // Initialize the position where the sphere will be rendered translateWorld(position); @@ -266,24 +254,6 @@ void ConvexMesh::createVBOAndVAO() { mVAO.unbind(); } -// Reset the transform -void ConvexMesh::resetTransform(const rp3d::Transform& transform) { - - // Reset the transform - mBody->setTransform(transform); - - mBody->setIsSleeping(false); - - // Reset the velocity of the rigid body - rp3d::RigidBody* rigidBody = dynamic_cast(mBody); - if (rigidBody != nullptr) { - rigidBody->setLinearVelocity(rp3d::Vector3(0, 0, 0)); - rigidBody->setAngularVelocity(rp3d::Vector3(0, 0, 0)); - } - - updateTransform(1.0f); -} - // Set the scaling of the object void ConvexMesh::setScaling(const openglframework::Vector3& scaling) { diff --git a/testbed/common/ConvexMesh.h b/testbed/common/ConvexMesh.h index 19b39220..b6cb90c1 100644 --- a/testbed/common/ConvexMesh.h +++ b/testbed/common/ConvexMesh.h @@ -89,9 +89,6 @@ class ConvexMesh : public PhysicsObject { void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe); - /// Set the position of the box - void resetTransform(const rp3d::Transform& transform); - /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; diff --git a/testbed/common/Cylinder.cpp b/testbed/common/Cylinder.cpp index 9b520d5c..2943c3e8 100644 --- a/testbed/common/Cylinder.cpp +++ b/testbed/common/Cylinder.cpp @@ -37,13 +37,7 @@ int Cylinder::totalNbCylinders = 0; Cylinder::Cylinder(float radius, float height, const openglframework::Vector3& position, reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath) - : mRadius(radius), mHeight(height) { - - // Load the mesh from a file - openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "cylinder.obj", *this); - - // Calculate the normals of the mesh - calculateNormals(); + : PhysicsObject(meshFolderPath + "cylinder.obj"), mRadius(radius), mHeight(height) { // Compute the scaling matrix mScalingMatrix = openglframework::Matrix4(mRadius, 0, 0, 0, @@ -85,13 +79,7 @@ Cylinder::Cylinder(float radius, float height, const openglframework::Vector3& p Cylinder::Cylinder(float radius, float height, const openglframework::Vector3& position, float mass, reactphysics3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath) - : mRadius(radius), mHeight(height) { - - // Load the mesh from a file - openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "cylinder.obj", *this); - - // Calculate the normals of the mesh - calculateNormals(); + : PhysicsObject(meshFolderPath + "cylinder.obj"), mRadius(radius), mHeight(height) { // Compute the scaling matrix mScalingMatrix = openglframework::Matrix4(mRadius, 0, 0, 0, @@ -270,24 +258,6 @@ void Cylinder::createVBOAndVAO() { mVAO.unbind(); } -// Reset the transform -void Cylinder::resetTransform(const rp3d::Transform& transform) { - - // Reset the transform - mBody->setTransform(transform); - - mBody->setIsSleeping(false); - - // Reset the velocity of the rigid body - rp3d::RigidBody* rigidBody = dynamic_cast(mBody); - if (rigidBody != nullptr) { - rigidBody->setLinearVelocity(rp3d::Vector3(0, 0, 0)); - rigidBody->setAngularVelocity(rp3d::Vector3(0, 0, 0)); - } - - updateTransform(1.0f); -} - // Set the scaling of the object void Cylinder::setScaling(const openglframework::Vector3& scaling) { diff --git a/testbed/common/Cylinder.h b/testbed/common/Cylinder.h index 4aab2dc9..3a94b443 100644 --- a/testbed/common/Cylinder.h +++ b/testbed/common/Cylinder.h @@ -96,9 +96,6 @@ class Cylinder : public PhysicsObject { void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe); - /// Set the position of the box - void resetTransform(const rp3d::Transform& transform); - /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; diff --git a/testbed/common/Dumbbell.cpp b/testbed/common/Dumbbell.cpp index 770f8ec1..03afd59b 100644 --- a/testbed/common/Dumbbell.cpp +++ b/testbed/common/Dumbbell.cpp @@ -35,13 +35,8 @@ int Dumbbell::totalNbDumbbells = 0; // Constructor Dumbbell::Dumbbell(const openglframework::Vector3 &position, - reactphysics3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath) { - - // Load the mesh from a file - openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "dumbbell.obj", *this); - - // Calculate the normals of the mesh - calculateNormals(); + reactphysics3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath) + : PhysicsObject(meshFolderPath + "dumbbell.obj") { // Identity scaling matrix mScalingMatrix.setToIdentity(); @@ -105,13 +100,8 @@ Dumbbell::Dumbbell(const openglframework::Vector3 &position, // Constructor Dumbbell::Dumbbell(const openglframework::Vector3 &position, - reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath) { - - // Load the mesh from a file - openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "dumbbell.obj", *this); - - // Calculate the normals of the mesh - calculateNormals(); + reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath) + : PhysicsObject(meshFolderPath + "dumbbell.obj"){ // Identity scaling matrix mScalingMatrix.setToIdentity(); @@ -309,24 +299,6 @@ void Dumbbell::createVBOAndVAO() { mVAO.unbind(); } -// Reset the transform -void Dumbbell::resetTransform(const rp3d::Transform& transform) { - - // Reset the transform - mBody->setTransform(transform); - - mBody->setIsSleeping(false); - - // Reset the velocity of the rigid body - rp3d::RigidBody* rigidBody = dynamic_cast(mBody); - if (rigidBody != NULL) { - rigidBody->setLinearVelocity(rp3d::Vector3(0, 0, 0)); - rigidBody->setAngularVelocity(rp3d::Vector3(0, 0, 0)); - } - - updateTransform(1.0f); -} - // Set the scaling of the object void Dumbbell::setScaling(const openglframework::Vector3& scaling) { diff --git a/testbed/common/Dumbbell.h b/testbed/common/Dumbbell.h index 5ce3ec95..81020935 100644 --- a/testbed/common/Dumbbell.h +++ b/testbed/common/Dumbbell.h @@ -97,9 +97,6 @@ class Dumbbell : public PhysicsObject { void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe); - /// Set the position of the box - void resetTransform(const rp3d::Transform& transform); - /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; diff --git a/testbed/common/HeightField.cpp b/testbed/common/HeightField.cpp index 55da4e1d..377cab07 100644 --- a/testbed/common/HeightField.cpp +++ b/testbed/common/HeightField.cpp @@ -328,24 +328,6 @@ void HeightField::createVBOAndVAO() { mVAO.unbind(); } -// Reset the transform -void HeightField::resetTransform(const rp3d::Transform& transform) { - - // Reset the transform - mBody->setTransform(transform); - - mBody->setIsSleeping(false); - - // Reset the velocity of the rigid body - rp3d::RigidBody* rigidBody = dynamic_cast(mBody); - if (rigidBody != NULL) { - rigidBody->setLinearVelocity(rp3d::Vector3(0, 0, 0)); - rigidBody->setAngularVelocity(rp3d::Vector3(0, 0, 0)); - } - - updateTransform(1.0f); -} - // Set the scaling of the object void HeightField::setScaling(const openglframework::Vector3& scaling) { diff --git a/testbed/common/HeightField.h b/testbed/common/HeightField.h index d9851992..acb39163 100644 --- a/testbed/common/HeightField.h +++ b/testbed/common/HeightField.h @@ -103,9 +103,6 @@ class HeightField : public PhysicsObject { void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe); - /// Set the position of the box - void resetTransform(const rp3d::Transform& transform); - /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; diff --git a/testbed/common/PhysicsObject.cpp b/testbed/common/PhysicsObject.cpp index c69f9485..acba8e67 100644 --- a/testbed/common/PhysicsObject.cpp +++ b/testbed/common/PhysicsObject.cpp @@ -33,6 +33,16 @@ PhysicsObject::PhysicsObject() : openglframework::Mesh() { mSleepingColor = openglframework::Color(1, 0, 0, 1); } +/// Constructor +PhysicsObject::PhysicsObject(const std::string& meshPath) : PhysicsObject() { + + // Load the mesh from a file + openglframework::MeshReaderWriter::loadMeshFromFile(meshPath, *this); + + // Calculate the normals of the mesh + calculateNormals(); +} + // Compute the new transform matrix openglframework::Matrix4 PhysicsObject::computeTransform(float interpolationFactor, const openglframework::Matrix4& scalingMatrix) { @@ -57,3 +67,21 @@ openglframework::Matrix4 PhysicsObject::computeTransform(float interpolationFact // Apply the scaling matrix to have the correct box dimensions return newMatrix * scalingMatrix; } + +// Reset the transform +void PhysicsObject::resetTransform(const rp3d::Transform& transform) { + + // Reset the transform + mBody->setTransform(transform); + + mBody->setIsSleeping(false); + + // Reset the velocity of the rigid body + rp3d::RigidBody* rigidBody = dynamic_cast(mBody); + if (rigidBody != nullptr) { + rigidBody->setLinearVelocity(rp3d::Vector3(0, 0, 0)); + rigidBody->setAngularVelocity(rp3d::Vector3(0, 0, 0)); + } + + updateTransform(1.0f); +} diff --git a/testbed/common/PhysicsObject.h b/testbed/common/PhysicsObject.h index bc470091..15f5cf80 100644 --- a/testbed/common/PhysicsObject.h +++ b/testbed/common/PhysicsObject.h @@ -56,6 +56,9 @@ class PhysicsObject : public openglframework::Mesh { /// Constructor PhysicsObject(); + /// Constructor + PhysicsObject(const std::string& meshPath); + /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor)=0; @@ -65,6 +68,9 @@ class PhysicsObject : public openglframework::Mesh { /// Set the sleeping color of the box void setSleepingColor(const openglframework::Color& color); + /// Set the position of the box + void resetTransform(const rp3d::Transform& transform); + /// Return a pointer to the collision body of the box reactphysics3d::CollisionBody* getCollisionBody(); diff --git a/testbed/common/Sphere.cpp b/testbed/common/Sphere.cpp index 93c48af2..9eaf62c2 100644 --- a/testbed/common/Sphere.cpp +++ b/testbed/common/Sphere.cpp @@ -37,13 +37,7 @@ int Sphere::totalNbSpheres = 0; Sphere::Sphere(float radius, const openglframework::Vector3 &position, reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath) - : mRadius(radius) { - - // Load the mesh from a file - openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "sphere.obj", *this); - - // Calculate the normals of the mesh - calculateNormals(); + : PhysicsObject(meshFolderPath + "sphere.obj"), mRadius(radius) { // Compute the scaling matrix mScalingMatrix = openglframework::Matrix4(mRadius, 0, 0, 0, @@ -86,13 +80,7 @@ Sphere::Sphere(float radius, const openglframework::Vector3 &position, Sphere::Sphere(float radius, const openglframework::Vector3 &position, float mass, reactphysics3d::DynamicsWorld* world, const std::string& meshFolderPath) - : mRadius(radius) { - - // Load the mesh from a file - openglframework::MeshReaderWriter::loadMeshFromFile(meshFolderPath + "sphere.obj", *this); - - // Calculate the normals of the mesh - calculateNormals(); + : PhysicsObject(meshFolderPath + "sphere.obj"), mRadius(radius) { // Compute the scaling matrix mScalingMatrix = openglframework::Matrix4(mRadius, 0, 0, 0, @@ -270,24 +258,6 @@ void Sphere::createVBOAndVAO() { mVAO.unbind(); } -// Reset the transform -void Sphere::resetTransform(const rp3d::Transform& transform) { - - // Reset the transform - mBody->setTransform(transform); - - mBody->setIsSleeping(false); - - // Reset the velocity of the rigid body - rp3d::RigidBody* rigidBody = dynamic_cast(mBody); - if (rigidBody != NULL) { - rigidBody->setLinearVelocity(rp3d::Vector3(0, 0, 0)); - rigidBody->setAngularVelocity(rp3d::Vector3(0, 0, 0)); - } - - updateTransform(1.0f); -} - // Set the scaling of the object void Sphere::setScaling(const openglframework::Vector3& scaling) { diff --git a/testbed/common/Sphere.h b/testbed/common/Sphere.h index d941d984..62f1809e 100644 --- a/testbed/common/Sphere.h +++ b/testbed/common/Sphere.h @@ -93,9 +93,6 @@ class Sphere : public PhysicsObject { void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe); - /// Set the position of the box - void resetTransform(const rp3d::Transform& transform); - /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.h b/testbed/scenes/collisiondetection/CollisionDetectionScene.h index d77cee7f..06b426fe 100644 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.h +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.h @@ -27,7 +27,6 @@ #define COLLISION_DETECTION_SCENE_H // Libraries -#define _USE_MATH_DEFINES #include #include "openglframework.h" #include "reactphysics3d.h" From adeac945061b4b737dc08c3609982b2b554709da Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sat, 28 Jan 2017 15:23:05 +0100 Subject: [PATCH 054/248] Working on collision detection scene --- testbed/common/PhysicsObject.cpp | 2 +- testbed/common/PhysicsObject.h | 12 ++- .../CollisionDetectionScene.cpp | 78 ++++++++++++++++--- .../CollisionDetectionScene.h | 3 +- .../collisionshapes/CollisionShapesScene.cpp | 14 ++-- .../scenes/concavemesh/ConcaveMeshScene.cpp | 4 +- .../scenes/heightfield/HeightFieldScene.cpp | 4 +- testbed/scenes/joints/JointsScene.cpp | 12 +-- testbed/src/TestbedApplication.h | 16 ---- 9 files changed, 96 insertions(+), 49 deletions(-) diff --git a/testbed/common/PhysicsObject.cpp b/testbed/common/PhysicsObject.cpp index acba8e67..9955725c 100644 --- a/testbed/common/PhysicsObject.cpp +++ b/testbed/common/PhysicsObject.cpp @@ -69,7 +69,7 @@ openglframework::Matrix4 PhysicsObject::computeTransform(float interpolationFact } // Reset the transform -void PhysicsObject::resetTransform(const rp3d::Transform& transform) { +void PhysicsObject::setTransform(const rp3d::Transform& transform) { // Reset the transform mBody->setTransform(transform); diff --git a/testbed/common/PhysicsObject.h b/testbed/common/PhysicsObject.h index 15f5cf80..0da224c3 100644 --- a/testbed/common/PhysicsObject.h +++ b/testbed/common/PhysicsObject.h @@ -68,8 +68,11 @@ class PhysicsObject : public openglframework::Mesh { /// Set the sleeping color of the box void setSleepingColor(const openglframework::Color& color); - /// Set the position of the box - void resetTransform(const rp3d::Transform& transform); + /// Get the transform + const rp3d::Transform& getTransform() const; + + /// Set the transform + void setTransform(const rp3d::Transform& transform); /// Return a pointer to the collision body of the box reactphysics3d::CollisionBody* getCollisionBody(); @@ -91,6 +94,11 @@ inline void PhysicsObject::setSleepingColor(const openglframework::Color& color) mSleepingColor = color; } +// Get the transform +inline const rp3d::Transform& PhysicsObject::getTransform() const { + return mBody->getTransform(); +} + // Return a pointer to the collision body of the box inline rp3d::CollisionBody* PhysicsObject::getCollisionBody() { return mBody; diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp index 09544540..8aae0145 100644 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp @@ -54,8 +54,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) // Create a sphere and a corresponding collision body in the dynamics world mSphere1 = new Sphere(6, position1, mCollisionWorld, mMeshFolderPath); - mAllShapesObjects.push_back(mSphere1); - mAllShapesPhysicsObjects.push_back(mSphere1); + mAllShapes.push_back(mSphere1); // Set the color mSphere1->setColor(mGreyColorDemo); @@ -66,8 +65,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) // Create a sphere and a corresponding collision body in the dynamics world mSphere2 = new Sphere(4, position2, mCollisionWorld, mMeshFolderPath); - mAllShapesObjects.push_back(mSphere2); - mAllShapesPhysicsObjects.push_back(mSphere2); + mAllShapes.push_back(mSphere2); // Set the color mSphere2->setColor(mGreyColorDemo); @@ -139,7 +137,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) // Create the VBO and VAO to render the lines createVBOAndVAO(mPhongShader); - mAllShapesPhysicsObjects[mSelectedShapeIndex]->setColor(mBlueColorDemo); + mAllShapes[mSelectedShapeIndex]->setColor(mBlueColorDemo); } // Reset the scene @@ -332,12 +330,12 @@ void CollisionDetectionScene::selectNextShape() { int previousIndex = mSelectedShapeIndex; mSelectedShapeIndex++; - if (mSelectedShapeIndex >= mAllShapesPhysicsObjects.size()) { + if (mSelectedShapeIndex >= mAllShapes.size()) { mSelectedShapeIndex = 0; } - mAllShapesPhysicsObjects[previousIndex]->setColor(mGreyColorDemo); - mAllShapesPhysicsObjects[mSelectedShapeIndex]->setColor(mBlueColorDemo); + mAllShapes[previousIndex]->setColor(mGreyColorDemo); + mAllShapes[mSelectedShapeIndex]->setColor(mBlueColorDemo); } // Called when a keyboard event occurs @@ -349,10 +347,68 @@ bool CollisionDetectionScene::keyboardEvent(int key, int scancode, int action, i return true; } + float stepDist = 0.5f; + float stepAngle = 20 * (3.14f / 180.0f); + if (key == GLFW_KEY_RIGHT && action == GLFW_PRESS) { - rp3d::Transform transform = mAllShapesPhysicsObjects[mSelectedShapeIndex]->getCollisionBody()->getTransform(); - transform.setPosition(transform.getPosition() + rp3d::Vector3(1, 0, 0)); - mAllShapesObjects[mSelectedShapeIndex]->translateWorld(openglframework::Vector3(1, 0, 0)); + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setPosition(transform.getPosition() + rp3d::Vector3(stepDist, 0, 0)); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_LEFT && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setPosition(transform.getPosition() + rp3d::Vector3(-stepDist, 0, 0)); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_UP && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setPosition(transform.getPosition() + rp3d::Vector3(0, stepDist, 0)); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_DOWN && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setPosition(transform.getPosition() + rp3d::Vector3(0, -stepDist, 0)); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_Z && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setPosition(transform.getPosition() + rp3d::Vector3(0, 0, stepDist)); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_H && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setPosition(transform.getPosition() + rp3d::Vector3(0, 0, -stepDist)); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_A && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setOrientation(rp3d::Quaternion(0, stepAngle, 0) * transform.getOrientation()); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_D && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setOrientation(rp3d::Quaternion(0, -stepAngle, 0) * transform.getOrientation()); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_W && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setOrientation(rp3d::Quaternion(stepAngle, 0, 0) * transform.getOrientation()); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_S && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setOrientation(rp3d::Quaternion(-stepAngle, 0, 0) * transform.getOrientation()); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_F && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setOrientation(rp3d::Quaternion(0, 0, stepAngle) * transform.getOrientation()); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_G && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setOrientation(rp3d::Quaternion(0, 0, -stepAngle) * transform.getOrientation()); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); } return false; diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.h b/testbed/scenes/collisiondetection/CollisionDetectionScene.h index 06b426fe..b7f57c1d 100644 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.h +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.h @@ -146,8 +146,7 @@ class CollisionDetectionScene : public SceneDemo { //ConcaveMesh* mConcaveMesh; //HeightField* mHeightField; - std::vector mAllShapesObjects; - std::vector mAllShapesPhysicsObjects; + std::vector mAllShapes; int mSelectedShapeIndex; diff --git a/testbed/scenes/collisionshapes/CollisionShapesScene.cpp b/testbed/scenes/collisionshapes/CollisionShapesScene.cpp index e146bd6b..8db4908a 100644 --- a/testbed/scenes/collisionshapes/CollisionShapesScene.cpp +++ b/testbed/scenes/collisionshapes/CollisionShapesScene.cpp @@ -524,7 +524,7 @@ void CollisionShapesScene::reset() { rp3d::Transform transform(initPosition, initOrientation); // Reset the transform - mDumbbells[i]->resetTransform(transform); + mDumbbells[i]->setTransform(transform); } // Create all the boxes of the scene @@ -542,7 +542,7 @@ void CollisionShapesScene::reset() { rp3d::Transform transform(initPosition, initOrientation); // Reset the transform - mBoxes[i]->resetTransform(transform); + mBoxes[i]->setTransform(transform); } // Create all the spheres of the scene @@ -560,7 +560,7 @@ void CollisionShapesScene::reset() { rp3d::Transform transform(initPosition, initOrientation); // Reset the transform - mSpheres[i]->resetTransform(transform); + mSpheres[i]->setTransform(transform); } // Create all the cones of the scene @@ -578,7 +578,7 @@ void CollisionShapesScene::reset() { rp3d::Transform transform(initPosition, initOrientation); // Reset the transform - mCones[i]->resetTransform(transform); + mCones[i]->setTransform(transform); } // Create all the cylinders of the scene @@ -596,7 +596,7 @@ void CollisionShapesScene::reset() { rp3d::Transform transform(initPosition, initOrientation); // Reset the transform - mCylinders[i]->resetTransform(transform); + mCylinders[i]->setTransform(transform); } // Create all the capsules of the scene @@ -614,7 +614,7 @@ void CollisionShapesScene::reset() { rp3d::Transform transform(initPosition, initOrientation); // Reset the transform - mCapsules[i]->resetTransform(transform); + mCapsules[i]->setTransform(transform); } // Create all the convex meshes of the scene @@ -632,6 +632,6 @@ void CollisionShapesScene::reset() { rp3d::Transform transform(initPosition, initOrientation); // Reset the transform - mConvexMeshes[i]->resetTransform(transform); + mConvexMeshes[i]->setTransform(transform); } } diff --git a/testbed/scenes/concavemesh/ConcaveMeshScene.cpp b/testbed/scenes/concavemesh/ConcaveMeshScene.cpp index 9b65893e..11474819 100644 --- a/testbed/scenes/concavemesh/ConcaveMeshScene.cpp +++ b/testbed/scenes/concavemesh/ConcaveMeshScene.cpp @@ -175,7 +175,7 @@ void ConcaveMeshScene::reset() { // Reset the transform rp3d::Transform transform(rp3d::Vector3::zero(), rp3d::Quaternion::identity()); - mConcaveMesh->resetTransform(transform); + mConcaveMesh->setTransform(transform); for (int i=0; iresetTransform(boxTransform); + mBoxes[i * NB_BOXES_Z + j]->setTransform(boxTransform); } } diff --git a/testbed/scenes/heightfield/HeightFieldScene.cpp b/testbed/scenes/heightfield/HeightFieldScene.cpp index 5b62f614..3e4061c9 100644 --- a/testbed/scenes/heightfield/HeightFieldScene.cpp +++ b/testbed/scenes/heightfield/HeightFieldScene.cpp @@ -171,13 +171,13 @@ void HeightFieldScene::reset() { // Reset the transform rp3d::Transform transform(rp3d::Vector3(0, 0, 0), rp3d::Quaternion::identity()); - mHeightField->resetTransform(transform); + mHeightField->setTransform(transform); float heightFieldWidth = 10.0f; float stepDist = heightFieldWidth / (NB_BOXES + 1); for (int i=0; iresetTransform(boxTransform); + mBoxes[i]->setTransform(boxTransform); } } diff --git a/testbed/scenes/joints/JointsScene.cpp b/testbed/scenes/joints/JointsScene.cpp index 34bb1503..23bcdb93 100644 --- a/testbed/scenes/joints/JointsScene.cpp +++ b/testbed/scenes/joints/JointsScene.cpp @@ -193,7 +193,7 @@ void JointsScene::reset() { rp3d::Transform transform(initPosition, initOrientation); // Create a box and a corresponding rigid in the dynamics world - mBallAndSocketJointChainBoxes[i]->resetTransform(transform); + mBallAndSocketJointChainBoxes[i]->setTransform(transform); positionBox.y -= boxDimension.y + 0.5f; } @@ -207,7 +207,7 @@ void JointsScene::reset() { rp3d::Transform transformBottomBox(initPosition, initOrientation); // Create a box and a corresponding rigid in the dynamics world - mSliderJointBottomBox->resetTransform(transformBottomBox); + mSliderJointBottomBox->setTransform(transformBottomBox); // Position of the box openglframework::Vector3 positionBox2(0, 4.2f, 0); @@ -216,7 +216,7 @@ void JointsScene::reset() { rp3d::Transform transformTopBox(initPosition, initOrientation); // Create a box and a corresponding rigid in the dynamics world - mSliderJointTopBox->resetTransform(transformTopBox); + mSliderJointTopBox->setTransform(transformTopBox); // --------------- Propeller Hinge joint --------------- // @@ -227,7 +227,7 @@ void JointsScene::reset() { rp3d::Transform transformHingeBox(initPosition, initOrientation); // Create a box and a corresponding rigid in the dynamics world - mPropellerBox->resetTransform(transformHingeBox); + mPropellerBox->setTransform(transformHingeBox); // --------------- Fixed joint --------------- // @@ -238,7 +238,7 @@ void JointsScene::reset() { rp3d::Transform transformFixedBox1(initPosition, initOrientation); // Create a box and a corresponding rigid in the dynamics world - mFixedJointBox1->resetTransform(transformFixedBox1); + mFixedJointBox1->setTransform(transformFixedBox1); // Position of the box positionBox2 = openglframework::Vector3(-5, 7, 0); @@ -247,7 +247,7 @@ void JointsScene::reset() { rp3d::Transform transformFixedBox2(initPosition, initOrientation); // Create a box and a corresponding rigid in the dynamics world - mFixedJointBox2->resetTransform(transformFixedBox2); + mFixedJointBox2->setTransform(transformFixedBox2); } // Create the boxes and joints for the Ball-and-Socket joint example diff --git a/testbed/src/TestbedApplication.h b/testbed/src/TestbedApplication.h index 93d85ea7..8790a1f7 100644 --- a/testbed/src/TestbedApplication.h +++ b/testbed/src/TestbedApplication.h @@ -162,12 +162,6 @@ class TestbedApplication : public Screen { /// Set the variable to know if we need to take a single physics step void toggleTakeSinglePhysicsStep(); - /// Enable/Disable shadow mapping - void enableShadows(bool enable); - - /// Display/Hide contact points - void displayContactPoints(bool display); - public : // -------------------- Methods -------------------- // @@ -252,16 +246,6 @@ inline void TestbedApplication::toggleTakeSinglePhysicsStep() { } } -// Enable/Disable shadow mapping -inline void TestbedApplication::enableShadows(bool enable) { - mIsShadowMappingEnabled = enable; -} - -/// Display/Hide contact points -inline void TestbedApplication::displayContactPoints(bool display) { - mIsContactPointsDisplayed = display; -} - // Enable/Disable Vertical synchronization inline void TestbedApplication::enableVSync(bool enable) { mIsVSyncEnabled = enable; From e9f2f94f6455ef366cd5ab33b457d007cd19a580 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 2 Feb 2017 22:58:40 +0100 Subject: [PATCH 055/248] Continue working on SAT, remove Cone and Cylinder shapes --- CMakeLists.txt | 22 +- src/collision/CollisionDetection.cpp | 35 +- src/collision/CollisionDetection.h | 26 +- src/collision/HalfEdgeStructure.cpp | 116 ++++ src/collision/HalfEdgeStructure.h | 142 +++++ src/collision/PolyhedronMesh.cpp | 62 +++ src/collision/PolyhedronMesh.h | 86 +++ src/collision/TriangleMesh.h | 2 +- ...tore.cpp => CapsuleVsCapsuleAlgorithm.cpp} | 12 +- .../narrowphase/CapsuleVsCapsuleAlgorithm.h | 71 +++ .../narrowphase/DefaultCollisionDispatch.cpp | 20 +- .../narrowphase/DefaultCollisionDispatch.h | 4 + .../narrowphase/EPA/EPAAlgorithm.cpp | 436 --------------- src/collision/narrowphase/EPA/EPAAlgorithm.h | 147 ----- src/collision/narrowphase/EPA/EdgeEPA.cpp | 125 ----- src/collision/narrowphase/EPA/TriangleEPA.cpp | 145 ----- src/collision/narrowphase/EPA/TriangleEPA.h | 197 ------- .../narrowphase/EPA/TrianglesStore.h | 139 ----- .../narrowphase/GJK/GJKAlgorithm.cpp | 119 +--- src/collision/narrowphase/GJK/GJKAlgorithm.h | 26 +- .../narrowphase/SAT/SATAlgorithm.cpp | 43 ++ .../{EPA/EdgeEPA.h => SAT/SATAlgorithm.h} | 89 +-- .../SphereVsConvexMeshAlgorithm.cpp | 62 +++ .../narrowphase/SphereVsConvexMeshAlgorithm.h | 71 +++ src/collision/shapes/CollisionShape.h | 3 +- src/collision/shapes/ConeShape.cpp | 209 ------- src/collision/shapes/ConeShape.h | 194 ------- src/collision/shapes/CylinderShape.cpp | 231 -------- src/collision/shapes/CylinderShape.h | 190 ------- src/engine/OverlappingPair.cpp | 4 +- src/mathematics/Quaternion.h | 2 +- src/reactphysics3d.h | 2 - test/tests/collision/TestCollisionWorld.h | 39 -- test/tests/collision/TestPointInside.h | 215 +------- test/tests/collision/TestRaycast.h | 508 +----------------- testbed/CMakeLists.txt | 4 - testbed/common/Cone.cpp | 272 ---------- testbed/common/Cone.h | 110 ---- testbed/common/Cylinder.cpp | 272 ---------- testbed/common/Cylinder.h | 111 ---- testbed/common/Dumbbell.cpp | 22 +- testbed/common/Dumbbell.h | 6 +- .../CollisionDetectionScene.h | 2 - .../collisionshapes/CollisionShapesScene.cpp | 136 ----- .../collisionshapes/CollisionShapesScene.h | 8 - testbed/scenes/raycast/RaycastScene.cpp | 50 +- testbed/scenes/raycast/RaycastScene.h | 4 - 47 files changed, 792 insertions(+), 3999 deletions(-) create mode 100644 src/collision/HalfEdgeStructure.cpp create mode 100644 src/collision/HalfEdgeStructure.h create mode 100644 src/collision/PolyhedronMesh.cpp create mode 100644 src/collision/PolyhedronMesh.h rename src/collision/narrowphase/{EPA/TrianglesStore.cpp => CapsuleVsCapsuleAlgorithm.cpp} (87%) create mode 100644 src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h delete mode 100644 src/collision/narrowphase/EPA/EPAAlgorithm.cpp delete mode 100644 src/collision/narrowphase/EPA/EPAAlgorithm.h delete mode 100644 src/collision/narrowphase/EPA/EdgeEPA.cpp delete mode 100644 src/collision/narrowphase/EPA/TriangleEPA.cpp delete mode 100644 src/collision/narrowphase/EPA/TriangleEPA.h delete mode 100644 src/collision/narrowphase/EPA/TrianglesStore.h create mode 100644 src/collision/narrowphase/SAT/SATAlgorithm.cpp rename src/collision/narrowphase/{EPA/EdgeEPA.h => SAT/SATAlgorithm.h} (51%) create mode 100644 src/collision/narrowphase/SphereVsConvexMeshAlgorithm.cpp create mode 100644 src/collision/narrowphase/SphereVsConvexMeshAlgorithm.h delete mode 100644 src/collision/shapes/ConeShape.cpp delete mode 100644 src/collision/shapes/ConeShape.h delete mode 100644 src/collision/shapes/CylinderShape.cpp delete mode 100644 src/collision/shapes/CylinderShape.h delete mode 100644 testbed/common/Cone.cpp delete mode 100644 testbed/common/Cone.h delete mode 100644 testbed/common/Cylinder.cpp delete mode 100644 testbed/common/Cylinder.h diff --git a/CMakeLists.txt b/CMakeLists.txt index b3d37ed1..9b6af8c9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -67,23 +67,21 @@ SET (REACTPHYSICS3D_SOURCES "src/collision/narrowphase/CollisionDispatch.h" "src/collision/narrowphase/DefaultCollisionDispatch.h" "src/collision/narrowphase/DefaultCollisionDispatch.cpp" - "src/collision/narrowphase/EPA/EdgeEPA.h" - "src/collision/narrowphase/EPA/EdgeEPA.cpp" - "src/collision/narrowphase/EPA/EPAAlgorithm.h" - "src/collision/narrowphase/EPA/EPAAlgorithm.cpp" - "src/collision/narrowphase/EPA/TriangleEPA.h" - "src/collision/narrowphase/EPA/TriangleEPA.cpp" - "src/collision/narrowphase/EPA/TrianglesStore.h" - "src/collision/narrowphase/EPA/TrianglesStore.cpp" "src/collision/narrowphase/GJK/VoronoiSimplex.h" "src/collision/narrowphase/GJK/VoronoiSimplex.cpp" "src/collision/narrowphase/GJK/GJKAlgorithm.h" "src/collision/narrowphase/GJK/GJKAlgorithm.cpp" + "src/collision/narrowphase/SAT/SATAlgorithm.h" + "src/collision/narrowphase/SAT/SATAlgorithm.cpp" "src/collision/narrowphase/NarrowPhaseAlgorithm.h" "src/collision/narrowphase/SphereVsSphereAlgorithm.h" "src/collision/narrowphase/SphereVsSphereAlgorithm.cpp" + "src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h" + "src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp" "src/collision/narrowphase/ConcaveVsConvexAlgorithm.h" "src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp" + "src/collision/narrowphase/SphereVsConvexMeshAlgorithm.h" + "src/collision/narrowphase/SphereVsConvexMeshAlgorithm.cpp" "src/collision/shapes/AABB.h" "src/collision/shapes/AABB.cpp" "src/collision/shapes/ConvexShape.h" @@ -96,12 +94,8 @@ SET (REACTPHYSICS3D_SOURCES "src/collision/shapes/CapsuleShape.cpp" "src/collision/shapes/CollisionShape.h" "src/collision/shapes/CollisionShape.cpp" - "src/collision/shapes/ConeShape.h" - "src/collision/shapes/ConeShape.cpp" "src/collision/shapes/ConvexMeshShape.h" "src/collision/shapes/ConvexMeshShape.cpp" - "src/collision/shapes/CylinderShape.h" - "src/collision/shapes/CylinderShape.cpp" "src/collision/shapes/SphereShape.h" "src/collision/shapes/SphereShape.cpp" "src/collision/shapes/TriangleShape.h" @@ -118,6 +112,10 @@ SET (REACTPHYSICS3D_SOURCES "src/collision/TriangleVertexArray.cpp" "src/collision/TriangleMesh.h" "src/collision/TriangleMesh.cpp" + "src/collision/PolyhedronMesh.h" + "src/collision/PolyhedronMesh.cpp" + "src/collision/HalfEdgeStructure.h" + "src/collision/HalfEdgeStructure.cpp" "src/collision/CollisionDetection.h" "src/collision/CollisionDetection.cpp" "src/collision/NarrowPhaseInfo.h" diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index be17e4f7..161f6328 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -300,9 +300,7 @@ void CollisionDetection::computeNarrowPhase() { // Select the narrow phase algorithm to use according to the two collision shapes const CollisionShapeType shape1Type = currentNarrowPhaseInfo->collisionShape1->getType(); const CollisionShapeType shape2Type = currentNarrowPhaseInfo->collisionShape2->getType(); - const int shape1Index = static_cast(shape1Type); - const int shape2Index = static_cast(shape2Type); - NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Index][shape2Index]; + NarrowPhaseAlgorithm* narrowPhaseAlgorithm = selectNarrowPhaseAlgorithm(shape1Type, shape2Type); // If there is no collision algorithm between those two kinds of shapes, skip it if (narrowPhaseAlgorithm != nullptr) { @@ -462,6 +460,17 @@ void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, Pro if ((shape1->getCollideWithMaskBits() & shape2->getCollisionCategoryBits()) == 0 || (shape1->getCollisionCategoryBits() & shape2->getCollideWithMaskBits()) == 0) return; + // Make sure the shape with the smallest collision shape type comes first + const uint shape1TypeIndex = static_cast(shape1->getCollisionShape()->getType()); + const uint shape2TypeIndex = static_cast(shape2->getCollisionShape()->getType()); + if (shape2TypeIndex > shape1TypeIndex) { + + // Swap the two shapes + ProxyShape* temp = shape1; + shape1 = shape2; + shape2 = temp; + } + // Compute the overlapping pair ID overlappingpairid pairID = OverlappingPair::computeID(shape1, shape2); @@ -681,9 +690,7 @@ bool CollisionDetection::testOverlap(CollisionBody* body1, CollisionBody* body2) if (!isColliding) { // Select the narrow phase algorithm to use according to the two collision shapes - const int shape1Index = static_cast(shape1Type); - const int shape2Index = static_cast(shape2Type); - NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Index][shape2Index]; + NarrowPhaseAlgorithm* narrowPhaseAlgorithm = selectNarrowPhaseAlgorithm(shape1Type, shape2Type); // If there is a collision algorithm for those two kinds of shapes if (narrowPhaseAlgorithm != nullptr) { @@ -771,9 +778,7 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl if (!isColliding) { // Select the narrow phase algorithm to use according to the two collision shapes - const int shape1Index = static_cast(shape1Type); - const int shape2Index = static_cast(shape2Type); - NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Index][shape2Index]; + NarrowPhaseAlgorithm* narrowPhaseAlgorithm = selectNarrowPhaseAlgorithm(shape1Type, shape2Type); // If there is a collision algorithm for those two kinds of shapes if (narrowPhaseAlgorithm != nullptr) { @@ -846,9 +851,7 @@ void CollisionDetection::testCollision(CollisionBody* body1, CollisionBody* body while (narrowPhaseInfo != nullptr) { // Select the narrow phase algorithm to use according to the two collision shapes - const int shape1Index = static_cast(shape1Type); - const int shape2Index = static_cast(shape2Type); - NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Index][shape2Index]; + NarrowPhaseAlgorithm* narrowPhaseAlgorithm = selectNarrowPhaseAlgorithm(shape1Type, shape2Type); // If there is a collision algorithm for those two kinds of shapes if (narrowPhaseAlgorithm != nullptr) { @@ -926,9 +929,7 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c while (narrowPhaseInfo != nullptr) { // Select the narrow phase algorithm to use according to the two collision shapes - const int shape1Index = static_cast(shape1Type); - const int shape2Index = static_cast(shape2Type); - NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Index][shape2Index]; + NarrowPhaseAlgorithm* narrowPhaseAlgorithm = selectNarrowPhaseAlgorithm(shape1Type, shape2Type); // If there is a collision algorithm for those two kinds of shapes if (narrowPhaseAlgorithm != nullptr) { @@ -999,9 +1000,7 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { while (narrowPhaseInfo != nullptr) { // Select the narrow phase algorithm to use according to the two collision shapes - const int shape1Index = static_cast(shape1Type); - const int shape2Index = static_cast(shape2Type); - NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Index][shape2Index]; + NarrowPhaseAlgorithm* narrowPhaseAlgorithm = selectNarrowPhaseAlgorithm(shape1Type, shape2Type); // If there is a collision algorithm for those two kinds of shapes if (narrowPhaseAlgorithm != nullptr) { diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index 3bb27366..c06a6357 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -124,6 +124,10 @@ class CollisionDetection { /// Fill-in the collision detection matrix void fillInCollisionMatrix(); + /// Return the corresponding narrow-phase algorithm + NarrowPhaseAlgorithm* selectNarrowPhaseAlgorithm(const CollisionShapeType& shape1Type, + const CollisionShapeType& shape2Type) const; + /// Add all the contact manifold of colliding pairs to their bodies void addAllContactManifoldsToBodies(); @@ -153,10 +157,6 @@ class CollisionDetection { /// Set the collision dispatch configuration void setCollisionDispatch(CollisionDispatch* collisionDispatch); - /// Return the Narrow-phase collision detection algorithm to use between two types of shapes - NarrowPhaseAlgorithm* getCollisionAlgorithm(CollisionShapeType shape1Type, - CollisionShapeType shape2Type) const; - /// Add a proxy collision shape to the collision detection void addProxyCollisionShape(ProxyShape* proxyShape, const AABB& aabb); @@ -231,12 +231,6 @@ class CollisionDetection { friend class ConvexMeshShape; }; -// Return the Narrow-phase collision detection algorithm to use between two types of shapes -inline NarrowPhaseAlgorithm* CollisionDetection::getCollisionAlgorithm(CollisionShapeType shape1Type, - CollisionShapeType shape2Type) const { - return mCollisionMatrix[static_cast(shape1Type)][static_cast(shape2Type)]; -} - // Set the collision dispatch configuration inline void CollisionDetection::setCollisionDispatch(CollisionDispatch* collisionDispatch) { mCollisionDispatch = collisionDispatch; @@ -280,6 +274,18 @@ inline void CollisionDetection::updateProxyCollisionShape(ProxyShape* shape, con mBroadPhaseAlgorithm.updateProxyCollisionShape(shape, aabb, displacement); } +// Return the corresponding narrow-phase algorithm +inline NarrowPhaseAlgorithm* CollisionDetection::selectNarrowPhaseAlgorithm(const CollisionShapeType& shape1Type, + const CollisionShapeType& shape2Type) const { + + const unsigned int shape1Index = static_cast(shape1Type); + const unsigned int shape2Index = static_cast(shape2Type); + + assert(shape1Index <= shape2Index); + + return mCollisionMatrix[shape1Index][shape2Index]; +} + // Ray casting method inline void CollisionDetection::raycast(RaycastCallback* raycastCallback, const Ray& ray, diff --git a/src/collision/HalfEdgeStructure.cpp b/src/collision/HalfEdgeStructure.cpp new file mode 100644 index 00000000..16a79704 --- /dev/null +++ b/src/collision/HalfEdgeStructure.cpp @@ -0,0 +1,116 @@ +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "HalfEdgeStructure.h" +#include + +using namespace reactphysics3d; + +// Initialize the structure +void HalfEdgeStructure::init(std::vector vertices, std::vector> faces) { + + using edgeKey = std::pair; + + std::map edges; + std::map nextEdges; + std::map mapEdgeToStartVertex; + + // For each vertices + for (uint v=0; v& faceVertices = faces[f]; + + std::vector currentFaceEdges; + + edgeKey firstEdgeKey; + + // For each edge of the face + for (uint e=0; e < faceVertices.size(); e++) { + uint v1Index = faceVertices[e]; + uint v2Index = faceVertices[e == (faceVertices.size() - 1) ? 0 : e + 1]; + + const edgeKey pairV1V2 = std::make_pair(v1Index, v2Index); + + // Create a new half-edge + Edge edge; + edge.faceIndex = f; + edge.vertexIndex = v1Index; + if (e == 0) { + firstEdgeKey = pairV1V2; + } + else if (e >= 1) { + nextEdges.insert(currentFaceEdges[currentFaceEdges.size() - 1], pairV1V2); + } + if (e == (faceVertices.size() - 1)) { + nextEdges.insert(pairV1V2, firstEdgeKey); + } + edges.insert(pairV1V2, edge); + + const edgeKey pairV2V1 = std::make_pair(v2Index, v1Index); + + mapEdgeToStartVertex.insert(pairV1V2, v1Index); + mapEdgeToStartVertex.insert(pairV2V1, v2Index); + + auto itEdge = edges.find(pairV2V1); + if (itEdge != edges.end()) { + + const uint edgeIndex = mEdges.size(); + mEdges.push_back(itEdge->second); + mEdges.push_back(edge); + + itEdge->second.twinEdgeIndex = edgeIndex + 1; + itEdge->second.nextEdgeIndex = nextEdges[pairV2V1]; + + edge.twinEdgeIndex = edgeIndex; + edge.nextEdgeIndex = edges[nextEdges[pairV1V2]].; + + mVertices[v1Index].edgeIndex = edgeIndex; + mVertices[v2Index].edgeIndex = edgeIndex + 1; + + face.edgeIndex = edgeIndex + 1; + } + + currentFaceEdges.push_back(pairV1V2); + } + + // For each edge of the face + for (uint e=0; e < currentFaceEdges.size(); e++) { + Edge& edge = currentFaceEdges[e]; + edge.nextEdgeIndex = + } + } +} diff --git a/src/collision/HalfEdgeStructure.h b/src/collision/HalfEdgeStructure.h new file mode 100644 index 00000000..71b549d0 --- /dev/null +++ b/src/collision/HalfEdgeStructure.h @@ -0,0 +1,142 @@ +/******************************************************************************** +* 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_HALF_EDGE_STRUCTURE_MESH_H +#define REACTPHYSICS3D_HALF_EDGE_STRUCTURE_MESH_H + +// Libraries +#include "mathematics/mathematics.h" +#include + +namespace reactphysics3d { + +// Class HalfEdgeStructure +/** + * This class describes a polyhedron mesh made of faces and vertices. + * The faces do not have to be triangle. Note that the half-edge structure + * is only valid if the mesh is closed (each edge has two adjacent faces). + */ +class HalfEdgeStructure { + + public: + + struct Edge { + uint vertexIndex; // Index of the vertex at the end of the edge + uint twinEdgeIndex; // Index of the twin edge + uint faceIndex; // Adjacent face index of the edge + uint nextEdgeIndex; // Index of the next edge + }; + + struct Face { + uint edgeIndex; // Index of an half-edge of the face + }; + + struct Vertex { + const Vector3 point; // Coordinates of the vertex + uint edgeIndex; // Index of one edge emanting from this vertex + + /// Constructor + Vertex(const Vector3& p) { point = p;} + }; + + private: + + /// All the faces + std::vector mFaces; + + /// All the vertices + std::vector mVertices; + + /// All the half-edges + std::vector mEdges; + + public: + + /// Constructor + HalfEdgeStructure() = default; + + /// Destructor + ~HalfEdgeStructure() = default; + + /// Initialize the structure + void init(std::vector vertices, std::vector> faces); + + /// Return the number of faces + uint getNbFaces() const; + + /// Return the number of edges + uint getNbEdges() const; + + /// Return the number of vertices + uint getNbVertices() const; + + /// Return a given face + Face getFace(uint index) const; + + /// Return a given edge + Edge getHalfEdge(uint index) const; + + /// Retunr a given vertex + Vertex getVertex(uint index) const; + +}; + +// Return the number of faces +inline uint HalfEdgeStructure::getNbFaces() const { + return mFaces.size(); +} + +// Return the number of edges +inline uint HalfEdgeStructure::getNbEdges() const { + return mEdges.size(); +} + +// Return the number of vertices +inline uint HalfEdgeStructure::getNbVertices() const { + return mVertices.size(); +} + +// Return a given face +inline HalfEdgeStructure::Face HalfEdgeStructure::getFace(uint index) const { + assert(index < mFaces.size()); + return mFaces[index]; +} + +// Return a given edge +inline HalfEdgeStructure::Edge HalfEdgeStructure::getHalfEdge(uint index) const { + assert(index < mEdges.size()); + return mEdges[index]; +} + +// Retunr a given vertex +inline HalfEdgeStructure::Vertex HalfEdgeStructure::getVertex(uint index) const { + assert(index < mVertices.size()); + return mVertices[index]; +} + +} + +#endif + diff --git a/src/collision/PolyhedronMesh.cpp b/src/collision/PolyhedronMesh.cpp new file mode 100644 index 00000000..891a2f47 --- /dev/null +++ b/src/collision/PolyhedronMesh.cpp @@ -0,0 +1,62 @@ +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "PolyhedronMesh.h" + +using namespace reactphysics3d; + + +// Constructor +PolyhedronMesh::PolyhedronMesh() : mIsFinalized(false) { + +} + +// Add a vertex into the polyhedron. +// This method returns the index of the vertex that you need to use +// to add faces. +uint PolyhedronMesh::addVertex(const Vector3& vertex) { + mVertices.push_back(vertex); + return mVertices.size() - 1; +} + +// Add a face into the polyhedron. +// A face is a list of vertices indices (returned by addVertex() method). +// The order of the indices are important. You need to specify the vertices of +// of the face sorted counter-clockwise as seen from the outside of the polyhedron. +void PolyhedronMesh::addFace(std::vector faceVertices) { + mFaces.push_back(faceVertices); +} + +// Call this method when you are done adding vertices and faces +void PolyhedronMesh::finalize() { + + if (mIsFinalized) return; + + // Initialize the half-edge structure + mHalfEdgeStructure.init(mVertices, mFaces); + + mIsFinalized = true; +} diff --git a/src/collision/PolyhedronMesh.h b/src/collision/PolyhedronMesh.h new file mode 100644 index 00000000..8f0e8abf --- /dev/null +++ b/src/collision/PolyhedronMesh.h @@ -0,0 +1,86 @@ +/******************************************************************************** +* 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_POLYHEDRON_MESH_H +#define REACTPHYSICS3D_POLYHEDRON_MESH_H + +// Libraries +#include "mathematics/mathematics.h" +#include "HalfEdgeStructure.h" +#include + +namespace reactphysics3d { + +// Class PolyhedronMesh +/** + * This class describes a polyhedron mesh made of faces and vertices. + * The faces do not have to be triangle + */ +class PolyhedronMesh { + + private: + + /// Half-edge structure of the mesh + HalfEdgeStructure mHalfEdgeStructure; + + /// True if the half-edge structure has been generated + bool mIsFinalized; + + /// All the vertices + std::vector mVertices; + + /// All the indexes of the face vertices + std::vector> mFaces; + + public: + + /// Constructor + PolyhedronMesh(); + + /// Destructor + ~PolyhedronMesh() = default; + + /// Add a vertex into the polyhedron + uint addVertex(const Vector3& vertex); + + /// Add a face into the polyhedron + void addFace(std::vector faceVertices); + + /// Call this method when you are done adding vertices and faces + void finalize(); + + /// Return the half-edge structure of the mesh + const HalfEdgeStructure& getHalfEdgeStructure() const; +}; + +// Return the half-edge structure of the mesh +inline const HalfEdgeStructure& PolyhedronMesh::getHalfEdgeStructure() const { + return mHalfEdgeStructure; +} + +} + +#endif + diff --git a/src/collision/TriangleMesh.h b/src/collision/TriangleMesh.h index 936824e9..e33fad67 100644 --- a/src/collision/TriangleMesh.h +++ b/src/collision/TriangleMesh.h @@ -38,7 +38,7 @@ namespace reactphysics3d { * This class represents a mesh made of triangles. A TriangleMesh contains * one or several parts. Each part is a set of triangles represented in a * TriangleVertexArray object describing all the triangles vertices of the part. - * A TriangleMesh object is used to create a ConcaveMeshShape from a triangle + * A TriangleMesh object can be used to create a ConcaveMeshShape from a triangle * mesh for instance. */ class TriangleMesh { diff --git a/src/collision/narrowphase/EPA/TrianglesStore.cpp b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp similarity index 87% rename from src/collision/narrowphase/EPA/TrianglesStore.cpp rename to src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp index 93fb95a6..44badf67 100644 --- a/src/collision/narrowphase/EPA/TrianglesStore.cpp +++ b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp @@ -24,12 +24,14 @@ ********************************************************************************/ // Libraries -#include "TrianglesStore.h" +#include "CapsuleVsCapsuleAlgorithm.h" +#include "collision/shapes/CapsuleShape.h" -// We use the ReactPhysics3D namespace +// We want to use the ReactPhysics3D namespace using namespace reactphysics3d; -// Constructor -TrianglesStore::TrianglesStore() : mNbTriangles(0) { - +bool CapsuleVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + ContactPointInfo& contactPointInfo) { + + } diff --git a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h new file mode 100644 index 00000000..6a48495e --- /dev/null +++ b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h @@ -0,0 +1,71 @@ +/******************************************************************************** +* 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_CAPSULE_VS_CAPSULE_ALGORITHM_H +#define REACTPHYSICS3D_CAPSULE_VS_CAPSULE_ALGORITHM_H + +// Libraries +#include "body/Body.h" +#include "constraint/ContactPoint.h" +#include "NarrowPhaseAlgorithm.h" + + +/// Namespace ReactPhysics3D +namespace reactphysics3d { + +// Class CapsuleVsCapsuleAlgorithm +/** + * This class is used to compute the narrow-phase collision detection + * between two capsule collision shapes. + */ +class CapsuleVsCapsuleAlgorithm : public NarrowPhaseAlgorithm { + + protected : + + public : + + // -------------------- Methods -------------------- // + + /// Constructor + CapsuleVsCapsuleAlgorithm() = default; + + /// Destructor + virtual ~CapsuleVsCapsuleAlgorithm() override = default; + + /// Deleted copy-constructor + CapsuleVsCapsuleAlgorithm(const CapsuleVsCapsuleAlgorithm& algorithm) = delete; + + /// Deleted assignment operator + CapsuleVsCapsuleAlgorithm& operator=(const CapsuleVsCapsuleAlgorithm& algorithm) = delete; + + /// Compute a contact info if the two bounding volume collide + virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + ContactPointInfo& contactPointInfo) override; +}; + +} + +#endif + diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.cpp b/src/collision/narrowphase/DefaultCollisionDispatch.cpp index 35b1e50b..4864dbbe 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.cpp +++ b/src/collision/narrowphase/DefaultCollisionDispatch.cpp @@ -33,18 +33,22 @@ using namespace reactphysics3d; // use between two types of collision shapes. NarrowPhaseAlgorithm* DefaultCollisionDispatch::selectAlgorithm(int type1, int type2) { + CollisionShapeType shape1Type = static_cast(type1); CollisionShapeType shape2Type = static_cast(type2); // Convex vs Convex algorithm (GJK algorithm) - if (CollisionShape::isConvex(shape1Type) && CollisionShape::isConvex(shape2Type)) { - return &mGJKAlgorithm; - } - // Sphere vs Sphere algorithm - else if (shape1Type == CollisionShapeType::SPHERE && shape2Type == CollisionShapeType::SPHERE) { - return &mSphereVsSphereAlgorithm; - } - else { + if (type1 > type2) { return nullptr; } + // Sphere vs Sphere algorithm + if (shape1Type == CollisionShapeType::SPHERE && shape2Type == CollisionShapeType::SPHERE) { + return &mSphereVsSphereAlgorithm; + } + // Sphere vs Convex shapes (convex Mesh, BoxShape) algorithm + if (shape1Type == CollisionShapeType::SPHERE && CollisionShape::isConvex(shape2Type)) { + return &mSphereVsConvexMeshAlgorithm; + } + + return nullptr; } diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.h b/src/collision/narrowphase/DefaultCollisionDispatch.h index f62a6564..07a819c0 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.h +++ b/src/collision/narrowphase/DefaultCollisionDispatch.h @@ -30,6 +30,7 @@ #include "CollisionDispatch.h" #include "ConcaveVsConvexAlgorithm.h" #include "SphereVsSphereAlgorithm.h" +#include "SphereVsConvexMeshAlgorithm.h" #include "GJK/GJKAlgorithm.h" namespace reactphysics3d { @@ -47,6 +48,9 @@ class DefaultCollisionDispatch : public CollisionDispatch { /// Sphere vs Sphere collision algorithm SphereVsSphereAlgorithm mSphereVsSphereAlgorithm; + /// Sphere vs Convex Mesh collision algorithm + SphereVsConvexMeshAlgorithm mSphereVsConvexMeshAlgorithm; + /// GJK Algorithm GJKAlgorithm mGJKAlgorithm; diff --git a/src/collision/narrowphase/EPA/EPAAlgorithm.cpp b/src/collision/narrowphase/EPA/EPAAlgorithm.cpp deleted file mode 100644 index 6afa7a10..00000000 --- a/src/collision/narrowphase/EPA/EPAAlgorithm.cpp +++ /dev/null @@ -1,436 +0,0 @@ -/******************************************************************************** -* 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. * -* * -********************************************************************************/ - -// Libraries -#include "EPAAlgorithm.h" -#include "engine/Profiler.h" -#include "collision/narrowphase//GJK/GJKAlgorithm.h" -#include "TrianglesStore.h" - -// We want to use the ReactPhysics3D namespace -using namespace reactphysics3d; - -// Decide if the origin is in the tetrahedron. -/// Return 0 if the origin is in the tetrahedron and return the number (1,2,3 or 4) of -/// the vertex that is wrong if the origin is not in the tetrahedron -int EPAAlgorithm::isOriginInTetrahedron(const Vector3& p1, const Vector3& p2, - const Vector3& p3, const Vector3& p4) const { - - // Check vertex 1 - Vector3 normal1 = (p2-p1).cross(p3-p1); - if ((normal1.dot(p1) > 0.0) == (normal1.dot(p4) > 0.0)) { - return 4; - } - - // Check vertex 2 - Vector3 normal2 = (p4-p2).cross(p3-p2); - if ((normal2.dot(p2) > 0.0) == (normal2.dot(p1) > 0.0)) { - return 1; - } - - // Check vertex 3 - Vector3 normal3 = (p4-p3).cross(p1-p3); - if ((normal3.dot(p3) > 0.0) == (normal3.dot(p2) > 0.0)) { - return 2; - } - - // Check vertex 4 - Vector3 normal4 = (p2-p4).cross(p1-p4); - if ((normal4.dot(p4) > 0.0) == (normal4.dot(p3) > 0.0)) { - return 3; - } - - // The origin is in the tetrahedron, we return 0 - return 0; -} - -// Compute the penetration depth with the EPA algorithm. -/// This method computes the penetration depth and contact points between two -/// enlarged objects (with margin) where the original objects (without margin) -/// intersect. An initial simplex that contains origin has been computed with -/// GJK algorithm. The EPA Algorithm will extend this simplex polytope to find -/// the correct penetration depth. This method returns true if the EPA penetration -/// depth computation has succeeded and false it has failed. -bool EPAAlgorithm::computePenetrationDepthAndContactPoints(const VoronoiSimplex& simplex, - const NarrowPhaseInfo* narrowPhaseInfo, - Vector3& v, - ContactPointInfo& contactPointInfo) { - - PROFILE("EPAAlgorithm::computePenetrationDepthAndContactPoints()"); - - decimal gjkPenDepthSquare = v.lengthSquare(); - - assert(narrowPhaseInfo->collisionShape1->isConvex()); - assert(narrowPhaseInfo->collisionShape2->isConvex()); - - const ConvexShape* shape1 = static_cast(narrowPhaseInfo->collisionShape1); - const ConvexShape* shape2 = static_cast(narrowPhaseInfo->collisionShape2); - - void** shape1CachedCollisionData = narrowPhaseInfo->cachedCollisionData1; - void** shape2CachedCollisionData = narrowPhaseInfo->cachedCollisionData2; - - Vector3 suppPointsA[MAX_SUPPORT_POINTS]; // Support points of object A in local coordinates - Vector3 suppPointsB[MAX_SUPPORT_POINTS]; // Support points of object B in local coordinates - Vector3 points[MAX_SUPPORT_POINTS]; // Current points - TrianglesStore triangleStore; // Store the triangles - TriangleEPA* triangleHeap[MAX_FACETS]; // Heap that contains the face - // candidate of the EPA algorithm - - // Transform a point from local space of body 2 to local - // space of body 1 (the GJK algorithm is done in local space of body 1) - Transform body2Tobody1 = narrowPhaseInfo->shape1ToWorldTransform.getInverse() * narrowPhaseInfo->shape2ToWorldTransform; - - // Matrix that transform a direction from local - // space of body 1 into local space of body 2 - Quaternion rotateToBody2 = narrowPhaseInfo->shape2ToWorldTransform.getOrientation().getInverse() * - narrowPhaseInfo->shape1ToWorldTransform.getOrientation(); - - // Get the simplex computed previously by the GJK algorithm - int nbVertices = simplex.getSimplex(suppPointsA, suppPointsB, points); - - // Compute the tolerance - decimal tolerance = MACHINE_EPSILON * simplex.getMaxLengthSquareOfAPoint(); - - // Number of triangles in the polytope - unsigned int nbTriangles = 0; - - // Clear the storing of triangles - triangleStore.clear(); - - // Select an action according to the number of points in the simplex - // computed with GJK algorithm in order to obtain an initial polytope for - // The EPA algorithm. - switch(nbVertices) { - case 1: - // Only one point in the simplex (which should be the origin). - // We have a touching contact with zero penetration depth. - // We drop that kind of contact. Therefore, we return false - return false; - - case 2: { - // The simplex returned by GJK is a line segment d containing the origin. - // We add two additional support points to construct a hexahedron (two tetrahedron - // glued together with triangle faces. The idea is to compute three different vectors - // v1, v2 and v3 that are orthogonal to the segment d. The three vectors are relatively - // rotated of 120 degree around the d segment. The the three new points to - // construct the polytope are the three support points in those three directions - // v1, v2 and v3. - - // Direction of the segment - Vector3 d = (points[1] - points[0]).getUnit(); - - // Choose the coordinate axis from the minimal absolute component of the vector d - int minAxis = d.getAbsoluteVector().getMinAxis(); - - // Compute sin(60) - const decimal sin60 = decimal(sqrt(3.0)) * decimal(0.5); - - // Create a rotation quaternion to rotate the vector v1 to get the vectors - // v2 and v3 - Quaternion rotationQuat(d.x * sin60, d.y * sin60, d.z * sin60, 0.5); - - // Compute the vector v1, v2, v3 - Vector3 v1 = d.cross(Vector3(minAxis == 0, minAxis == 1, minAxis == 2)); - Vector3 v2 = rotationQuat * v1; - Vector3 v3 = rotationQuat * v2; - - // Compute the support point in the direction of v1 - suppPointsA[2] = shape1->getLocalSupportPointWithMargin(v1, shape1CachedCollisionData); - suppPointsB[2] = body2Tobody1 * - shape2->getLocalSupportPointWithMargin(rotateToBody2 * (-v1), shape2CachedCollisionData); - points[2] = suppPointsA[2] - suppPointsB[2]; - - // Compute the support point in the direction of v2 - suppPointsA[3] = shape1->getLocalSupportPointWithMargin(v2, shape1CachedCollisionData); - suppPointsB[3] = body2Tobody1 * - shape2->getLocalSupportPointWithMargin(rotateToBody2 * (-v2), shape2CachedCollisionData); - points[3] = suppPointsA[3] - suppPointsB[3]; - - // Compute the support point in the direction of v3 - suppPointsA[4] = shape1->getLocalSupportPointWithMargin(v3, shape1CachedCollisionData); - suppPointsB[4] = body2Tobody1 * - shape2->getLocalSupportPointWithMargin(rotateToBody2 * (-v3), shape2CachedCollisionData); - points[4] = suppPointsA[4] - suppPointsB[4]; - - // Now we have an hexahedron (two tetrahedron glued together). We can simply keep the - // tetrahedron that contains the origin in order that the initial polytope of the - // EPA algorithm is a tetrahedron, which is simpler to deal with. - - // If the origin is in the tetrahedron of points 0, 2, 3, 4 - if (isOriginInTetrahedron(points[0], points[2], points[3], points[4]) == 0) { - // We use the point 4 instead of point 1 for the initial tetrahedron - suppPointsA[1] = suppPointsA[4]; - suppPointsB[1] = suppPointsB[4]; - points[1] = points[4]; - } - // If the origin is in the tetrahedron of points 1, 2, 3, 4 - else if (isOriginInTetrahedron(points[1], points[2], points[3], points[4]) == 0) { - // We use the point 4 instead of point 0 for the initial tetrahedron - suppPointsA[0] = suppPointsA[4]; - suppPointsB[0] = suppPointsB[4]; - points[0] = points[4]; - } - else { - // The origin is not in the initial polytope - return false; - } - - // The polytope contains now 4 vertices - nbVertices = 4; - } - case 4: { - // The simplex computed by the GJK algorithm is a tetrahedron. Here we check - // if this tetrahedron contains the origin. If it is the case, we keep it and - // otherwise we remove the wrong vertex of the tetrahedron and go in the case - // where the GJK algorithm compute a simplex of three vertices. - - // Check if the tetrahedron contains the origin (or wich is the wrong vertex otherwise) - int badVertex = isOriginInTetrahedron(points[0], points[1], points[2], points[3]); - - // If the origin is in the tetrahedron - if (badVertex == 0) { - // The tetrahedron is a correct initial polytope for the EPA algorithm. - // Therefore, we construct the tetrahedron. - - // Comstruct the 4 triangle faces of the tetrahedron - TriangleEPA* face0 = triangleStore.newTriangle(points, 0, 1, 2); - TriangleEPA* face1 = triangleStore.newTriangle(points, 0, 3, 1); - TriangleEPA* face2 = triangleStore.newTriangle(points, 0, 2, 3); - TriangleEPA* face3 = triangleStore.newTriangle(points, 1, 3, 2); - - // If the constructed tetrahedron is not correct - if (!((face0 != nullptr) && (face1 != nullptr) && (face2 != nullptr) && (face3 != nullptr) - && face0->getDistSquare() > 0.0 && face1->getDistSquare() > 0.0 - && face2->getDistSquare() > 0.0 && face3->getDistSquare() > 0.0)) { - return false; - } - - // Associate the edges of neighbouring triangle faces - link(EdgeEPA(face0, 0), EdgeEPA(face1, 2)); - link(EdgeEPA(face0, 1), EdgeEPA(face3, 2)); - link(EdgeEPA(face0, 2), EdgeEPA(face2, 0)); - link(EdgeEPA(face1, 0), EdgeEPA(face2, 2)); - link(EdgeEPA(face1, 1), EdgeEPA(face3, 0)); - link(EdgeEPA(face2, 1), EdgeEPA(face3, 1)); - - // Add the triangle faces in the candidate heap - addFaceCandidate(face0, triangleHeap, nbTriangles, DECIMAL_LARGEST); - addFaceCandidate(face1, triangleHeap, nbTriangles, DECIMAL_LARGEST); - addFaceCandidate(face2, triangleHeap, nbTriangles, DECIMAL_LARGEST); - addFaceCandidate(face3, triangleHeap, nbTriangles, DECIMAL_LARGEST); - - break; - } - - // The tetrahedron contains a wrong vertex (the origin is not inside the tetrahedron) - // Remove the wrong vertex and continue to the next case with the - // three remaining vertices - if (badVertex < 4) { - - suppPointsA[badVertex-1] = suppPointsA[3]; - suppPointsB[badVertex-1] = suppPointsB[3]; - points[badVertex-1] = points[3]; - } - - // We have removed the wrong vertex - nbVertices = 3; - } - case 3: { - // The GJK algorithm returned a triangle that contains the origin. - // We need two new vertices to create two tetrahedron. The two new - // vertices are the support points in the "n" and "-n" direction - // where "n" is the normal of the triangle. Then, we use only the - // tetrahedron that contains the origin. - - // Compute the normal of the triangle - Vector3 v1 = points[1] - points[0]; - Vector3 v2 = points[2] - points[0]; - Vector3 n = v1.cross(v2); - - // Compute the two new vertices to obtain a hexahedron - suppPointsA[3] = shape1->getLocalSupportPointWithMargin(n, shape1CachedCollisionData); - suppPointsB[3] = body2Tobody1 * - shape2->getLocalSupportPointWithMargin(rotateToBody2 * (-n), shape2CachedCollisionData); - points[3] = suppPointsA[3] - suppPointsB[3]; - suppPointsA[4] = shape1->getLocalSupportPointWithMargin(-n, shape1CachedCollisionData); - suppPointsB[4] = body2Tobody1 * - shape2->getLocalSupportPointWithMargin(rotateToBody2 * n, shape2CachedCollisionData); - points[4] = suppPointsA[4] - suppPointsB[4]; - - TriangleEPA* face0 = nullptr; - TriangleEPA* face1 = nullptr; - TriangleEPA* face2 = nullptr; - TriangleEPA* face3 = nullptr; - - // If the origin is in the first tetrahedron - if (isOriginInTetrahedron(points[0], points[1], - points[2], points[3]) == 0) { - // The tetrahedron is a correct initial polytope for the EPA algorithm. - // Therefore, we construct the tetrahedron. - - // Comstruct the 4 triangle faces of the tetrahedron - face0 = triangleStore.newTriangle(points, 0, 1, 2); - face1 = triangleStore.newTriangle(points, 0, 3, 1); - face2 = triangleStore.newTriangle(points, 0, 2, 3); - face3 = triangleStore.newTriangle(points, 1, 3, 2); - } - else if (isOriginInTetrahedron(points[0], points[1], - points[2], points[4]) == 0) { - - // The tetrahedron is a correct initial polytope for the EPA algorithm. - // Therefore, we construct the tetrahedron. - - // Comstruct the 4 triangle faces of the tetrahedron - face0 = triangleStore.newTriangle(points, 0, 1, 2); - face1 = triangleStore.newTriangle(points, 0, 4, 1); - face2 = triangleStore.newTriangle(points, 0, 2, 4); - face3 = triangleStore.newTriangle(points, 1, 4, 2); - } - else { - return false; - } - - // If the constructed tetrahedron is not correct - if (!((face0 != nullptr) && (face1 != nullptr) && (face2 != nullptr) && (face3 != nullptr) - && face0->getDistSquare() > 0.0 && face1->getDistSquare() > 0.0 - && face2->getDistSquare() > 0.0 && face3->getDistSquare() > 0.0)) { - return false; - } - - // Associate the edges of neighbouring triangle faces - link(EdgeEPA(face0, 0), EdgeEPA(face1, 2)); - link(EdgeEPA(face0, 1), EdgeEPA(face3, 2)); - link(EdgeEPA(face0, 2), EdgeEPA(face2, 0)); - link(EdgeEPA(face1, 0), EdgeEPA(face2, 2)); - link(EdgeEPA(face1, 1), EdgeEPA(face3, 0)); - link(EdgeEPA(face2, 1), EdgeEPA(face3, 1)); - - // Add the triangle faces in the candidate heap - addFaceCandidate(face0, triangleHeap, nbTriangles, DECIMAL_LARGEST); - addFaceCandidate(face1, triangleHeap, nbTriangles, DECIMAL_LARGEST); - addFaceCandidate(face2, triangleHeap, nbTriangles, DECIMAL_LARGEST); - addFaceCandidate(face3, triangleHeap, nbTriangles, DECIMAL_LARGEST); - - nbVertices = 4; - - } - break; - } - - // At this point, we have a polytope that contains the origin. Therefore, we - // can run the EPA algorithm. - - if (nbTriangles == 0) { - return false; - } - - TriangleEPA* triangle = 0; - decimal upperBoundSquarePenDepth = DECIMAL_LARGEST; - - do { - triangle = triangleHeap[0]; - - // Get the next candidate face (the face closest to the origin) - std::pop_heap(&triangleHeap[0], &triangleHeap[nbTriangles], mTriangleComparison); - nbTriangles--; - - // If the candidate face in the heap is not obsolete - if (!triangle->getIsObsolete()) { - - // If we have reached the maximum number of support points - if (nbVertices == MAX_SUPPORT_POINTS) { - assert(false); - break; - } - - // Compute the support point of the Minkowski - // difference (A-B) in the closest point direction - suppPointsA[nbVertices] = shape1->getLocalSupportPointWithMargin( - triangle->getClosestPoint(), shape1CachedCollisionData); - suppPointsB[nbVertices] = body2Tobody1 * - shape2->getLocalSupportPointWithMargin(rotateToBody2 * - (-triangle->getClosestPoint()), shape2CachedCollisionData); - points[nbVertices] = suppPointsA[nbVertices] - suppPointsB[nbVertices]; - - int indexNewVertex = nbVertices; - nbVertices++; - - // Update the upper bound of the penetration depth - decimal wDotv = points[indexNewVertex].dot(triangle->getClosestPoint()); - - decimal wDotVSquare = wDotv * wDotv / triangle->getDistSquare(); - if (wDotVSquare < upperBoundSquarePenDepth) { - upperBoundSquarePenDepth = wDotVSquare; - } - - // Compute the error - decimal error = wDotv - triangle->getDistSquare(); - if (error <= std::max(tolerance, REL_ERROR_SQUARE * wDotv) || - points[indexNewVertex] == points[(*triangle)[0]] || - points[indexNewVertex] == points[(*triangle)[1]] || - points[indexNewVertex] == points[(*triangle)[2]]) { - break; - } - - // Now, we compute the silhouette cast by the new vertex. The current triangle - // face will not be in the convex hull. We start the local recursive silhouette - // algorithm from the current triangle face. - int i = triangleStore.getNbTriangles(); - if (!triangle->computeSilhouette(points, indexNewVertex, triangleStore)) { - break; - } - - // Add all the new triangle faces computed with the silhouette algorithm - // to the candidates list of faces of the current polytope - while(i != triangleStore.getNbTriangles()) { - TriangleEPA* newTriangle = &triangleStore[i]; - addFaceCandidate(newTriangle, triangleHeap, nbTriangles, upperBoundSquarePenDepth); - i++; - } - } - } while(nbTriangles > 0 && triangleHeap[0]->getDistSquare() <= upperBoundSquarePenDepth); - - // Compute the contact info - v = narrowPhaseInfo->shape1ToWorldTransform.getOrientation() * triangle->getClosestPoint(); - Vector3 pALocal = triangle->computeClosestPointOfObject(suppPointsA); - Vector3 pBLocal = body2Tobody1.getInverse() * triangle->computeClosestPointOfObject(suppPointsB); - Vector3 normal = v.getUnit(); - decimal penetrationDepth = v.length(); - - // If the length of the normal vector is too small, skip this contact point - if (normal.lengthSquare() < MACHINE_EPSILON) { - return false; - } - - if (penetrationDepth * penetrationDepth > gjkPenDepthSquare && penetrationDepth > 0) { - - // Create the contact info object - contactPointInfo.init(normal, penetrationDepth, pALocal, pBLocal); - - return true; - } - - return false; -} diff --git a/src/collision/narrowphase/EPA/EPAAlgorithm.h b/src/collision/narrowphase/EPA/EPAAlgorithm.h deleted file mode 100644 index 1d241540..00000000 --- a/src/collision/narrowphase/EPA/EPAAlgorithm.h +++ /dev/null @@ -1,147 +0,0 @@ -/******************************************************************************** -* 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_EPA_ALGORITHM_H -#define REACTPHYSICS3D_EPA_ALGORITHM_H - -// Libraries -#include "collision/narrowphase/GJK/VoronoiSimplex.h" -#include "collision/shapes/CollisionShape.h" -#include "collision/NarrowPhaseInfo.h" -#include "constraint/ContactPoint.h" -#include "collision/narrowphase/NarrowPhaseAlgorithm.h" -#include "mathematics/mathematics.h" -#include "TriangleEPA.h" -#include "memory/PoolAllocator.h" -#include - -/// ReactPhysics3D namespace -namespace reactphysics3d { - -// ---------- Constants ---------- // - -/// Maximum number of support points of the polytope -constexpr unsigned int MAX_SUPPORT_POINTS = 100; - -/// Maximum number of facets of the polytope -constexpr unsigned int MAX_FACETS = 200; - - -// Class TriangleComparison -/** - * This class allows the comparison of two triangles in the heap - * The comparison between two triangles is made using their square distance to the closest - * point to the origin. The goal is that in the heap, the first triangle is the one with the - * smallest square distance. - */ -class TriangleComparison { - - public: - - /// Comparison operator - bool operator()(const TriangleEPA* face1, const TriangleEPA* face2) { - return (face1->getDistSquare() > face2->getDistSquare()); - } -}; - - -// Class EPAAlgorithm -/** - * This class is the implementation of the Expanding Polytope Algorithm (EPA). - * The EPA algorithm computes the penetration depth and contact points between - * two enlarged objects (with margin) where the original objects (without margin) - * intersect. The penetration depth of a pair of intersecting objects A and B is - * the length of a point on the boundary of the Minkowski sum (A-B) closest to the - * origin. The goal of the EPA algorithm is to start with an initial simplex polytope - * that contains the origin and expend it in order to find the point on the boundary - * of (A-B) that is closest to the origin. An initial simplex that contains origin - * has been computed wit GJK algorithm. The EPA Algorithm will extend this simplex - * polytope to find the correct penetration depth. The implementation of the EPA - * algorithm is based on the book "Collision Detection in 3D Environments". - */ -class EPAAlgorithm { - - private: - - // -------------------- Attributes -------------------- // - - /// Triangle comparison operator - TriangleComparison mTriangleComparison; - - // -------------------- Methods -------------------- // - - /// Add a triangle face in the candidate triangle heap - void addFaceCandidate(TriangleEPA* triangle, TriangleEPA** heap, uint& nbTriangles, - decimal upperBoundSquarePenDepth); - - /// Decide if the origin is in the tetrahedron. - int isOriginInTetrahedron(const Vector3& p1, const Vector3& p2, - const Vector3& p3, const Vector3& p4) const; - - public: - - // -------------------- Methods -------------------- // - - /// Constructor - EPAAlgorithm() = default; - - /// Destructor - ~EPAAlgorithm() = default; - - /// Deleted copy-constructor - EPAAlgorithm(const EPAAlgorithm& algorithm) = delete; - - /// Deleted assignment operator - EPAAlgorithm& operator=(const EPAAlgorithm& algorithm) = delete; - - /// Compute the penetration depth with EPA algorithm. - bool computePenetrationDepthAndContactPoints(const VoronoiSimplex& simplex, - const NarrowPhaseInfo* narrowPhaseInfo, - Vector3& v, - ContactPointInfo &contactPointInfo); -}; - -// Add a triangle face in the candidate triangle heap in the EPA algorithm -inline void EPAAlgorithm::addFaceCandidate(TriangleEPA* triangle, TriangleEPA** heap, - uint& nbTriangles, decimal upperBoundSquarePenDepth) { - - // If the closest point of the affine hull of triangle - // points is internal to the triangle and if the distance - // of the closest point from the origin is at most the - // penetration depth upper bound - if (triangle->isClosestPointInternalToTriangle() && - triangle->getDistSquare() <= upperBoundSquarePenDepth) { - - // Add the triangle face to the list of candidates - heap[nbTriangles] = triangle; - nbTriangles++; - std::push_heap(&heap[0], &heap[nbTriangles], mTriangleComparison); - } -} - -} - -#endif - diff --git a/src/collision/narrowphase/EPA/EdgeEPA.cpp b/src/collision/narrowphase/EPA/EdgeEPA.cpp deleted file mode 100644 index dcbf61fd..00000000 --- a/src/collision/narrowphase/EPA/EdgeEPA.cpp +++ /dev/null @@ -1,125 +0,0 @@ -/******************************************************************************** -* 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. * -* * -********************************************************************************/ - -// Libraries -#include "EdgeEPA.h" -#include "TriangleEPA.h" -#include "TrianglesStore.h" -#include - -// We want to use the ReactPhysics3D namespace -using namespace reactphysics3d; - -// Constructor -EdgeEPA::EdgeEPA(TriangleEPA* ownerTriangle, int index) - : mOwnerTriangle(ownerTriangle), mIndex(index) { - assert(index >= 0 && index < 3); -} - -// Copy-constructor -EdgeEPA::EdgeEPA(const EdgeEPA& edge) { - mOwnerTriangle = edge.mOwnerTriangle; - mIndex = edge.mIndex; -} - -// Return the index of the source vertex of the edge (vertex starting the edge) -uint EdgeEPA::getSourceVertexIndex() const { - return (*mOwnerTriangle)[mIndex]; -} - -// Return the index of the target vertex of the edge (vertex ending the edge) -uint EdgeEPA::getTargetVertexIndex() const { - return (*mOwnerTriangle)[indexOfNextCounterClockwiseEdge(mIndex)]; -} - -// Execute the recursive silhouette algorithm from this edge -bool EdgeEPA::computeSilhouette(const Vector3* vertices, uint indexNewVertex, - TrianglesStore& triangleStore) { - // If the edge has not already been visited - if (!mOwnerTriangle->getIsObsolete()) { - - // If the triangle of this edge is not visible from the given point - if (!mOwnerTriangle->isVisibleFromVertex(vertices, indexNewVertex)) { - TriangleEPA* triangle = triangleStore.newTriangle(vertices, indexNewVertex, - getTargetVertexIndex(), - getSourceVertexIndex()); - - // If the triangle has been created - if (triangle != nullptr) { - halfLink(EdgeEPA(triangle, 1), *this); - return true; - } - - return false; - } - else { - - // The current triangle is visible and therefore obsolete - mOwnerTriangle->setIsObsolete(true); - - int backup = triangleStore.getNbTriangles(); - - if(!mOwnerTriangle->getAdjacentEdge(indexOfNextCounterClockwiseEdge( - this->mIndex)).computeSilhouette(vertices, - indexNewVertex, - triangleStore)) { - mOwnerTriangle->setIsObsolete(false); - - TriangleEPA* triangle = triangleStore.newTriangle(vertices, indexNewVertex, - getTargetVertexIndex(), - getSourceVertexIndex()); - - // If the triangle has been created - if (triangle != nullptr) { - halfLink(EdgeEPA(triangle, 1), *this); - return true; - } - - return false; - } - else if (!mOwnerTriangle->getAdjacentEdge(indexOfPreviousCounterClockwiseEdge( - this->mIndex)).computeSilhouette(vertices, - indexNewVertex, - triangleStore)) { - mOwnerTriangle->setIsObsolete(false); - - triangleStore.setNbTriangles(backup); - - TriangleEPA* triangle = triangleStore.newTriangle(vertices, indexNewVertex, - getTargetVertexIndex(), - getSourceVertexIndex()); - - if (triangle != nullptr) { - halfLink(EdgeEPA(triangle, 1), *this); - return true; - } - - return false; - } - } - } - - return true; -} diff --git a/src/collision/narrowphase/EPA/TriangleEPA.cpp b/src/collision/narrowphase/EPA/TriangleEPA.cpp deleted file mode 100644 index c322059f..00000000 --- a/src/collision/narrowphase/EPA/TriangleEPA.cpp +++ /dev/null @@ -1,145 +0,0 @@ -/******************************************************************************** -* 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. * -* * -********************************************************************************/ - - -// Libraries -#include "TriangleEPA.h" -#include "EdgeEPA.h" -#include "TrianglesStore.h" - -// We use the ReactPhysics3D namespace -using namespace reactphysics3d; - -// Constructor -TriangleEPA::TriangleEPA(uint indexVertex1, uint indexVertex2, uint indexVertex3) - : mIsObsolete(false) { - mIndicesVertices[0] = indexVertex1; - mIndicesVertices[1] = indexVertex2; - mIndicesVertices[2] = indexVertex3; -} - -// Compute the point v closest to the origin of this triangle -bool TriangleEPA::computeClosestPoint(const Vector3* vertices) { - const Vector3& p0 = vertices[mIndicesVertices[0]]; - - Vector3 v1 = vertices[mIndicesVertices[1]] - p0; - Vector3 v2 = vertices[mIndicesVertices[2]] - p0; - decimal v1Dotv1 = v1.dot(v1); - decimal v1Dotv2 = v1.dot(v2); - decimal v2Dotv2 = v2.dot(v2); - decimal p0Dotv1 = p0.dot(v1); - decimal p0Dotv2 = p0.dot(v2); - - // Compute determinant - mDet = v1Dotv1 * v2Dotv2 - v1Dotv2 * v1Dotv2; - - // Compute lambda values - mLambda1 = p0Dotv2 * v1Dotv2 - p0Dotv1 * v2Dotv2; - mLambda2 = p0Dotv1 * v1Dotv2 - p0Dotv2 * v1Dotv1; - - // If the determinant is positive - if (mDet > 0.0) { - // Compute the closest point v - mClosestPoint = p0 + decimal(1.0) / mDet * (mLambda1 * v1 + mLambda2 * v2); - - // Compute the square distance of closest point to the origin - mDistSquare = mClosestPoint.dot(mClosestPoint); - - return true; - } - - return false; -} - -/// Link an edge with another one. It means that the current edge of a triangle will -/// be associated with the edge of another triangle in order that both triangles -/// are neighbour along both edges). -bool reactphysics3d::link(const EdgeEPA& edge0, const EdgeEPA& edge1) { - bool isPossible = (edge0.getSourceVertexIndex() == edge1.getTargetVertexIndex() && - edge0.getTargetVertexIndex() == edge1.getSourceVertexIndex()); - - if (isPossible) { - edge0.getOwnerTriangle()->mAdjacentEdges[edge0.getIndex()] = edge1; - edge1.getOwnerTriangle()->mAdjacentEdges[edge1.getIndex()] = edge0; - } - - return isPossible; -} - -/// Make an half link of an edge with another one from another triangle. An half-link -/// between an edge "edge0" and an edge "edge1" represents the fact that "edge1" is an -/// adjacent edge of "edge0" but not the opposite. The opposite edge connection will -/// be made later. -void reactphysics3d::halfLink(const EdgeEPA& edge0, const EdgeEPA& edge1) { - assert(edge0.getSourceVertexIndex() == edge1.getTargetVertexIndex() && - edge0.getTargetVertexIndex() == edge1.getSourceVertexIndex()); - - // Link - edge0.getOwnerTriangle()->mAdjacentEdges[edge0.getIndex()] = edge1; -} - -// Execute the recursive silhouette algorithm from this triangle face. -/// The parameter "vertices" is an array that contains the vertices of the current polytope and the -/// parameter "indexNewVertex" is the index of the new vertex in this array. The goal of the -/// silhouette algorithm is to add the new vertex in the polytope by keeping it convex. Therefore, -/// the triangle faces that are visible from the new vertex must be removed from the polytope and we -/// need to add triangle faces where each face contains the new vertex and an edge of the silhouette. -/// The silhouette is the connected set of edges that are part of the border between faces that -/// are seen and faces that are not seen from the new vertex. This method starts from the nearest -/// face from the new vertex, computes the silhouette and create the new faces from the new vertex in -/// order that we always have a convex polytope. The faces visible from the new vertex are set -/// obselete and will not be considered as being a candidate face in the future. -bool TriangleEPA::computeSilhouette(const Vector3* vertices, uint indexNewVertex, - TrianglesStore& triangleStore) { - - uint first = triangleStore.getNbTriangles(); - - // Mark the current triangle as obsolete because it - setIsObsolete(true); - - // Execute recursively the silhouette algorithm for the adjacent edges of neighboring - // triangles of the current triangle - bool result = mAdjacentEdges[0].computeSilhouette(vertices, indexNewVertex, triangleStore) && - mAdjacentEdges[1].computeSilhouette(vertices, indexNewVertex, triangleStore) && - mAdjacentEdges[2].computeSilhouette(vertices, indexNewVertex, triangleStore); - - if (result) { - int i,j; - - // For each triangle face that contains the new vertex and an edge of the silhouette - for (i=first, j=triangleStore.getNbTriangles()-1; - i != triangleStore.getNbTriangles(); j = i++) { - TriangleEPA* triangle = &triangleStore[i]; - halfLink(triangle->getAdjacentEdge(1), EdgeEPA(triangle, 1)); - - if (!link(EdgeEPA(triangle, 0), EdgeEPA(&triangleStore[j], 2))) { - return false; - } - } - - } - - return result; -} diff --git a/src/collision/narrowphase/EPA/TriangleEPA.h b/src/collision/narrowphase/EPA/TriangleEPA.h deleted file mode 100644 index 865c69d4..00000000 --- a/src/collision/narrowphase/EPA/TriangleEPA.h +++ /dev/null @@ -1,197 +0,0 @@ -/******************************************************************************** -* 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_TRIANGLE_EPA_H -#define REACTPHYSICS3D_TRIANGLE_EPA_H - -// Libraries -#include "mathematics/mathematics.h" -#include "configuration.h" -#include "EdgeEPA.h" -#include - -/// ReactPhysics3D namespace -namespace reactphysics3d { - -// Prototypes -bool link(const EdgeEPA& edge0, const EdgeEPA& edge1); -void halfLink(const EdgeEPA& edge0, const EdgeEPA& edge1); - - -// Class TriangleEPA -/** - * This class represents a triangle face of the current polytope in the EPA algorithm. - */ -class TriangleEPA { - - private: - - // -------------------- Attributes -------------------- // - - /// Indices of the vertices y_i of the triangle - uint mIndicesVertices[3]; - - /// Three adjacent edges of the triangle (edges of other triangles) - EdgeEPA mAdjacentEdges[3]; - - /// True if the triangle face is visible from the new support point - bool mIsObsolete; - - /// Determinant - decimal mDet; - - /// Point v closest to the origin on the affine hull of the triangle - Vector3 mClosestPoint; - - /// Lambda1 value such that v = lambda0 * y_0 + lambda1 * y_1 + lambda2 * y_2 - decimal mLambda1; - - /// Lambda1 value such that v = lambda0 * y_0 + lambda1 * y_1 + lambda2 * y_2 - decimal mLambda2; - - /// Square distance of the point closest point v to the origin - decimal mDistSquare; - - public: - - // -------------------- Methods -------------------- // - - /// Constructor - TriangleEPA() = default; - - /// Constructor - TriangleEPA(uint v1, uint v2, uint v3); - - /// Destructor - ~TriangleEPA() = default; - - /// Deleted copy-constructor - TriangleEPA(const TriangleEPA& triangle) = delete; - - /// Deleted assignment operator - TriangleEPA& operator=(const TriangleEPA& triangle) = delete; - - /// Return an adjacent edge of the triangle - EdgeEPA& getAdjacentEdge(int index); - - /// Set an adjacent edge of the triangle - void setAdjacentEdge(int index, EdgeEPA& edge); - - /// Return the square distance of the closest point to origin - decimal getDistSquare() const; - - /// Set the isObsolete value - void setIsObsolete(bool isObsolete); - - /// Return true if the triangle face is obsolete - bool getIsObsolete() const; - - /// Return the point closest to the origin - const Vector3& getClosestPoint() const; - - // Return true if the closest point on affine hull is inside the triangle - bool isClosestPointInternalToTriangle() const; - - /// Return true if the triangle is visible from a given vertex - bool isVisibleFromVertex(const Vector3* vertices, uint index) const; - - /// Compute the point v closest to the origin of this triangle - bool computeClosestPoint(const Vector3* vertices); - - /// Compute the point of an object closest to the origin - Vector3 computeClosestPointOfObject(const Vector3* supportPointsOfObject) const; - - /// Execute the recursive silhouette algorithm from this triangle face. - bool computeSilhouette(const Vector3* vertices, uint index, TrianglesStore& triangleStore); - - /// Access operator - uint operator[](int i) const; - - /// Associate two edges - friend bool link(const EdgeEPA& edge0, const EdgeEPA& edge1); - - /// Make a half-link between two edges - friend void halfLink(const EdgeEPA& edge0, const EdgeEPA& edge1); -}; - -// Return an edge of the triangle -inline EdgeEPA& TriangleEPA::getAdjacentEdge(int index) { - assert(index >= 0 && index < 3); - return mAdjacentEdges[index]; -} - -// Set an adjacent edge of the triangle -inline void TriangleEPA::setAdjacentEdge(int index, EdgeEPA& edge) { - assert(index >=0 && index < 3); - mAdjacentEdges[index] = edge; -} - -// Return the square distance of the closest point to origin -inline decimal TriangleEPA::getDistSquare() const { - return mDistSquare; -} - -// Set the isObsolete value -inline void TriangleEPA::setIsObsolete(bool isObsolete) { - mIsObsolete = isObsolete; -} - -// Return true if the triangle face is obsolete -inline bool TriangleEPA::getIsObsolete() const { - return mIsObsolete; -} - -// Return the point closest to the origin -inline const Vector3& TriangleEPA::getClosestPoint() const { - return mClosestPoint; -} - -// Return true if the closest point on affine hull is inside the triangle -inline bool TriangleEPA::isClosestPointInternalToTriangle() const { - return (mLambda1 >= 0.0 && mLambda2 >= 0.0 && (mLambda1 + mLambda2) <= mDet); -} - -// Return true if the triangle is visible from a given vertex -inline bool TriangleEPA::isVisibleFromVertex(const Vector3* vertices, uint index) const { - Vector3 closestToVert = vertices[index] - mClosestPoint; - return (mClosestPoint.dot(closestToVert) > 0.0); -} - -// Compute the point of an object closest to the origin -inline Vector3 TriangleEPA::computeClosestPointOfObject(const Vector3* supportPointsOfObject) const{ - const Vector3& p0 = supportPointsOfObject[mIndicesVertices[0]]; - return p0 + decimal(1.0)/mDet * (mLambda1 * (supportPointsOfObject[mIndicesVertices[1]] - p0) + - mLambda2 * (supportPointsOfObject[mIndicesVertices[2]] - p0)); -} - -// Access operator -inline uint TriangleEPA::operator[](int i) const { - assert(i >= 0 && i <3); - return mIndicesVertices[i]; -} - -} - -#endif diff --git a/src/collision/narrowphase/EPA/TrianglesStore.h b/src/collision/narrowphase/EPA/TrianglesStore.h deleted file mode 100644 index d21ccd35..00000000 --- a/src/collision/narrowphase/EPA/TrianglesStore.h +++ /dev/null @@ -1,139 +0,0 @@ -/******************************************************************************** -* 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_TRIANGLES_STORE_H -#define REACTPHYSICS3D_TRIANGLES_STORE_H - -#include "TriangleEPA.h" - - -// Libraries -#include - -/// ReactPhysics3D namespace -namespace reactphysics3d { - -// Constants -constexpr unsigned int MAX_TRIANGLES = 200; // Maximum number of triangles - -// Class TriangleStore -/** - * This class stores several triangles of the polytope in the EPA algorithm. - */ -class TrianglesStore { - - private: - - // -------------------- Attributes -------------------- // - - /// Triangles - TriangleEPA mTriangles[MAX_TRIANGLES]; - - /// Number of triangles - int mNbTriangles; - - public: - - // -------------------- Methods -------------------- // - - /// Constructor - TrianglesStore(); - - /// Destructor - ~TrianglesStore() = default; - - /// Deleted copy-constructor - TrianglesStore(const TrianglesStore& triangleStore) = delete; - - /// Deleted assignment operator - TrianglesStore& operator=(const TrianglesStore& triangleStore) = delete; - - /// Clear all the storage - void clear(); - - /// Return the number of triangles - int getNbTriangles() const; - - /// Set the number of triangles - void setNbTriangles(int backup); - - /// Return the last triangle - TriangleEPA& last(); - - /// Create a new triangle - TriangleEPA* newTriangle(const Vector3* vertices, uint v0, uint v1, uint v2); - - /// Access operator - TriangleEPA& operator[](int i); -}; - -// Clear all the storage -inline void TrianglesStore::clear() { - mNbTriangles = 0; -} - -// Return the number of triangles -inline int TrianglesStore::getNbTriangles() const { - return mNbTriangles; -} - - -inline void TrianglesStore::setNbTriangles(int backup) { - mNbTriangles = backup; -} - -// Return the last triangle -inline TriangleEPA& TrianglesStore::last() { - assert(mNbTriangles > 0); - return mTriangles[mNbTriangles - 1]; -} - -// Create a new triangle -inline TriangleEPA* TrianglesStore::newTriangle(const Vector3* vertices, - uint v0,uint v1, uint v2) { - TriangleEPA* newTriangle = nullptr; - - // If we have not reached the maximum number of triangles - if (mNbTriangles != MAX_TRIANGLES) { - newTriangle = &mTriangles[mNbTriangles++]; - new (newTriangle) TriangleEPA(v0, v1, v2); - if (!newTriangle->computeClosestPoint(vertices)) { - mNbTriangles--; - newTriangle = nullptr; - } - } - - // Return the new triangle - return newTriangle; -} - -// Access operator -inline TriangleEPA& TrianglesStore::operator[](int i) { - return mTriangles[i]; -} - -} - -#endif diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp index e1649af0..cd84f5a0 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp @@ -45,7 +45,7 @@ using namespace reactphysics3d; /// algorithm on the enlarged object to obtain a simplex polytope that contains the /// origin, they we give that simplex polytope to the EPA algorithm which will compute /// the correct penetration depth and contact points between the enlarged objects. -bool GJKAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, +GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactPointInfo& contactPointInfo) { PROFILE("GJKAlgorithm::testCollision()"); @@ -101,8 +101,7 @@ bool GJKAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, // Compute the support points for original objects (without margins) A and B suppA = shape1->getLocalSupportPointWithoutMargin(-v, shape1CachedCollisionData); - suppB = body2Tobody1 * - shape2->getLocalSupportPointWithoutMargin(rotateToBody2 * v, shape2CachedCollisionData); + suppB = body2Tobody1 * shape2->getLocalSupportPointWithoutMargin(rotateToBody2 * v, shape2CachedCollisionData); // Compute the support point for the Minkowski difference A-B w = suppA - suppB; @@ -116,7 +115,7 @@ bool GJKAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, narrowPhaseInfo->overlappingPair->setCachedSeparatingAxis(v); // No intersection, we return - return false; + return GJKResult::SEPARATED; } // If the objects intersect only in the margins @@ -135,7 +134,8 @@ bool GJKAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, // Contact point has been found contactFound = true; - break; + + return GJKResult::INTERPENETRATE; } // Compute the point of the simplex closest to the origin @@ -144,13 +144,14 @@ bool GJKAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, // Contact point has been found contactFound = true; - break; + + return GJKResult::INTERPENETRATE; } // Closest point is almost the origin, go to EPA algorithm // Vector v to small to continue computing support points if (v.lengthSquare() < MACHINE_EPSILON) { - break; + return GJKResult::INTERPENETRATE; } // Store and update the squared distance of the closest point @@ -173,20 +174,6 @@ bool GJKAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, } while((isPolytopeShape && !simplex.isFull()) || (!isPolytopeShape && !simplex.isFull() && distSquare > MACHINE_EPSILON * simplex.getMaxLengthSquareOfAPoint())); - // If no contact has been found (penetration case) - if (!contactFound) { - - // The objects (without margins) intersect. Therefore, we run the GJK algorithm - // again but on the enlarged objects to compute a simplex polytope that contains - // the origin. Then, we give that simplex polytope to the EPA algorithm to compute - // the correct penetration depth and contact points between the enlarged objects. - if(computePenetrationDepthForEnlargedObjects(narrowPhaseInfo, contactPointInfo, v)) { - - // A contact has been found with EPA algorithm, we return true - return true; - } - } - if (contactFound && distSquare > MACHINE_EPSILON) { // Compute the closet points of both objects (without the margins) @@ -205,103 +192,21 @@ bool GJKAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, // If the penetration depth is negative (due too numerical errors), there is no contact if (penetrationDepth <= decimal(0.0)) { - return false; + return GJKResult::INTERPENETRATE; } // Do not generate a contact point with zero normal length if (normal.lengthSquare() < MACHINE_EPSILON) { - return false; + return GJKResult::INTERPENETRATE; } // Create the contact info object contactPointInfo.init(normal, penetrationDepth, pA, pB); - return true; + return GJKResult::COLLIDE_IN_MARGIN; } - return false; -} - -/// This method runs the GJK algorithm on the two enlarged objects (with margin) -/// to compute a simplex polytope that contains the origin. The two objects are -/// assumed to intersect in the original objects (without margin). Therefore such -/// a polytope must exist. Then, we give that polytope to the EPA algorithm to -/// compute the correct penetration depth and contact points of the enlarged objects. -bool GJKAlgorithm::computePenetrationDepthForEnlargedObjects(const NarrowPhaseInfo* narrowPhaseInfo, - ContactPointInfo& contactPointInfo, - Vector3& v) { - PROFILE("GJKAlgorithm::computePenetrationDepthForEnlargedObjects()"); - - VoronoiSimplex simplex; - Vector3 suppA; - Vector3 suppB; - Vector3 w; - decimal vDotw; - decimal distSquare = DECIMAL_LARGEST; - decimal prevDistSquare; - - assert(narrowPhaseInfo->collisionShape1->isConvex()); - assert(narrowPhaseInfo->collisionShape2->isConvex()); - - const ConvexShape* shape1 = static_cast(narrowPhaseInfo->collisionShape1); - const ConvexShape* shape2 = static_cast(narrowPhaseInfo->collisionShape2); - - bool isPolytopeShape = shape1->isPolyhedron() && shape2->isPolyhedron(); - - void** shape1CachedCollisionData = narrowPhaseInfo->cachedCollisionData1; - void** shape2CachedCollisionData = narrowPhaseInfo->cachedCollisionData2; - - // Transform a point from local space of body 2 to local space - // of body 1 (the GJK algorithm is done in local space of body 1) - Transform body2ToBody1 = narrowPhaseInfo->shape1ToWorldTransform.getInverse() * narrowPhaseInfo->shape2ToWorldTransform; - - // Matrix that transform a direction from local space of body 1 into local space of body 2 - Matrix3x3 rotateToBody2 = narrowPhaseInfo->shape2ToWorldTransform.getOrientation().getMatrix().getTranspose() * - narrowPhaseInfo->shape1ToWorldTransform.getOrientation().getMatrix(); - - do { - // Compute the support points for the enlarged object A and B - suppA = shape1->getLocalSupportPointWithMargin(-v, shape1CachedCollisionData); - suppB = body2ToBody1 * shape2->getLocalSupportPointWithMargin(rotateToBody2 * v, shape2CachedCollisionData); - - // Compute the support point for the Minkowski difference A-B - w = suppA - suppB; - - vDotw = v.dot(w); - - // If the enlarge objects do not intersect - if (vDotw > decimal(0.0)) { - - // No intersection, we return - return false; - } - - // Add the new support point to the simplex - simplex.addPoint(w, suppA, suppB); - - if (simplex.isAffinelyDependent()) { - return false; - } - - if (!simplex.computeClosestPoint(v)) { - return false; - } - - // Store and update the square distance - prevDistSquare = distSquare; - distSquare = v.lengthSquare(); - - if (prevDistSquare - distSquare <= MACHINE_EPSILON * prevDistSquare) { - return false; - } - - } while((!simplex.isFull() && isPolytopeShape) || (!isPolytopeShape && !simplex.isFull() && - distSquare > MACHINE_EPSILON * simplex.getMaxLengthSquareOfAPoint())); - - // Give the simplex computed with GJK algorithm to the EPA algorithm - // which will compute the correct penetration depth and contact points - // between the two enlarged objects - return mAlgoEPA.computePenetrationDepthAndContactPoints(simplex, narrowPhaseInfo, v, contactPointInfo); + return GJKResult::SEPARATED; } // Use the GJK Algorithm to find if a point is inside a convex collision shape diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.h b/src/collision/narrowphase/GJK/GJKAlgorithm.h index e0dad891..8ca25e33 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.h +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.h @@ -27,11 +27,9 @@ #define REACTPHYSICS3D_GJK_ALGORITHM_H // Libraries -#include "collision/narrowphase/NarrowPhaseAlgorithm.h" #include "constraint/ContactPoint.h" #include "collision/shapes/ConvexShape.h" -#include "collision/narrowphase/EPA/EPAAlgorithm.h" - +#include "VoronoiSimplex.h" /// ReactPhysics3D namespace namespace reactphysics3d { @@ -57,24 +55,22 @@ constexpr int MAX_ITERATIONS_GJK_RAYCAST = 32; * Polytope Algorithm) to compute the correct penetration depth between the * enlarged objects. */ -class GJKAlgorithm : public NarrowPhaseAlgorithm { +class GJKAlgorithm { private : // -------------------- Attributes -------------------- // - /// EPA Algorithm - EPAAlgorithm mAlgoEPA; - // -------------------- Methods -------------------- // - /// Compute the penetration depth for enlarged objects. - bool computePenetrationDepthForEnlargedObjects(const NarrowPhaseInfo* narrowPhaseInfo, - ContactPointInfo& contactPointInfo, - Vector3& v); - public : + enum class GJKResult { + SEPARATED, // The two shapes are separated outside the margin + COLLIDE_IN_MARGIN, // The two shapes overlap only in the margin (shallow penetration) + INTERPENETRATE // The two shapes overlap event without the margin (deep penetration) + }; + // -------------------- Methods -------------------- // /// Constructor @@ -90,14 +86,16 @@ class GJKAlgorithm : public NarrowPhaseAlgorithm { GJKAlgorithm& operator=(const GJKAlgorithm& algorithm) = delete; /// Compute a contact info if the two bounding volumes collide. - virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactPointInfo& contactPointInfo) override; + GJKResult testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + ContactPointInfo& contactPointInfo); /// Use the GJK Algorithm to find if a point is inside a convex collision shape bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape); /// Ray casting algorithm agains a convex collision shape using the GJK Algorithm bool raycast(const Ray& ray, ProxyShape* proxyShape, RaycastInfo& raycastInfo); + + }; } diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp new file mode 100644 index 00000000..d74faf09 --- /dev/null +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -0,0 +1,43 @@ +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "SATAlgorithm.h" +#include "constraint/ContactPoint.h" +#include "configuration.h" +#include "engine/Profiler.h" +#include +#include +#include +#include + +// We want to use the ReactPhysics3D namespace +using namespace reactphysics3d; + +bool SATAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + ContactPointInfo& contactPointInfo) { + + +} diff --git a/src/collision/narrowphase/EPA/EdgeEPA.h b/src/collision/narrowphase/SAT/SATAlgorithm.h similarity index 51% rename from src/collision/narrowphase/EPA/EdgeEPA.h rename to src/collision/narrowphase/SAT/SATAlgorithm.h index ba3dcfee..30156cc2 100644 --- a/src/collision/narrowphase/EPA/EdgeEPA.h +++ b/src/collision/narrowphase/SAT/SATAlgorithm.h @@ -23,100 +23,45 @@ * * ********************************************************************************/ -#ifndef REACTPHYSICS3D_EDGE_EPA_H -#define REACTPHYSICS3D_EDGE_EPA_H - +#ifndef REACTPHYSICS3D_SAT_ALGORITHM_H +#define REACTPHYSICS3D_SAT_ALGORITHM_H // Libraries -#include "mathematics/mathematics.h" +#include "constraint/ContactPoint.h" /// ReactPhysics3D namespace namespace reactphysics3d { -// Class declarations -class TriangleEPA; -class TrianglesStore; +// Class SATAlgorithm +class SATAlgorithm { -// Class EdgeEPA -/** - * This class represents an edge of the current polytope in the EPA algorithm. - */ -class EdgeEPA { - - private: + private : // -------------------- Attributes -------------------- // - /// Pointer to the triangle that contains this edge - TriangleEPA* mOwnerTriangle; + // -------------------- Methods -------------------- // - /// Index of the edge in the triangle (between 0 and 2). - /// The edge with index i connect triangle vertices i and (i+1 % 3) - int mIndex; - - public: + public : // -------------------- Methods -------------------- // /// Constructor - EdgeEPA() = default; - - /// Constructor - EdgeEPA(TriangleEPA* ownerTriangle, int index); - - /// Copy-constructor - EdgeEPA(const EdgeEPA& edge); + SATAlgorithm() = default; /// Destructor - ~EdgeEPA() = default; + ~SATAlgorithm() = default; - /// Return the pointer to the owner triangle - TriangleEPA* getOwnerTriangle() const; + /// Deleted copy-constructor + SATAlgorithm(const SATAlgorithm& algorithm) = delete; - /// Return the index of the edge in the triangle - int getIndex() const; + /// Deleted assignment operator + SATAlgorithm& operator=(const SATAlgorithm& algorithm) = delete; - /// Return index of the source vertex of the edge - uint getSourceVertexIndex() const; - - /// Return the index of the target vertex of the edge - uint getTargetVertexIndex() const; - - /// Execute the recursive silhouette algorithm from this edge - bool computeSilhouette(const Vector3* vertices, uint index, TrianglesStore& triangleStore); - - /// Assignment operator - EdgeEPA& operator=(const EdgeEPA& edge); + /// Compute a contact info if the two bounding volumes collide. + bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + ContactPointInfo& contactPointInfo); }; -// Return the pointer to the owner triangle -inline TriangleEPA* EdgeEPA::getOwnerTriangle() const { - return mOwnerTriangle; -} - -// Return the edge index -inline int EdgeEPA::getIndex() const { - return mIndex; -} - -// Assignment operator -inline EdgeEPA& EdgeEPA::operator=(const EdgeEPA& edge) { - mOwnerTriangle = edge.mOwnerTriangle; - mIndex = edge.mIndex; - return *this; -} - -// Return the index of the next counter-clockwise edge of the ownver triangle -inline int indexOfNextCounterClockwiseEdge(int i) { - return (i + 1) % 3; -} - -// Return the index of the previous counter-clockwise edge of the ownver triangle -inline int indexOfPreviousCounterClockwiseEdge(int i) { - return (i + 2) % 3; -} - } #endif - diff --git a/src/collision/narrowphase/SphereVsConvexMeshAlgorithm.cpp b/src/collision/narrowphase/SphereVsConvexMeshAlgorithm.cpp new file mode 100644 index 00000000..65371e4f --- /dev/null +++ b/src/collision/narrowphase/SphereVsConvexMeshAlgorithm.cpp @@ -0,0 +1,62 @@ +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "SphereVsConvexMeshAlgorithm.h" +#include "SAT/SATAlgorithm.h" +#include "collision/shapes/SphereShape.h" +#include "collision/shapes/ConvexMeshShape.h" + +// We want to use the ReactPhysics3D namespace +using namespace reactphysics3d; + +bool SphereVsConvexMeshAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + ContactPointInfo& contactPointInfo) { + + // Get the local-space to world-space transforms + const Transform& transform1 = narrowPhaseInfo->shape1ToWorldTransform; + const Transform& transform2 = narrowPhaseInfo->shape2ToWorldTransform; + + // First, we run the GJK algorithm + GJKAlgorithm gjkAlgorithm; + GJKAlgorithm::GJKResult result = gjkAlgorithm.testCollision(narrowPhaseInfo, contactPointInfo); + + // If we have found a contact point inside the margins (shallow penetration) + if (result == GJKAlgorithm::GJKResult::COLLIDE_IN_MARGIN) { + + // Return true + return true; + } + + // If we have overlap even without the margins (deep penetration) + if (result == GJKAlgorithm::GJKResult::INTERPENETRATE) { + + // Run the SAT algorithm to find the separating axis and compute contact point + SATAlgorithm satAlgorithm; + return satAlgorithm.testCollision(narrowPhaseInfo, contactPointInfo); + } + + return false; +} diff --git a/src/collision/narrowphase/SphereVsConvexMeshAlgorithm.h b/src/collision/narrowphase/SphereVsConvexMeshAlgorithm.h new file mode 100644 index 00000000..448b8a5d --- /dev/null +++ b/src/collision/narrowphase/SphereVsConvexMeshAlgorithm.h @@ -0,0 +1,71 @@ +/******************************************************************************** +* 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_SPHERE_VS_CONVEX_MESH_ALGORITHM_H +#define REACTPHYSICS3D_SPHERE_VS_CONVEX_MESH_ALGORITHM_H + +// Libraries +#include "body/Body.h" +#include "constraint/ContactPoint.h" +#include "NarrowPhaseAlgorithm.h" + + +/// Namespace ReactPhysics3D +namespace reactphysics3d { + +// Class SphereVsConvexMeshAlgorithm +/** + * This class is used to compute the narrow-phase collision detection + * between a sphere and a convex mesh. + */ +class SphereVsConvexMeshAlgorithm : public NarrowPhaseAlgorithm { + + protected : + + public : + + // -------------------- Methods -------------------- // + + /// Constructor + SphereVsConvexMeshAlgorithm() = default; + + /// Destructor + virtual ~SphereVsConvexMeshAlgorithm() override = default; + + /// Deleted copy-constructor + SphereVsConvexMeshAlgorithm(const SphereVsConvexMeshAlgorithm& algorithm) = delete; + + /// Deleted assignment operator + SphereVsConvexMeshAlgorithm& operator=(const SphereVsConvexMeshAlgorithm& algorithm) = delete; + + /// Compute a contact info if the two bounding volume collide + virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + ContactPointInfo& contactPointInfo) override; +}; + +} + +#endif + diff --git a/src/collision/shapes/CollisionShape.h b/src/collision/shapes/CollisionShape.h index b33ed4f1..8a591614 100644 --- a/src/collision/shapes/CollisionShape.h +++ b/src/collision/shapes/CollisionShape.h @@ -40,8 +40,7 @@ namespace reactphysics3d { /// Type of the collision shape -enum class CollisionShapeType {TRIANGLE, BOX, SPHERE, CONE, CYLINDER, - CAPSULE, CONVEX_MESH, CONCAVE_MESH, HEIGHTFIELD}; +enum class CollisionShapeType {TRIANGLE, BOX, SPHERE, CAPSULE, CONVEX_MESH, CONCAVE_MESH, HEIGHTFIELD}; const int NB_COLLISION_SHAPE_TYPES = 9; // Declarations diff --git a/src/collision/shapes/ConeShape.cpp b/src/collision/shapes/ConeShape.cpp deleted file mode 100644 index 4a1ece33..00000000 --- a/src/collision/shapes/ConeShape.cpp +++ /dev/null @@ -1,209 +0,0 @@ -/******************************************************************************** -* 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. * -* * -********************************************************************************/ - -// Libraries -#include -#include "configuration.h" -#include "ConeShape.h" -#include "collision/ProxyShape.h" - -using namespace reactphysics3d; - -// Constructor -/** - * @param radius Radius of the cone (in meters) - * @param height Height of the cone (in meters) - * @param margin Collision margin (in meters) around the collision shape - */ -ConeShape::ConeShape(decimal radius, decimal height, decimal margin) - : ConvexShape(CollisionShapeType::CONE, margin), mRadius(radius), mHalfHeight(height * decimal(0.5)) { - assert(mRadius > decimal(0.0)); - assert(mHalfHeight > decimal(0.0)); - - // Compute the sine of the semi-angle at the apex point - mSinTheta = mRadius / (sqrt(mRadius * mRadius + height * height)); -} - -// Return a local support point in a given direction without the object margin -Vector3 ConeShape::getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const { - - const Vector3& v = direction; - decimal sinThetaTimesLengthV = mSinTheta * v.length(); - Vector3 supportPoint; - - if (v.y > sinThetaTimesLengthV) { - supportPoint = Vector3(0.0, mHalfHeight, 0.0); - } - else { - decimal projectedLength = sqrt(v.x * v.x + v.z * v.z); - if (projectedLength > MACHINE_EPSILON) { - decimal d = mRadius / projectedLength; - supportPoint = Vector3(v.x * d, -mHalfHeight, v.z * d); - } - else { - supportPoint = Vector3(0.0, -mHalfHeight, 0.0); - } - } - - return supportPoint; -} - -// Raycast method with feedback information -// This implementation is based on the technique described by David Eberly in the article -// "Intersection of a Line and a Cone" that can be found at -// http://www.geometrictools.com/Documentation/IntersectionLineCone.pdf -bool ConeShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const { - - const Vector3 r = ray.point2 - ray.point1; - - const decimal epsilon = decimal(0.00001); - Vector3 V(0, mHalfHeight, 0); - Vector3 centerBase(0, -mHalfHeight, 0); - Vector3 axis(0, decimal(-1.0), 0); - decimal heightSquare = decimal(4.0) * mHalfHeight * mHalfHeight; - decimal cosThetaSquare = heightSquare / (heightSquare + mRadius * mRadius); - decimal factor = decimal(1.0) - cosThetaSquare; - Vector3 delta = ray.point1 - V; - decimal c0 = -cosThetaSquare * delta.x * delta.x + factor * delta.y * delta.y - - cosThetaSquare * delta.z * delta.z; - decimal c1 = -cosThetaSquare * delta.x * r.x + factor * delta.y * r.y - cosThetaSquare * delta.z * r.z; - decimal c2 = -cosThetaSquare * r.x * r.x + factor * r.y * r.y - cosThetaSquare * r.z * r.z; - decimal tHit[] = {decimal(-1.0), decimal(-1.0), decimal(-1.0)}; - Vector3 localHitPoint[3]; - Vector3 localNormal[3]; - - // If c2 is different from zero - if (std::abs(c2) > MACHINE_EPSILON) { - decimal gamma = c1 * c1 - c0 * c2; - - // If there is no real roots in the quadratic equation - if (gamma < decimal(0.0)) { - return false; - } - else if (gamma > decimal(0.0)) { // The equation has two real roots - - // Compute two intersections - decimal sqrRoot = std::sqrt(gamma); - tHit[0] = (-c1 - sqrRoot) / c2; - tHit[1] = (-c1 + sqrRoot) / c2; - } - else { // If the equation has a single real root - - // Compute the intersection - tHit[0] = -c1 / c2; - } - } - else { // If c2 == 0 - - // If c2 = 0 and c1 != 0 - if (std::abs(c1) > MACHINE_EPSILON) { - tHit[0] = -c0 / (decimal(2.0) * c1); - } - else { // If c2 = c1 = 0 - - // If c0 is different from zero, no solution and if c0 = 0, we have a - // degenerate case, the whole ray is contained in the cone side - // but we return no hit in this case - return false; - } - } - - // If the origin of the ray is inside the cone, we return no hit - if (testPointInside(ray.point1, nullptr)) return false; - - localHitPoint[0] = ray.point1 + tHit[0] * r; - localHitPoint[1] = ray.point1 + tHit[1] * r; - - // Only keep hit points in one side of the double cone (the cone we are interested in) - if (axis.dot(localHitPoint[0] - V) < decimal(0.0)) { - tHit[0] = decimal(-1.0); - } - if (axis.dot(localHitPoint[1] - V) < decimal(0.0)) { - tHit[1] = decimal(-1.0); - } - - // Only keep hit points that are within the correct height of the cone - if (localHitPoint[0].y < decimal(-mHalfHeight)) { - tHit[0] = decimal(-1.0); - } - if (localHitPoint[1].y < decimal(-mHalfHeight)) { - tHit[1] = decimal(-1.0); - } - - // If the ray is in direction of the base plane of the cone - if (r.y > epsilon) { - - // Compute the intersection with the base plane of the cone - tHit[2] = (-ray.point1.y - mHalfHeight) / (r.y); - - // Only keep this intersection if it is inside the cone radius - localHitPoint[2] = ray.point1 + tHit[2] * r; - - if ((localHitPoint[2] - centerBase).lengthSquare() > mRadius * mRadius) { - tHit[2] = decimal(-1.0); - } - - // Compute the normal direction - localNormal[2] = axis; - } - - // Find the smallest positive t value - int hitIndex = -1; - decimal t = DECIMAL_LARGEST; - for (int i=0; i<3; i++) { - if (tHit[i] < decimal(0.0)) continue; - if (tHit[i] < t) { - hitIndex = i; - t = tHit[hitIndex]; - } - } - - if (hitIndex < 0) return false; - if (t > ray.maxFraction) return false; - - // Compute the normal direction for hit against side of the cone - if (hitIndex != 2) { - decimal h = decimal(2.0) * mHalfHeight; - decimal value1 = (localHitPoint[hitIndex].x * localHitPoint[hitIndex].x + - localHitPoint[hitIndex].z * localHitPoint[hitIndex].z); - decimal rOverH = mRadius / h; - decimal value2 = decimal(1.0) + rOverH * rOverH; - decimal factor = decimal(1.0) / std::sqrt(value1 * value2); - decimal x = localHitPoint[hitIndex].x * factor; - decimal z = localHitPoint[hitIndex].z * factor; - localNormal[hitIndex].x = x; - localNormal[hitIndex].y = std::sqrt(x * x + z * z) * rOverH; - localNormal[hitIndex].z = z; - } - - raycastInfo.body = proxyShape->getBody(); - raycastInfo.proxyShape = proxyShape; - raycastInfo.hitFraction = t; - raycastInfo.worldPoint = localHitPoint[hitIndex]; - raycastInfo.worldNormal = localNormal[hitIndex]; - - return true; -} diff --git a/src/collision/shapes/ConeShape.h b/src/collision/shapes/ConeShape.h deleted file mode 100644 index 16102163..00000000 --- a/src/collision/shapes/ConeShape.h +++ /dev/null @@ -1,194 +0,0 @@ -/******************************************************************************** -* 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_CONE_SHAPE_H -#define REACTPHYSICS3D_CONE_SHAPE_H - -// Libraries -#include "ConvexShape.h" -#include "body/CollisionBody.h" -#include "mathematics/mathematics.h" - -/// ReactPhysics3D namespace -namespace reactphysics3d { - -// Class ConeShape -/** - * This class represents a cone collision shape centered at the - * origin and alligned with the Y axis. The cone is defined - * by its height and by the radius of its base. The center of the - * cone is at the half of the height. The "transform" of the - * corresponding rigid body gives an orientation and a position - * to the cone. This collision shape uses an extra margin distance around - * it for collision detection purpose. The default margin is 4cm (if your - * units are meters, which is recommended). In case, you want to simulate small - * objects (smaller than the margin distance), you might want to reduce the margin - * by specifying your own margin distance using the "margin" parameter in the - * constructor of the cone shape. Otherwise, it is recommended to use the - * default margin distance by not using the "margin" parameter in the constructor. - */ -class ConeShape : public ConvexShape { - - protected : - - // -------------------- Attributes -------------------- // - - /// Radius of the base - decimal mRadius; - - /// Half height of the cone - decimal mHalfHeight; - - /// sine of the semi angle at the apex point - decimal mSinTheta; - - // -------------------- Methods -------------------- // - - /// Return a local support point in a given direction without the object margin - virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const override; - - /// Return true if a point is inside the collision shape - 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; - - /// Return the number of bytes used by the collision shape - virtual size_t getSizeInBytes() const override; - - public : - - // -------------------- Methods -------------------- // - - /// Constructor - ConeShape(decimal mRadius, decimal height, decimal margin = OBJECT_MARGIN); - - /// Destructor - virtual ~ConeShape() override = default; - - /// Deleted copy-constructor - ConeShape(const ConeShape& shape) = delete; - - /// Deleted assignment operator - ConeShape& operator=(const ConeShape& shape) = delete; - - /// Return the radius - decimal getRadius() const; - - /// Return the height - decimal getHeight() const; - - /// Set the scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling) override; - - /// Return the local bounds of the shape in x, y and z directions - virtual void getLocalBounds(Vector3& min, Vector3& max) const override; - - /// Return true if the collision shape is a polyhedron - virtual bool isPolyhedron() const override; - - /// Return the local inertia tensor of the collision shape - virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; -}; - -// Return the radius -/** - * @return Radius of the cone (in meters) - */ -inline decimal ConeShape::getRadius() const { - return mRadius; -} - -// Return the height -/** - * @return Height of the cone (in meters) - */ -inline decimal ConeShape::getHeight() const { - return decimal(2.0) * mHalfHeight; -} - -// Set the scaling vector of the collision shape -inline void ConeShape::setLocalScaling(const Vector3& scaling) { - - mHalfHeight = (mHalfHeight / mScaling.y) * scaling.y; - mRadius = (mRadius / mScaling.x) * scaling.x; - - CollisionShape::setLocalScaling(scaling); -} - -// Return the number of bytes used by the collision shape -inline size_t ConeShape::getSizeInBytes() const { - return sizeof(ConeShape); -} - -// Return the local bounds of the shape in x, y and z directions -/** - * @param min The minimum bounds of the shape in local-space coordinates - * @param max The maximum bounds of the shape in local-space coordinates - */ -inline void ConeShape::getLocalBounds(Vector3& min, Vector3& max) const { - - // Maximum bounds - max.x = mRadius + mMargin; - max.y = mHalfHeight + mMargin; - max.z = max.x; - - // Minimum bounds - min.x = -max.x; - min.y = -max.y; - min.z = min.x; -} - -// Return true if the collision shape is a polyhedron -inline bool ConeShape::isPolyhedron() const { - return false; -} - -// Return the local inertia tensor of the collision shape -/** - * @param[out] tensor The 3x3 inertia tensor matrix of the shape in local-space - * coordinates - * @param mass Mass to use to compute the inertia tensor of the collision shape - */ -inline void ConeShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const { - decimal rSquare = mRadius * mRadius; - decimal diagXZ = decimal(0.15) * mass * (rSquare + mHalfHeight); - tensor.setAllValues(diagXZ, 0.0, 0.0, - 0.0, decimal(0.3) * mass * rSquare, - 0.0, 0.0, 0.0, diagXZ); -} - -// Return true if a point is inside the collision shape -inline bool ConeShape::testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const { - const decimal radiusHeight = mRadius * (-localPoint.y + mHalfHeight) / - (mHalfHeight * decimal(2.0)); - return (localPoint.y < mHalfHeight && localPoint.y > -mHalfHeight) && - (localPoint.x * localPoint.x + localPoint.z * localPoint.z < radiusHeight *radiusHeight); -} - -} - -#endif diff --git a/src/collision/shapes/CylinderShape.cpp b/src/collision/shapes/CylinderShape.cpp deleted file mode 100644 index 8cb405f1..00000000 --- a/src/collision/shapes/CylinderShape.cpp +++ /dev/null @@ -1,231 +0,0 @@ -/******************************************************************************** -* 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. * -* * -********************************************************************************/ - -// Libraries -#include "CylinderShape.h" -#include "collision/ProxyShape.h" -#include "configuration.h" - -using namespace reactphysics3d; - -// Constructor -/** - * @param radius Radius of the cylinder (in meters) - * @param height Height of the cylinder (in meters) - * @param margin Collision margin (in meters) around the collision shape - */ -CylinderShape::CylinderShape(decimal radius, decimal height, decimal margin) - : ConvexShape(CollisionShapeType::CYLINDER, margin), mRadius(radius), - mHalfHeight(height/decimal(2.0)) { - assert(radius > decimal(0.0)); - assert(height > decimal(0.0)); -} - -// Return a local support point in a given direction without the object margin -Vector3 CylinderShape::getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const { - - Vector3 supportPoint(0.0, 0.0, 0.0); - decimal uDotv = direction.y; - Vector3 w(direction.x, 0.0, direction.z); - decimal lengthW = std::sqrt(direction.x * direction.x + direction.z * direction.z); - - if (lengthW > MACHINE_EPSILON) { - if (uDotv < 0.0) supportPoint.y = -mHalfHeight; - else supportPoint.y = mHalfHeight; - supportPoint += (mRadius / lengthW) * w; - } - else { - if (uDotv < 0.0) supportPoint.y = -mHalfHeight; - else supportPoint.y = mHalfHeight; - } - - return supportPoint; -} - -// Raycast method with feedback information -/// Algorithm based on the one described at page 194 in Real-ime Collision Detection by -/// Morgan Kaufmann. -bool CylinderShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const { - - const Vector3 n = ray.point2 - ray.point1; - - const decimal epsilon = decimal(0.01); - Vector3 p(decimal(0), -mHalfHeight, decimal(0)); - Vector3 q(decimal(0), mHalfHeight, decimal(0)); - Vector3 d = q - p; - Vector3 m = ray.point1 - p; - decimal t; - - decimal mDotD = m.dot(d); - decimal nDotD = n.dot(d); - decimal dDotD = d.dot(d); - - // Test if the segment is outside the cylinder - if (mDotD < decimal(0.0) && mDotD + nDotD < decimal(0.0)) return false; - if (mDotD > dDotD && mDotD + nDotD > dDotD) return false; - - decimal nDotN = n.dot(n); - decimal mDotN = m.dot(n); - - decimal a = dDotD * nDotN - nDotD * nDotD; - decimal k = m.dot(m) - mRadius * mRadius; - decimal c = dDotD * k - mDotD * mDotD; - - // If the ray is parallel to the cylinder axis - if (std::abs(a) < epsilon) { - - // If the origin is outside the surface of the cylinder, we return no hit - if (c > decimal(0.0)) return false; - - // Here we know that the segment intersect an endcap of the cylinder - - // If the ray intersects with the "p" endcap of the cylinder - if (mDotD < decimal(0.0)) { - - t = -mDotN / nDotN; - - // If the intersection is behind the origin of the ray or beyond the maximum - // raycasting distance, we return no hit - if (t < decimal(0.0) || t > ray.maxFraction) return false; - - // Compute the hit information - Vector3 localHitPoint = ray.point1 + t * n; - raycastInfo.body = proxyShape->getBody(); - raycastInfo.proxyShape = proxyShape; - raycastInfo.hitFraction = t; - raycastInfo.worldPoint = localHitPoint; - Vector3 normalDirection(0, decimal(-1), 0); - raycastInfo.worldNormal = normalDirection; - - return true; - } - else if (mDotD > dDotD) { // If the ray intersects with the "q" endcap of the cylinder - - t = (nDotD - mDotN) / nDotN; - - // If the intersection is behind the origin of the ray or beyond the maximum - // raycasting distance, we return no hit - if (t < decimal(0.0) || t > ray.maxFraction) return false; - - // Compute the hit information - Vector3 localHitPoint = ray.point1 + t * n; - raycastInfo.body = proxyShape->getBody(); - raycastInfo.proxyShape = proxyShape; - raycastInfo.hitFraction = t; - raycastInfo.worldPoint = localHitPoint; - Vector3 normalDirection(0, decimal(1.0), 0); - raycastInfo.worldNormal = normalDirection; - - return true; - } - else { // If the origin is inside the cylinder, we return no hit - return false; - } - } - decimal b = dDotD * mDotN - nDotD * mDotD; - decimal discriminant = b * b - a * c; - - // If the discriminant is negative, no real roots and therfore, no hit - if (discriminant < decimal(0.0)) return false; - - // Compute the smallest root (first intersection along the ray) - decimal t0 = t = (-b - std::sqrt(discriminant)) / a; - - // If the intersection is outside the cylinder on "p" endcap side - decimal value = mDotD + t * nDotD; - if (value < decimal(0.0)) { - - // If the ray is pointing away from the "p" endcap, we return no hit - if (nDotD <= decimal(0.0)) return false; - - // Compute the intersection against the "p" endcap (intersection agains whole plane) - t = -mDotD / nDotD; - - // Keep the intersection if the it is inside the cylinder radius - if (k + t * (decimal(2.0) * mDotN + t) > decimal(0.0)) return false; - - // If the intersection is behind the origin of the ray or beyond the maximum - // raycasting distance, we return no hit - if (t < decimal(0.0) || t > ray.maxFraction) return false; - - // Compute the hit information - Vector3 localHitPoint = ray.point1 + t * n; - raycastInfo.body = proxyShape->getBody(); - raycastInfo.proxyShape = proxyShape; - raycastInfo.hitFraction = t; - raycastInfo.worldPoint = localHitPoint; - Vector3 normalDirection(0, decimal(-1.0), 0); - raycastInfo.worldNormal = normalDirection; - - return true; - } - else if (value > dDotD) { // If the intersection is outside the cylinder on the "q" side - - // If the ray is pointing away from the "q" endcap, we return no hit - if (nDotD >= decimal(0.0)) return false; - - // Compute the intersection against the "q" endcap (intersection against whole plane) - t = (dDotD - mDotD) / nDotD; - - // Keep the intersection if it is inside the cylinder radius - if (k + dDotD - decimal(2.0) * mDotD + t * (decimal(2.0) * (mDotN - nDotD) + t) > - decimal(0.0)) return false; - - // If the intersection is behind the origin of the ray or beyond the maximum - // raycasting distance, we return no hit - if (t < decimal(0.0) || t > ray.maxFraction) return false; - - // Compute the hit information - Vector3 localHitPoint = ray.point1 + t * n; - raycastInfo.body = proxyShape->getBody(); - raycastInfo.proxyShape = proxyShape; - raycastInfo.hitFraction = t; - raycastInfo.worldPoint = localHitPoint; - Vector3 normalDirection(0, decimal(1.0), 0); - raycastInfo.worldNormal = normalDirection; - - return true; - } - - t = t0; - - // If the intersection is behind the origin of the ray or beyond the maximum - // raycasting distance, we return no hit - if (t < decimal(0.0) || t > ray.maxFraction) return false; - - // Compute the hit information - Vector3 localHitPoint = ray.point1 + t * n; - raycastInfo.body = proxyShape->getBody(); - raycastInfo.proxyShape = proxyShape; - raycastInfo.hitFraction = t; - raycastInfo.worldPoint = localHitPoint; - Vector3 v = localHitPoint - p; - Vector3 w = (v.dot(d) / d.lengthSquare()) * d; - Vector3 normalDirection = (localHitPoint - (p + w)); - raycastInfo.worldNormal = normalDirection; - - return true; -} diff --git a/src/collision/shapes/CylinderShape.h b/src/collision/shapes/CylinderShape.h deleted file mode 100644 index e0744a80..00000000 --- a/src/collision/shapes/CylinderShape.h +++ /dev/null @@ -1,190 +0,0 @@ -/******************************************************************************** -* 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_CYLINDER_SHAPE_H -#define REACTPHYSICS3D_CYLINDER_SHAPE_H - -// Libraries -#include "ConvexShape.h" -#include "body/CollisionBody.h" -#include "mathematics/mathematics.h" - - -/// ReactPhysics3D namespace -namespace reactphysics3d { - -// Class CylinderShape -/** - * This class represents a cylinder collision shape around the Y axis - * and centered at the origin. The cylinder is defined by its height - * and the radius of its base. The "transform" of the corresponding - * rigid body gives an orientation and a position to the cylinder. - * This collision shape uses an extra margin distance around it for collision - * detection purpose. The default margin is 4cm (if your units are meters, - * which is recommended). In case, you want to simulate small objects - * (smaller than the margin distance), you might want to reduce the margin by - * specifying your own margin distance using the "margin" parameter in the - * constructor of the cylinder shape. Otherwise, it is recommended to use the - * default margin distance by not using the "margin" parameter in the constructor. - */ -class CylinderShape : public ConvexShape { - - protected : - - // -------------------- Attributes -------------------- // - - /// Radius of the base - decimal mRadius; - - /// Half height of the cylinder - decimal mHalfHeight; - - // -------------------- Methods -------------------- // - - /// Return a local support point in a given direction without the object margin - virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const override; - - /// Return true if a point is inside the collision shape - 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 ; - - /// Return the number of bytes used by the collision shape - virtual size_t getSizeInBytes() const override; - - public : - - // -------------------- Methods -------------------- // - - /// Constructor - CylinderShape(decimal radius, decimal height, decimal margin = OBJECT_MARGIN); - - /// Destructor - virtual ~CylinderShape() override = default; - - /// Deleted copy-constructor - CylinderShape(const CylinderShape& shape) = delete; - - /// Deleted assignment operator - CylinderShape& operator=(const CylinderShape& shape) = delete; - - /// Return the radius - decimal getRadius() const; - - /// Return the height - decimal getHeight() const; - - /// Return true if the collision shape is a polyhedron - virtual bool isPolyhedron() const override; - - /// Set the scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling) override; - - /// Return the local bounds of the shape in x, y and z directions - virtual void getLocalBounds(Vector3& min, Vector3& max) const override; - - /// Return the local inertia tensor of the collision shape - virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; -}; - -// Return the radius -/** - * @return Radius of the cylinder (in meters) - */ -inline decimal CylinderShape::getRadius() const { - return mRadius; -} - -// Return the height -/** - * @return Height of the cylinder (in meters) - */ -inline decimal CylinderShape::getHeight() const { - return mHalfHeight + mHalfHeight; -} - -// Return true if the collision shape is a polyhedron -inline bool CylinderShape::isPolyhedron() const { - return false; -} - -// Set the scaling vector of the collision shape -inline void CylinderShape::setLocalScaling(const Vector3& scaling) { - - mHalfHeight = (mHalfHeight / mScaling.y) * scaling.y; - mRadius = (mRadius / mScaling.x) * scaling.x; - - CollisionShape::setLocalScaling(scaling); -} - -// Return the number of bytes used by the collision shape -inline size_t CylinderShape::getSizeInBytes() const { - return sizeof(CylinderShape); -} - -// Return the local bounds of the shape in x, y and z directions -/** - * @param min The minimum bounds of the shape in local-space coordinates - * @param max The maximum bounds of the shape in local-space coordinates - */ -inline void CylinderShape::getLocalBounds(Vector3& min, Vector3& max) const { - - // Maximum bounds - max.x = mRadius + mMargin; - max.y = mHalfHeight + mMargin; - max.z = max.x; - - // Minimum bounds - min.x = -max.x; - min.y = -max.y; - min.z = min.x; -} - -// Return the local inertia tensor of the cylinder -/** - * @param[out] tensor The 3x3 inertia tensor matrix of the shape in local-space - * coordinates - * @param mass Mass to use to compute the inertia tensor of the collision shape - */ -inline void CylinderShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const { - decimal height = decimal(2.0) * mHalfHeight; - decimal diag = (decimal(1.0) / decimal(12.0)) * mass * (3 * mRadius * mRadius + height * height); - tensor.setAllValues(diag, 0.0, 0.0, 0.0, - decimal(0.5) * mass * mRadius * mRadius, 0.0, - 0.0, 0.0, diag); -} - -// Return true if a point is inside the collision shape -inline bool CylinderShape::testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const{ - return ((localPoint.x * localPoint.x + localPoint.z * localPoint.z) < mRadius * mRadius && - localPoint.y < mHalfHeight && localPoint.y > -mHalfHeight); -} - -} - -#endif - diff --git a/src/engine/OverlappingPair.cpp b/src/engine/OverlappingPair.cpp index 48658f5c..6df4bf4e 100644 --- a/src/engine/OverlappingPair.cpp +++ b/src/engine/OverlappingPair.cpp @@ -24,15 +24,17 @@ ********************************************************************************/ // Libraries +#include #include "OverlappingPair.h" using namespace reactphysics3d; - // Constructor OverlappingPair::OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, int nbMaxContactManifolds, PoolAllocator& memoryAllocator) : mContactManifoldSet(shape1, shape2, memoryAllocator, nbMaxContactManifolds), mCachedSeparatingAxis(0.0, 1.0, 0.0) { + assert(static_cast(shape1->getCollisionShape()->getType()) <= + static_cast(shape2->getCollisionShape()->getType())); } diff --git a/src/mathematics/Quaternion.h b/src/mathematics/Quaternion.h index 360cf229..28f7b636 100644 --- a/src/mathematics/Quaternion.h +++ b/src/mathematics/Quaternion.h @@ -199,7 +199,7 @@ inline Vector3 Quaternion::getVectorV() const { // Return the length of the quaternion (inline) inline decimal Quaternion::length() const { - return sqrt(x*x + y*y + z*z + w*w); + return std::sqrt(x*x + y*y + z*z + w*w); } // Return the square of the length of the quaternion diff --git a/src/reactphysics3d.h b/src/reactphysics3d.h index 6f1e42f4..a1bef6dc 100644 --- a/src/reactphysics3d.h +++ b/src/reactphysics3d.h @@ -46,8 +46,6 @@ #include "collision/shapes/CollisionShape.h" #include "collision/shapes/BoxShape.h" #include "collision/shapes/SphereShape.h" -#include "collision/shapes/ConeShape.h" -#include "collision/shapes/CylinderShape.h" #include "collision/shapes/CapsuleShape.h" #include "collision/shapes/ConvexMeshShape.h" #include "collision/shapes/ConcaveMeshShape.h" diff --git a/test/tests/collision/TestCollisionWorld.h b/test/tests/collision/TestCollisionWorld.h index 94d44a98..242ebcf9 100644 --- a/test/tests/collision/TestCollisionWorld.h +++ b/test/tests/collision/TestCollisionWorld.h @@ -48,8 +48,6 @@ class WorldCollisionCallback : public CollisionCallback public: bool boxCollideWithSphere1; - bool boxCollideWithCylinder; - bool sphere1CollideWithCylinder; bool sphere1CollideWithSphere2; CollisionBody* boxBody; @@ -65,8 +63,6 @@ class WorldCollisionCallback : public CollisionCallback void reset() { boxCollideWithSphere1 = false; - boxCollideWithCylinder = false; - sphere1CollideWithCylinder = false; sphere1CollideWithSphere2 = false; } @@ -76,12 +72,6 @@ class WorldCollisionCallback : public CollisionCallback if (isContactBetweenBodies(boxBody, sphere1Body, collisionCallbackInfo)) { boxCollideWithSphere1 = true; } - else if (isContactBetweenBodies(boxBody, cylinderBody, collisionCallbackInfo)) { - boxCollideWithCylinder = true; - } - else if (isContactBetweenBodies(sphere1Body, cylinderBody, collisionCallbackInfo)) { - sphere1CollideWithCylinder = true; - } else if (isContactBetweenBodies(sphere1Body, sphere2Body, collisionCallbackInfo)) { sphere1CollideWithSphere2 = true; } @@ -118,7 +108,6 @@ class TestCollisionWorld : public Test { // Collision shapes BoxShape* mBoxShape; SphereShape* mSphereShape; - CylinderShape* mCylinderShape; // Proxy shapes ProxyShape* mBoxProxyShape; @@ -154,11 +143,6 @@ class TestCollisionWorld : public Test { mSphere2Body = mWorld->createCollisionBody(sphere2Transform); mSphere2ProxyShape = mSphere2Body->addCollisionShape(mSphereShape, Transform::identity()); - Transform cylinderTransform(Vector3(10, -5, 0), Quaternion::identity()); - mCylinderBody = mWorld->createCollisionBody(cylinderTransform); - mCylinderShape = new CylinderShape(2, 5); - mCylinderProxyShape = mCylinderBody->addCollisionShape(mCylinderShape, Transform::identity()); - // Assign collision categories to proxy shapes mBoxProxyShape->setCollisionCategoryBits(CATEGORY_1); mSphere1ProxyShape->setCollisionCategoryBits(CATEGORY_1); @@ -175,7 +159,6 @@ class TestCollisionWorld : public Test { ~TestCollisionWorld() { delete mBoxShape; delete mSphereShape; - delete mCylinderShape; } /// Run the tests @@ -189,8 +172,6 @@ class TestCollisionWorld : public Test { mCollisionCallback.reset(); mWorld->testCollision(&mCollisionCallback); test(mCollisionCallback.boxCollideWithSphere1); - test(mCollisionCallback.boxCollideWithCylinder); - test(!mCollisionCallback.sphere1CollideWithCylinder); test(!mCollisionCallback.sphere1CollideWithSphere2); test(mWorld->testAABBOverlap(mBoxBody, mSphere1Body)); @@ -206,22 +187,16 @@ class TestCollisionWorld : public Test { mCollisionCallback.reset(); mWorld->testCollision(mCylinderBody, &mCollisionCallback); test(!mCollisionCallback.boxCollideWithSphere1); - test(mCollisionCallback.boxCollideWithCylinder); - test(!mCollisionCallback.sphere1CollideWithCylinder); test(!mCollisionCallback.sphere1CollideWithSphere2); mCollisionCallback.reset(); mWorld->testCollision(mBoxBody, mSphere1Body, &mCollisionCallback); test(mCollisionCallback.boxCollideWithSphere1); - test(!mCollisionCallback.boxCollideWithCylinder); - test(!mCollisionCallback.sphere1CollideWithCylinder); test(!mCollisionCallback.sphere1CollideWithSphere2); mCollisionCallback.reset(); mWorld->testCollision(mBoxBody, mCylinderBody, &mCollisionCallback); test(!mCollisionCallback.boxCollideWithSphere1); - test(mCollisionCallback.boxCollideWithCylinder); - test(!mCollisionCallback.sphere1CollideWithCylinder); test(!mCollisionCallback.sphere1CollideWithSphere2); // Move sphere 1 to collide with sphere 2 @@ -230,22 +205,16 @@ class TestCollisionWorld : public Test { mCollisionCallback.reset(); mWorld->testCollision(&mCollisionCallback); test(!mCollisionCallback.boxCollideWithSphere1); - test(mCollisionCallback.boxCollideWithCylinder); - test(!mCollisionCallback.sphere1CollideWithCylinder); test(mCollisionCallback.sphere1CollideWithSphere2); mCollisionCallback.reset(); mWorld->testCollision(mBoxBody, mSphere1Body, &mCollisionCallback); test(!mCollisionCallback.boxCollideWithSphere1); - test(!mCollisionCallback.boxCollideWithCylinder); - test(!mCollisionCallback.sphere1CollideWithCylinder); test(!mCollisionCallback.sphere1CollideWithSphere2); mCollisionCallback.reset(); mWorld->testCollision(mBoxBody, mCylinderBody, &mCollisionCallback); test(!mCollisionCallback.boxCollideWithSphere1); - test(mCollisionCallback.boxCollideWithCylinder); - test(!mCollisionCallback.sphere1CollideWithCylinder); test(!mCollisionCallback.sphere1CollideWithSphere2); // Move sphere 1 to collide with box @@ -260,8 +229,6 @@ class TestCollisionWorld : public Test { mSphere2Body->setIsActive(false); mWorld->testCollision(&mCollisionCallback); test(!mCollisionCallback.boxCollideWithSphere1); - test(!mCollisionCallback.boxCollideWithCylinder); - test(!mCollisionCallback.sphere1CollideWithCylinder); test(!mCollisionCallback.sphere1CollideWithSphere2); test(!mWorld->testAABBOverlap(mBoxBody, mSphere1Body)); @@ -289,8 +256,6 @@ class TestCollisionWorld : public Test { mCollisionCallback.reset(); mWorld->testCollision(&mCollisionCallback); test(mCollisionCallback.boxCollideWithSphere1); - test(mCollisionCallback.boxCollideWithCylinder); - test(!mCollisionCallback.sphere1CollideWithCylinder); test(!mCollisionCallback.sphere1CollideWithSphere2); // Move sphere 1 to collide with sphere 2 @@ -299,8 +264,6 @@ class TestCollisionWorld : public Test { mCollisionCallback.reset(); mWorld->testCollision(&mCollisionCallback); test(!mCollisionCallback.boxCollideWithSphere1); - test(mCollisionCallback.boxCollideWithCylinder); - test(!mCollisionCallback.sphere1CollideWithCylinder); test(mCollisionCallback.sphere1CollideWithSphere2); mBoxProxyShape->setCollideWithMaskBits(CATEGORY_2); @@ -311,8 +274,6 @@ class TestCollisionWorld : public Test { mCollisionCallback.reset(); mWorld->testCollision(&mCollisionCallback); test(!mCollisionCallback.boxCollideWithSphere1); - test(!mCollisionCallback.boxCollideWithCylinder); - test(!mCollisionCallback.sphere1CollideWithCylinder); test(!mCollisionCallback.sphere1CollideWithSphere2); // Move sphere 1 to collide with box diff --git a/test/tests/collision/TestPointInside.h b/test/tests/collision/TestPointInside.h index 68345739..dd2a793b 100644 --- a/test/tests/collision/TestPointInside.h +++ b/test/tests/collision/TestPointInside.h @@ -31,9 +31,7 @@ #include "collision/shapes/BoxShape.h" #include "collision/shapes/SphereShape.h" #include "collision/shapes/CapsuleShape.h" -#include "collision/shapes/ConeShape.h" #include "collision/shapes/ConvexMeshShape.h" -#include "collision/shapes/CylinderShape.h" /// Reactphysics3D namespace namespace reactphysics3d { @@ -65,10 +63,8 @@ class TestPointInside : public Test { BoxShape* mBoxShape; SphereShape* mSphereShape; CapsuleShape* mCapsuleShape; - ConeShape* mConeShape; ConvexMeshShape* mConvexMeshShape; ConvexMeshShape* mConvexMeshShapeBodyEdgesInfo; - CylinderShape* mCylinderShape; // Transform Transform mBodyTransform; @@ -128,9 +124,6 @@ class TestPointInside : public Test { mCapsuleShape = new CapsuleShape(2, 10); mCapsuleProxyShape = mCapsuleBody->addCollisionShape(mCapsuleShape, mShapeTransform); - mConeShape = new ConeShape(2, 6, 0); - mConeProxyShape = mConeBody->addCollisionShape(mConeShape, mShapeTransform); - mConvexMeshShape = new ConvexMeshShape(0.0); // Box of dimension (2, 3, 4) mConvexMeshShape->addVertex(Vector3(-2, -3, -4)); mConvexMeshShape->addVertex(Vector3(2, -3, -4)); @@ -168,15 +161,12 @@ class TestPointInside : public Test { mConvexMeshShapeBodyEdgesInfo, mShapeTransform); - mCylinderShape = new CylinderShape(3, 8, 0); - mCylinderProxyShape = mCylinderBody->addCollisionShape(mCylinderShape, mShapeTransform); - - // Compound shape is a cylinder and a sphere + // Compound shape is a capsule and a sphere Vector3 positionShape2(Vector3(4, 2, -3)); Quaternion orientationShape2(-3 *PI / 8, 1.5 * PI/ 3, PI / 13); Transform shapeTransform2(positionShape2, orientationShape2); mLocalShape2ToWorld = mBodyTransform * shapeTransform2; - mCompoundBody->addCollisionShape(mCylinderShape, mShapeTransform); + mCompoundBody->addCollisionShape(mCapsuleShape, mShapeTransform); mCompoundBody->addCollisionShape(mSphereShape, shapeTransform2); } @@ -185,10 +175,8 @@ class TestPointInside : public Test { delete mBoxShape; delete mSphereShape; delete mCapsuleShape; - delete mConeShape; delete mConvexMeshShape; delete mConvexMeshShapeBodyEdgesInfo; - delete mCylinderShape; } /// Run the tests @@ -196,9 +184,7 @@ class TestPointInside : public Test { testBox(); testSphere(); testCapsule(); - testCone(); testConvexMesh(); - testCylinder(); testCompound(); } @@ -407,83 +393,6 @@ class TestPointInside : public Test { test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(1.5, -5, -1.7))); } - /// Test the ProxyConeShape::testPointInside() and - /// CollisionBody::testPointInside() methods - void testCone() { - - // Tests with CollisionBody - test(mConeBody->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 0))); - test(mConeBody->testPointInside(mLocalShapeToWorld * Vector3(0.9, 0, 0))); - test(mConeBody->testPointInside(mLocalShapeToWorld * Vector3(-0.9, 0, 0))); - test(mConeBody->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 0.9))); - test(mConeBody->testPointInside(mLocalShapeToWorld * Vector3(0, 0, -0.9))); - test(mConeBody->testPointInside(mLocalShapeToWorld * Vector3(0.6, 0, -0.7))); - test(mConeBody->testPointInside(mLocalShapeToWorld * Vector3(0.6, 0, 0.7))); - test(mConeBody->testPointInside(mLocalShapeToWorld * Vector3(-0.6, 0, -0.7))); - test(mConeBody->testPointInside(mLocalShapeToWorld * Vector3(-0.6, 0, 0.7))); - test(mConeBody->testPointInside(mLocalShapeToWorld * Vector3(0, 2.9, 0))); - test(mConeBody->testPointInside(mLocalShapeToWorld * Vector3(0, -2.9, 0))); - test(mConeBody->testPointInside(mLocalShapeToWorld * Vector3(1.96, -2.9, 0))); - test(mConeBody->testPointInside(mLocalShapeToWorld * Vector3(-1.96, -2.9, 0))); - test(mConeBody->testPointInside(mLocalShapeToWorld * Vector3(0, -2.9, 1.96))); - test(mConeBody->testPointInside(mLocalShapeToWorld * Vector3(0, -2.9, -1.96))); - test(mConeBody->testPointInside(mLocalShapeToWorld * Vector3(1.3, -2.9, -1.4))); - test(mConeBody->testPointInside(mLocalShapeToWorld * Vector3(-1.3, -2.9, 1.4))); - - test(!mConeBody->testPointInside(mLocalShapeToWorld * Vector3(1.1, 0, 0))); - test(!mConeBody->testPointInside(mLocalShapeToWorld * Vector3(-1.1, 0, 0))); - test(!mConeBody->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 1.1))); - test(!mConeBody->testPointInside(mLocalShapeToWorld * Vector3(0, 0, -1.1))); - test(!mConeBody->testPointInside(mLocalShapeToWorld * Vector3(0.8, 0, -0.8))); - test(!mConeBody->testPointInside(mLocalShapeToWorld * Vector3(0.8, 0, 0.8))); - test(!mConeBody->testPointInside(mLocalShapeToWorld * Vector3(-0.8, 0, -0.8))); - test(!mConeBody->testPointInside(mLocalShapeToWorld * Vector3(-0.8, 0, 0.8))); - test(!mConeBody->testPointInside(mLocalShapeToWorld * Vector3(0, 3.1, 0))); - test(!mConeBody->testPointInside(mLocalShapeToWorld * Vector3(0, -3.1, 0))); - test(!mConeBody->testPointInside(mLocalShapeToWorld * Vector3(1.97, -2.9, 0))); - test(!mConeBody->testPointInside(mLocalShapeToWorld * Vector3(-1.97, -2.9, 0))); - test(!mConeBody->testPointInside(mLocalShapeToWorld * Vector3(0, -2.9, 1.97))); - test(!mConeBody->testPointInside(mLocalShapeToWorld * Vector3(0, -2.9, -1.97))); - test(!mConeBody->testPointInside(mLocalShapeToWorld * Vector3(1.5, -2.9, -1.5))); - test(!mConeBody->testPointInside(mLocalShapeToWorld * Vector3(-1.5, -2.9, 1.5))); - - // Tests with ProxyConeShape - test(mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 0))); - test(mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0.9, 0, 0))); - test(mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-0.9, 0, 0))); - test(mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 0.9))); - test(mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 0, -0.9))); - test(mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0.6, 0, -0.7))); - test(mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0.6, 0, 0.7))); - test(mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-0.6, 0, -0.7))); - test(mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-0.6, 0, 0.7))); - test(mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 2.9, 0))); - test(mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, -2.9, 0))); - test(mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(1.96, -2.9, 0))); - test(mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-1.96, -2.9, 0))); - test(mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, -2.9, 1.96))); - test(mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, -2.9, -1.96))); - test(mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(1.3, -2.9, -1.4))); - test(mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-1.3, -2.9, 1.4))); - - test(!mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(1.1, 0, 0))); - test(!mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-1.1, 0, 0))); - test(!mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 1.1))); - test(!mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 0, -1.1))); - test(!mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0.8, 0, -0.8))); - test(!mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0.8, 0, 0.8))); - test(!mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-0.8, 0, -0.8))); - test(!mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-0.8, 0, 0.8))); - test(!mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 3.1, 0))); - test(!mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, -3.1, 0))); - test(!mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(1.97, -2.9, 0))); - test(!mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-1.97, -2.9, 0))); - test(!mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, -2.9, 1.97))); - test(!mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, -2.9, -1.97))); - test(!mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(1.5, -2.9, -1.5))); - test(!mConeProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-1.5, -2.9, 1.5))); - } - /// Test the ProxyConvexMeshShape::testPointInside() and /// CollisionBody::testPointInside() methods void testConvexMesh() { @@ -597,127 +506,11 @@ class TestPointInside : public Test { test(!mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(1, -2, 4.5))); } - /// Test the ProxyCylinderShape::testPointInside() and - /// CollisionBody::testPointInside() methods - void testCylinder() { - - // Tests with CollisionBody - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 0))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(0, 3.9, 0))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(0, -3.9, 0))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(2.9, 0, 0))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(-2.9, 0, 0))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 2.9))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(0, 0, -2.9))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(1.7, 0, 1.7))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(1.7, 0, -1.7))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(-1.7, 0, -1.7))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(-1.7, 0, 1.7))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(2.9, 3.9, 0))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(-2.9, 3.9, 0))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(0, 3.9, 2.9))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(0, 3.9, -2.9))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(1.7, 3.9, 1.7))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(1.7, 3.9, -1.7))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(-1.7, 3.9, -1.7))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(-1.7, 3.9, 1.7))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(2.9, -3.9, 0))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(-2.9, -3.9, 0))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(0, -3.9, 2.9))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(0, -3.9, -2.9))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(1.7, -3.9, 1.7))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(1.7, -3.9, -1.7))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(-1.7, -3.9, -1.7))); - test(mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(-1.7, -3.9, 1.7))); - - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(0, 4.1, 0))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(0, -4.1, 0))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(3.1, 0, 0))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(-3.1, 0, 0))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 3.1))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(0, 0, -3.1))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(2.2, 0, 2.2))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(2.2, 0, -2.2))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(-2.2, 0, -2.2))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(-1.3, 0, 2.8))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(3.1, 3.9, 0))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(-3.1, 3.9, 0))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(0, 3.9, 3.1))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(0, 3.9, -3.1))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(2.2, 3.9, 2.2))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(2.2, 3.9, -2.2))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(-2.2, 3.9, -2.2))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(-2.2, 3.9, 2.2))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(3.1, -3.9, 0))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(-3.1, -3.9, 0))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(0, -3.9, 3.1))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(0, -3.9, -3.1))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(2.2, -3.9, 2.2))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(2.2, -3.9, -2.2))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(-2.2, -3.9, -2.2))); - test(!mCylinderBody->testPointInside(mLocalShapeToWorld * Vector3(-2.2, -3.9, 2.2))); - - // Tests with ProxyCylinderShape - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 0))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 3.9, 0))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, -3.9, 0))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(2.9, 0, 0))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-2.9, 0, 0))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 2.9))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 0, -2.9))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(1.7, 0, 1.7))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(1.7, 0, -1.7))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-1.7, 0, -1.7))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-1.7, 0, 1.7))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(2.9, 3.9, 0))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-2.9, 3.9, 0))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 3.9, 2.9))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 3.9, -2.9))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(1.7, 3.9, 1.7))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(1.7, 3.9, -1.7))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-1.7, 3.9, -1.7))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-1.7, 3.9, 1.7))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(2.9, -3.9, 0))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-2.9, -3.9, 0))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, -3.9, 2.9))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, -3.9, -2.9))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(1.7, -3.9, 1.7))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(1.7, -3.9, -1.7))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-1.7, -3.9, -1.7))); - test(mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-1.7, -3.9, 1.7))); - - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 4.1, 0))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, -4.1, 0))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(3.1, 0, 0))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-3.1, 0, 0))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 3.1))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 0, -3.1))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(2.2, 0, 2.2))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(2.2, 0, -2.2))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-2.2, 0, -2.2))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-1.3, 0, 2.8))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(3.1, 3.9, 0))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-3.1, 3.9, 0))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 3.9, 3.1))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 3.9, -3.1))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(2.2, 3.9, 2.2))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(2.2, 3.9, -2.2))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-2.2, 3.9, -2.2))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-2.2, 3.9, 2.2))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(3.1, -3.9, 0))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-3.1, -3.9, 0))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, -3.9, 3.1))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, -3.9, -3.1))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(2.2, -3.9, 2.2))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(2.2, -3.9, -2.2))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-2.2, -3.9, -2.2))); - test(!mCylinderProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-2.2, -3.9, 2.2))); - } - /// Test the CollisionBody::testPointInside() method void testCompound() { - // Points on the cylinder + // Points on the capsule + // TODO : Previous it was a cylinder (not a capsule). Maybe those tests are wrong now test(mCompoundBody->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 0))); test(mCompoundBody->testPointInside(mLocalShapeToWorld * Vector3(0, 3.9, 0))); test(mCompoundBody->testPointInside(mLocalShapeToWorld * Vector3(0, -3.9, 0))); diff --git a/test/tests/collision/TestRaycast.h b/test/tests/collision/TestRaycast.h index 7295a8d9..b39b751b 100644 --- a/test/tests/collision/TestRaycast.h +++ b/test/tests/collision/TestRaycast.h @@ -33,9 +33,7 @@ #include "collision/shapes/BoxShape.h" #include "collision/shapes/SphereShape.h" #include "collision/shapes/CapsuleShape.h" -#include "collision/shapes/ConeShape.h" #include "collision/shapes/ConvexMeshShape.h" -#include "collision/shapes/CylinderShape.h" #include "collision/shapes/TriangleShape.h" #include "collision/shapes/ConcaveMeshShape.h" #include "collision/shapes/HeightFieldShape.h" @@ -130,10 +128,8 @@ class TestRaycast : public Test { BoxShape* mBoxShape; SphereShape* mSphereShape; CapsuleShape* mCapsuleShape; - ConeShape* mConeShape; ConvexMeshShape* mConvexMeshShape; ConvexMeshShape* mConvexMeshShapeEdgesInfo; - CylinderShape* mCylinderShape; TriangleShape* mTriangleShape; ConcaveShape* mConcaveMeshShape; HeightFieldShape* mHeightFieldShape; @@ -214,9 +210,6 @@ class TestRaycast : public Test { mCapsuleShape = new CapsuleShape(2, 5); mCapsuleProxyShape = mCapsuleBody->addCollisionShape(mCapsuleShape, mShapeTransform); - mConeShape = new ConeShape(2, 6, 0); - mConeProxyShape = mConeBody->addCollisionShape(mConeShape, mShapeTransform); - // Box of dimension (2, 3, 4) mConvexMeshShape = new ConvexMeshShape(0.0); mConvexMeshShape->addVertex(Vector3(-2, -3, -4)); @@ -255,15 +248,12 @@ class TestRaycast : public Test { mConvexMeshShapeEdgesInfo, mShapeTransform); - mCylinderShape = new CylinderShape(2, 5, 0); - mCylinderProxyShape = mCylinderBody->addCollisionShape(mCylinderShape, mShapeTransform); - // Compound shape is a cylinder and a sphere Vector3 positionShape2(Vector3(4, 2, -3)); Quaternion orientationShape2(-3 *PI / 8, 1.5 * PI/ 3, PI / 13); Transform shapeTransform2(positionShape2, orientationShape2); mLocalShape2ToWorld = mBodyTransform * shapeTransform2; - mCompoundCylinderProxyShape = mCompoundBody->addCollisionShape(mCylinderShape, mShapeTransform); + mCompoundCylinderProxyShape = mCompoundBody->addCollisionShape(mCapsuleShape, mShapeTransform); mCompoundSphereProxyShape = mCompoundBody->addCollisionShape(mSphereShape, shapeTransform2); // Concave Mesh shape @@ -328,10 +318,8 @@ class TestRaycast : public Test { delete mBoxShape; delete mSphereShape; delete mCapsuleShape; - delete mConeShape; delete mConvexMeshShape; delete mConvexMeshShapeEdgesInfo; - delete mCylinderShape; delete mTriangleShape; delete mConcaveMeshShape; delete mHeightFieldShape; @@ -344,9 +332,7 @@ class TestRaycast : public Test { testBox(); testSphere(); testCapsule(); - testCone(); testConvexMesh(); - testCylinder(); testCompound(); testTriangle(); testConcaveMesh(); @@ -1313,253 +1299,6 @@ class TestRaycast : public Test { mWorld->raycast(Ray(ray6Back.point1, ray6Back.point2, decimal(0.8)), &mCallback); } - /// Test the ProxyConeShape::raycast(), CollisionBody::raycast() and - /// CollisionWorld::raycast() methods. - void testCone() { - - // ----- Test feedback data ----- // - Vector3 point1A = mLocalShapeToWorld * Vector3(0 , 0, 3); - Vector3 point1B = mLocalShapeToWorld * Vector3(0, 0, -7); - Ray ray(point1A, point1B); - Vector3 hitPoint = mLocalShapeToWorld * Vector3(0, 0, 1); - - Vector3 point2A = mLocalShapeToWorld * Vector3(1 , -5, 0); - Vector3 point2B = mLocalShapeToWorld * Vector3(1, 5, 0); - Ray rayBottom(point2A, point2B); - Vector3 hitPoint2 = mLocalShapeToWorld * Vector3(1, -3, 0); - - mCallback.shapeToTest = mConeProxyShape; - - // CollisionWorld::raycast() - mCallback.reset(); - mWorld->raycast(ray, &mCallback); - test(mCallback.isHit); - test(mCallback.raycastInfo.body == mConeBody); - test(mCallback.raycastInfo.proxyShape == mConeProxyShape); - test(approxEqual(mCallback.raycastInfo.hitFraction, decimal(0.2), epsilon)); - test(approxEqual(mCallback.raycastInfo.worldPoint.x, hitPoint.x, epsilon)); - test(approxEqual(mCallback.raycastInfo.worldPoint.y, hitPoint.y, epsilon)); - test(approxEqual(mCallback.raycastInfo.worldPoint.z, hitPoint.z, epsilon)); - - // Correct category filter mask - mCallback.reset(); - mWorld->raycast(ray, &mCallback, CATEGORY2); - test(mCallback.isHit); - - // Wrong category filter mask - mCallback.reset(); - mWorld->raycast(ray, &mCallback, CATEGORY1); - test(!mCallback.isHit); - - // CollisionBody::raycast() - RaycastInfo raycastInfo2; - test(mConeBody->raycast(ray, raycastInfo2)); - test(raycastInfo2.body == mConeBody); - test(raycastInfo2.proxyShape == mConeProxyShape); - test(approxEqual(raycastInfo2.hitFraction, decimal(0.2), epsilon)); - test(approxEqual(raycastInfo2.worldPoint.x, hitPoint.x, epsilon)); - test(approxEqual(raycastInfo2.worldPoint.y, hitPoint.y, epsilon)); - test(approxEqual(raycastInfo2.worldPoint.z, hitPoint.z, epsilon)); - - // ProxyCollisionShape::raycast() - RaycastInfo raycastInfo3; - test(mConeProxyShape->raycast(ray, raycastInfo3)); - test(raycastInfo3.body == mConeBody); - test(raycastInfo3.proxyShape == mConeProxyShape); - test(approxEqual(raycastInfo3.hitFraction, decimal(0.2), epsilon)); - test(approxEqual(raycastInfo3.worldPoint.x, hitPoint.x, epsilon)); - test(approxEqual(raycastInfo3.worldPoint.y, hitPoint.y, epsilon)); - test(approxEqual(raycastInfo3.worldPoint.z, hitPoint.z, epsilon)); - - mCallback.reset(); - mWorld->raycast(rayBottom, &mCallback); - test(mCallback.isHit); - test(mCallback.raycastInfo.body == mConeBody); - test(mCallback.raycastInfo.proxyShape == mConeProxyShape); - test(approxEqual(mCallback.raycastInfo.hitFraction, decimal(0.2), epsilon)); - test(approxEqual(mCallback.raycastInfo.worldPoint.x, hitPoint2.x, epsilon)); - test(approxEqual(mCallback.raycastInfo.worldPoint.y, hitPoint2.y, epsilon)); - test(approxEqual(mCallback.raycastInfo.worldPoint.z, hitPoint2.z, epsilon)); - - // CollisionBody::raycast() - RaycastInfo raycastInfo5; - test(mConeBody->raycast(rayBottom, raycastInfo5)); - test(raycastInfo5.body == mConeBody); - test(raycastInfo5.proxyShape == mConeProxyShape); - test(approxEqual(raycastInfo5.hitFraction, decimal(0.2), epsilon)); - test(approxEqual(raycastInfo5.worldPoint.x, hitPoint2.x, epsilon)); - test(approxEqual(raycastInfo5.worldPoint.y, hitPoint2.y, epsilon)); - test(approxEqual(raycastInfo5.worldPoint.z, hitPoint2.z, epsilon)); - - // ProxyCollisionShape::raycast() - RaycastInfo raycastInfo6; - test(mConeProxyShape->raycast(rayBottom, raycastInfo6)); - test(raycastInfo6.body == mConeBody); - test(raycastInfo6.proxyShape == mConeProxyShape); - test(approxEqual(raycastInfo6.hitFraction, decimal(0.2), epsilon)); - test(approxEqual(raycastInfo6.worldPoint.x, hitPoint2.x, epsilon)); - test(approxEqual(raycastInfo6.worldPoint.y, hitPoint2.y, epsilon)); - test(approxEqual(raycastInfo6.worldPoint.z, hitPoint2.z, epsilon)); - - Ray ray1(mLocalShapeToWorld * Vector3(0, 0, 0), mLocalShapeToWorld * Vector3(5, 7, -1)); - Ray ray2(mLocalShapeToWorld * Vector3(5, 11, 7), mLocalShapeToWorld * Vector3(17, 29, 28)); - Ray ray3(mLocalShapeToWorld * Vector3(-1, -2, 1), mLocalShapeToWorld * Vector3(-13, -2, 22)); - Ray ray4(mLocalShapeToWorld * Vector3(10, 10, 10), mLocalShapeToWorld * Vector3(22, 28, 31)); - Ray ray5(mLocalShapeToWorld * Vector3(4, 1, -1), mLocalShapeToWorld * Vector3(-26, 1, -1)); - Ray ray6(mLocalShapeToWorld * Vector3(3, 4, 1), mLocalShapeToWorld * Vector3(3, -16, 1)); - Ray ray7(mLocalShapeToWorld * Vector3(1, -4, 3), mLocalShapeToWorld * Vector3(1, -4, -17)); - Ray ray8(mLocalShapeToWorld * Vector3(-4, 4, 0), mLocalShapeToWorld * Vector3(26, 4, 0)); - Ray ray9(mLocalShapeToWorld * Vector3(0, -4, -7), mLocalShapeToWorld * Vector3(0, 46, -7)); - Ray ray10(mLocalShapeToWorld * Vector3(-3, -2, -6), mLocalShapeToWorld * Vector3(-3, -2, 74)); - Ray ray11(mLocalShapeToWorld * Vector3(3, -1, 0.5), mLocalShapeToWorld * Vector3(-27, -1, 0.5)); - Ray ray12(mLocalShapeToWorld * Vector3(1, 4, -1), mLocalShapeToWorld * Vector3(1, -26, -1)); - Ray ray13(mLocalShapeToWorld * Vector3(-1, -2, 3), mLocalShapeToWorld * Vector3(-1, -2, -27)); - Ray ray14(mLocalShapeToWorld * Vector3(-2, 0, 0.8), mLocalShapeToWorld * Vector3(30, 0, 0.8)); - Ray ray15(mLocalShapeToWorld * Vector3(0, -4, 1), mLocalShapeToWorld * Vector3(0, 30, 1)); - Ray ray16(mLocalShapeToWorld * Vector3(-0.9, 0, -4), mLocalShapeToWorld * Vector3(-0.9, 0, 30)); - - // ----- Test raycast miss ----- // - test(!mConeBody->raycast(ray1, raycastInfo3)); - test(!mConeProxyShape->raycast(ray1, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray1, &mCallback); - test(!mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray1.point1, ray1.point2, decimal(0.01)), &mCallback); - test(!mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray1.point1, ray1.point2, decimal(100.0)), &mCallback); - test(!mCallback.isHit); - - test(!mConeBody->raycast(ray2, raycastInfo3)); - test(!mConeProxyShape->raycast(ray2, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray2, &mCallback); - test(!mCallback.isHit); - - test(!mConeBody->raycast(ray3, raycastInfo3)); - test(!mConeProxyShape->raycast(ray3, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray3, &mCallback); - test(!mCallback.isHit); - - test(!mConeBody->raycast(ray4, raycastInfo3)); - test(!mConeProxyShape->raycast(ray4, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray4, &mCallback); - test(!mCallback.isHit); - - test(!mConeBody->raycast(ray5, raycastInfo3)); - test(!mConeProxyShape->raycast(ray5, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray5, &mCallback); - test(!mCallback.isHit); - - test(!mConeBody->raycast(ray6, raycastInfo3)); - test(!mConeProxyShape->raycast(ray6, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray6, &mCallback); - test(!mCallback.isHit); - - test(!mConeBody->raycast(ray7, raycastInfo3)); - test(!mConeProxyShape->raycast(ray7, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray7, &mCallback); - test(!mCallback.isHit); - - test(!mConeBody->raycast(ray8, raycastInfo3)); - test(!mConeProxyShape->raycast(ray8, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray8, &mCallback); - test(!mCallback.isHit); - - test(!mConeBody->raycast(ray9, raycastInfo3)); - test(!mConeProxyShape->raycast(ray9, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray9, &mCallback); - test(!mCallback.isHit); - - test(!mConeBody->raycast(ray10, raycastInfo3)); - test(!mConeProxyShape->raycast(ray10, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray10, &mCallback); - test(!mCallback.isHit); - - mCallback.reset(); - mWorld->raycast(Ray(ray11.point1, ray11.point2, decimal(0.01)), &mCallback); - test(!mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray12.point1, ray12.point2, decimal(0.01)), &mCallback); - test(!mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray13.point1, ray13.point2, decimal(0.01)), &mCallback); - test(!mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray14.point1, ray14.point2, decimal(0.01)), &mCallback); - test(!mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray15.point1, ray15.point2, decimal(0.01)), &mCallback); - test(!mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray16.point1, ray16.point2, decimal(0.01)), &mCallback); - test(!mCallback.isHit); - - // ----- Test raycast hits ----- // - test(mConeBody->raycast(ray11, raycastInfo3)); - test(mConeProxyShape->raycast(ray11, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray11, &mCallback); - test(mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray11.point1, ray11.point2, decimal(0.8)), &mCallback); - test(mCallback.isHit); - - test(mConeBody->raycast(ray12, raycastInfo3)); - test(mConeProxyShape->raycast(ray12, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray12, &mCallback); - test(mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray12.point1, ray12.point2, decimal(0.8)), &mCallback); - test(mCallback.isHit); - - test(mConeBody->raycast(ray13, raycastInfo3)); - test(mConeProxyShape->raycast(ray13, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray13, &mCallback); - test(mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray13.point1, ray13.point2, decimal(0.8)), &mCallback); - test(mCallback.isHit); - - test(mConeBody->raycast(ray14, raycastInfo3)); - test(mConeProxyShape->raycast(ray14, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray14, &mCallback); - test(mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray14.point1, ray14.point2, decimal(0.8)), &mCallback); - test(mCallback.isHit); - - test(mConeBody->raycast(ray15, raycastInfo3)); - test(mConeProxyShape->raycast(ray15, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray15, &mCallback); - test(mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray15.point1, ray15.point2, decimal(0.8)), &mCallback); - test(mCallback.isHit); - - test(mConeBody->raycast(ray16, raycastInfo3)); - test(mConeProxyShape->raycast(ray16, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray16, &mCallback); - test(mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray16.point1, ray16.point2, decimal(0.8)), &mCallback); - test(mCallback.isHit); - } - /// Test the ProxyConvexMeshShape::raycast(), CollisionBody::raycast() and /// CollisionWorld::raycast() methods. void testConvexMesh() { @@ -1824,248 +1563,6 @@ class TestRaycast : public Test { test(mCallback.isHit); } - /// Test the ProxyCylinderShape::raycast(), CollisionBody::raycast() and - /// CollisionWorld::raycast() methods. - void testCylinder() { - - // ----- Test feedback data ----- // - Vector3 point1A = mLocalShapeToWorld * Vector3(4 , 1, 0); - Vector3 point1B = mLocalShapeToWorld * Vector3(-6, 1, 0); - Ray ray(point1A, point1B); - Vector3 hitPoint = mLocalShapeToWorld * Vector3(2, 1, 0); - - Vector3 point2A = mLocalShapeToWorld * Vector3(0 , 4.5, 0); - Vector3 point2B = mLocalShapeToWorld * Vector3(0, -5.5, 0); - Ray rayTop(point2A, point2B); - Vector3 hitPointTop = mLocalShapeToWorld * Vector3(0, decimal(2.5), 0); - - Vector3 point3A = mLocalShapeToWorld * Vector3(0 , -4.5, 0); - Vector3 point3B = mLocalShapeToWorld * Vector3(0, 5.5, 0); - Ray rayBottom(point3A, point3B); - Vector3 hitPointBottom = mLocalShapeToWorld * Vector3(0, decimal(-2.5), 0); - - mCallback.shapeToTest = mCylinderProxyShape; - - // CollisionWorld::raycast() - mCallback.reset(); - mWorld->raycast(ray, &mCallback); - test(mCallback.isHit); - test(mCallback.raycastInfo.body == mCylinderBody); - test(mCallback.raycastInfo.proxyShape == mCylinderProxyShape); - test(approxEqual(mCallback.raycastInfo.hitFraction, decimal(0.2), epsilon)); - test(approxEqual(mCallback.raycastInfo.worldPoint.x, hitPoint.x, epsilon)); - test(approxEqual(mCallback.raycastInfo.worldPoint.y, hitPoint.y, epsilon)); - test(approxEqual(mCallback.raycastInfo.worldPoint.z, hitPoint.z, epsilon)); - - // Correct category filter mask - mCallback.reset(); - mWorld->raycast(ray, &mCallback, CATEGORY2); - test(mCallback.isHit); - - // Wrong category filter mask - mCallback.reset(); - mWorld->raycast(ray, &mCallback, CATEGORY1); - test(!mCallback.isHit); - - // CollisionBody::raycast() - RaycastInfo raycastInfo2; - test(mCylinderBody->raycast(ray, raycastInfo2)); - test(raycastInfo2.body == mCylinderBody); - test(raycastInfo2.proxyShape == mCylinderProxyShape); - test(approxEqual(raycastInfo2.hitFraction, decimal(0.2), epsilon)); - test(approxEqual(raycastInfo2.worldPoint.x, hitPoint.x, epsilon)); - test(approxEqual(raycastInfo2.worldPoint.y, hitPoint.y, epsilon)); - test(approxEqual(raycastInfo2.worldPoint.z, hitPoint.z, epsilon)); - - // ProxyCollisionShape::raycast() - RaycastInfo raycastInfo3; - test(mCylinderProxyShape->raycast(ray, raycastInfo3)); - test(raycastInfo3.body == mCylinderBody); - test(raycastInfo3.proxyShape == mCylinderProxyShape); - test(approxEqual(raycastInfo3.hitFraction, decimal(0.2), epsilon)); - test(approxEqual(raycastInfo3.worldPoint.x, hitPoint.x, epsilon)); - test(approxEqual(raycastInfo3.worldPoint.y, hitPoint.y, epsilon)); - test(approxEqual(raycastInfo3.worldPoint.z, hitPoint.z, epsilon)); - - // ProxyCollisionShape::raycast() - RaycastInfo raycastInfo5; - test(mCylinderProxyShape->raycast(rayTop, raycastInfo5)); - test(raycastInfo5.body == mCylinderBody); - test(raycastInfo5.proxyShape == mCylinderProxyShape); - test(approxEqual(raycastInfo5.hitFraction, decimal(0.2), epsilon)); - test(approxEqual(raycastInfo5.worldPoint.x, hitPointTop.x, epsilon)); - test(approxEqual(raycastInfo5.worldPoint.y, hitPointTop.y, epsilon)); - test(approxEqual(raycastInfo5.worldPoint.z, hitPointTop.z, epsilon)); - - // ProxyCollisionShape::raycast() - RaycastInfo raycastInfo6; - test(mCylinderProxyShape->raycast(rayBottom, raycastInfo6)); - test(raycastInfo6.body == mCylinderBody); - test(raycastInfo6.proxyShape == mCylinderProxyShape); - test(approxEqual(raycastInfo6.hitFraction, decimal(0.2), epsilon)); - test(approxEqual(raycastInfo6.worldPoint.x, hitPointBottom.x, epsilon)); - test(approxEqual(raycastInfo6.worldPoint.y, hitPointBottom.y, epsilon)); - test(approxEqual(raycastInfo6.worldPoint.z, hitPointBottom.z, epsilon)); - - Ray ray1(mLocalShapeToWorld * Vector3(0, 0, 0), mLocalShapeToWorld * Vector3(5, 7, -1)); - Ray ray2(mLocalShapeToWorld * Vector3(5, 11, 7), mLocalShapeToWorld * Vector3(17, 20, 28)); - Ray ray3(mLocalShapeToWorld * Vector3(1, 3, -1), mLocalShapeToWorld * Vector3(-11,3, 20)); - Ray ray4(mLocalShapeToWorld * Vector3(10, 10, 10), mLocalShapeToWorld * Vector3(22, 28, 31)); - Ray ray5(mLocalShapeToWorld * Vector3(4, 1, -5), mLocalShapeToWorld * Vector3(-30, 1, -5)); - Ray ray6(mLocalShapeToWorld * Vector3(4, 9, 1), mLocalShapeToWorld * Vector3(4, -30, 1)); - Ray ray7(mLocalShapeToWorld * Vector3(1, -9, 5), mLocalShapeToWorld * Vector3(1, -9, -30)); - Ray ray8(mLocalShapeToWorld * Vector3(-4, 9, 0), mLocalShapeToWorld * Vector3(30, 9, 0)); - Ray ray9(mLocalShapeToWorld * Vector3(0, -9, -4), mLocalShapeToWorld * Vector3(0, 30, -4)); - Ray ray10(mLocalShapeToWorld * Vector3(-4, 0, -6), mLocalShapeToWorld * Vector3(-4, 0, 30)); - Ray ray11(mLocalShapeToWorld * Vector3(4, 1, 1.5), mLocalShapeToWorld * Vector3(-30, 1, 1.5)); - Ray ray12(mLocalShapeToWorld * Vector3(1, 9, -1), mLocalShapeToWorld * Vector3(1, -30, -1)); - Ray ray13(mLocalShapeToWorld * Vector3(-1, 2, 3), mLocalShapeToWorld * Vector3(-1, 2, -30)); - Ray ray14(mLocalShapeToWorld * Vector3(-3, 2, -1.7), mLocalShapeToWorld * Vector3(30, 2, -1.7)); - Ray ray15(mLocalShapeToWorld * Vector3(0, -9, 1), mLocalShapeToWorld * Vector3(0, 30, 1)); - Ray ray16(mLocalShapeToWorld * Vector3(-1, 2, -7), mLocalShapeToWorld * Vector3(-1, 2, 30)); - - // ----- Test raycast miss ----- // - test(!mCylinderBody->raycast(ray1, raycastInfo3)); - test(!mCylinderProxyShape->raycast(ray1, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray1, &mCallback); - test(!mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray1.point1, ray1.point2, decimal(0.01)), &mCallback); - test(!mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray1.point1, ray1.point2, decimal(100.0)), &mCallback); - test(!mCallback.isHit); - - test(!mCylinderBody->raycast(ray2, raycastInfo3)); - test(!mCylinderProxyShape->raycast(ray2, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray2, &mCallback); - test(!mCallback.isHit); - - test(!mCylinderBody->raycast(ray3, raycastInfo3)); - test(!mCylinderProxyShape->raycast(ray3, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray3, &mCallback); - test(!mCallback.isHit); - - test(!mCylinderBody->raycast(ray4, raycastInfo3)); - test(!mCylinderProxyShape->raycast(ray4, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray4, &mCallback); - test(!mCallback.isHit); - - test(!mCylinderBody->raycast(ray5, raycastInfo3)); - test(!mCylinderProxyShape->raycast(ray5, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray5, &mCallback); - test(!mCallback.isHit); - - test(!mCylinderBody->raycast(ray6, raycastInfo3)); - test(!mCylinderProxyShape->raycast(ray6, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray6, &mCallback); - test(!mCallback.isHit); - - test(!mCylinderBody->raycast(ray7, raycastInfo3)); - test(!mCylinderProxyShape->raycast(ray7, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray7, &mCallback); - test(!mCallback.isHit); - - test(!mCylinderBody->raycast(ray8, raycastInfo3)); - test(!mCylinderProxyShape->raycast(ray8, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray8, &mCallback); - test(!mCallback.isHit); - - test(!mCylinderBody->raycast(ray9, raycastInfo3)); - test(!mCylinderProxyShape->raycast(ray9, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray9, &mCallback); - test(!mCallback.isHit); - - test(!mCylinderBody->raycast(ray10, raycastInfo3)); - test(!mCylinderProxyShape->raycast(ray10, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray10, &mCallback); - test(!mCallback.isHit); - - mCallback.reset(); - mWorld->raycast(Ray(ray11.point1, ray11.point2, decimal(0.01)), &mCallback); - test(!mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray12.point1, ray12.point2, decimal(0.01)), &mCallback); - test(!mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray13.point1, ray13.point2, decimal(0.01)), &mCallback); - test(!mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray14.point1, ray14.point2, decimal(0.01)), &mCallback); - test(!mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray15.point1, ray15.point2, decimal(0.01)), &mCallback); - test(!mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray16.point1, ray16.point2, decimal(0.01)), &mCallback); - test(!mCallback.isHit); - - // ----- Test raycast hits ----- // - test(mCylinderBody->raycast(ray11, raycastInfo3)); - test(mCylinderProxyShape->raycast(ray11, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray11, &mCallback); - test(mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray11.point1, ray11.point2, decimal(0.8)), &mCallback); - test(mCallback.isHit); - - test(mCylinderBody->raycast(ray12, raycastInfo3)); - test(mCylinderProxyShape->raycast(ray12, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray12, &mCallback); - test(mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray12.point1, ray12.point2, decimal(0.8)), &mCallback); - test(mCallback.isHit); - - test(mCylinderBody->raycast(ray13, raycastInfo3)); - test(mCylinderProxyShape->raycast(ray13, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray13, &mCallback); - test(mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray13.point1, ray13.point2, decimal(0.8)), &mCallback); - test(mCallback.isHit); - - test(mCylinderBody->raycast(ray14, raycastInfo3)); - test(mCylinderProxyShape->raycast(ray14, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray14, &mCallback); - test(mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray14.point1, ray14.point2, decimal(0.8)), &mCallback); - test(mCallback.isHit); - - test(mCylinderBody->raycast(ray15, raycastInfo3)); - test(mCylinderProxyShape->raycast(ray15, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray15, &mCallback); - test(mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray15.point1, ray15.point2, decimal(0.8)), &mCallback); - test(mCallback.isHit); - - test(mCylinderBody->raycast(ray16, raycastInfo3)); - test(mCylinderProxyShape->raycast(ray16, raycastInfo3)); - mCallback.reset(); - mWorld->raycast(ray16, &mCallback); - test(mCallback.isHit); - mCallback.reset(); - mWorld->raycast(Ray(ray16.point1, ray16.point2, decimal(0.8)), &mCallback); - test(mCallback.isHit); - } - /// Test the CollisionBody::raycast() and /// CollisionWorld::raycast() methods. void testCompound() { @@ -2141,7 +1638,8 @@ class TestRaycast : public Test { mWorld->raycast(Ray(ray6.point1, ray6.point2, decimal(0.8)), &mCallback); test(mCallback.isHit); - // Raycast hit agains the cylinder shape + // Raycast hit agains the capsule shape + // TODO : Previous it was a cylinder, now it is a capsule shape, maybe those tests are wrong now Ray ray11(mLocalShapeToWorld * Vector3(4, 1, 1.5), mLocalShapeToWorld * Vector3(-30, 1.5, 2)); Ray ray12(mLocalShapeToWorld * Vector3(1.5, 9, -1), mLocalShapeToWorld * Vector3(1.5, -30, -1)); Ray ray13(mLocalShapeToWorld * Vector3(-1, 2, 3), mLocalShapeToWorld * Vector3(-1, 2, -30)); diff --git a/testbed/CMakeLists.txt b/testbed/CMakeLists.txt index 8d402ad3..a5620028 100644 --- a/testbed/CMakeLists.txt +++ b/testbed/CMakeLists.txt @@ -74,8 +74,6 @@ SET(TESTBED_SOURCES SET(COMMON_SOURCES common/Box.h common/Box.cpp - common/Cone.h - common/Cone.cpp common/Sphere.h common/Sphere.cpp common/Line.h @@ -86,8 +84,6 @@ SET(COMMON_SOURCES common/ConvexMesh.cpp common/ConcaveMesh.h common/ConcaveMesh.cpp - common/Cylinder.h - common/Cylinder.cpp common/Dumbbell.h common/Dumbbell.cpp common/HeightField.h diff --git a/testbed/common/Cone.cpp b/testbed/common/Cone.cpp deleted file mode 100644 index bbd32ed9..00000000 --- a/testbed/common/Cone.cpp +++ /dev/null @@ -1,272 +0,0 @@ -/******************************************************************************** -* 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. * -* * -********************************************************************************/ - -// Libraries -#include "Cone.h" - -openglframework::VertexBufferObject Cone::mVBOVertices(GL_ARRAY_BUFFER); -openglframework::VertexBufferObject Cone::mVBONormals(GL_ARRAY_BUFFER); -openglframework::VertexBufferObject Cone::mVBOTextureCoords(GL_ARRAY_BUFFER); -openglframework::VertexBufferObject Cone::mVBOIndices(GL_ELEMENT_ARRAY_BUFFER); -openglframework::VertexArrayObject Cone::mVAO; -int Cone::totalNbCones = 0; - -// Constructor -Cone::Cone(float radius, float height, const openglframework::Vector3 &position, - reactphysics3d::CollisionWorld* world, - const std::string& meshFolderPath) - : PhysicsObject(meshFolderPath + "cone.obj"), mRadius(radius), mHeight(height) { - - // Compute the scaling matrix - mScalingMatrix = openglframework::Matrix4(mRadius, 0, 0, 0, - 0, mHeight, 0, 0, - 0, 0, mRadius, 0, - 0, 0, 0, 1); - - // Initialize the position where the cone will be rendered - translateWorld(position); - - // Create the collision shape for the rigid body (cone shape) and do - // not forget to delete it at the end - mConeShape = new rp3d::ConeShape(mRadius, mHeight); - - // Initial position and orientation of the rigid body - rp3d::Vector3 initPosition(position.x, position.y, position.z); - rp3d::Quaternion initOrientation = rp3d::Quaternion::identity(); - rp3d::Transform transform(initPosition, initOrientation); - - mPreviousTransform = transform; - - // Create a rigid body corresponding to the cone in the dynamics world - mBody = world->createCollisionBody(transform); - - // Add a collision shape to the body and specify the mass of the shape - mProxyShape = mBody->addCollisionShape(mConeShape, rp3d::Transform::identity()); - - mTransformMatrix = mTransformMatrix * mScalingMatrix; - - // Create the VBOs and VAO - if (totalNbCones == 0) { - createVBOAndVAO(); - } - - totalNbCones++; -} - -// Constructor -Cone::Cone(float radius, float height, const openglframework::Vector3 &position, - float mass, reactphysics3d::DynamicsWorld* dynamicsWorld, - const std::string& meshFolderPath) - : PhysicsObject(meshFolderPath + "cone.obj"), mRadius(radius), mHeight(height) { - - // Compute the scaling matrix - mScalingMatrix = openglframework::Matrix4(mRadius, 0, 0, 0, - 0, mHeight, 0, 0, - 0, 0, mRadius, 0, - 0, 0, 0, 1); - - // Initialize the position where the cone will be rendered - translateWorld(position); - - // Create the collision shape for the rigid body (cone shape) and do not - // forget to delete it at the end - mConeShape = new rp3d::ConeShape(mRadius, mHeight); - - // Initial position and orientation of the rigid body - rp3d::Vector3 initPosition(position.x, position.y, position.z); - rp3d::Quaternion initOrientation = rp3d::Quaternion::identity(); - rp3d::Transform transform(initPosition, initOrientation); - - // Create a rigid body corresponding to the cone in the dynamics world - rp3d::RigidBody* body = dynamicsWorld->createRigidBody(transform); - - // Add a collision shape to the body and specify the mass of the shape - mProxyShape = body->addCollisionShape(mConeShape, rp3d::Transform::identity(), mass); - - mBody = body; - - mTransformMatrix = mTransformMatrix * mScalingMatrix; - - // Create the VBOs and VAO - if (totalNbCones == 0) { - createVBOAndVAO(); - } - - totalNbCones++; -} - -// Destructor -Cone::~Cone() { - - if (totalNbCones == 1) { - // Destroy the mesh - destroy(); - - // Destroy the VBOs and VAO - mVBOIndices.destroy(); - mVBOVertices.destroy(); - mVBONormals.destroy(); - mVBOTextureCoords.destroy(); - mVAO.destroy(); - } - delete mConeShape; - totalNbCones--; -} - -// Render the cone at the correct position and with the correct orientation -void Cone::render(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix, bool wireframe) { - - if (wireframe) { - glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); - } - - // Bind the shader - shader.bind(); - - // Set the model to camera matrix - shader.setMatrix4x4Uniform("localToWorldMatrix", mTransformMatrix); - shader.setMatrix4x4Uniform("worldToCameraMatrix", worldToCameraMatrix); - - // Set the normal matrix (inverse transpose of the 3x3 upper-left sub matrix of the - // model-view matrix) - const openglframework::Matrix4 localToCameraMatrix = worldToCameraMatrix * mTransformMatrix; - const openglframework::Matrix3 normalMatrix = - localToCameraMatrix.getUpperLeft3x3Matrix().getInverse().getTranspose(); - shader.setMatrix3x3Uniform("normalMatrix", normalMatrix, false); - - // Set the vertex color - openglframework::Color currentColor = mBody->isSleeping() ? mSleepingColor : mColor; - openglframework::Vector4 color(currentColor.r, currentColor.g, currentColor.b, currentColor.a); - shader.setVector4Uniform("vertexColor", color, false); - - // Bind the VAO - mVAO.bind(); - - mVBOVertices.bind(); - - // Get the location of shader attribute variables - GLint vertexPositionLoc = shader.getAttribLocation("vertexPosition"); - GLint vertexNormalLoc = shader.getAttribLocation("vertexNormal", false); - - glEnableVertexAttribArray(vertexPositionLoc); - glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)nullptr); - - mVBONormals.bind(); - - if (vertexNormalLoc != -1) glVertexAttribPointer(vertexNormalLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)nullptr); - if (vertexNormalLoc != -1) glEnableVertexAttribArray(vertexNormalLoc); - - // For each part of the mesh - for (unsigned int i=0; isetLocalScaling(rp3d::Vector3(scaling.x, scaling.y, scaling.z)); - - // Scale the graphics object - mScalingMatrix = openglframework::Matrix4(mRadius * scaling.x, 0, 0, 0, - 0, mHeight * scaling.y, 0, 0, - 0, 0, mRadius * scaling.z, 0, - 0, 0, 0, 1); -} - diff --git a/testbed/common/Cone.h b/testbed/common/Cone.h deleted file mode 100644 index 8f71493c..00000000 --- a/testbed/common/Cone.h +++ /dev/null @@ -1,110 +0,0 @@ -/******************************************************************************** -* 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 CONE_H -#define CONE_H - -// Libraries -#include "openglframework.h" -#include "reactphysics3d.h" -#include "PhysicsObject.h" - -// Class Cone -class Cone : public PhysicsObject { - - private : - - // -------------------- Attributes -------------------- // - - /// Radius of the cone - float mRadius; - - /// Height of the cone - float mHeight; - - /// Collision shape - rp3d::ConeShape* mConeShape; - rp3d::ProxyShape* mProxyShape; - - /// Scaling matrix (applied to a sphere to obtain the correct cone dimensions) - openglframework::Matrix4 mScalingMatrix; - - /// Previous transform (for interpolation) - rp3d::Transform mPreviousTransform; - - /// Vertex Buffer Object for the vertices data - static openglframework::VertexBufferObject mVBOVertices; - - /// Vertex Buffer Object for the normals data - static openglframework::VertexBufferObject mVBONormals; - - /// Vertex Buffer Object for the texture coords - static openglframework::VertexBufferObject mVBOTextureCoords; - - /// Vertex Buffer Object for the indices - static openglframework::VertexBufferObject mVBOIndices; - - /// Vertex Array Object for the vertex data - static openglframework::VertexArrayObject mVAO; - - // Total number of cones created - static int totalNbCones; - - // -------------------- Methods -------------------- // - - // Create the Vertex Buffer Objects used to render with OpenGL. - void createVBOAndVAO(); - - public : - - // -------------------- Methods -------------------- // - - /// Constructor - Cone(float radius, float height, const openglframework::Vector3& position, - rp3d::CollisionWorld* world, const std::string& meshFolderPath); - - /// Constructor - Cone(float radius, float height, const openglframework::Vector3& position, - float mass, rp3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath); - - /// Destructor - ~Cone(); - - /// Render the cone at the correct position and with the correct orientation - void render(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix, bool wireframe); - - /// Update the transform matrix of the object - virtual void updateTransform(float interpolationFactor) override; - - /// Set the scaling of the object - void setScaling(const openglframework::Vector3& scaling); -}; - -inline void Cone::updateTransform(float interpolationFactor) { - mTransformMatrix = computeTransform(interpolationFactor, mScalingMatrix); -} - -#endif diff --git a/testbed/common/Cylinder.cpp b/testbed/common/Cylinder.cpp deleted file mode 100644 index 2943c3e8..00000000 --- a/testbed/common/Cylinder.cpp +++ /dev/null @@ -1,272 +0,0 @@ -/******************************************************************************** -* 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. * -* * -********************************************************************************/ - -// Libraries -#include "Cylinder.h" - -openglframework::VertexBufferObject Cylinder::mVBOVertices(GL_ARRAY_BUFFER); -openglframework::VertexBufferObject Cylinder::mVBONormals(GL_ARRAY_BUFFER); -openglframework::VertexBufferObject Cylinder::mVBOTextureCoords(GL_ARRAY_BUFFER); -openglframework::VertexBufferObject Cylinder::mVBOIndices(GL_ELEMENT_ARRAY_BUFFER); -openglframework::VertexArrayObject Cylinder::mVAO; -int Cylinder::totalNbCylinders = 0; - -// Constructor -Cylinder::Cylinder(float radius, float height, const openglframework::Vector3& position, - reactphysics3d::CollisionWorld* world, - const std::string& meshFolderPath) - : PhysicsObject(meshFolderPath + "cylinder.obj"), mRadius(radius), mHeight(height) { - - // Compute the scaling matrix - mScalingMatrix = openglframework::Matrix4(mRadius, 0, 0, 0, - 0, mHeight, 0, 0, - 0, 0, mRadius, 0, - 0, 0, 0, 1); - - // Initialize the position where the cylinder will be rendered - translateWorld(position); - - // Create the collision shape for the rigid body (cylinder shape) and do not - // forget to delete it at the end - mCylinderShape = new rp3d::CylinderShape(mRadius, mHeight); - - // Initial position and orientation of the rigid body - rp3d::Vector3 initPosition(position.x, position.y, position.z); - rp3d::Quaternion initOrientation = rp3d::Quaternion::identity(); - rp3d::Transform transform(initPosition, initOrientation); - - mPreviousTransform = transform; - - // Create a rigid body corresponding to the cylinder in the dynamics world - mBody = world->createCollisionBody(transform); - - // Add a collision shape to the body and specify the mass of the shape - mProxyShape = mBody->addCollisionShape(mCylinderShape, rp3d::Transform::identity()); - - mTransformMatrix = mTransformMatrix * mScalingMatrix; - - // Create the VBOs and VAO - if (totalNbCylinders == 0) { - createVBOAndVAO(); - } - - totalNbCylinders++; -} - -// Constructor -Cylinder::Cylinder(float radius, float height, const openglframework::Vector3& position, - float mass, reactphysics3d::DynamicsWorld* dynamicsWorld, - const std::string& meshFolderPath) - : PhysicsObject(meshFolderPath + "cylinder.obj"), mRadius(radius), mHeight(height) { - - // Compute the scaling matrix - mScalingMatrix = openglframework::Matrix4(mRadius, 0, 0, 0, - 0, mHeight, 0, 0, - 0, 0, mRadius, 0, - 0, 0, 0, 1); - - // Initialize the position where the cylinder will be rendered - translateWorld(position); - - // Create the collision shape for the rigid body (cylinder shape) and do - // not forget to delete it at the end - mCylinderShape = new rp3d::CylinderShape(mRadius, mHeight); - - // Initial position and orientation of the rigid body - rp3d::Vector3 initPosition(position.x, position.y, position.z); - rp3d::Quaternion initOrientation = rp3d::Quaternion::identity(); - rp3d::Transform transform(initPosition, initOrientation); - - // Create a rigid body corresponding to the cylinder in the dynamics world - rp3d::RigidBody* body = dynamicsWorld->createRigidBody(transform); - - // Add a collision shape to the body and specify the mass of the shape - mProxyShape = body->addCollisionShape(mCylinderShape, rp3d::Transform::identity(), mass); - - mTransformMatrix = mTransformMatrix * mScalingMatrix; - - mBody = body; - - // Create the VBOs and VAO - if (totalNbCylinders == 0) { - createVBOAndVAO(); - } - - totalNbCylinders++; -} - -// Destructor -Cylinder::~Cylinder() { - - if (totalNbCylinders == 1) { - - // Destroy the mesh - destroy(); - - // Destroy the VBOs and VAO - mVBOIndices.destroy(); - mVBOVertices.destroy(); - mVBONormals.destroy(); - mVBOTextureCoords.destroy(); - mVAO.destroy(); - } - delete mCylinderShape; - totalNbCylinders--; -} - -// Render the cylinder at the correct position and with the correct orientation -void Cylinder::render(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix, bool wireframe) { - - if (wireframe) { - glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); - } - - // Bind the shader - shader.bind(); - - // Set the model to camera matrix - shader.setMatrix4x4Uniform("localToWorldMatrix", mTransformMatrix); - shader.setMatrix4x4Uniform("worldToCameraMatrix", worldToCameraMatrix); - - // Set the normal matrix (inverse transpose of the 3x3 upper-left sub matrix of the - // model-view matrix) - const openglframework::Matrix4 localToCameraMatrix = worldToCameraMatrix * mTransformMatrix; - const openglframework::Matrix3 normalMatrix = - localToCameraMatrix.getUpperLeft3x3Matrix().getInverse().getTranspose(); - shader.setMatrix3x3Uniform("normalMatrix", normalMatrix, false); - - // Set the vertex color - openglframework::Color currentColor = mBody->isSleeping() ? mSleepingColor : mColor; - openglframework::Vector4 color(currentColor.r, currentColor.g, currentColor.b, currentColor.a); - shader.setVector4Uniform("vertexColor", color, false); - - // Bind the VAO - mVAO.bind(); - - mVBOVertices.bind(); - - // Get the location of shader attribute variables - GLint vertexPositionLoc = shader.getAttribLocation("vertexPosition"); - GLint vertexNormalLoc = shader.getAttribLocation("vertexNormal", false); - - glEnableVertexAttribArray(vertexPositionLoc); - glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)nullptr); - - mVBONormals.bind(); - - if (vertexNormalLoc != -1) glVertexAttribPointer(vertexNormalLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)nullptr); - if (vertexNormalLoc != -1) glEnableVertexAttribArray(vertexNormalLoc); - - // For each part of the mesh - for (unsigned int i=0; isetLocalScaling(rp3d::Vector3(scaling.x, scaling.y, scaling.z)); - - // Scale the graphics object - mScalingMatrix = openglframework::Matrix4(mRadius * scaling.x, 0, 0, 0, - 0, mHeight * scaling.y, 0, 0, - 0, 0, mRadius * scaling.z, 0, - 0, 0, 0, 1); -} diff --git a/testbed/common/Cylinder.h b/testbed/common/Cylinder.h deleted file mode 100644 index 3a94b443..00000000 --- a/testbed/common/Cylinder.h +++ /dev/null @@ -1,111 +0,0 @@ -/******************************************************************************** -* 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 CYLINDER_H -#define CYLINDER_H - -// Libraries -#include "openglframework.h" -#include "reactphysics3d.h" -#include "PhysicsObject.h" - -// Class Cylinder -class Cylinder : public PhysicsObject { - - private : - - // -------------------- Attributes -------------------- // - - /// Radius of the cylinder - float mRadius; - - /// Height of the cylinder - float mHeight; - - /// Scaling matrix (applied to a sphere to obtain the correct cylinder dimensions) - openglframework::Matrix4 mScalingMatrix; - - /// Previous transform (for interpolation) - rp3d::Transform mPreviousTransform; - - /// Collision shape - rp3d::CylinderShape* mCylinderShape; - rp3d::ProxyShape* mProxyShape; - - /// Vertex Buffer Object for the vertices data - static openglframework::VertexBufferObject mVBOVertices; - - /// Vertex Buffer Object for the normals data - static openglframework::VertexBufferObject mVBONormals; - - /// Vertex Buffer Object for the texture coords - static openglframework::VertexBufferObject mVBOTextureCoords; - - /// Vertex Buffer Object for the indices - static openglframework::VertexBufferObject mVBOIndices; - - /// Vertex Array Object for the vertex data - static openglframework::VertexArrayObject mVAO; - - // Total number of capsules created - static int totalNbCylinders; - - // -------------------- Methods -------------------- // - - // Create the Vertex Buffer Objects used to render with OpenGL. - void createVBOAndVAO(); - - public : - - // -------------------- Methods -------------------- // - - /// Constructor - Cylinder(float radius, float height, const openglframework::Vector3& position, - rp3d::CollisionWorld* world, const std::string &meshFolderPath); - - /// Constructor - Cylinder(float radius, float height, const openglframework::Vector3& position, - float mass, rp3d::DynamicsWorld* dynamicsWorld, const std::string &meshFolderPath); - - /// Destructor - ~Cylinder(); - - /// Render the cylinder at the correct position and with the correct orientation - void render(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix, bool wireframe); - - /// Update the transform matrix of the object - virtual void updateTransform(float interpolationFactor) override; - - /// Set the scaling of the object - void setScaling(const openglframework::Vector3& scaling); -}; - -// Update the transform matrix of the object -inline void Cylinder::updateTransform(float interpolationFactor) { - mTransformMatrix = computeTransform(interpolationFactor, mScalingMatrix); -} - -#endif diff --git a/testbed/common/Dumbbell.cpp b/testbed/common/Dumbbell.cpp index 03afd59b..02afe091 100644 --- a/testbed/common/Dumbbell.cpp +++ b/testbed/common/Dumbbell.cpp @@ -53,13 +53,13 @@ Dumbbell::Dumbbell(const openglframework::Vector3 &position, const rp3d::decimal massSphere = rp3d::decimal(2.0); mSphereShape = new rp3d::SphereShape(radiusSphere); - // Create a cylinder collision shape for the middle of the dumbbell + // Create a capsule collision shape for the middle of the dumbbell // ReactPhysics3D will clone this object to create an internal one. Therefore, // it is OK if this object is destroyed right after calling RigidBody::addCollisionShape() - const rp3d::decimal radiusCylinder = rp3d::decimal(0.5); - const rp3d::decimal heightCylinder = rp3d::decimal(8.0); + const rp3d::decimal radiusCapsule = rp3d::decimal(0.5); + const rp3d::decimal heightCapsule = rp3d::decimal(7.0); const rp3d::decimal massCylinder = rp3d::decimal(1.0); - mCylinderShape = new rp3d::CylinderShape(radiusCylinder, heightCylinder); + mCapsuleShape = new rp3d::CapsuleShape(radiusCapsule, heightCapsule); // Initial position and orientation of the rigid body rp3d::Vector3 initPosition(position.x, position.y, position.z); @@ -84,7 +84,7 @@ Dumbbell::Dumbbell(const openglframework::Vector3 &position, // Add the three collision shapes to the body and specify the mass and transform of the shapes mProxyShapeSphere1 = body->addCollisionShape(mSphereShape, transformSphereShape1, massSphere); mProxyShapeSphere2 = body->addCollisionShape(mSphereShape, transformSphereShape2, massSphere); - mProxyShapeCylinder = body->addCollisionShape(mCylinderShape, transformCylinderShape, massCylinder); + mProxyShapeCapsule = body->addCollisionShape(mCapsuleShape, transformCylinderShape, massCylinder); mBody = body; @@ -120,9 +120,9 @@ Dumbbell::Dumbbell(const openglframework::Vector3 &position, // Create a cylinder collision shape for the middle of the dumbbell // ReactPhysics3D will clone this object to create an internal one. Therefore, // it is OK if this object is destroyed right after calling RigidBody::addCollisionShape() - const rp3d::decimal radiusCylinder = rp3d::decimal(0.5); - const rp3d::decimal heightCylinder = rp3d::decimal(8.0); - mCylinderShape = new rp3d::CylinderShape(radiusCylinder, heightCylinder); + const rp3d::decimal radiusCapsule = rp3d::decimal(0.5); + const rp3d::decimal heightCapsule = rp3d::decimal(7.0); + mCapsuleShape = new rp3d::CapsuleShape(radiusCapsule, heightCapsule); // Initial position and orientation of the rigid body rp3d::Vector3 initPosition(position.x, position.y, position.z); @@ -145,7 +145,7 @@ Dumbbell::Dumbbell(const openglframework::Vector3 &position, // Add the three collision shapes to the body and specify the mass and transform of the shapes mProxyShapeSphere1 = mBody->addCollisionShape(mSphereShape, transformSphereShape1); mProxyShapeSphere2 = mBody->addCollisionShape(mSphereShape, transformSphereShape2); - mProxyShapeCylinder = mBody->addCollisionShape(mCylinderShape, transformCylinderShape); + mProxyShapeCapsule = mBody->addCollisionShape(mCapsuleShape, transformCylinderShape); mTransformMatrix = mTransformMatrix * mScalingMatrix; @@ -173,7 +173,7 @@ Dumbbell::~Dumbbell() { mVAO.destroy(); } delete mSphereShape; - delete mCylinderShape; + delete mCapsuleShape; totalNbDumbbells--; } @@ -304,7 +304,7 @@ void Dumbbell::setScaling(const openglframework::Vector3& scaling) { // Scale the collision shape rp3d::Vector3 newScaling(scaling.x, scaling.y, scaling.z); - mProxyShapeCylinder->setLocalScaling(newScaling); + mProxyShapeCapsule->setLocalScaling(newScaling); mProxyShapeSphere1->setLocalScaling(newScaling); mProxyShapeSphere2->setLocalScaling(newScaling); diff --git a/testbed/common/Dumbbell.h b/testbed/common/Dumbbell.h index 81020935..ea2d3d88 100644 --- a/testbed/common/Dumbbell.h +++ b/testbed/common/Dumbbell.h @@ -31,7 +31,7 @@ #include "reactphysics3d.h" #include "PhysicsObject.h" -// Class Sphere +// Class Dumbbell class Dumbbell : public PhysicsObject { private : @@ -42,9 +42,9 @@ class Dumbbell : public PhysicsObject { float mDistanceBetweenSphere; /// Collision shapes - rp3d::CylinderShape* mCylinderShape; + rp3d::CapsuleShape* mCapsuleShape; rp3d::SphereShape* mSphereShape; - rp3d::ProxyShape* mProxyShapeCylinder; + rp3d::ProxyShape* mProxyShapeCapsule; rp3d::ProxyShape* mProxyShapeSphere1; rp3d::ProxyShape* mProxyShapeSphere2; diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.h b/testbed/scenes/collisiondetection/CollisionDetectionScene.h index b7f57c1d..d3a7de00 100644 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.h +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.h @@ -33,8 +33,6 @@ #include "SceneDemo.h" #include "Sphere.h" #include "Box.h" -#include "Cone.h" -#include "Cylinder.h" #include "Capsule.h" #include "Line.h" #include "ConvexMesh.h" diff --git a/testbed/scenes/collisionshapes/CollisionShapesScene.cpp b/testbed/scenes/collisionshapes/CollisionShapesScene.cpp index 8db4908a..746942ff 100644 --- a/testbed/scenes/collisionshapes/CollisionShapesScene.cpp +++ b/testbed/scenes/collisionshapes/CollisionShapesScene.cpp @@ -125,62 +125,6 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name) mSpheres.push_back(sphere); } - // Create all the cones of the scene - for (int i=0; igetRigidBody()->getMaterial().setRollingResistance(0.08); - - // Set the box color - cone->setColor(mDemoColors[i % mNbDemoColors]); - cone->setSleepingColor(mRedColorDemo); - - // Change the material properties of the rigid body - rp3d::Material& material = cone->getRigidBody()->getMaterial(); - material.setBounciness(rp3d::decimal(0.2)); - - // Add the cone the list of sphere in the scene - mCones.push_back(cone); - } - - // Create all the cylinders of the scene - for (int i=0; igetRigidBody()->getMaterial().setRollingResistance(0.08); - - // Set the box color - cylinder->setColor(mDemoColors[i % mNbDemoColors]); - cylinder->setSleepingColor(mRedColorDemo); - - // Change the material properties of the rigid body - rp3d::Material& material = cylinder->getRigidBody()->getMaterial(); - material.setBounciness(rp3d::decimal(0.2)); - - // Add the cylinder the list of sphere in the scene - mCylinders.push_back(cylinder); - } - // Create all the capsules of the scene for (int i=0; i::iterator it = mCones.begin(); it != mCones.end(); ++it) { - - // Destroy the corresponding rigid body from the dynamics world - mDynamicsWorld->destroyRigidBody((*it)->getRigidBody()); - - // Destroy the sphere - delete (*it); - } - - // Destroy all the cylinders of the scene - for (std::vector::iterator it = mCylinders.begin(); it != mCylinders.end(); ++it) { - - // Destroy the corresponding rigid body from the dynamics world - mDynamicsWorld->destroyRigidBody((*it)->getRigidBody()); - - // Destroy the sphere - delete (*it); - } - // Destroy all the capsules of the scene for (std::vector::iterator it = mCapsules.begin(); it != mCapsules.end(); ++it) { @@ -410,20 +334,6 @@ void CollisionShapesScene::update() { (*it)->updateTransform(mInterpolationFactor); } - // Update the position and orientation of the cones - for (std::vector::iterator it = mCones.begin(); it != mCones.end(); ++it) { - - // Update the transform used for the rendering - (*it)->updateTransform(mInterpolationFactor); - } - - // Update the position and orientation of the cylinders - for (std::vector::iterator it = mCylinders.begin(); it != mCylinders.end(); ++it) { - - // Update the transform used for the rendering - (*it)->updateTransform(mInterpolationFactor); - } - // Update the position and orientation of the capsules for (std::vector::iterator it = mCapsules.begin(); it != mCapsules.end(); ++it) { @@ -469,16 +379,6 @@ void CollisionShapesScene::renderSinglePass(openglframework::Shader& shader, (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); } - // Render all the cones of the scene - for (std::vector::iterator it = mCones.begin(); it != mCones.end(); ++it) { - (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - } - - // Render all the cylinders of the scene - for (std::vector::iterator it = mCylinders.begin(); it != mCylinders.end(); ++it) { - (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - } - // Render all the capsules of the scene for (std::vector::iterator it = mCapsules.begin(); it != mCapsules.end(); ++it) { (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); @@ -563,42 +463,6 @@ void CollisionShapesScene::reset() { mSpheres[i]->setTransform(transform); } - // Create all the cones of the scene - for (int i=0; isetTransform(transform); - } - - // Create all the cylinders of the scene - for (int i=0; isetTransform(transform); - } - // Create all the capsules of the scene for (int i=0; i mSpheres; - std::vector mCones; - - std::vector mCylinders; - std::vector mCapsules; /// All the convex meshes of the scene diff --git a/testbed/scenes/raycast/RaycastScene.cpp b/testbed/scenes/raycast/RaycastScene.cpp index 58b19055..c403ebb2 100644 --- a/testbed/scenes/raycast/RaycastScene.cpp +++ b/testbed/scenes/raycast/RaycastScene.cpp @@ -79,28 +79,6 @@ RaycastScene::RaycastScene(const std::string& name) mSphere->setColor(mGreyColorDemo); mSphere->setSleepingColor(mRedColorDemo); - // ---------- Cone ---------- // - openglframework::Vector3 position4(0, 0, 0); - - // Create a cone and a corresponding collision body in the dynamics world - mCone = new Cone(CONE_RADIUS, CONE_HEIGHT, position4, mCollisionWorld, - mMeshFolderPath); - - // Set the color - mCone->setColor(mGreyColorDemo); - mCone->setSleepingColor(mRedColorDemo); - - // ---------- Cylinder ---------- // - openglframework::Vector3 position5(0, 0, 0); - - // Create a cylinder and a corresponding collision body in the dynamics world - mCylinder = new Cylinder(CYLINDER_RADIUS, CYLINDER_HEIGHT, position5, - mCollisionWorld, mMeshFolderPath); - - // Set the color - mCylinder->setColor(mGreyColorDemo); - mCylinder->setSleepingColor(mRedColorDemo); - // ---------- Capsule ---------- // openglframework::Vector3 position6(0, 0, 0); @@ -188,8 +166,6 @@ void RaycastScene::changeBody() { mSphere->getCollisionBody()->setIsActive(false); mBox->getCollisionBody()->setIsActive(false); - mCone->getCollisionBody()->setIsActive(false); - mCylinder->getCollisionBody()->setIsActive(false); mCapsule->getCollisionBody()->setIsActive(false); mConvexMesh->getCollisionBody()->setIsActive(false); mDumbbell->getCollisionBody()->setIsActive(false); @@ -201,19 +177,15 @@ void RaycastScene::changeBody() { break; case 1: mBox->getCollisionBody()->setIsActive(true); break; - case 2: mCone->getCollisionBody()->setIsActive(true); + case 2: mCapsule->getCollisionBody()->setIsActive(true); break; - case 3: mCylinder->getCollisionBody()->setIsActive(true); + case 3: mConvexMesh->getCollisionBody()->setIsActive(true); break; - case 4: mCapsule->getCollisionBody()->setIsActive(true); + case 4: mDumbbell->getCollisionBody()->setIsActive(true); break; - case 5: mConvexMesh->getCollisionBody()->setIsActive(true); + case 5: mConcaveMesh->getCollisionBody()->setIsActive(true); break; - case 6: mDumbbell->getCollisionBody()->setIsActive(true); - break; - case 7: mConcaveMesh->getCollisionBody()->setIsActive(true); - break; - case 8: mHeightField->getCollisionBody()->setIsActive(true); + case 6: mHeightField->getCollisionBody()->setIsActive(true); break; } @@ -238,16 +210,6 @@ RaycastScene::~RaycastScene() { mCollisionWorld->destroyCollisionBody(mSphere->getCollisionBody()); delete mSphere; - // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mCone->getCollisionBody()); - delete mCone; - - // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mCylinder->getCollisionBody()); - - // Destroy the sphere - delete mCylinder; - // Destroy the corresponding rigid body from the dynamics world mCollisionWorld->destroyCollisionBody(mCapsule->getCollisionBody()); @@ -378,8 +340,6 @@ void RaycastScene::renderSinglePass(openglframework::Shader& shader, // Render the shapes if (mBox->getCollisionBody()->isActive()) mBox->render(shader, worldToCameraMatrix, mIsWireframeEnabled); if (mSphere->getCollisionBody()->isActive()) mSphere->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - if (mCone->getCollisionBody()->isActive()) mCone->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - if (mCylinder->getCollisionBody()->isActive()) mCylinder->render(shader, worldToCameraMatrix, mIsWireframeEnabled); if (mCapsule->getCollisionBody()->isActive()) mCapsule->render(shader, worldToCameraMatrix, mIsWireframeEnabled); if (mConvexMesh->getCollisionBody()->isActive()) mConvexMesh->render(shader, worldToCameraMatrix, mIsWireframeEnabled); if (mDumbbell->getCollisionBody()->isActive()) mDumbbell->render(shader, worldToCameraMatrix, mIsWireframeEnabled); diff --git a/testbed/scenes/raycast/RaycastScene.h b/testbed/scenes/raycast/RaycastScene.h index 56ebb565..be698e53 100644 --- a/testbed/scenes/raycast/RaycastScene.h +++ b/testbed/scenes/raycast/RaycastScene.h @@ -34,8 +34,6 @@ #include "SceneDemo.h" #include "Sphere.h" #include "Box.h" -#include "Cone.h" -#include "Cylinder.h" #include "Capsule.h" #include "Line.h" #include "ConvexMesh.h" @@ -141,8 +139,6 @@ class RaycastScene : public SceneDemo { /// All objects on the scene Box* mBox; Sphere* mSphere; - Cone* mCone; - Cylinder* mCylinder; Capsule* mCapsule; ConvexMesh* mConvexMesh; Dumbbell* mDumbbell; From 30e0132e158accaa87a5eb21eeab6ab8b79fd476 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 2 Feb 2017 23:10:01 +0100 Subject: [PATCH 056/248] Add capsule/capsule and capsule/sphere collision algorithm --- CMakeLists.txt | 2 + .../narrowphase/CapsuleVsCapsuleAlgorithm.cpp | 188 +++- .../narrowphase/CapsuleVsCapsuleAlgorithm.h | 142 +-- .../narrowphase/SphereVsSphereAlgorithm.cpp | 138 +-- .../narrowphase/SphereVsSphereAlgorithm.h | 142 +-- src/mathematics/mathematics_functions.cpp | 261 ++++-- src/mathematics/mathematics_functions.h | 190 ++-- .../mathematics/TestMathematicsFunctions.h | 312 ++++--- .../CollisionDetectionScene.cpp | 832 +++++++++--------- .../CollisionDetectionScene.h | 466 +++++----- 10 files changed, 1500 insertions(+), 1173 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 9b6af8c9..37b8febe 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -78,6 +78,8 @@ SET (REACTPHYSICS3D_SOURCES "src/collision/narrowphase/SphereVsSphereAlgorithm.cpp" "src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h" "src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp" + "src/collision/narrowphase/SphereVsCapsuleAlgorithm.h" + "src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp" "src/collision/narrowphase/ConcaveVsConvexAlgorithm.h" "src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp" "src/collision/narrowphase/SphereVsConvexMeshAlgorithm.h" diff --git a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp index 44badf67..2f9f8703 100644 --- a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp @@ -1,37 +1,151 @@ -/******************************************************************************** -* 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. * -* * -********************************************************************************/ - -// Libraries -#include "CapsuleVsCapsuleAlgorithm.h" -#include "collision/shapes/CapsuleShape.h" - -// We want to use the ReactPhysics3D namespace -using namespace reactphysics3d; - -bool CapsuleVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactPointInfo& contactPointInfo) { - - -} +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "CapsuleVsCapsuleAlgorithm.h" +#include "collision/shapes/CapsuleShape.h" + +// We want to use the ReactPhysics3D namespace +using namespace reactphysics3d; + +bool CapsuleVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactPointInfo& contactPointInfo) { + + const decimal parallelEpsilon = decimal(0.001); + + // Get the capsule collision shapes + const CapsuleShape* capsuleShape1 = static_cast(narrowPhaseInfo->collisionShape1); + const CapsuleShape* capsuleShape2 = static_cast(narrowPhaseInfo->collisionShape2); + + // Get the transform from capsule 1 local-space to capsule 2 local-space + const Transform capsule1ToCapsule2SpaceTransform = narrowPhaseInfo->shape1ToWorldTransform * narrowPhaseInfo->shape2ToWorldTransform.getInverse(); + + // Compute the end-points of the inner segment of the first capsule + Vector3 capsule1SegA(0, -capsuleShape1->getHeight() * decimal(0.5), 0); + Vector3 capsule1SegB(0, capsuleShape1->getHeight() * decimal(0.5), 0); + capsule1SegA = capsule1ToCapsule2SpaceTransform * capsule1SegA; + capsule1SegB = capsule1ToCapsule2SpaceTransform * capsule1SegB; + + // Compute the end-points of the inner segment of the second capsule + const Vector3 capsule2SegA(0, -capsuleShape2->getHeight() * decimal(0.5), 0); + const Vector3 capsule2SegB(0, capsuleShape2->getHeight() * decimal(0.5), 0); + + // The two inner capsule segments + const Vector3 seg1 = capsule1SegB - capsule1SegA; + const Vector3 seg2 = capsule2SegB - capsule2SegA; + + // Compute the sum of the radius of the two capsules (virtual spheres) + decimal sumRadius = capsuleShape2->getRadius() + capsuleShape1->getRadius(); + + // If the two capsules are parallel (we create two contact points) + if (seg1.cross(seg2).lengthSquare() < parallelEpsilon * parallelEpsilon) { + + // If the distance between the two segments is larger than the sum of the capsules radius (we do not have overlapping) + const decimal segmentsDistance = computeDistancePointToLineDistance(capsule1SegA, capsule1SegB, capsule2SegA); + if (segmentsDistance > sumRadius || segmentsDistance < MACHINE_EPSILON) { + + // The capsule are parallel but their inner segment distance is larger than the sum of the capsules radius. + // Therefore, we do not have overlap. If the inner segments overlap, we do not report any collision. + return false; + } + + // Compute the planes that goes through the extrem points of the inner segment of capsule 1 + decimal d1 = seg1.dot(capsule1SegA); + decimal d2 = -seg1.dot(capsule1SegB); + + // Clip the inner segment of capsule 2 with the two planes that go through extreme points of inner + // segment of capsule 1 + decimal t1 = computePlaneSegmentIntersection(capsule2SegB, capsule2SegA, d1, seg1); + decimal t2 = computePlaneSegmentIntersection(capsule2SegA, capsule2SegB, d2, -seg1); + + bool isClipValid = false; // True if the segments were overlapping (the clip segment is valid) + + // Clip the inner segment of capsule 2 + Vector3 clipPointA, clipPointB; + if (t1 >= decimal(0.0)) { + + if (t1 > decimal(1.0)) t1 = decimal(1.0); + clipPointA = capsule2SegB - t1 * seg2; + isClipValid = true; + } + if (t2 >= decimal(0.0) && t2 <= decimal(1.0)) { + + if (t2 > decimal(1.0)) t2 = decimal(1.0); + clipPointB = capsule2SegA + t2 * seg2; + isClipValid = true; + } + + // If we have a valid clip segment + if (isClipValid) { + + Vector3 segment1ToSegment2 = (capsule2SegA - capsule1SegA); + Vector3 segment1ToSegment2Normalized = segment1ToSegment2.getUnit(); + + const Vector3 contactPointACapsule1Local = capsule1ToCapsule2SpaceTransform.getInverse() * (clipPointA - segment1ToSegment2 + segment1ToSegment2Normalized * capsuleShape1->getRadius()); + const Vector3 contactPointBCapsule1Local = capsule1ToCapsule2SpaceTransform.getInverse() * (clipPointB - segment1ToSegment2 + segment1ToSegment2Normalized * capsuleShape1->getRadius()); + const Vector3 contactPointACapsule2Local = clipPointA - segment1ToSegment2Normalized * capsuleShape2->getRadius(); + const Vector3 contactPointBCapsule2Local = clipPointB - segment1ToSegment2Normalized * capsuleShape2->getRadius(); + + const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * segment1ToSegment2Normalized; + + decimal penetrationDepth = sumRadius - segmentsDistance; + + // Create the contact info object + // TODO : Make sure we create two contact points at the same time (same method here) + contactPointInfo.init(normalWorld, penetrationDepth, contactPointACapsule1Local, contactPointBCapsule1Local); + contactPointInfo.init(normalWorld, penetrationDepth, contactPointACapsule2Local, contactPointBCapsule2Local); + } + } + + // Compute the closest points between the two inner capsule segments + Vector3 closestPointCapsule1Seg; + Vector3 closestPointCapsule2Seg; + computeClosestPointBetweenTwoSegments(capsule1SegA, capsule1SegB, capsule2SegA, capsule2SegB, + closestPointCapsule1Seg, closestPointCapsule2Seg); + + // Compute the distance between the sphere center and the closest point on the segment + Vector3 closestPointsSeg1ToSeg2 = (closestPointCapsule2Seg - closestPointCapsule1Seg); + const decimal closestPointsDistanceSquare = closestPointsSeg1ToSeg2.lengthSquare(); + + // If the collision shapes overlap + if (closestPointsDistanceSquare <= sumRadius * sumRadius && closestPointsDistanceSquare > MACHINE_EPSILON) { + + decimal closestPointsDistance = std::sqrt(closestPointsDistanceSquare); + closestPointsSeg1ToSeg2 /= closestPointsDistance; + + const Vector3 contactPointCapsule1Local = capsule1ToCapsule2SpaceTransform.getInverse() * (closestPointCapsule1Seg + closestPointsSeg1ToSeg2 * capsuleShape1->getRadius()); + const Vector3 contactPointCapsule2Local = closestPointCapsule2Seg - closestPointsSeg1ToSeg2 * capsuleShape2->getRadius(); + + const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * closestPointsSeg1ToSeg2; + + decimal penetrationDepth = sumRadius - closestPointsDistance; + + // Create the contact info object + contactPointInfo.init(normalWorld, penetrationDepth, contactPointCapsule1Local, contactPointCapsule2Local); + + return true; + } + + return false; +} diff --git a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h index 6a48495e..7a46f73a 100644 --- a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h +++ b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h @@ -1,71 +1,71 @@ -/******************************************************************************** -* 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_CAPSULE_VS_CAPSULE_ALGORITHM_H -#define REACTPHYSICS3D_CAPSULE_VS_CAPSULE_ALGORITHM_H - -// Libraries -#include "body/Body.h" -#include "constraint/ContactPoint.h" -#include "NarrowPhaseAlgorithm.h" - - -/// Namespace ReactPhysics3D -namespace reactphysics3d { - -// Class CapsuleVsCapsuleAlgorithm -/** - * This class is used to compute the narrow-phase collision detection - * between two capsule collision shapes. - */ -class CapsuleVsCapsuleAlgorithm : public NarrowPhaseAlgorithm { - - protected : - - public : - - // -------------------- Methods -------------------- // - - /// Constructor - CapsuleVsCapsuleAlgorithm() = default; - - /// Destructor - virtual ~CapsuleVsCapsuleAlgorithm() override = default; - - /// Deleted copy-constructor - CapsuleVsCapsuleAlgorithm(const CapsuleVsCapsuleAlgorithm& algorithm) = delete; - - /// Deleted assignment operator - CapsuleVsCapsuleAlgorithm& operator=(const CapsuleVsCapsuleAlgorithm& algorithm) = delete; - - /// Compute a contact info if the two bounding volume collide - virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactPointInfo& contactPointInfo) override; -}; - -} - -#endif - +/******************************************************************************** +* 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_CAPSULE_VS_CAPSULE_ALGORITHM_H +#define REACTPHYSICS3D_CAPSULE_VS_CAPSULE_ALGORITHM_H + +// Libraries +#include "body/Body.h" +#include "constraint/ContactPoint.h" +#include "NarrowPhaseAlgorithm.h" + + +/// Namespace ReactPhysics3D +namespace reactphysics3d { + +// Class CapsuleVsCapsuleAlgorithm +/** + * This class is used to compute the narrow-phase collision detection + * between two capsules collision shapes. + */ +class CapsuleVsCapsuleAlgorithm : public NarrowPhaseAlgorithm { + + protected : + + public : + + // -------------------- Methods -------------------- // + + /// Constructor + CapsuleVsCapsuleAlgorithm() = default; + + /// Destructor + virtual ~CapsuleVsCapsuleAlgorithm() override = default; + + /// Deleted copy-constructor + CapsuleVsCapsuleAlgorithm(const CapsuleVsCapsuleAlgorithm& algorithm) = delete; + + /// Deleted assignment operator + CapsuleVsCapsuleAlgorithm& operator=(const CapsuleVsCapsuleAlgorithm& algorithm) = delete; + + /// Compute a contact info if the two bounding volume collide + virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + ContactPointInfo& contactPointInfo) override; +}; + +} + +#endif + diff --git a/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp b/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp index 6b28372d..e80688d5 100644 --- a/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp @@ -1,69 +1,69 @@ -/******************************************************************************** -* 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. * -* * -********************************************************************************/ - -// Libraries -#include "SphereVsSphereAlgorithm.h" -#include "collision/shapes/SphereShape.h" - -// We want to use the ReactPhysics3D namespace -using namespace reactphysics3d; - -bool SphereVsSphereAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactPointInfo& contactPointInfo) { - - // Get the sphere collision shapes - const SphereShape* sphereShape1 = static_cast(narrowPhaseInfo->collisionShape1); - const SphereShape* sphereShape2 = static_cast(narrowPhaseInfo->collisionShape2); - - // Get the local-space to world-space transforms - const Transform& transform1 = narrowPhaseInfo->shape1ToWorldTransform; - const Transform& transform2 = narrowPhaseInfo->shape2ToWorldTransform; - - // Compute the distance between the centers - Vector3 vectorBetweenCenters = transform2.getPosition() - transform1.getPosition(); - decimal squaredDistanceBetweenCenters = vectorBetweenCenters.lengthSquare(); - - // Compute the sum of the radius - decimal sumRadius = sphereShape1->getRadius() + sphereShape2->getRadius(); - - // If the sphere collision shapes intersect - if (squaredDistanceBetweenCenters <= sumRadius * sumRadius) { - Vector3 centerSphere2InBody1LocalSpace = transform1.getInverse() * transform2.getPosition(); - Vector3 centerSphere1InBody2LocalSpace = transform2.getInverse() * transform1.getPosition(); - Vector3 intersectionOnBody1 = sphereShape1->getRadius() * - centerSphere2InBody1LocalSpace.getUnit(); - Vector3 intersectionOnBody2 = sphereShape2->getRadius() * - centerSphere1InBody2LocalSpace.getUnit(); - decimal penetrationDepth = sumRadius - std::sqrt(squaredDistanceBetweenCenters); - - // Create the contact info object - contactPointInfo.init(vectorBetweenCenters.getUnit(), penetrationDepth, - intersectionOnBody1, intersectionOnBody2); - - return true; - } - - return false; -} +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "SphereVsSphereAlgorithm.h" +#include "collision/shapes/SphereShape.h" + +// We want to use the ReactPhysics3D namespace +using namespace reactphysics3d; + +bool SphereVsSphereAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + ContactPointInfo& contactPointInfo) { + + // Get the sphere collision shapes + const SphereShape* sphereShape1 = static_cast(narrowPhaseInfo->collisionShape1); + const SphereShape* sphereShape2 = static_cast(narrowPhaseInfo->collisionShape2); + + // Get the local-space to world-space transforms + const Transform& transform1 = narrowPhaseInfo->shape1ToWorldTransform; + const Transform& transform2 = narrowPhaseInfo->shape2ToWorldTransform; + + // Compute the distance between the centers + Vector3 vectorBetweenCenters = transform2.getPosition() - transform1.getPosition(); + decimal squaredDistanceBetweenCenters = vectorBetweenCenters.lengthSquare(); + + // Compute the sum of the radius + decimal sumRadius = sphereShape1->getRadius() + sphereShape2->getRadius(); + + // If the sphere collision shapes intersect + if (squaredDistanceBetweenCenters <= sumRadius * sumRadius) { + Vector3 centerSphere2InBody1LocalSpace = transform1.getInverse() * transform2.getPosition(); + Vector3 centerSphere1InBody2LocalSpace = transform2.getInverse() * transform1.getPosition(); + Vector3 intersectionOnBody1 = sphereShape1->getRadius() * + centerSphere2InBody1LocalSpace.getUnit(); + Vector3 intersectionOnBody2 = sphereShape2->getRadius() * + centerSphere1InBody2LocalSpace.getUnit(); + decimal penetrationDepth = sumRadius - std::sqrt(squaredDistanceBetweenCenters); + + // Create the contact info object + contactPointInfo.init(vectorBetweenCenters.getUnit(), penetrationDepth, + intersectionOnBody1, intersectionOnBody2); + + return true; + } + + return false; +} diff --git a/src/collision/narrowphase/SphereVsSphereAlgorithm.h b/src/collision/narrowphase/SphereVsSphereAlgorithm.h index 24886f7f..be10d5a1 100644 --- a/src/collision/narrowphase/SphereVsSphereAlgorithm.h +++ b/src/collision/narrowphase/SphereVsSphereAlgorithm.h @@ -1,71 +1,71 @@ -/******************************************************************************** -* 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_SPHERE_VS_SPHERE_ALGORITHM_H -#define REACTPHYSICS3D_SPHERE_VS_SPHERE_ALGORITHM_H - -// Libraries -#include "body/Body.h" -#include "constraint/ContactPoint.h" -#include "NarrowPhaseAlgorithm.h" - - -/// Namespace ReactPhysics3D -namespace reactphysics3d { - -// Class SphereVsSphereAlgorithm -/** - * This class is used to compute the narrow-phase collision detection - * between two sphere collision shapes. - */ -class SphereVsSphereAlgorithm : public NarrowPhaseAlgorithm { - - protected : - - public : - - // -------------------- Methods -------------------- // - - /// Constructor - SphereVsSphereAlgorithm() = default; - - /// Destructor - virtual ~SphereVsSphereAlgorithm() override = default; - - /// Deleted copy-constructor - SphereVsSphereAlgorithm(const SphereVsSphereAlgorithm& algorithm) = delete; - - /// Deleted assignment operator - SphereVsSphereAlgorithm& operator=(const SphereVsSphereAlgorithm& algorithm) = delete; - - /// Compute a contact info if the two bounding volume collide - virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactPointInfo& contactPointInfo) override; -}; - -} - -#endif - +/******************************************************************************** +* 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_SPHERE_VS_SPHERE_ALGORITHM_H +#define REACTPHYSICS3D_SPHERE_VS_SPHERE_ALGORITHM_H + +// Libraries +#include "body/Body.h" +#include "constraint/ContactPoint.h" +#include "NarrowPhaseAlgorithm.h" + + +/// Namespace ReactPhysics3D +namespace reactphysics3d { + +// Class SphereVsSphereAlgorithm +/** + * This class is used to compute the narrow-phase collision detection + * between two sphere collision shapes. + */ +class SphereVsSphereAlgorithm : public NarrowPhaseAlgorithm { + + protected : + + public : + + // -------------------- Methods -------------------- // + + /// Constructor + SphereVsSphereAlgorithm() = default; + + /// Destructor + virtual ~SphereVsSphereAlgorithm() override = default; + + /// Deleted copy-constructor + SphereVsSphereAlgorithm(const SphereVsSphereAlgorithm& algorithm) = delete; + + /// Deleted assignment operator + SphereVsSphereAlgorithm& operator=(const SphereVsSphereAlgorithm& algorithm) = delete; + + /// Compute a contact info if the two bounding volume collide + virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + ContactPointInfo& contactPointInfo) override; +}; + +} + +#endif + diff --git a/src/mathematics/mathematics_functions.cpp b/src/mathematics/mathematics_functions.cpp index 97bf6dcf..578cecdd 100644 --- a/src/mathematics/mathematics_functions.cpp +++ b/src/mathematics/mathematics_functions.cpp @@ -1,59 +1,202 @@ -/******************************************************************************** -* 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. * -* * -********************************************************************************/ - -// Libraries -#include "mathematics_functions.h" -#include "Vector3.h" - -using namespace reactphysics3d; - -/// Compute the barycentric coordinates u, v, w of a point p inside the triangle (a, b, c) -/// This method uses the technique described in the book Real-Time collision detection by -/// Christer Ericson. -void reactphysics3d::computeBarycentricCoordinatesInTriangle(const Vector3& a, const Vector3& b, const Vector3& c, - const Vector3& p, decimal& u, decimal& v, decimal& w) { - const Vector3 v0 = b - a; - const Vector3 v1 = c - a; - const Vector3 v2 = p - a; - - decimal d00 = v0.dot(v0); - decimal d01 = v0.dot(v1); - decimal d11 = v1.dot(v1); - decimal d20 = v2.dot(v0); - decimal d21 = v2.dot(v1); - - decimal denom = d00 * d11 - d01 * d01; - v = (d11 * d20 - d01 * d21) / denom; - w = (d00 * d21 - d01 * d20) / denom; - u = decimal(1.0) - v - w; -} - -// Clamp a vector such that it is no longer than a given maximum length -Vector3 reactphysics3d::clamp(const Vector3& vector, decimal maxLength) { - if (vector.lengthSquare() > maxLength * maxLength) { - return vector.getUnit() * maxLength; - } - return vector; -} +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "mathematics_functions.h" +#include "Vector3.h" +#include + +using namespace reactphysics3d; + +/// Compute the barycentric coordinates u, v, w of a point p inside the triangle (a, b, c) +/// This method uses the technique described in the book Real-Time collision detection by +/// Christer Ericson. +void reactphysics3d::computeBarycentricCoordinatesInTriangle(const Vector3& a, const Vector3& b, const Vector3& c, + const Vector3& p, decimal& u, decimal& v, decimal& w) { + const Vector3 v0 = b - a; + const Vector3 v1 = c - a; + const Vector3 v2 = p - a; + + decimal d00 = v0.dot(v0); + decimal d01 = v0.dot(v1); + decimal d11 = v1.dot(v1); + decimal d20 = v2.dot(v0); + decimal d21 = v2.dot(v1); + + decimal denom = d00 * d11 - d01 * d01; + v = (d11 * d20 - d01 * d21) / denom; + w = (d00 * d21 - d01 * d20) / denom; + u = decimal(1.0) - v - w; +} + +/// Clamp a vector such that it is no longer than a given maximum length +Vector3 reactphysics3d::clamp(const Vector3& vector, decimal maxLength) { + if (vector.lengthSquare() > maxLength * maxLength) { + return vector.getUnit() * maxLength; + } + return vector; +} + +/// Compute and return a point on segment from "segPointA" and "segPointB" that is closest to point "pointC" +Vector3 reactphysics3d::computeClosestPointOnSegment(const Vector3& segPointA, const Vector3& segPointB, const Vector3& pointC) { + + const Vector3 ab = segPointB - segPointA; + + decimal abLengthSquare = ab.lengthSquare(); + + // If the segment has almost zero length + if (abLengthSquare < MACHINE_EPSILON) { + + // Return one end-point of the segment as the closest point + return segPointA; + } + + // Project point C onto "AB" line + decimal t = (pointC - segPointA).dot(ab) / abLengthSquare; + + // If projected point onto the line is outside the segment, clamp it to the segment + if (t < decimal(0.0)) t = decimal(0.0); + if (t > decimal(1.0)) t = decimal(1.0); + + // Return the closest point on the segment + return segPointA + t * ab; +} + +/// Compute the closest points between two segments +/// This method uses the technique described in the book Real-Time +/// collision detection by Christer Ericson. +void computeClosestPointBetweenTwoSegments(const Vector3& seg1PointA, const Vector3& seg1PointB, + const Vector3& seg2PointA, const Vector3& seg2PointB, + Vector3& closestPointSeg1, Vector3& closestPointSeg2) { + + const Vector3 d1 = seg1PointB - seg1PointA; + const Vector3 d2 = seg2PointB - seg2PointA; + const Vector3 r = seg1PointA - seg2PointA; + decimal a = d1.lengthSquare(); + decimal e = d2.lengthSquare(); + decimal f = d2.dot(r); + decimal s, t; + + // If both segments degenerate into points + if (a <= MACHINE_EPSILON && e <= MACHINE_EPSILON) { + + closestPointSeg1 = seg1PointA; + closestPointSeg2 = seg2PointA; + return; + } + if (a <= MACHINE_EPSILON) { // If first segment degenerates into a point + + s = decimal(0.0); + + // Compute the closest point on second segment + t = clamp(f / e, decimal(0.0), decimal(1.0)); + } + else { + + decimal c = d1.dot(r); + + // If the second segment degenerates into a point + if (e <= MACHINE_EPSILON) { + + t = decimal(0.0); + s = clamp(-c / a, decimal(0.0), decimal(1.0)); + } + else { + + decimal b = d1.dot(d2); + decimal denom = a * e - b * b; + + // If the segments are not parallel + if (denom != decimal(0.0)) { + + // Compute the closest point on line 1 to line 2 and + // clamp to first segment. + s = clamp((b * f - c * e) / denom, decimal(0.0), decimal(1.0)); + } + else { + + // Pick an arbitrary point on first segment + s = decimal(0.0); + } + + // Compute the point on line 2 closest to the closest point + // we have just found + t = (b * s + f) / e; + + // If this closest point is inside second segment (t in [0, 1]), we are done. + // Otherwise, we clamp the point to the second segment and compute again the + // closest point on segment 1 + if (t < decimal(0.0)) { + t = decimal(0.0); + s = clamp(-c / a, decimal(0.0), decimal(1.0)); + } + else if (t > decimal(1.0)) { + t = decimal(1.0); + s = clamp((b - c) / a, decimal(0.0), decimal(1.0)); + } + } + } + + // Compute the closest points on both segments + closestPointSeg1 = seg1PointA + d1 * s; + closestPointSeg2 = seg2PointA + d2 * t; +} + +/// Compute the intersection between a plane and a segment +// Let the plane define by the equation planeNormal.dot(X) = planeD with X a point on the plane and "planeNormal" the plane normal. This method +// computes the intersection P between the plane and the segment (segA, segB). The method returns the value "t" such +// that P = segA + t * (segB - segA). Note that it only returns a value in [0, 1] if there is an intersection. Otherwise, +// there is no intersection between the plane and the segment. +decimal computePlaneSegmentIntersection(const Vector3& segA, const Vector3& segB, const decimal planeD, const Vector3& planeNormal) { + + const decimal parallelEpsilon = decimal(0.0001); + decimal t = decimal(-1); + + // Segment AB + const Vector3 ab = segB - segA; + + decimal nDotAB = planeNormal.dot(ab); + + // If the segment is not parallel to the plane + if (nDotAB > parallelEpsilon) { + t = (planeD - planeNormal.dot(segA)) / nDotAB; + } + + return t; +} + +/// Compute the distance between a point "point" and a line given by the points "linePointA" and "linePointB" +decimal computeDistancePointToLineDistance(const Vector3& linePointA, const Vector3& linePointB, const Vector3& point) { + + decimal distAB = (linePointB - linePointA).length(); + + if (distAB < MACHINE_EPSILON) { + return (point - linePointA).length(); + } + + return ((point - linePointA).cross(point - linePointB)).length() / distAB; +} + + diff --git a/src/mathematics/mathematics_functions.h b/src/mathematics/mathematics_functions.h index 7efe6d44..315de65c 100644 --- a/src/mathematics/mathematics_functions.h +++ b/src/mathematics/mathematics_functions.h @@ -1,87 +1,103 @@ -/******************************************************************************** -* 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_MATHEMATICS_FUNCTIONS_H -#define REACTPHYSICS3D_MATHEMATICS_FUNCTIONS_H - -// Libraries -#include "configuration.h" -#include "decimal.h" -#include -#include -#include - -/// ReactPhysics3D namespace -namespace reactphysics3d { - -struct Vector3; - -// ---------- Mathematics functions ---------- // - -/// Function to test if two real numbers are (almost) equal -/// We test if two numbers a and b are such that (a-b) are in [-EPSILON; EPSILON] -inline bool approxEqual(decimal a, decimal b, decimal epsilon = MACHINE_EPSILON) { - return (std::fabs(a - b) < epsilon); -} - -/// Function that returns the result of the "value" clamped by -/// two others values "lowerLimit" and "upperLimit" -inline int clamp(int value, int lowerLimit, int upperLimit) { - assert(lowerLimit <= upperLimit); - return std::min(std::max(value, lowerLimit), upperLimit); -} - -/// Function that returns the result of the "value" clamped by -/// two others values "lowerLimit" and "upperLimit" -inline decimal clamp(decimal value, decimal lowerLimit, decimal upperLimit) { - assert(lowerLimit <= upperLimit); - return std::min(std::max(value, lowerLimit), upperLimit); -} - -/// Return the minimum value among three values -inline decimal min3(decimal a, decimal b, decimal c) { - return std::min(std::min(a, b), c); -} - -/// Return the maximum value among three values -inline decimal max3(decimal a, decimal b, decimal c) { - return std::max(std::max(a, b), c); -} - -/// Return true if two values have the same sign -inline bool sameSign(decimal a, decimal b) { - return a * b >= decimal(0.0); -} - -/// Clamp a vector such that it is no longer than a given maximum length -Vector3 clamp(const Vector3& vector, decimal maxLength); - -/// Compute the barycentric coordinates u, v, w of a point p inside the triangle (a, b, c) -void computeBarycentricCoordinatesInTriangle(const Vector3& a, const Vector3& b, const Vector3& c, - const Vector3& p, decimal& u, decimal& v, decimal& w); - -} - -#endif +/******************************************************************************** +* 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_MATHEMATICS_FUNCTIONS_H +#define REACTPHYSICS3D_MATHEMATICS_FUNCTIONS_H + +// Libraries +#include "configuration.h" +#include "decimal.h" +#include +#include +#include + +/// ReactPhysics3D namespace +namespace reactphysics3d { + +struct Vector3; + +// ---------- Mathematics functions ---------- // + +/// Function to test if two real numbers are (almost) equal +/// We test if two numbers a and b are such that (a-b) are in [-EPSILON; EPSILON] +inline bool approxEqual(decimal a, decimal b, decimal epsilon = MACHINE_EPSILON) { + return (std::fabs(a - b) < epsilon); +} + +/// Function that returns the result of the "value" clamped by +/// two others values "lowerLimit" and "upperLimit" +inline int clamp(int value, int lowerLimit, int upperLimit) { + assert(lowerLimit <= upperLimit); + return std::min(std::max(value, lowerLimit), upperLimit); +} + +/// Function that returns the result of the "value" clamped by +/// two others values "lowerLimit" and "upperLimit" +inline decimal clamp(decimal value, decimal lowerLimit, decimal upperLimit) { + assert(lowerLimit <= upperLimit); + return std::min(std::max(value, lowerLimit), upperLimit); +} + +/// Return the minimum value among three values +inline decimal min3(decimal a, decimal b, decimal c) { + return std::min(std::min(a, b), c); +} + +/// Return the maximum value among three values +inline decimal max3(decimal a, decimal b, decimal c) { + return std::max(std::max(a, b), c); +} + +/// Return true if two values have the same sign +inline bool sameSign(decimal a, decimal b) { + return a * b >= decimal(0.0); +} + +/// Clamp a vector such that it is no longer than a given maximum length +Vector3 clamp(const Vector3& vector, decimal maxLength); + +// Compute and return a point on segment from "segPointA" and "segPointB" that is closest to point "pointC" +Vector3 computeClosestPointOnSegment(const Vector3& segPointA, const Vector3& segPointB, const Vector3& pointC); + +// Compute the closest points between two segments +void computeClosestPointBetweenTwoSegments(const Vector3& seg1PointA, const Vector3& seg1PointB, + const Vector3& seg2PointA, const Vector3& seg2PointB, + Vector3& closestPointSeg1, Vector3& closestPointSeg2); + +/// Compute the barycentric coordinates u, v, w of a point p inside the triangle (a, b, c) +void computeBarycentricCoordinatesInTriangle(const Vector3& a, const Vector3& b, const Vector3& c, + const Vector3& p, decimal& u, decimal& v, decimal& w); + +/// Compute the intersection between a plane and a segment +decimal computePlaneSegmentIntersection(const Vector3& segA, const Vector3& segB, const decimal planeD, const Vector3& planeNormal); + +/// Compute the distance between a point and a line +decimal computeDistancePointToLineDistance(const Vector3& linePointA, const Vector3& linePointB, const Vector3& point); + +} + + + +#endif diff --git a/test/tests/mathematics/TestMathematicsFunctions.h b/test/tests/mathematics/TestMathematicsFunctions.h index 5041fd48..32e19aad 100644 --- a/test/tests/mathematics/TestMathematicsFunctions.h +++ b/test/tests/mathematics/TestMathematicsFunctions.h @@ -1,133 +1,179 @@ -/******************************************************************************** -* 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 TEST_MATHEMATICS_FUNCTIONS_H -#define TEST_MATHEMATICS_FUNCTIONS_H - -// Libraries -#include "Test.h" -#include "mathematics/mathematics_functions.h" - -/// Reactphysics3D namespace -namespace reactphysics3d { - -// Class TestMathematicsFunctions -/** - * Unit test for mathematics functions - */ -class TestMathematicsFunctions : public Test { - - private : - - // ---------- Atributes ---------- // - - - - public : - - // ---------- Methods ---------- // - - /// Constructor - TestMathematicsFunctions(const std::string& name): Test(name) {} - - /// Run the tests - void run() { - - // Test approxEqual() - test(approxEqual(2, 7, 5.2)); - test(approxEqual(7, 2, 5.2)); - test(approxEqual(6, 6)); - test(!approxEqual(1, 5)); - test(!approxEqual(1, 5, 3)); - test(approxEqual(-2, -2)); - test(approxEqual(-2, -7, 6)); - test(!approxEqual(-2, 7, 2)); - test(approxEqual(-3, 8, 12)); - test(!approxEqual(-3, 8, 6)); - - // Test clamp() - test(clamp(4, -3, 5) == 4); - test(clamp(-3, 1, 8) == 1); - test(clamp(45, -6, 7) == 7); - test(clamp(-5, -2, -1) == -2); - test(clamp(-5, -9, -1) == -5); - test(clamp(6, 6, 9) == 6); - test(clamp(9, 6, 9) == 9); - test(clamp(decimal(4), decimal(-3), decimal(5)) == decimal(4)); - test(clamp(decimal(-3), decimal(1), decimal(8)) == decimal(1)); - test(clamp(decimal(45), decimal(-6), decimal(7)) == decimal(7)); - test(clamp(decimal(-5), decimal(-2), decimal(-1)) == decimal(-2)); - test(clamp(decimal(-5), decimal(-9), decimal(-1)) == decimal(-5)); - test(clamp(decimal(6), decimal(6), decimal(9)) == decimal(6)); - test(clamp(decimal(9), decimal(6), decimal(9)) == decimal(9)); - - // Test min3() - test(min3(1, 5, 7) == 1); - test(min3(-4, 2, 4) == -4); - test(min3(-1, -5, -7) == -7); - test(min3(13, 5, 47) == 5); - test(min3(4, 4, 4) == 4); - - // Test max3() - test(max3(1, 5, 7) == 7); - test(max3(-4, 2, 4) == 4); - test(max3(-1, -5, -7) == -1); - test(max3(13, 5, 47) == 47); - test(max3(4, 4, 4) == 4); - - // Test sameSign() - test(sameSign(4, 53)); - test(sameSign(-4, -8)); - test(!sameSign(4, -7)); - test(!sameSign(-4, 53)); - - // Test computeBarycentricCoordinatesInTriangle() - Vector3 a(0, 0, 0); - Vector3 b(5, 0, 0); - Vector3 c(0, 0, 5); - Vector3 testPoint(4, 0, 1); - decimal u,v,w; - computeBarycentricCoordinatesInTriangle(a, b, c, a, u, v, w); - test(approxEqual(u, 1.0, 0.000001)); - test(approxEqual(v, 0.0, 0.000001)); - test(approxEqual(w, 0.0, 0.000001)); - computeBarycentricCoordinatesInTriangle(a, b, c, b, u, v, w); - test(approxEqual(u, 0.0, 0.000001)); - test(approxEqual(v, 1.0, 0.000001)); - test(approxEqual(w, 0.0, 0.000001)); - computeBarycentricCoordinatesInTriangle(a, b, c, c, u, v, w); - test(approxEqual(u, 0.0, 0.000001)); - test(approxEqual(v, 0.0, 0.000001)); - test(approxEqual(w, 1.0, 0.000001)); - - computeBarycentricCoordinatesInTriangle(a, b, c, testPoint, u, v, w); - test(approxEqual(u + v + w, 1.0, 0.000001)); - } - - }; - -} - -#endif +/******************************************************************************** +* 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 TEST_MATHEMATICS_FUNCTIONS_H +#define TEST_MATHEMATICS_FUNCTIONS_H + +// Libraries +#include "Test.h" +#include "mathematics/mathematics_functions.h" + +/// Reactphysics3D namespace +namespace reactphysics3d { + +// Class TestMathematicsFunctions +/** + * Unit test for mathematics functions + */ +class TestMathematicsFunctions : public Test { + + private : + + // ---------- Atributes ---------- // + + + + public : + + // ---------- Methods ---------- // + + /// Constructor + TestMathematicsFunctions(const std::string& name): Test(name) {} + + /// Run the tests + void run() { + + // Test approxEqual() + test(approxEqual(2, 7, 5.2)); + test(approxEqual(7, 2, 5.2)); + test(approxEqual(6, 6)); + test(!approxEqual(1, 5)); + test(!approxEqual(1, 5, 3)); + test(approxEqual(-2, -2)); + test(approxEqual(-2, -7, 6)); + test(!approxEqual(-2, 7, 2)); + test(approxEqual(-3, 8, 12)); + test(!approxEqual(-3, 8, 6)); + + // Test clamp() + test(clamp(4, -3, 5) == 4); + test(clamp(-3, 1, 8) == 1); + test(clamp(45, -6, 7) == 7); + test(clamp(-5, -2, -1) == -2); + test(clamp(-5, -9, -1) == -5); + test(clamp(6, 6, 9) == 6); + test(clamp(9, 6, 9) == 9); + test(clamp(decimal(4), decimal(-3), decimal(5)) == decimal(4)); + test(clamp(decimal(-3), decimal(1), decimal(8)) == decimal(1)); + test(clamp(decimal(45), decimal(-6), decimal(7)) == decimal(7)); + test(clamp(decimal(-5), decimal(-2), decimal(-1)) == decimal(-2)); + test(clamp(decimal(-5), decimal(-9), decimal(-1)) == decimal(-5)); + test(clamp(decimal(6), decimal(6), decimal(9)) == decimal(6)); + test(clamp(decimal(9), decimal(6), decimal(9)) == decimal(9)); + + // Test min3() + test(min3(1, 5, 7) == 1); + test(min3(-4, 2, 4) == -4); + test(min3(-1, -5, -7) == -7); + test(min3(13, 5, 47) == 5); + test(min3(4, 4, 4) == 4); + + // Test max3() + test(max3(1, 5, 7) == 7); + test(max3(-4, 2, 4) == 4); + test(max3(-1, -5, -7) == -1); + test(max3(13, 5, 47) == 47); + test(max3(4, 4, 4) == 4); + + // Test sameSign() + test(sameSign(4, 53)); + test(sameSign(-4, -8)); + test(!sameSign(4, -7)); + test(!sameSign(-4, 53)); + + // Test computeBarycentricCoordinatesInTriangle() + Vector3 a(0, 0, 0); + Vector3 b(5, 0, 0); + Vector3 c(0, 0, 5); + Vector3 testPoint(4, 0, 1); + decimal u,v,w; + computeBarycentricCoordinatesInTriangle(a, b, c, a, u, v, w); + test(approxEqual(u, 1.0, 0.000001)); + test(approxEqual(v, 0.0, 0.000001)); + test(approxEqual(w, 0.0, 0.000001)); + computeBarycentricCoordinatesInTriangle(a, b, c, b, u, v, w); + test(approxEqual(u, 0.0, 0.000001)); + test(approxEqual(v, 1.0, 0.000001)); + test(approxEqual(w, 0.0, 0.000001)); + computeBarycentricCoordinatesInTriangle(a, b, c, c, u, v, w); + test(approxEqual(u, 0.0, 0.000001)); + test(approxEqual(v, 0.0, 0.000001)); + test(approxEqual(w, 1.0, 0.000001)); + + computeBarycentricCoordinatesInTriangle(a, b, c, testPoint, u, v, w); + test(approxEqual(u + v + w, 1.0, 0.000001)); + + // Test computeClosestPointBetweenTwoSegments() + Vector3 closestSeg1, closestSeg2; + computeClosestPointBetweenTwoSegments(Vector3(4, 0, 0), Vector3(6, 0, 0), Vector3(8, 0, 0), Vector3(8, 6, 0), closestSeg1, closestSeg2); + test(approxEqual(closestSeg1.x, 6.0, 0.000001)); + test(approxEqual(closestSeg1.y, 0.0, 0.000001)); + test(approxEqual(closestSeg1.z, 0.0, 0.000001)); + test(approxEqual(closestSeg2.x, 8.0, 0.000001)); + test(approxEqual(closestSeg2.y, 0.0, 0.000001)); + test(approxEqual(closestSeg2.z, 0.0, 0.000001)); + computeClosestPointBetweenTwoSegments(Vector3(4, 6, 5), Vector3(4, 6, 5), Vector3(8, 3, -9), Vector3(8, 3, -9), closestSeg1, closestSeg2); + test(approxEqual(closestSeg1.x, 4.0, 0.000001)); + test(approxEqual(closestSeg1.y, 6.0, 0.000001)); + test(approxEqual(closestSeg1.z, 5.0, 0.000001)); + test(approxEqual(closestSeg2.x, 8.0, 0.000001)); + test(approxEqual(closestSeg2.y, 3.0, 0.000001)); + test(approxEqual(closestSeg2.z, -9.0, 0.000001)); + computeClosestPointBetweenTwoSegments(Vector3(0, -5, 0), Vector3(0, 8, 0), Vector3(6, 3, 0), Vector3(10, -3, 0), closestSeg1, closestSeg2); + test(approxEqual(closestSeg1.x, 0.0, 0.000001)); + test(approxEqual(closestSeg1.y, 3.0, 0.000001)); + test(approxEqual(closestSeg1.z, 0.0, 0.000001)); + test(approxEqual(closestSeg2.x, 6.0, 0.000001)); + test(approxEqual(closestSeg2.y, 3.0, 0.000001)); + test(approxEqual(closestSeg2.z, 0.0, 0.000001)); + computeClosestPointBetweenTwoSegments(Vector3(1, -4, -5), Vector3(1, 4, -5), Vector3(-6, 5, -5), Vector3(6, 5, -5), closestSeg1, closestSeg2); + test(approxEqual(closestSeg1.x, 1.0, 0.000001)); + test(approxEqual(closestSeg1.y, 5.0, 0.000001)); + test(approxEqual(closestSeg1.z, -5.0, 0.000001)); + test(approxEqual(closestSeg2.x, 1.0, 0.000001)); + test(approxEqual(closestSeg2.y, 5.0, 0.000001)); + test(approxEqual(closestSeg2.z, -5.0, 0.000001)); + + // Test computePlaneSegmentIntersection(); + test(approxEqual(computePlaneSegmentIntersection(Vector3(-6, 3, 0), Vector3(6, 3, 0), 0.0, Vector3(-1, 0, 0)), 0.5, 0.000001)); + test(approxEqual(computePlaneSegmentIntersection(Vector3(-6, 3, 0), Vector3(6, 3, 0), 0.0, Vector3(1, 0, 0)), 0.5, 0.000001)); + test(approxEqual(computePlaneSegmentIntersection(Vector3(5, 12, 0), Vector3(5, 4, 0), 6, Vector3(0, 1, 0)), 0.75, 0.000001)); + test(approxEqual(computePlaneSegmentIntersection(Vector3(5, 4, 8), Vector3(9, 14, 8), 4, Vector3(0, 1, 0)), 0.0, 0.000001)); + decimal tIntersect = computePlaneSegmentIntersection(Vector3(5, 4, 0), Vector3(9, 4, 0), 4, Vector3(0, 1, 0)); + test(tIntersect < 0.0 && tIntersect > 1.0); + + // Test computeDistancePointToLineDistance() + test(approxEqual(computeDistancePointToLineDistance(Vector3(6, 0, 0), Vector3(14, 0, 0), Vector3(5, 3, 0)), 3.0, 0.000001)); + test(approxEqual(computeDistancePointToLineDistance(Vector3(6, -5, 0), Vector3(10, -5, 0), Vector3(4, 3, 0)), 8.0, 0.000001)); + test(approxEqual(computeDistancePointToLineDistance(Vector3(6, -5, 0), Vector3(10, -5, 0), Vector3(-43, 254, 0)), 259.0, 0.000001)); + test(approxEqual(computeDistancePointToLineDistance(Vector3(6, -5, 8), Vector3(10, -5, -5), Vector3(6, -5, 8)), 0.0, 0.000001)); + test(approxEqual(computeDistancePointToLineDistance(Vector3(6, -5, 8), Vector3(10, -5, -5), Vector3(10, -5, -5)), 0.0, 0.000001)); + } + + }; + +} + +#endif diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp index 8aae0145..3d692501 100644 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp @@ -1,415 +1,417 @@ -/******************************************************************************** -* 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. * -* * -********************************************************************************/ - -// Libraries -#include "CollisionDetectionScene.h" - -// Namespaces -using namespace openglframework; -using namespace collisiondetectionscene; - -// Constructor -CollisionDetectionScene::CollisionDetectionScene(const std::string& name) - : SceneDemo(name, SCENE_RADIUS, false), mMeshFolderPath("meshes/"), - mContactManager(mPhongShader, mMeshFolderPath), - mAreNormalsDisplayed(false), mVBOVertices(GL_ARRAY_BUFFER) { - - mSelectedShapeIndex = 0; - mIsContactPointsDisplayed = true; - mIsWireframeEnabled = true; - - // Compute the radius and the center of the scene - openglframework::Vector3 center(0, 0, 0); - - // Set the center of the scene - setScenePosition(center, SCENE_RADIUS); - - // Create the dynamics world for the physics simulation - mCollisionWorld = new rp3d::CollisionWorld(); - - // ---------- Sphere 1 ---------- // - openglframework::Vector3 position1(0, 0, 0); - - // Create a sphere and a corresponding collision body in the dynamics world - mSphere1 = new Sphere(6, position1, mCollisionWorld, mMeshFolderPath); - mAllShapes.push_back(mSphere1); - - // Set the color - mSphere1->setColor(mGreyColorDemo); - mSphere1->setSleepingColor(mRedColorDemo); - - // ---------- Sphere 2 ---------- // - openglframework::Vector3 position2(4, 0, 0); - - // Create a sphere and a corresponding collision body in the dynamics world - mSphere2 = new Sphere(4, position2, mCollisionWorld, mMeshFolderPath); - mAllShapes.push_back(mSphere2); - - // Set the color - mSphere2->setColor(mGreyColorDemo); - mSphere2->setSleepingColor(mRedColorDemo); - - // ---------- Cone ---------- // - //openglframework::Vector3 position4(0, 0, 0); - - // Create a cone and a corresponding collision body in the dynamics world - //mCone = new Cone(CONE_RADIUS, CONE_HEIGHT, position4, mCollisionWorld, - // mMeshFolderPath); - - // Set the color - //mCone->setColor(mGreyColorDemo); - //mCone->setSleepingColor(mRedColorDemo); - - // ---------- Cylinder ---------- // - //openglframework::Vector3 position5(0, 0, 0); - - // Create a cylinder and a corresponding collision body in the dynamics world - //mCylinder = new Cylinder(CYLINDER_RADIUS, CYLINDER_HEIGHT, position5, - // mCollisionWorld, mMeshFolderPath); - - // Set the color - //mCylinder->setColor(mGreyColorDemo); - //mCylinder->setSleepingColor(mRedColorDemo); - - // ---------- Capsule ---------- // - //openglframework::Vector3 position6(0, 0, 0); - - // Create a cylinder and a corresponding collision body in the dynamics world - //mCapsule = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, position6 , - // mCollisionWorld, mMeshFolderPath); - - // Set the color - //mCapsule->setColor(mGreyColorDemo); - //mCapsule->setSleepingColor(mRedColorDemo); - - // ---------- Convex Mesh ---------- // - //openglframework::Vector3 position7(0, 0, 0); - - // Create a convex mesh and a corresponding collision body in the dynamics world - //mConvexMesh = new ConvexMesh(position7, mCollisionWorld, mMeshFolderPath + "convexmesh.obj"); - - // Set the color - //mConvexMesh->setColor(mGreyColorDemo); - //mConvexMesh->setSleepingColor(mRedColorDemo); - - // ---------- Concave Mesh ---------- // - //openglframework::Vector3 position8(0, 0, 0); - - // Create a convex mesh and a corresponding collision body in the dynamics world - //mConcaveMesh = new ConcaveMesh(position8, mCollisionWorld, mMeshFolderPath + "city.obj"); - - // Set the color - //mConcaveMesh->setColor(mGreyColorDemo); - //mConcaveMesh->setSleepingColor(mRedColorDemo); - - // ---------- Heightfield ---------- // - //openglframework::Vector3 position9(0, 0, 0); - - // Create a convex mesh and a corresponding collision body in the dynamics world - //mHeightField = new HeightField(position9, mCollisionWorld); - - // Set the color - //mHeightField->setColor(mGreyColorDemo); - //mHeightField->setSleepingColor(mRedColorDemo); - - // Create the VBO and VAO to render the lines - createVBOAndVAO(mPhongShader); - - mAllShapes[mSelectedShapeIndex]->setColor(mBlueColorDemo); -} - -// Reset the scene -void CollisionDetectionScene::reset() { - -} - -// Destructor -CollisionDetectionScene::~CollisionDetectionScene() { - - // Destroy the shader - mPhongShader.destroy(); - - // Destroy the box rigid body from the dynamics world - //mCollisionWorld->destroyCollisionBody(mBox->getCollisionBody()); - //delete mBox; - - // Destroy the spheres - mCollisionWorld->destroyCollisionBody(mSphere1->getCollisionBody()); - delete mSphere1; - - mCollisionWorld->destroyCollisionBody(mSphere2->getCollisionBody()); - delete mSphere2; - - /* - // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mCone->getCollisionBody()); - delete mCone; - - // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mCylinder->getCollisionBody()); - - // Destroy the sphere - delete mCylinder; - - // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mCapsule->getCollisionBody()); - - // Destroy the sphere - delete mCapsule; - - // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mConvexMesh->getCollisionBody()); - - // Destroy the convex mesh - delete mConvexMesh; - - // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mDumbbell->getCollisionBody()); - - // Destroy the dumbbell - delete mDumbbell; - - // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mConcaveMesh->getCollisionBody()); - - // Destroy the convex mesh - delete mConcaveMesh; - - // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mHeightField->getCollisionBody()); - - // Destroy the convex mesh - delete mHeightField; - */ - - mContactManager.resetPoints(); - - // Destroy the static data for the visual contact points - VisualContactPoint::destroyStaticData(); - - // Destroy the collision world - delete mCollisionWorld; - - // Destroy the VBOs and VAO - mVBOVertices.destroy(); - mVAO.destroy(); -} - -// Update the physics world (take a simulation step) -void CollisionDetectionScene::updatePhysics() { - - -} - -// Take a step for the simulation -void CollisionDetectionScene::update() { - - mContactManager.resetPoints(); - - mCollisionWorld->testCollision(&mContactManager); - - SceneDemo::update(); -} - -// Render the scene -void CollisionDetectionScene::renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix) { - - /* - // Bind the VAO - mVAO.bind(); - - // Bind the shader - shader.bind(); - - mVBOVertices.bind(); - - // Set the model to camera matrix - const Matrix4 localToCameraMatrix = Matrix4::identity(); - shader.setMatrix4x4Uniform("localToWorldMatrix", localToCameraMatrix); - shader.setMatrix4x4Uniform("worldToCameraMatrix", worldToCameraMatrix); - - // Set the normal matrix (inverse transpose of the 3x3 upper-left sub matrix of the - // model-view matrix) - const openglframework::Matrix3 normalMatrix = - localToCameraMatrix.getUpperLeft3x3Matrix().getInverse().getTranspose(); - shader.setMatrix3x3Uniform("normalMatrix", normalMatrix, false); - - // Set the vertex color - openglframework::Vector4 color(1, 0, 0, 1); - shader.setVector4Uniform("vertexColor", color, false); - - // Get the location of shader attribute variables - GLint vertexPositionLoc = shader.getAttribLocation("vertexPosition"); - - glEnableVertexAttribArray(vertexPositionLoc); - glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)NULL); - - // Draw the lines - glDrawArrays(GL_LINES, 0, NB_RAYS); - - glDisableVertexAttribArray(vertexPositionLoc); - - mVBOVertices.unbind(); - - // Unbind the VAO - mVAO.unbind(); - - shader.unbind(); - */ - - // Render the shapes - if (mSphere1->getCollisionBody()->isActive()) mSphere1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - if (mSphere2->getCollisionBody()->isActive()) mSphere2->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - - /* - if (mBox->getCollisionBody()->isActive()) mBox->render(shader, worldToCameraMatrix); - if (mCone->getCollisionBody()->isActive()) mCone->render(shader, worldToCameraMatrix); - if (mCylinder->getCollisionBody()->isActive()) mCylinder->render(shader, worldToCameraMatrix); - if (mCapsule->getCollisionBody()->isActive()) mCapsule->render(shader, worldToCameraMatrix); - if (mConvexMesh->getCollisionBody()->isActive()) mConvexMesh->render(shader, worldToCameraMatrix); - if (mDumbbell->getCollisionBody()->isActive()) mDumbbell->render(shader, worldToCameraMatrix); - if (mConcaveMesh->getCollisionBody()->isActive()) mConcaveMesh->render(shader, worldToCameraMatrix); - if (mHeightField->getCollisionBody()->isActive()) mHeightField->render(shader, worldToCameraMatrix); - */ - - shader.unbind(); -} - -// Create the Vertex Buffer Objects used to render with OpenGL. -/// We create two VBOs (one for vertices and one for indices) -void CollisionDetectionScene::createVBOAndVAO(openglframework::Shader& shader) { - - // Bind the shader - shader.bind(); - - // Create the VBO for the vertices data - mVBOVertices.create(); - mVBOVertices.bind(); - size_t sizeVertices = mLinePoints.size() * sizeof(openglframework::Vector3); - mVBOVertices.copyDataIntoVBO(sizeVertices, &mLinePoints[0], GL_STATIC_DRAW); - mVBOVertices.unbind(); - - // Create the VAO for both VBOs - mVAO.create(); - mVAO.bind(); - - // Bind the VBO of vertices - mVBOVertices.bind(); - - // Unbind the VAO - mVAO.unbind(); - - // Unbind the shader - shader.unbind(); -} - -void CollisionDetectionScene::selectNextShape() { - - int previousIndex = mSelectedShapeIndex; - mSelectedShapeIndex++; - if (mSelectedShapeIndex >= mAllShapes.size()) { - mSelectedShapeIndex = 0; - } - - mAllShapes[previousIndex]->setColor(mGreyColorDemo); - mAllShapes[mSelectedShapeIndex]->setColor(mBlueColorDemo); -} - -// Called when a keyboard event occurs -bool CollisionDetectionScene::keyboardEvent(int key, int scancode, int action, int mods) { - - // If the space key has been pressed - if (key == GLFW_KEY_SPACE && action == GLFW_PRESS) { - selectNextShape(); - return true; - } - - float stepDist = 0.5f; - float stepAngle = 20 * (3.14f / 180.0f); - - if (key == GLFW_KEY_RIGHT && action == GLFW_PRESS) { - rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); - transform.setPosition(transform.getPosition() + rp3d::Vector3(stepDist, 0, 0)); - mAllShapes[mSelectedShapeIndex]->setTransform(transform); - } - else if (key == GLFW_KEY_LEFT && action == GLFW_PRESS) { - rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); - transform.setPosition(transform.getPosition() + rp3d::Vector3(-stepDist, 0, 0)); - mAllShapes[mSelectedShapeIndex]->setTransform(transform); - } - else if (key == GLFW_KEY_UP && action == GLFW_PRESS) { - rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); - transform.setPosition(transform.getPosition() + rp3d::Vector3(0, stepDist, 0)); - mAllShapes[mSelectedShapeIndex]->setTransform(transform); - } - else if (key == GLFW_KEY_DOWN && action == GLFW_PRESS) { - rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); - transform.setPosition(transform.getPosition() + rp3d::Vector3(0, -stepDist, 0)); - mAllShapes[mSelectedShapeIndex]->setTransform(transform); - } - else if (key == GLFW_KEY_Z && action == GLFW_PRESS) { - rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); - transform.setPosition(transform.getPosition() + rp3d::Vector3(0, 0, stepDist)); - mAllShapes[mSelectedShapeIndex]->setTransform(transform); - } - else if (key == GLFW_KEY_H && action == GLFW_PRESS) { - rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); - transform.setPosition(transform.getPosition() + rp3d::Vector3(0, 0, -stepDist)); - mAllShapes[mSelectedShapeIndex]->setTransform(transform); - } - else if (key == GLFW_KEY_A && action == GLFW_PRESS) { - rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); - transform.setOrientation(rp3d::Quaternion(0, stepAngle, 0) * transform.getOrientation()); - mAllShapes[mSelectedShapeIndex]->setTransform(transform); - } - else if (key == GLFW_KEY_D && action == GLFW_PRESS) { - rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); - transform.setOrientation(rp3d::Quaternion(0, -stepAngle, 0) * transform.getOrientation()); - mAllShapes[mSelectedShapeIndex]->setTransform(transform); - } - else if (key == GLFW_KEY_W && action == GLFW_PRESS) { - rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); - transform.setOrientation(rp3d::Quaternion(stepAngle, 0, 0) * transform.getOrientation()); - mAllShapes[mSelectedShapeIndex]->setTransform(transform); - } - else if (key == GLFW_KEY_S && action == GLFW_PRESS) { - rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); - transform.setOrientation(rp3d::Quaternion(-stepAngle, 0, 0) * transform.getOrientation()); - mAllShapes[mSelectedShapeIndex]->setTransform(transform); - } - else if (key == GLFW_KEY_F && action == GLFW_PRESS) { - rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); - transform.setOrientation(rp3d::Quaternion(0, 0, stepAngle) * transform.getOrientation()); - mAllShapes[mSelectedShapeIndex]->setTransform(transform); - } - else if (key == GLFW_KEY_G && action == GLFW_PRESS) { - rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); - transform.setOrientation(rp3d::Quaternion(0, 0, -stepAngle) * transform.getOrientation()); - mAllShapes[mSelectedShapeIndex]->setTransform(transform); - } - - return false; -} +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "CollisionDetectionScene.h" + +// Namespaces +using namespace openglframework; +using namespace collisiondetectionscene; + +// Constructor +CollisionDetectionScene::CollisionDetectionScene(const std::string& name) + : SceneDemo(name, SCENE_RADIUS, false), mMeshFolderPath("meshes/"), + mContactManager(mPhongShader, mMeshFolderPath), + mAreNormalsDisplayed(false), mVBOVertices(GL_ARRAY_BUFFER) { + + mSelectedShapeIndex = 0; + mIsContactPointsDisplayed = true; + mIsWireframeEnabled = true; + + // Compute the radius and the center of the scene + openglframework::Vector3 center(0, 0, 0); + + // Set the center of the scene + setScenePosition(center, SCENE_RADIUS); + + // Create the dynamics world for the physics simulation + mCollisionWorld = new rp3d::CollisionWorld(); + + // ---------- Sphere 1 ---------- // + openglframework::Vector3 position1(0, 0, 0); + + // Create a sphere and a corresponding collision body in the dynamics world + mSphere1 = new Sphere(6, position1, mCollisionWorld, mMeshFolderPath); + mAllShapes.push_back(mSphere1); + + // Set the color + mSphere1->setColor(mGreyColorDemo); + mSphere1->setSleepingColor(mRedColorDemo); + + // ---------- Sphere 2 ---------- // + openglframework::Vector3 position2(4, 0, 0); + + // Create a sphere and a corresponding collision body in the dynamics world + mSphere2 = new Sphere(4, position2, mCollisionWorld, mMeshFolderPath); + mAllShapes.push_back(mSphere2); + + // Set the color + mSphere2->setColor(mGreyColorDemo); + mSphere2->setSleepingColor(mRedColorDemo); + + // ---------- Capsule 1 ---------- // + openglframework::Vector3 position3(4, 0, 0); + + // Create a cylinder and a corresponding collision body in the dynamics world + mCapsule1 = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, position3, mCollisionWorld, mMeshFolderPath); + mAllShapes.push_back(mCapsule1); + + // Set the color + mCapsule1->setColor(mGreyColorDemo); + mCapsule1->setSleepingColor(mRedColorDemo); + + // ---------- Cone ---------- // + //openglframework::Vector3 position4(0, 0, 0); + + // Create a cone and a corresponding collision body in the dynamics world + //mCone = new Cone(CONE_RADIUS, CONE_HEIGHT, position4, mCollisionWorld, + // mMeshFolderPath); + + // Set the color + //mCone->setColor(mGreyColorDemo); + //mCone->setSleepingColor(mRedColorDemo); + + // ---------- Cylinder ---------- // + //openglframework::Vector3 position5(0, 0, 0); + + // Create a cylinder and a corresponding collision body in the dynamics world + //mCylinder = new Cylinder(CYLINDER_RADIUS, CYLINDER_HEIGHT, position5, + // mCollisionWorld, mMeshFolderPath); + + // Set the color + //mCylinder->setColor(mGreyColorDemo); + //mCylinder->setSleepingColor(mRedColorDemo); + + + // ---------- Convex Mesh ---------- // + //openglframework::Vector3 position7(0, 0, 0); + + // Create a convex mesh and a corresponding collision body in the dynamics world + //mConvexMesh = new ConvexMesh(position7, mCollisionWorld, mMeshFolderPath + "convexmesh.obj"); + + // Set the color + //mConvexMesh->setColor(mGreyColorDemo); + //mConvexMesh->setSleepingColor(mRedColorDemo); + + // ---------- Concave Mesh ---------- // + //openglframework::Vector3 position8(0, 0, 0); + + // Create a convex mesh and a corresponding collision body in the dynamics world + //mConcaveMesh = new ConcaveMesh(position8, mCollisionWorld, mMeshFolderPath + "city.obj"); + + // Set the color + //mConcaveMesh->setColor(mGreyColorDemo); + //mConcaveMesh->setSleepingColor(mRedColorDemo); + + // ---------- Heightfield ---------- // + //openglframework::Vector3 position9(0, 0, 0); + + // Create a convex mesh and a corresponding collision body in the dynamics world + //mHeightField = new HeightField(position9, mCollisionWorld); + + // Set the color + //mHeightField->setColor(mGreyColorDemo); + //mHeightField->setSleepingColor(mRedColorDemo); + + // Create the VBO and VAO to render the lines + //createVBOAndVAO(mPhongShader); + + mAllShapes[mSelectedShapeIndex]->setColor(mBlueColorDemo); +} + +// Reset the scene +void CollisionDetectionScene::reset() { + +} + +// Destructor +CollisionDetectionScene::~CollisionDetectionScene() { + + // Destroy the shader + mPhongShader.destroy(); + + // Destroy the box rigid body from the dynamics world + //mCollisionWorld->destroyCollisionBody(mBox->getCollisionBody()); + //delete mBox; + + // Destroy the spheres + mCollisionWorld->destroyCollisionBody(mSphere1->getCollisionBody()); + delete mSphere1; + + mCollisionWorld->destroyCollisionBody(mSphere2->getCollisionBody()); + delete mSphere2; + + /* + // Destroy the corresponding rigid body from the dynamics world + mCollisionWorld->destroyCollisionBody(mCone->getCollisionBody()); + delete mCone; + + // Destroy the corresponding rigid body from the dynamics world + mCollisionWorld->destroyCollisionBody(mCylinder->getCollisionBody()); + + // Destroy the sphere + delete mCylinder; + + // Destroy the corresponding rigid body from the dynamics world + mCollisionWorld->destroyCollisionBody(mCapsule->getCollisionBody()); + + // Destroy the sphere + delete mCapsule; + + // Destroy the corresponding rigid body from the dynamics world + mCollisionWorld->destroyCollisionBody(mConvexMesh->getCollisionBody()); + + // Destroy the convex mesh + delete mConvexMesh; + + // Destroy the corresponding rigid body from the dynamics world + mCollisionWorld->destroyCollisionBody(mDumbbell->getCollisionBody()); + + // Destroy the dumbbell + delete mDumbbell; + + // Destroy the corresponding rigid body from the dynamics world + mCollisionWorld->destroyCollisionBody(mConcaveMesh->getCollisionBody()); + + // Destroy the convex mesh + delete mConcaveMesh; + + // Destroy the corresponding rigid body from the dynamics world + mCollisionWorld->destroyCollisionBody(mHeightField->getCollisionBody()); + + // Destroy the convex mesh + delete mHeightField; + */ + + mContactManager.resetPoints(); + + // Destroy the static data for the visual contact points + VisualContactPoint::destroyStaticData(); + + // Destroy the collision world + delete mCollisionWorld; + + // Destroy the VBOs and VAO + mVBOVertices.destroy(); + mVAO.destroy(); +} + +// Update the physics world (take a simulation step) +void CollisionDetectionScene::updatePhysics() { + + +} + +// Take a step for the simulation +void CollisionDetectionScene::update() { + + mContactManager.resetPoints(); + + mCollisionWorld->testCollision(&mContactManager); + + SceneDemo::update(); +} + +// Render the scene +void CollisionDetectionScene::renderSinglePass(openglframework::Shader& shader, + const openglframework::Matrix4& worldToCameraMatrix) { + + /* + // Bind the VAO + mVAO.bind(); + + // Bind the shader + shader.bind(); + + mVBOVertices.bind(); + + // Set the model to camera matrix + const Matrix4 localToCameraMatrix = Matrix4::identity(); + shader.setMatrix4x4Uniform("localToWorldMatrix", localToCameraMatrix); + shader.setMatrix4x4Uniform("worldToCameraMatrix", worldToCameraMatrix); + + // Set the normal matrix (inverse transpose of the 3x3 upper-left sub matrix of the + // model-view matrix) + const openglframework::Matrix3 normalMatrix = + localToCameraMatrix.getUpperLeft3x3Matrix().getInverse().getTranspose(); + shader.setMatrix3x3Uniform("normalMatrix", normalMatrix, false); + + // Set the vertex color + openglframework::Vector4 color(1, 0, 0, 1); + shader.setVector4Uniform("vertexColor", color, false); + + // Get the location of shader attribute variables + GLint vertexPositionLoc = shader.getAttribLocation("vertexPosition"); + + glEnableVertexAttribArray(vertexPositionLoc); + glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)NULL); + + // Draw the lines + glDrawArrays(GL_LINES, 0, NB_RAYS); + + glDisableVertexAttribArray(vertexPositionLoc); + + mVBOVertices.unbind(); + + // Unbind the VAO + mVAO.unbind(); + + shader.unbind(); + */ + + // Render the shapes + if (mSphere1->getCollisionBody()->isActive()) mSphere1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + if (mSphere2->getCollisionBody()->isActive()) mSphere2->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + if (mCapsule1->getCollisionBody()->isActive()) mCapsule1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + + /* + if (mBox->getCollisionBody()->isActive()) mBox->render(shader, worldToCameraMatrix); + if (mCone->getCollisionBody()->isActive()) mCone->render(shader, worldToCameraMatrix); + if (mCylinder->getCollisionBody()->isActive()) mCylinder->render(shader, worldToCameraMatrix); + if (mCapsule->getCollisionBody()->isActive()) mCapsule->render(shader, worldToCameraMatrix); + if (mConvexMesh->getCollisionBody()->isActive()) mConvexMesh->render(shader, worldToCameraMatrix); + if (mDumbbell->getCollisionBody()->isActive()) mDumbbell->render(shader, worldToCameraMatrix); + if (mConcaveMesh->getCollisionBody()->isActive()) mConcaveMesh->render(shader, worldToCameraMatrix); + if (mHeightField->getCollisionBody()->isActive()) mHeightField->render(shader, worldToCameraMatrix); + */ + + shader.unbind(); +} + +// Create the Vertex Buffer Objects used to render with OpenGL. +/// We create two VBOs (one for vertices and one for indices) +void CollisionDetectionScene::createVBOAndVAO(openglframework::Shader& shader) { + + // Bind the shader + shader.bind(); + + // Create the VBO for the vertices data + mVBOVertices.create(); + mVBOVertices.bind(); + size_t sizeVertices = mLinePoints.size() * sizeof(openglframework::Vector3); + mVBOVertices.copyDataIntoVBO(sizeVertices, &mLinePoints[0], GL_STATIC_DRAW); + mVBOVertices.unbind(); + + // Create the VAO for both VBOs + mVAO.create(); + mVAO.bind(); + + // Bind the VBO of vertices + mVBOVertices.bind(); + + // Unbind the VAO + mVAO.unbind(); + + // Unbind the shader + shader.unbind(); +} + +void CollisionDetectionScene::selectNextShape() { + + int previousIndex = mSelectedShapeIndex; + mSelectedShapeIndex++; + if (mSelectedShapeIndex >= mAllShapes.size()) { + mSelectedShapeIndex = 0; + } + + mAllShapes[previousIndex]->setColor(mGreyColorDemo); + mAllShapes[mSelectedShapeIndex]->setColor(mBlueColorDemo); +} + +// Called when a keyboard event occurs +bool CollisionDetectionScene::keyboardEvent(int key, int scancode, int action, int mods) { + + // If the space key has been pressed + if (key == GLFW_KEY_SPACE && action == GLFW_PRESS) { + selectNextShape(); + return true; + } + + float stepDist = 0.5f; + float stepAngle = 20 * (3.14f / 180.0f); + + if (key == GLFW_KEY_RIGHT && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setPosition(transform.getPosition() + rp3d::Vector3(stepDist, 0, 0)); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_LEFT && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setPosition(transform.getPosition() + rp3d::Vector3(-stepDist, 0, 0)); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_UP && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setPosition(transform.getPosition() + rp3d::Vector3(0, stepDist, 0)); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_DOWN && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setPosition(transform.getPosition() + rp3d::Vector3(0, -stepDist, 0)); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_Z && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setPosition(transform.getPosition() + rp3d::Vector3(0, 0, stepDist)); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_H && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setPosition(transform.getPosition() + rp3d::Vector3(0, 0, -stepDist)); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_A && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setOrientation(rp3d::Quaternion(0, stepAngle, 0) * transform.getOrientation()); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_D && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setOrientation(rp3d::Quaternion(0, -stepAngle, 0) * transform.getOrientation()); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_W && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setOrientation(rp3d::Quaternion(stepAngle, 0, 0) * transform.getOrientation()); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_S && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setOrientation(rp3d::Quaternion(-stepAngle, 0, 0) * transform.getOrientation()); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_F && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setOrientation(rp3d::Quaternion(0, 0, stepAngle) * transform.getOrientation()); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + else if (key == GLFW_KEY_G && action == GLFW_PRESS) { + rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); + transform.setOrientation(rp3d::Quaternion(0, 0, -stepAngle) * transform.getOrientation()); + mAllShapes[mSelectedShapeIndex]->setTransform(transform); + } + + return false; +} diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.h b/testbed/scenes/collisiondetection/CollisionDetectionScene.h index d3a7de00..323b9c34 100644 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.h +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.h @@ -1,231 +1,235 @@ -/******************************************************************************** -* 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 COLLISION_DETECTION_SCENE_H -#define COLLISION_DETECTION_SCENE_H - -// Libraries -#include -#include "openglframework.h" -#include "reactphysics3d.h" -#include "SceneDemo.h" -#include "Sphere.h" -#include "Box.h" -#include "Capsule.h" -#include "Line.h" -#include "ConvexMesh.h" -#include "ConcaveMesh.h" -#include "HeightField.h" -#include "Dumbbell.h" -#include "VisualContactPoint.h" - -namespace collisiondetectionscene { - -// Constants -const float SCENE_RADIUS = 30.0f; -const openglframework::Vector3 BOX_SIZE(4, 2, 1); -const float SPHERE_RADIUS = 3.0f; -const float CONE_RADIUS = 3.0f; -const float CONE_HEIGHT = 5.0f; -const float CYLINDER_RADIUS = 3.0f; -const float CYLINDER_HEIGHT = 5.0f; -const float CAPSULE_RADIUS = 3.0f; -const float CAPSULE_HEIGHT = 5.0f; -const float DUMBBELL_HEIGHT = 5.0f; -const int NB_RAYS = 100; -const float RAY_LENGTH = 30.0f; -const int NB_BODIES = 9; - -// Raycast manager -class ContactManager : public rp3d::CollisionCallback { - - private: - - /// All the visual contact points - std::vector mContactPoints; - - /// All the normals at contact points - std::vector mNormals; - - /// Contact point mesh folder path - std::string mMeshFolderPath; - - public: - - ContactManager(openglframework::Shader& shader, - const std::string& meshFolderPath) - : mMeshFolderPath(meshFolderPath) { - - } - - /// This method will be called for each reported contact point - virtual void notifyContact(const CollisionCallbackInfo& collisionCallbackInfo) override { - - rp3d::Vector3 point1 = collisionCallbackInfo.contactPoint.localPoint1; - point1 = collisionCallbackInfo.proxyShape1->getLocalToWorldTransform() * point1; - openglframework::Vector3 position1(point1.x, point1.y, point1.z); - mContactPoints.push_back(ContactPoint(position1)); - - rp3d::Vector3 point2 = collisionCallbackInfo.contactPoint.localPoint2; - point2 = collisionCallbackInfo.proxyShape2->getLocalToWorldTransform() * point2; - openglframework::Vector3 position2(point2.x, point2.y, point2.z); - mContactPoints.push_back(ContactPoint(position2)); - - // Create a line to display the normal at hit point - rp3d::Vector3 n = collisionCallbackInfo.contactPoint.normal; - openglframework::Vector3 normal(n.x, n.y, n.z); - Line* normalLine = new Line(position1, position1 + normal); - mNormals.push_back(normalLine); - } - - void resetPoints() { - - mContactPoints.clear(); - - // Destroy all the normals - for (std::vector::iterator it = mNormals.begin(); - it != mNormals.end(); ++it) { - delete (*it); - } - mNormals.clear(); - } - - std::vector getContactPoints() const { - return mContactPoints; - } -}; - -// Class CollisionDetectionScene -class CollisionDetectionScene : public SceneDemo { - - private : - - // -------------------- Attributes -------------------- // - - /// Contact point mesh folder path - std::string mMeshFolderPath; - - /// Contact manager - ContactManager mContactManager; - - bool mAreNormalsDisplayed; - - /// All objects on the scene - //Box* mBox; - Sphere* mSphere1; - Sphere* mSphere2; - //Cone* mCone; - //Cylinder* mCylinder; - //Capsule* mCapsule; - //ConvexMesh* mConvexMesh; - //Dumbbell* mDumbbell; - //ConcaveMesh* mConcaveMesh; - //HeightField* mHeightField; - - std::vector mAllShapes; - - int mSelectedShapeIndex; - - /// Collision world used for the physics simulation - rp3d::CollisionWorld* mCollisionWorld; - - /// All the points to render the lines - std::vector mLinePoints; - - /// Vertex Buffer Object for the vertices data - openglframework::VertexBufferObject mVBOVertices; - - /// Vertex Array Object for the vertex data - openglframework::VertexArrayObject mVAO; - - /// Create the Vertex Buffer Objects used to render with OpenGL. - void createVBOAndVAO(openglframework::Shader& shader); - - /// Select the next shape - void selectNextShape(); - - public: - - // -------------------- Methods -------------------- // - - /// Constructor - CollisionDetectionScene(const std::string& name); - - /// Destructor - virtual ~CollisionDetectionScene() override; - - /// Update the physics world (take a simulation step) - /// Can be called several times per frame - virtual void updatePhysics() override; - - /// Take a step for the simulation - virtual void update() override; - - /// Render the scene in a single pass - virtual void renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix) override; - - /// Reset the scene - virtual void reset() override; - - /// Display or not the surface normals at hit points - void showHideNormals(); - - /// Called when a keyboard event occurs - virtual bool keyboardEvent(int key, int scancode, int action, int mods) override; - - /// Enabled/Disable the shadow mapping - virtual void setIsShadowMappingEnabled(bool isShadowMappingEnabled) override; - - /// Display/Hide the contact points - virtual void setIsContactPointsDisplayed(bool display) override; - - /// Return all the contact points of the scene - virtual std::vector getContactPoints() const override; -}; - -// Display or not the surface normals at hit points -inline void CollisionDetectionScene::showHideNormals() { - mAreNormalsDisplayed = !mAreNormalsDisplayed; -} - -// Enabled/Disable the shadow mapping -inline void CollisionDetectionScene::setIsShadowMappingEnabled(bool isShadowMappingEnabled) { - SceneDemo::setIsShadowMappingEnabled(false); -} - -// Display/Hide the contact points -inline void CollisionDetectionScene::setIsContactPointsDisplayed(bool display) { - SceneDemo::setIsContactPointsDisplayed(true); -} - -// Return all the contact points of the scene -inline std::vector CollisionDetectionScene::getContactPoints() const { - return mContactManager.getContactPoints(); -} - -} - -#endif +/******************************************************************************** +* 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 COLLISION_DETECTION_SCENE_H +#define COLLISION_DETECTION_SCENE_H + +// Libraries +#include +#include "openglframework.h" +#include "reactphysics3d.h" +#include "SceneDemo.h" +#include "Sphere.h" +#include "Box.h" +#include "Cone.h" +#include "Cylinder.h" +#include "Capsule.h" +#include "Line.h" +#include "ConvexMesh.h" +#include "ConcaveMesh.h" +#include "HeightField.h" +#include "Dumbbell.h" +#include "VisualContactPoint.h" + +namespace collisiondetectionscene { + +// Constants +const float SCENE_RADIUS = 30.0f; +const openglframework::Vector3 BOX_SIZE(4, 2, 1); +const float SPHERE_RADIUS = 3.0f; +const float CONE_RADIUS = 3.0f; +const float CONE_HEIGHT = 5.0f; +const float CYLINDER_RADIUS = 3.0f; +const float CYLINDER_HEIGHT = 5.0f; +const float CAPSULE_RADIUS = 3.0f; +const float CAPSULE_HEIGHT = 5.0f; +const float DUMBBELL_HEIGHT = 5.0f; +const int NB_RAYS = 100; +const float RAY_LENGTH = 30.0f; +const int NB_BODIES = 9; + +// Raycast manager +class ContactManager : public rp3d::CollisionCallback { + + private: + + /// All the visual contact points + std::vector mContactPoints; + + /// All the normals at contact points + std::vector mNormals; + + /// Contact point mesh folder path + std::string mMeshFolderPath; + + public: + + ContactManager(openglframework::Shader& shader, + const std::string& meshFolderPath) + : mMeshFolderPath(meshFolderPath) { + + } + + /// This method will be called for each reported contact point + virtual void notifyContact(const CollisionCallbackInfo& collisionCallbackInfo) override { + + rp3d::Vector3 point1 = collisionCallbackInfo.contactPoint.localPoint1; + point1 = collisionCallbackInfo.proxyShape1->getLocalToWorldTransform() * point1; + openglframework::Vector3 position1(point1.x, point1.y, point1.z); + mContactPoints.push_back(ContactPoint(position1)); + + rp3d::Vector3 point2 = collisionCallbackInfo.contactPoint.localPoint2; + point2 = collisionCallbackInfo.proxyShape2->getLocalToWorldTransform() * point2; + openglframework::Vector3 position2(point2.x, point2.y, point2.z); + mContactPoints.push_back(ContactPoint(position2)); + + // Create a line to display the normal at hit point + rp3d::Vector3 n = collisionCallbackInfo.contactPoint.normal; + openglframework::Vector3 normal(n.x, n.y, n.z); + Line* normalLine = new Line(position1, position1 + normal); + mNormals.push_back(normalLine); + } + + void resetPoints() { + + mContactPoints.clear(); + + // Destroy all the normals + for (std::vector::iterator it = mNormals.begin(); + it != mNormals.end(); ++it) { + delete (*it); + } + mNormals.clear(); + } + + std::vector getContactPoints() const { + return mContactPoints; + } +}; + +// Class CollisionDetectionScene +class CollisionDetectionScene : public SceneDemo { + + private : + + // -------------------- Attributes -------------------- // + + /// Contact point mesh folder path + std::string mMeshFolderPath; + + /// Contact manager + ContactManager mContactManager; + + bool mAreNormalsDisplayed; + + /// All objects on the scene + //Box* mBox; + Sphere* mSphere1; + Sphere* mSphere2; + Capsule* mCapsule1; + Capsule* mCapsule2; + //Cone* mCone; + //Cylinder* mCylinder; + //Capsule* mCapsule; + //ConvexMesh* mConvexMesh; + //Dumbbell* mDumbbell; + //ConcaveMesh* mConcaveMesh; + //HeightField* mHeightField; + + std::vector mAllShapes; + + int mSelectedShapeIndex; + + /// Collision world used for the physics simulation + rp3d::CollisionWorld* mCollisionWorld; + + /// All the points to render the lines + std::vector mLinePoints; + + /// Vertex Buffer Object for the vertices data + openglframework::VertexBufferObject mVBOVertices; + + /// Vertex Array Object for the vertex data + openglframework::VertexArrayObject mVAO; + + /// Create the Vertex Buffer Objects used to render with OpenGL. + void createVBOAndVAO(openglframework::Shader& shader); + + /// Select the next shape + void selectNextShape(); + + public: + + // -------------------- Methods -------------------- // + + /// Constructor + CollisionDetectionScene(const std::string& name); + + /// Destructor + virtual ~CollisionDetectionScene() override; + + /// Update the physics world (take a simulation step) + /// Can be called several times per frame + virtual void updatePhysics() override; + + /// Take a step for the simulation + virtual void update() override; + + /// Render the scene in a single pass + virtual void renderSinglePass(openglframework::Shader& shader, + const openglframework::Matrix4& worldToCameraMatrix) override; + + /// Reset the scene + virtual void reset() override; + + /// Display or not the surface normals at hit points + void showHideNormals(); + + /// Called when a keyboard event occurs + virtual bool keyboardEvent(int key, int scancode, int action, int mods) override; + + /// Enabled/Disable the shadow mapping + virtual void setIsShadowMappingEnabled(bool isShadowMappingEnabled) override; + + /// Display/Hide the contact points + virtual void setIsContactPointsDisplayed(bool display) override; + + /// Return all the contact points of the scene + virtual std::vector getContactPoints() const override; +}; + +// Display or not the surface normals at hit points +inline void CollisionDetectionScene::showHideNormals() { + mAreNormalsDisplayed = !mAreNormalsDisplayed; +} + +// Enabled/Disable the shadow mapping +inline void CollisionDetectionScene::setIsShadowMappingEnabled(bool isShadowMappingEnabled) { + SceneDemo::setIsShadowMappingEnabled(false); +} + +// Display/Hide the contact points +inline void CollisionDetectionScene::setIsContactPointsDisplayed(bool display) { + SceneDemo::setIsContactPointsDisplayed(true); +} + +// Return all the contact points of the scene +inline std::vector CollisionDetectionScene::getContactPoints() const { + return mContactManager.getContactPoints(); +} + +} + +#endif From 7a656aedc93e7931b0afca9983696e8f754f7a71 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 13 Feb 2017 22:38:47 +0100 Subject: [PATCH 057/248] Working on HalfEdgeStructure --- src/collision/HalfEdgeStructure.cpp | 42 +++++----- src/collision/HalfEdgeStructure.h | 6 +- src/collision/PolyhedronMesh.h | 2 +- .../narrowphase/DefaultCollisionDispatch.cpp | 11 ++- .../narrowphase/DefaultCollisionDispatch.h | 9 ++- .../narrowphase/GJK/GJKAlgorithm.cpp | 1 + .../narrowphase/SphereVsCapsuleAlgorithm.cpp | 80 +++++++++++++++++++ .../narrowphase/SphereVsCapsuleAlgorithm.h | 71 ++++++++++++++++ src/collision/shapes/CollisionShape.h | 2 +- src/mathematics/mathematics_functions.cpp | 6 +- src/reactphysics3d.h | 1 + .../CollisionDetectionScene.h | 2 - 12 files changed, 197 insertions(+), 36 deletions(-) create mode 100644 src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp create mode 100644 src/collision/narrowphase/SphereVsCapsuleAlgorithm.h diff --git a/src/collision/HalfEdgeStructure.cpp b/src/collision/HalfEdgeStructure.cpp index 16a79704..dba49c15 100644 --- a/src/collision/HalfEdgeStructure.cpp +++ b/src/collision/HalfEdgeStructure.cpp @@ -30,13 +30,14 @@ using namespace reactphysics3d; // Initialize the structure -void HalfEdgeStructure::init(std::vector vertices, std::vector> faces) { +void HalfEdgeStructure::init(std::vector vertices, std::vector> faces) { using edgeKey = std::pair; std::map edges; std::map nextEdges; std::map mapEdgeToStartVertex; + std::map mapEdgeToIndex; // For each vertices for (uint v=0; v vertices, std::vector vertices, std::vector= 1) { - nextEdges.insert(currentFaceEdges[currentFaceEdges.size() - 1], pairV1V2); + else if (v >= 1) { + nextEdges.insert(std::make_pair(currentFaceEdges[currentFaceEdges.size() - 1], pairV1V2)); } - if (e == (faceVertices.size() - 1)) { - nextEdges.insert(pairV1V2, firstEdgeKey); + if (v == (faceVertices.size() - 1)) { + nextEdges.insert(std::make_pair(pairV1V2, firstEdgeKey)); } - edges.insert(pairV1V2, edge); + edges.insert(std::make_pair(pairV1V2, edge)); const edgeKey pairV2V1 = std::make_pair(v2Index, v1Index); - mapEdgeToStartVertex.insert(pairV1V2, v1Index); - mapEdgeToStartVertex.insert(pairV2V1, v2Index); + mapEdgeToStartVertex.insert(std::make_pair(pairV1V2, v1Index)); + mapEdgeToStartVertex.insert(std::make_pair(pairV2V1, v2Index)); auto itEdge = edges.find(pairV2V1); if (itEdge != edges.end()) { @@ -93,24 +94,25 @@ void HalfEdgeStructure::init(std::vector vertices, std::vectorsecond.twinEdgeIndex = edgeIndex + 1; - itEdge->second.nextEdgeIndex = nextEdges[pairV2V1]; edge.twinEdgeIndex = edgeIndex; - edge.nextEdgeIndex = edges[nextEdges[pairV1V2]].; mVertices[v1Index].edgeIndex = edgeIndex; mVertices[v2Index].edgeIndex = edgeIndex + 1; + mapEdgeToIndex.insert(std::make_pair(pairV1V2, edgeIndex + 1)); + mapEdgeToIndex.insert(std::make_pair(pairV2V1, edgeIndex)); + face.edgeIndex = edgeIndex + 1; } currentFaceEdges.push_back(pairV1V2); } + } - // For each edge of the face - for (uint e=0; e < currentFaceEdges.size(); e++) { - Edge& edge = currentFaceEdges[e]; - edge.nextEdgeIndex = - } + // Set next edges + std::map::iterator it; + for (it = edges.begin(); it != edges.end(); ++it) { + it->second.nextEdgeIndex = mapEdgeToIndex[nextEdges[it->first]]; } } diff --git a/src/collision/HalfEdgeStructure.h b/src/collision/HalfEdgeStructure.h index 71b549d0..4a3f67ed 100644 --- a/src/collision/HalfEdgeStructure.h +++ b/src/collision/HalfEdgeStructure.h @@ -54,11 +54,11 @@ class HalfEdgeStructure { }; struct Vertex { - const Vector3 point; // Coordinates of the vertex + Vector3 point; // Coordinates of the vertex uint edgeIndex; // Index of one edge emanting from this vertex /// Constructor - Vertex(const Vector3& p) { point = p;} + Vertex(Vector3& p) { point = p;} }; private: @@ -81,7 +81,7 @@ class HalfEdgeStructure { ~HalfEdgeStructure() = default; /// Initialize the structure - void init(std::vector vertices, std::vector> faces); + void init(std::vector vertices, std::vector> faces); /// Return the number of faces uint getNbFaces() const; diff --git a/src/collision/PolyhedronMesh.h b/src/collision/PolyhedronMesh.h index 8f0e8abf..c7182bd8 100644 --- a/src/collision/PolyhedronMesh.h +++ b/src/collision/PolyhedronMesh.h @@ -49,7 +49,7 @@ class PolyhedronMesh { bool mIsFinalized; /// All the vertices - std::vector mVertices; + std::vector mVertices; /// All the indexes of the face vertices std::vector> mFaces; diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.cpp b/src/collision/narrowphase/DefaultCollisionDispatch.cpp index 4864dbbe..88d4b9b2 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.cpp +++ b/src/collision/narrowphase/DefaultCollisionDispatch.cpp @@ -33,7 +33,6 @@ using namespace reactphysics3d; // use between two types of collision shapes. NarrowPhaseAlgorithm* DefaultCollisionDispatch::selectAlgorithm(int type1, int type2) { - CollisionShapeType shape1Type = static_cast(type1); CollisionShapeType shape2Type = static_cast(type2); @@ -45,9 +44,13 @@ NarrowPhaseAlgorithm* DefaultCollisionDispatch::selectAlgorithm(int type1, int t if (shape1Type == CollisionShapeType::SPHERE && shape2Type == CollisionShapeType::SPHERE) { return &mSphereVsSphereAlgorithm; } - // Sphere vs Convex shapes (convex Mesh, BoxShape) algorithm - if (shape1Type == CollisionShapeType::SPHERE && CollisionShape::isConvex(shape2Type)) { - return &mSphereVsConvexMeshAlgorithm; + // Sphere vs Capsule algorithm + if (shape1Type == CollisionShapeType::CAPSULE && shape2Type == CollisionShapeType::SPHERE) { + return &mSphereVsCapsuleAlgorithm; + } + // Capsule vs Capsule algorithm + if (shape1Type == CollisionShapeType::CAPSULE && shape2Type == CollisionShapeType::CAPSULE) { + return &mCapsuleVsCapsuleAlgorithm; } return nullptr; diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.h b/src/collision/narrowphase/DefaultCollisionDispatch.h index 07a819c0..65e05497 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.h +++ b/src/collision/narrowphase/DefaultCollisionDispatch.h @@ -31,6 +31,8 @@ #include "ConcaveVsConvexAlgorithm.h" #include "SphereVsSphereAlgorithm.h" #include "SphereVsConvexMeshAlgorithm.h" +#include "SphereVsCapsuleAlgorithm.h" +#include "CapsuleVsCapsuleAlgorithm.h" #include "GJK/GJKAlgorithm.h" namespace reactphysics3d { @@ -51,8 +53,11 @@ class DefaultCollisionDispatch : public CollisionDispatch { /// Sphere vs Convex Mesh collision algorithm SphereVsConvexMeshAlgorithm mSphereVsConvexMeshAlgorithm; - /// GJK Algorithm - GJKAlgorithm mGJKAlgorithm; + /// Sphere vs Capsule collision algorithm + SphereVsCapsuleAlgorithm mSphereVsCapsuleAlgorithm; + + /// Capsule vs Capsule collision algorithm + CapsuleVsCapsuleAlgorithm mCapsuleVsCapsuleAlgorithm; public: diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp index cd84f5a0..4ea55ba4 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp @@ -26,6 +26,7 @@ // Libraries #include "GJKAlgorithm.h" #include "constraint/ContactPoint.h" +#include "engine/OverlappingPair.h" #include "configuration.h" #include "engine/Profiler.h" #include diff --git a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp new file mode 100644 index 00000000..24cb4e96 --- /dev/null +++ b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp @@ -0,0 +1,80 @@ +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "SphereVsCapsuleAlgorithm.h" +#include "collision/shapes/SphereShape.h" +#include "collision/shapes/CapsuleShape.h" + +// We want to use the ReactPhysics3D namespace +using namespace reactphysics3d; + +bool SphereVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactPointInfo& contactPointInfo) { + + // Get the collision shapes + const SphereShape* sphereShape = static_cast(narrowPhaseInfo->collisionShape1); + const CapsuleShape* capsuleShape = static_cast(narrowPhaseInfo->collisionShape2); + + // Get the transform from sphere local-space to capsule local-space + const Transform sphereToCapsuleSpaceTransform = narrowPhaseInfo->shape1ToWorldTransform * narrowPhaseInfo->shape2ToWorldTransform.getInverse(); + + // Transform the center of the sphere into the local-space of the capsule shape + const Vector3 sphereCenter = sphereToCapsuleSpaceTransform.getPosition(); + + // Compute the end-points of the inner segment of the capsule + const Vector3 capsuleSegA(0, -capsuleShape->getHeight() * decimal(0.5), 0); + const Vector3 capsuleSegB(0, capsuleShape->getHeight() * decimal(0.5), 0); + + // Compute the point on the inner capsule segment that is the closes to center of sphere + const Vector3 closestPointOnSegment = computeClosestPointOnSegment(capsuleSegA, capsuleSegB, sphereCenter); + + // Compute the distance between the sphere center and the closest point on the segment + Vector3 sphereCenterToSegment = (closestPointOnSegment - sphereCenter); + const decimal sphereSegmentDistanceSquare = sphereCenterToSegment.lengthSquare(); + + // Compute the sum of the radius of the sphere and the capsule (virtual sphere) + decimal sumRadius = sphereShape->getRadius() + capsuleShape->getRadius(); + + // If the collision shapes overlap + if (sphereSegmentDistanceSquare <= sumRadius * sumRadius && sphereSegmentDistanceSquare > MACHINE_EPSILON) { + + decimal sphereSegmentDistance = std::sqrt(sphereSegmentDistanceSquare); + sphereCenterToSegment /= sphereSegmentDistance; + + const Vector3 contactPointSphereLocal = sphereToCapsuleSpaceTransform.getInverse() * (sphereCenter + sphereCenterToSegment * sphereShape->getRadius()); + const Vector3 contactPointCapsuleLocal = closestPointOnSegment - sphereCenterToSegment * capsuleShape->getRadius(); + + const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * sphereCenterToSegment; + + decimal penetrationDepth = sumRadius - sphereSegmentDistance; + + // Create the contact info object + contactPointInfo.init(normalWorld, penetrationDepth, contactPointSphereLocal, contactPointCapsuleLocal); + + return true; + } + + return false; +} diff --git a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h new file mode 100644 index 00000000..98eaf894 --- /dev/null +++ b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h @@ -0,0 +1,71 @@ +/******************************************************************************** +* 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_SPHERE_VS_CAPSULE_ALGORITHM_H +#define REACTPHYSICS3D_SPHERE_VS_CAPSULE_ALGORITHM_H + +// Libraries +#include "body/Body.h" +#include "constraint/ContactPoint.h" +#include "NarrowPhaseAlgorithm.h" + + +/// Namespace ReactPhysics3D +namespace reactphysics3d { + +// Class SphereVsCapsuleAlgorithm +/** + * This class is used to compute the narrow-phase collision detection + * between a sphere collision shape and a capsule collision shape. + */ +class SphereVsCapsuleAlgorithm : public NarrowPhaseAlgorithm { + + protected : + + public : + + // -------------------- Methods -------------------- // + + /// Constructor + SphereVsCapsuleAlgorithm() = default; + + /// Destructor + virtual ~SphereVsCapsuleAlgorithm() override = default; + + /// Deleted copy-constructor + SphereVsCapsuleAlgorithm(const SphereVsCapsuleAlgorithm& algorithm) = delete; + + /// Deleted assignment operator + SphereVsCapsuleAlgorithm& operator=(const SphereVsCapsuleAlgorithm& algorithm) = delete; + + /// Compute a contact info if the two bounding volume collide + virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + ContactPointInfo& contactPointInfo) override; +}; + +} + +#endif + diff --git a/src/collision/shapes/CollisionShape.h b/src/collision/shapes/CollisionShape.h index 8a591614..464c1bd5 100644 --- a/src/collision/shapes/CollisionShape.h +++ b/src/collision/shapes/CollisionShape.h @@ -40,7 +40,7 @@ namespace reactphysics3d { /// Type of the collision shape -enum class CollisionShapeType {TRIANGLE, BOX, SPHERE, CAPSULE, CONVEX_MESH, CONCAVE_MESH, HEIGHTFIELD}; +enum class CollisionShapeType {TRIANGLE, BOX, CAPSULE, SPHERE, CONVEX_MESH, CONCAVE_MESH, HEIGHTFIELD}; const int NB_COLLISION_SHAPE_TYPES = 9; // Declarations diff --git a/src/mathematics/mathematics_functions.cpp b/src/mathematics/mathematics_functions.cpp index 578cecdd..1cd750ed 100644 --- a/src/mathematics/mathematics_functions.cpp +++ b/src/mathematics/mathematics_functions.cpp @@ -87,7 +87,7 @@ Vector3 reactphysics3d::computeClosestPointOnSegment(const Vector3& segPointA, c /// Compute the closest points between two segments /// This method uses the technique described in the book Real-Time /// collision detection by Christer Ericson. -void computeClosestPointBetweenTwoSegments(const Vector3& seg1PointA, const Vector3& seg1PointB, +void reactphysics3d::computeClosestPointBetweenTwoSegments(const Vector3& seg1PointA, const Vector3& seg1PointB, const Vector3& seg2PointA, const Vector3& seg2PointB, Vector3& closestPointSeg1, Vector3& closestPointSeg2) { @@ -169,7 +169,7 @@ void computeClosestPointBetweenTwoSegments(const Vector3& seg1PointA, const Vect // computes the intersection P between the plane and the segment (segA, segB). The method returns the value "t" such // that P = segA + t * (segB - segA). Note that it only returns a value in [0, 1] if there is an intersection. Otherwise, // there is no intersection between the plane and the segment. -decimal computePlaneSegmentIntersection(const Vector3& segA, const Vector3& segB, const decimal planeD, const Vector3& planeNormal) { +decimal reactphysics3d::computePlaneSegmentIntersection(const Vector3& segA, const Vector3& segB, const decimal planeD, const Vector3& planeNormal) { const decimal parallelEpsilon = decimal(0.0001); decimal t = decimal(-1); @@ -188,7 +188,7 @@ decimal computePlaneSegmentIntersection(const Vector3& segA, const Vector3& segB } /// Compute the distance between a point "point" and a line given by the points "linePointA" and "linePointB" -decimal computeDistancePointToLineDistance(const Vector3& linePointA, const Vector3& linePointB, const Vector3& point) { +decimal reactphysics3d::computeDistancePointToLineDistance(const Vector3& linePointA, const Vector3& linePointB, const Vector3& point) { decimal distAB = (linePointB - linePointA).length(); diff --git a/src/reactphysics3d.h b/src/reactphysics3d.h index a1bef6dc..3dbbd302 100644 --- a/src/reactphysics3d.h +++ b/src/reactphysics3d.h @@ -50,6 +50,7 @@ #include "collision/shapes/ConvexMeshShape.h" #include "collision/shapes/ConcaveMeshShape.h" #include "collision/shapes/HeightFieldShape.h" +#include "collision/PolyhedronMesh.h" #include "collision/shapes/AABB.h" #include "collision/ProxyShape.h" #include "collision/RaycastInfo.h" diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.h b/testbed/scenes/collisiondetection/CollisionDetectionScene.h index 323b9c34..c2aec0cd 100644 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.h +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.h @@ -33,8 +33,6 @@ #include "SceneDemo.h" #include "Sphere.h" #include "Box.h" -#include "Cone.h" -#include "Cylinder.h" #include "Capsule.h" #include "Line.h" #include "ConvexMesh.h" From 6a01abfae8c70896096420e338779ce88c2de5e3 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 20 Feb 2017 17:11:13 +0200 Subject: [PATCH 058/248] Fix issues, work on HalfEdgeStructure and add unit tests --- src/collision/CollisionDetection.cpp | 2 +- src/collision/CollisionDetection.h | 12 - src/collision/HalfEdgeStructure.cpp | 27 +- src/collision/HalfEdgeStructure.h | 10 +- src/mathematics/mathematics_functions.cpp | 6 +- test/main.cpp | 2 + test/tests/collision/TestAABB.h | 2 +- test/tests/collision/TestCollisionWorld.h | 22 +- test/tests/collision/TestHalfEdgeStructure.h | 245 ++++++++++++++++++ test/tests/collision/TestPointInside.h | 2 +- test/tests/collision/TestRaycast.h | 18 +- .../mathematics/TestMathematicsFunctions.h | 6 +- 12 files changed, 286 insertions(+), 68 deletions(-) create mode 100644 test/tests/collision/TestHalfEdgeStructure.h diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 161f6328..96f683d7 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -463,7 +463,7 @@ void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, Pro // Make sure the shape with the smallest collision shape type comes first const uint shape1TypeIndex = static_cast(shape1->getCollisionShape()->getType()); const uint shape2TypeIndex = static_cast(shape2->getCollisionShape()->getType()); - if (shape2TypeIndex > shape1TypeIndex) { + if (shape1TypeIndex > shape2TypeIndex) { // Swap the two shapes ProxyShape* temp = shape1; diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index c06a6357..9444b319 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -179,12 +179,6 @@ class CollisionDetection { /// Compute the collision detection void computeCollisionDetection(); - // TODO : Remove this method - /// Report collision between two sets of shapes - //void reportCollisionBetweenShapes(CollisionCallback* callback, - // const std::set& shapes1, - // const std::set& shapes2) ; - /// Ray casting method void raycast(RaycastCallback* raycastCallback, const Ray& ray, unsigned short raycastWithCategoryMaskBits) const; @@ -210,12 +204,6 @@ class CollisionDetection { /// Allow the broadphase to notify the collision detection about an overlapping pair. void broadPhaseNotifyOverlappingPair(ProxyShape* shape1, ProxyShape* shape2); - // TODO : Remove this method - /// Compute the narrow-phase collision detection - //void computeNarrowPhaseBetweenShapes(CollisionCallback* callback, - // const std::set& shapes1, - // const std::set& shapes2); - /// Return a pointer to the world CollisionWorld* getWorld(); diff --git a/src/collision/HalfEdgeStructure.cpp b/src/collision/HalfEdgeStructure.cpp index dba49c15..6393acb0 100644 --- a/src/collision/HalfEdgeStructure.cpp +++ b/src/collision/HalfEdgeStructure.cpp @@ -38,6 +38,8 @@ void HalfEdgeStructure::init(std::vector vertices, std::vector nextEdges; std::map mapEdgeToStartVertex; std::map mapEdgeToIndex; + std::map mapEdgeIndexToKey; + std::map mapFaceIndexToEdgeKey; // For each vertices for (uint v=0; v vertices, std::vectorsecond); - mEdges.push_back(edge); itEdge->second.twinEdgeIndex = edgeIndex + 1; - edge.twinEdgeIndex = edgeIndex; - mVertices[v1Index].edgeIndex = edgeIndex; - mVertices[v2Index].edgeIndex = edgeIndex + 1; + mapEdgeIndexToKey[edgeIndex] = pairV2V1; + mapEdgeIndexToKey[edgeIndex + 1] = pairV1V2; + + mVertices[v1Index].edgeIndex = edgeIndex + 1; + mVertices[v2Index].edgeIndex = edgeIndex; mapEdgeToIndex.insert(std::make_pair(pairV1V2, edgeIndex + 1)); mapEdgeToIndex.insert(std::make_pair(pairV2V1, edgeIndex)); - face.edgeIndex = edgeIndex + 1; + mEdges.push_back(itEdge->second); + mEdges.push_back(edge); } currentFaceEdges.push_back(pairV1V2); @@ -111,8 +116,12 @@ void HalfEdgeStructure::init(std::vector vertices, std::vector::iterator it; - for (it = edges.begin(); it != edges.end(); ++it) { - it->second.nextEdgeIndex = mapEdgeToIndex[nextEdges[it->first]]; + for (uint i=0; i < mEdges.size(); i++) { + mEdges[i].nextEdgeIndex = mapEdgeToIndex[nextEdges[mapEdgeIndexToKey[i]]]; + } + + // Set face edge + for (uint f=0; f < faces.size(); f++) { + mFaces[f].edgeIndex = mapEdgeToIndex[mapFaceIndexToEdgeKey[f]]; } } diff --git a/src/collision/HalfEdgeStructure.h b/src/collision/HalfEdgeStructure.h index 4a3f67ed..707c7d83 100644 --- a/src/collision/HalfEdgeStructure.h +++ b/src/collision/HalfEdgeStructure.h @@ -43,7 +43,7 @@ class HalfEdgeStructure { public: struct Edge { - uint vertexIndex; // Index of the vertex at the end of the edge + uint vertexIndex; // Index of the vertex at the beginning of the edge uint twinEdgeIndex; // Index of the twin edge uint faceIndex; // Adjacent face index of the edge uint nextEdgeIndex; // Index of the next edge @@ -54,7 +54,7 @@ class HalfEdgeStructure { }; struct Vertex { - Vector3 point; // Coordinates of the vertex + Vector3 point; // Coordinates of the vertex uint edgeIndex; // Index of one edge emanting from this vertex /// Constructor @@ -86,8 +86,8 @@ class HalfEdgeStructure { /// Return the number of faces uint getNbFaces() const; - /// Return the number of edges - uint getNbEdges() const; + /// Return the number of half-edges + uint getNbHalfEdges() const; /// Return the number of vertices uint getNbVertices() const; @@ -109,7 +109,7 @@ inline uint HalfEdgeStructure::getNbFaces() const { } // Return the number of edges -inline uint HalfEdgeStructure::getNbEdges() const { +inline uint HalfEdgeStructure::getNbHalfEdges() const { return mEdges.size(); } diff --git a/src/mathematics/mathematics_functions.cpp b/src/mathematics/mathematics_functions.cpp index 1cd750ed..7de898ae 100644 --- a/src/mathematics/mathematics_functions.cpp +++ b/src/mathematics/mathematics_functions.cpp @@ -171,16 +171,16 @@ void reactphysics3d::computeClosestPointBetweenTwoSegments(const Vector3& seg1Po // there is no intersection between the plane and the segment. decimal reactphysics3d::computePlaneSegmentIntersection(const Vector3& segA, const Vector3& segB, const decimal planeD, const Vector3& planeNormal) { - const decimal parallelEpsilon = decimal(0.0001); + const decimal parallelEpsilon = decimal(0.0001); decimal t = decimal(-1); // Segment AB const Vector3 ab = segB - segA; - decimal nDotAB = planeNormal.dot(ab); + decimal nDotAB = planeNormal.dot(ab); // If the segment is not parallel to the plane - if (nDotAB > parallelEpsilon) { + if (std::abs(nDotAB) > parallelEpsilon) { t = (planeD - planeNormal.dot(segA)) / nDotAB; } diff --git a/test/main.cpp b/test/main.cpp index bf949030..54bfbb8f 100644 --- a/test/main.cpp +++ b/test/main.cpp @@ -37,6 +37,7 @@ #include "tests/collision/TestCollisionWorld.h" #include "tests/collision/TestAABB.h" #include "tests/collision/TestDynamicAABBTree.h" +#include "tests/collision/TestHalfEdgeStructure.h" using namespace reactphysics3d; @@ -61,6 +62,7 @@ int main() { testSuite.addTest(new TestRaycast("Raycasting")); testSuite.addTest(new TestCollisionWorld("CollisionWorld")); testSuite.addTest(new TestDynamicAABBTree("DynamicAABBTree")); + testSuite.addTest(new TestHalfEdgeStructure("HalfEdgeStructure")); // Run the tests testSuite.run(); diff --git a/test/tests/collision/TestAABB.h b/test/tests/collision/TestAABB.h index 32d03f45..4328625c 100644 --- a/test/tests/collision/TestAABB.h +++ b/test/tests/collision/TestAABB.h @@ -72,7 +72,7 @@ class TestAABB : public Test { } /// Destructor - ~TestAABB() { + virtual ~TestAABB() { } diff --git a/test/tests/collision/TestCollisionWorld.h b/test/tests/collision/TestCollisionWorld.h index 242ebcf9..678b5f21 100644 --- a/test/tests/collision/TestCollisionWorld.h +++ b/test/tests/collision/TestCollisionWorld.h @@ -103,7 +103,6 @@ class TestCollisionWorld : public Test { CollisionBody* mBoxBody; CollisionBody* mSphere1Body; CollisionBody* mSphere2Body; - CollisionBody* mCylinderBody; // Collision shapes BoxShape* mBoxShape; @@ -113,7 +112,6 @@ class TestCollisionWorld : public Test { ProxyShape* mBoxProxyShape; ProxyShape* mSphere1ProxyShape; ProxyShape* mSphere2ProxyShape; - ProxyShape* mCylinderProxyShape; // Collision callback class WorldCollisionCallback mCollisionCallback; @@ -147,16 +145,14 @@ class TestCollisionWorld : public Test { mBoxProxyShape->setCollisionCategoryBits(CATEGORY_1); mSphere1ProxyShape->setCollisionCategoryBits(CATEGORY_1); mSphere2ProxyShape->setCollisionCategoryBits(CATEGORY_2); - mCylinderProxyShape->setCollisionCategoryBits(CATEGORY_3); mCollisionCallback.boxBody = mBoxBody; mCollisionCallback.sphere1Body = mSphere1Body; mCollisionCallback.sphere2Body = mSphere2Body; - mCollisionCallback.cylinderBody = mCylinderBody; } /// Destructor - ~TestCollisionWorld() { + virtual ~TestCollisionWorld() { delete mBoxShape; delete mSphereShape; } @@ -175,17 +171,12 @@ class TestCollisionWorld : public Test { test(!mCollisionCallback.sphere1CollideWithSphere2); test(mWorld->testAABBOverlap(mBoxBody, mSphere1Body)); - test(mWorld->testAABBOverlap(mBoxBody, mCylinderBody)); - test(!mWorld->testAABBOverlap(mSphere1Body, mCylinderBody)); test(!mWorld->testAABBOverlap(mSphere1Body, mSphere2Body)); test(mBoxProxyShape->testAABBOverlap(mSphere1ProxyShape->getWorldAABB())); - test(mBoxProxyShape->testAABBOverlap(mCylinderProxyShape->getWorldAABB())); - test(!mSphere1ProxyShape->testAABBOverlap(mCylinderProxyShape->getWorldAABB())); test(!mSphere1ProxyShape->testAABBOverlap(mSphere2ProxyShape->getWorldAABB())); mCollisionCallback.reset(); - mWorld->testCollision(mCylinderBody, &mCollisionCallback); test(!mCollisionCallback.boxCollideWithSphere1); test(!mCollisionCallback.sphere1CollideWithSphere2); @@ -195,7 +186,6 @@ class TestCollisionWorld : public Test { test(!mCollisionCallback.sphere1CollideWithSphere2); mCollisionCallback.reset(); - mWorld->testCollision(mBoxBody, mCylinderBody, &mCollisionCallback); test(!mCollisionCallback.boxCollideWithSphere1); test(!mCollisionCallback.sphere1CollideWithSphere2); @@ -213,7 +203,6 @@ class TestCollisionWorld : public Test { test(!mCollisionCallback.sphere1CollideWithSphere2); mCollisionCallback.reset(); - mWorld->testCollision(mBoxBody, mCylinderBody, &mCollisionCallback); test(!mCollisionCallback.boxCollideWithSphere1); test(!mCollisionCallback.sphere1CollideWithSphere2); @@ -224,7 +213,6 @@ class TestCollisionWorld : public Test { mCollisionCallback.reset(); mBoxBody->setIsActive(false); - mCylinderBody->setIsActive(false); mSphere1Body->setIsActive(false); mSphere2Body->setIsActive(false); mWorld->testCollision(&mCollisionCallback); @@ -232,17 +220,12 @@ class TestCollisionWorld : public Test { test(!mCollisionCallback.sphere1CollideWithSphere2); test(!mWorld->testAABBOverlap(mBoxBody, mSphere1Body)); - test(!mWorld->testAABBOverlap(mBoxBody, mCylinderBody)); - test(!mWorld->testAABBOverlap(mSphere1Body, mCylinderBody)); test(!mWorld->testAABBOverlap(mSphere1Body, mSphere2Body)); test(!mBoxProxyShape->testAABBOverlap(mSphere1ProxyShape->getWorldAABB())); - test(!mBoxProxyShape->testAABBOverlap(mCylinderProxyShape->getWorldAABB())); - test(!mSphere1ProxyShape->testAABBOverlap(mCylinderProxyShape->getWorldAABB())); test(!mSphere1ProxyShape->testAABBOverlap(mSphere2ProxyShape->getWorldAABB())); mBoxBody->setIsActive(true); - mCylinderBody->setIsActive(true); mSphere1Body->setIsActive(true); mSphere2Body->setIsActive(true); @@ -251,7 +234,6 @@ class TestCollisionWorld : public Test { mBoxProxyShape->setCollideWithMaskBits(CATEGORY_1 | CATEGORY_3); mSphere1ProxyShape->setCollideWithMaskBits(CATEGORY_1 | CATEGORY_2); mSphere2ProxyShape->setCollideWithMaskBits(CATEGORY_1); - mCylinderProxyShape->setCollideWithMaskBits(CATEGORY_1); mCollisionCallback.reset(); mWorld->testCollision(&mCollisionCallback); @@ -269,7 +251,6 @@ class TestCollisionWorld : public Test { mBoxProxyShape->setCollideWithMaskBits(CATEGORY_2); mSphere1ProxyShape->setCollideWithMaskBits(CATEGORY_2); mSphere2ProxyShape->setCollideWithMaskBits(CATEGORY_3); - mCylinderProxyShape->setCollideWithMaskBits(CATEGORY_1); mCollisionCallback.reset(); mWorld->testCollision(&mCollisionCallback); @@ -282,7 +263,6 @@ class TestCollisionWorld : public Test { mBoxProxyShape->setCollideWithMaskBits(0xFFFF); mSphere1ProxyShape->setCollideWithMaskBits(0xFFFF); mSphere2ProxyShape->setCollideWithMaskBits(0xFFFF); - mCylinderProxyShape->setCollideWithMaskBits(0xFFFF); } }; diff --git a/test/tests/collision/TestHalfEdgeStructure.h b/test/tests/collision/TestHalfEdgeStructure.h new file mode 100644 index 00000000..871a8ed1 --- /dev/null +++ b/test/tests/collision/TestHalfEdgeStructure.h @@ -0,0 +1,245 @@ +#ifndef TEST_HALF_EDGE_STRUCTURE_H +#define TEST_HALF_EDGE_STRUCTURE_H + +// Libraries +#include "reactphysics3d.h" +#include "Test.h" + +/// Reactphysics3D namespace +namespace reactphysics3d { + + +// Class TestHalfEdgeStructure +/** + * Unit test for the HalfEdgeStructure class. + */ +class TestHalfEdgeStructure : public Test { + + private : + + // ---------- Atributes ---------- // + + + public : + + // ---------- Methods ---------- // + + /// Constructor + TestHalfEdgeStructure(const std::string& name) : Test(name) { + + } + + /// Destructor + virtual ~TestHalfEdgeStructure() { + + } + + /// Run the tests + void run() { + testCube(); + testTetrahedron(); + } + + void testCube() { + + // Create the half-edge structure for a cube + std::vector vertices; + std::vector> faces; + rp3d::HalfEdgeStructure cubeStructure; + + // Vertices + vertices.push_back(rp3d::Vector3(-0.5, -0.5, 0.5)); + vertices.push_back(rp3d::Vector3(0.5, -0.5, 0.5)); + vertices.push_back(rp3d::Vector3(0.5, 0.5, 0.5)); + vertices.push_back(rp3d::Vector3(-0.5, 0.5, 0.5)); + vertices.push_back(rp3d::Vector3(-0.5, -0.5, -0.5)); + vertices.push_back(rp3d::Vector3(0.5, -0.5, -0.5)); + vertices.push_back(rp3d::Vector3(0.5, 0.5, -0.5)); + vertices.push_back(rp3d::Vector3(-0.5, 0.5, -0.5)); + + // Faces + std::vector face0; + face0.push_back(0); face0.push_back(1); face0.push_back(2); face0.push_back(3); + std::vector face1; + face1.push_back(1); face1.push_back(5); face1.push_back(6); face1.push_back(2); + std::vector face2; + face2.push_back(5); face2.push_back(4); face2.push_back(7); face2.push_back(6); + std::vector face3; + face3.push_back(4); face3.push_back(0); face3.push_back(3); face3.push_back(7); + std::vector face4; + face4.push_back(0); face4.push_back(4); face4.push_back(5); face4.push_back(1); + std::vector face5; + face5.push_back(2); face5.push_back(6); face5.push_back(7); face5.push_back(3); + + faces.push_back(face0); + faces.push_back(face1); + faces.push_back(face2); + faces.push_back(face3); + faces.push_back(face4); + faces.push_back(face5); + + cubeStructure.init(vertices, faces); + + // --- Test that the half-edge structure of the cube is valid --- // + + test(cubeStructure.getNbFaces() == 6); + test(cubeStructure.getNbVertices() == 8); + test(cubeStructure.getNbHalfEdges() == 24); + + // Test vertices + test(cubeStructure.getVertex(0).point.x == -0.5); + test(cubeStructure.getVertex(0).point.y == -0.5); + test(cubeStructure.getVertex(0).point.z == 0.5); + test(cubeStructure.getHalfEdge(cubeStructure.getVertex(0).edgeIndex).vertexIndex == 0); + + test(cubeStructure.getVertex(1).point.x == 0.5); + test(cubeStructure.getVertex(1).point.y == -0.5); + test(cubeStructure.getVertex(1).point.z == 0.5); + test(cubeStructure.getHalfEdge(cubeStructure.getVertex(1).edgeIndex).vertexIndex == 1); + + test(cubeStructure.getVertex(2).point.x == 0.5); + test(cubeStructure.getVertex(2).point.y == 0.5); + test(cubeStructure.getVertex(2).point.z == 0.5); + test(cubeStructure.getHalfEdge(cubeStructure.getVertex(2).edgeIndex).vertexIndex == 2); + + test(cubeStructure.getVertex(3).point.x == -0.5); + test(cubeStructure.getVertex(3).point.y == 0.5); + test(cubeStructure.getVertex(3).point.z == 0.5); + test(cubeStructure.getHalfEdge(cubeStructure.getVertex(3).edgeIndex).vertexIndex == 3); + + test(cubeStructure.getVertex(4).point.x == -0.5); + test(cubeStructure.getVertex(4).point.y == -0.5); + test(cubeStructure.getVertex(4).point.z == -0.5); + test(cubeStructure.getHalfEdge(cubeStructure.getVertex(4).edgeIndex).vertexIndex == 4); + + test(cubeStructure.getVertex(5).point.x == 0.5); + test(cubeStructure.getVertex(5).point.y == -0.5); + test(cubeStructure.getVertex(5).point.z == -0.5); + test(cubeStructure.getHalfEdge(cubeStructure.getVertex(5).edgeIndex).vertexIndex == 5); + + test(cubeStructure.getVertex(6).point.x == 0.5); + test(cubeStructure.getVertex(6).point.y == 0.5); + test(cubeStructure.getVertex(6).point.z == -0.5); + test(cubeStructure.getHalfEdge(cubeStructure.getVertex(6).edgeIndex).vertexIndex == 6); + + test(cubeStructure.getVertex(7).point.x == -0.5); + test(cubeStructure.getVertex(7).point.y == 0.5); + test(cubeStructure.getVertex(7).point.z == -0.5); + test(cubeStructure.getHalfEdge(cubeStructure.getVertex(7).edgeIndex).vertexIndex == 7); + + // Test faces + for (uint f=0; f<6; f++) { + test(cubeStructure.getHalfEdge(cubeStructure.getFace(f).edgeIndex).faceIndex == f); + } + + // Test edges + for (uint f=0; f<6; f++) { + + + uint edgeIndex = cubeStructure.getFace(f).edgeIndex; + const uint firstEdgeIndex = edgeIndex; + + // For each half-edge of the face + for (uint e=0; e<4; e++) { + + rp3d::HalfEdgeStructure::Edge edge = cubeStructure.getHalfEdge(edgeIndex); + + test(cubeStructure.getHalfEdge(edge.twinEdgeIndex).twinEdgeIndex == edgeIndex); + test(edge.faceIndex == f); + + // Go to the next edge + edgeIndex = edge.nextEdgeIndex; + } + + test(firstEdgeIndex == edgeIndex); + } + } + + void testTetrahedron() { + + // Create the half-edge structure for a tetrahedron + std::vector vertices; + std::vector> faces; + rp3d::HalfEdgeStructure tetrahedron; + + // Vertices + vertices.push_back(rp3d::Vector3(1, -1, -1)); + vertices.push_back(rp3d::Vector3(-1, -1, -1)); + vertices.push_back(rp3d::Vector3(0, -1, 1)); + vertices.push_back(rp3d::Vector3(0, 1, 0)); + + // Faces + std::vector face0; + face0.push_back(0); face0.push_back(1); face0.push_back(2); + std::vector face1; + face1.push_back(0); face1.push_back(3); face1.push_back(1); + std::vector face2; + face2.push_back(1); face2.push_back(3); face2.push_back(2); + std::vector face3; + face3.push_back(0); face3.push_back(2); face3.push_back(3); + + faces.push_back(face0); + faces.push_back(face1); + faces.push_back(face2); + faces.push_back(face3); + + tetrahedron.init(vertices, faces); + + // --- Test that the half-edge structure of the tetrahedron is valid --- // + + test(tetrahedron.getNbFaces() == 4); + test(tetrahedron.getNbVertices() == 4); + test(tetrahedron.getNbHalfEdges() == 12); + + // Test vertices + test(tetrahedron.getVertex(0).point.x == 1); + test(tetrahedron.getVertex(0).point.y == -1); + test(tetrahedron.getVertex(0).point.z == -1); + test(tetrahedron.getHalfEdge(tetrahedron.getVertex(0).edgeIndex).vertexIndex == 0); + + test(tetrahedron.getVertex(1).point.x == -1); + test(tetrahedron.getVertex(1).point.y == -1); + test(tetrahedron.getVertex(1).point.z == -1); + test(tetrahedron.getHalfEdge(tetrahedron.getVertex(1).edgeIndex).vertexIndex == 1); + + test(tetrahedron.getVertex(2).point.x == 0); + test(tetrahedron.getVertex(2).point.y == -1); + test(tetrahedron.getVertex(2).point.z == 1); + test(tetrahedron.getHalfEdge(tetrahedron.getVertex(2).edgeIndex).vertexIndex == 2); + + test(tetrahedron.getVertex(3).point.x == 0); + test(tetrahedron.getVertex(3).point.y == 1); + test(tetrahedron.getVertex(3).point.z == 0); + test(tetrahedron.getHalfEdge(tetrahedron.getVertex(3).edgeIndex).vertexIndex == 3); + + // Test faces + for (uint f=0; f<4; f++) { + test(tetrahedron.getHalfEdge(tetrahedron.getFace(f).edgeIndex).faceIndex == f); + } + + // Test edges + for (uint f=0; f<4; f++) { + + uint edgeIndex = tetrahedron.getFace(f).edgeIndex; + const uint firstEdgeIndex = edgeIndex; + + // For each half-edge of the face + for (uint e=0; e<3; e++) { + + rp3d::HalfEdgeStructure::Edge edge = tetrahedron.getHalfEdge(edgeIndex); + + test(tetrahedron.getHalfEdge(edge.twinEdgeIndex).twinEdgeIndex == edgeIndex); + test(edge.faceIndex == f); + + // Go to the next edge + edgeIndex = edge.nextEdgeIndex; + } + + test(firstEdgeIndex == edgeIndex); + } + } + }; + +} + +#endif diff --git a/test/tests/collision/TestPointInside.h b/test/tests/collision/TestPointInside.h index dd2a793b..9fd20110 100644 --- a/test/tests/collision/TestPointInside.h +++ b/test/tests/collision/TestPointInside.h @@ -171,7 +171,7 @@ class TestPointInside : public Test { } /// Destructor - ~TestPointInside() { + virtual ~TestPointInside() { delete mBoxShape; delete mSphereShape; delete mCapsuleShape; diff --git a/test/tests/collision/TestRaycast.h b/test/tests/collision/TestRaycast.h index b39b751b..852455c2 100644 --- a/test/tests/collision/TestRaycast.h +++ b/test/tests/collision/TestRaycast.h @@ -109,7 +109,6 @@ class TestRaycast : public Test { CollisionBody* mBoxBody; CollisionBody* mSphereBody; CollisionBody* mCapsuleBody; - CollisionBody* mConeBody; CollisionBody* mConvexMeshBody; CollisionBody* mConvexMeshBodyEdgesInfo; CollisionBody* mCylinderBody; @@ -138,12 +137,10 @@ class TestRaycast : public Test { ProxyShape* mBoxProxyShape; ProxyShape* mSphereProxyShape; ProxyShape* mCapsuleProxyShape; - ProxyShape* mConeProxyShape; ProxyShape* mConvexMeshProxyShape; ProxyShape* mConvexMeshProxyShapeEdgesInfo; - ProxyShape* mCylinderProxyShape; ProxyShape* mCompoundSphereProxyShape; - ProxyShape* mCompoundCylinderProxyShape; + ProxyShape* mCompoundCapsuleProxyShape; ProxyShape* mTriangleProxyShape; ProxyShape* mConcaveMeshProxyShape; ProxyShape* mHeightFieldProxyShape; @@ -177,7 +174,6 @@ class TestRaycast : public Test { mBoxBody = mWorld->createCollisionBody(mBodyTransform); mSphereBody = mWorld->createCollisionBody(mBodyTransform); mCapsuleBody = mWorld->createCollisionBody(mBodyTransform); - mConeBody = mWorld->createCollisionBody(mBodyTransform); mConvexMeshBody = mWorld->createCollisionBody(mBodyTransform); mConvexMeshBodyEdgesInfo = mWorld->createCollisionBody(mBodyTransform); mCylinderBody = mWorld->createCollisionBody(mBodyTransform); @@ -253,7 +249,7 @@ class TestRaycast : public Test { Quaternion orientationShape2(-3 *PI / 8, 1.5 * PI/ 3, PI / 13); Transform shapeTransform2(positionShape2, orientationShape2); mLocalShape2ToWorld = mBodyTransform * shapeTransform2; - mCompoundCylinderProxyShape = mCompoundBody->addCollisionShape(mCapsuleShape, mShapeTransform); + mCompoundCapsuleProxyShape = mCompoundBody->addCollisionShape(mCapsuleShape, mShapeTransform); mCompoundSphereProxyShape = mCompoundBody->addCollisionShape(mSphereShape, shapeTransform2); // Concave Mesh shape @@ -284,7 +280,7 @@ class TestRaycast : public Test { new TriangleVertexArray(8, &(mConcaveMeshVertices[0]), sizeof(Vector3), 12, &(mConcaveMeshIndices[0]), sizeof(uint), vertexType, - TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE); + TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE); // Add the triangle vertex array of the subpart to the triangle mesh @@ -302,19 +298,17 @@ class TestRaycast : public Test { mBoxProxyShape->setCollisionCategoryBits(CATEGORY1); mSphereProxyShape->setCollisionCategoryBits(CATEGORY1); mCapsuleProxyShape->setCollisionCategoryBits(CATEGORY1); - mConeProxyShape->setCollisionCategoryBits(CATEGORY2); mConvexMeshProxyShape->setCollisionCategoryBits(CATEGORY2); mConvexMeshProxyShapeEdgesInfo->setCollisionCategoryBits(CATEGORY2); - mCylinderProxyShape->setCollisionCategoryBits(CATEGORY2); mCompoundSphereProxyShape->setCollisionCategoryBits(CATEGORY2); - mCompoundCylinderProxyShape->setCollisionCategoryBits(CATEGORY2); + mCompoundCapsuleProxyShape->setCollisionCategoryBits(CATEGORY2); mTriangleProxyShape->setCollisionCategoryBits(CATEGORY1); mConcaveMeshProxyShape->setCollisionCategoryBits(CATEGORY2); mHeightFieldProxyShape->setCollisionCategoryBits(CATEGORY2); } /// Destructor - ~TestRaycast() { + virtual ~TestRaycast() { delete mBoxShape; delete mSphereShape; delete mCapsuleShape; @@ -1647,7 +1641,7 @@ class TestRaycast : public Test { Ray ray15(mLocalShapeToWorld * Vector3(0, -9, 1), mLocalShapeToWorld * Vector3(0, 30, 1)); Ray ray16(mLocalShapeToWorld * Vector3(-1, 2, -7), mLocalShapeToWorld * Vector3(-1, 2, 30)); - mCallback.shapeToTest = mCompoundCylinderProxyShape; + mCallback.shapeToTest = mCompoundCapsuleProxyShape; test(mCompoundBody->raycast(ray11, raycastInfo)); mCallback.reset(); diff --git a/test/tests/mathematics/TestMathematicsFunctions.h b/test/tests/mathematics/TestMathematicsFunctions.h index 32e19aad..42e1065c 100644 --- a/test/tests/mathematics/TestMathematicsFunctions.h +++ b/test/tests/mathematics/TestMathematicsFunctions.h @@ -150,19 +150,19 @@ class TestMathematicsFunctions : public Test { test(approxEqual(closestSeg2.z, 0.0, 0.000001)); computeClosestPointBetweenTwoSegments(Vector3(1, -4, -5), Vector3(1, 4, -5), Vector3(-6, 5, -5), Vector3(6, 5, -5), closestSeg1, closestSeg2); test(approxEqual(closestSeg1.x, 1.0, 0.000001)); - test(approxEqual(closestSeg1.y, 5.0, 0.000001)); + test(approxEqual(closestSeg1.y, 4.0, 0.000001)); test(approxEqual(closestSeg1.z, -5.0, 0.000001)); test(approxEqual(closestSeg2.x, 1.0, 0.000001)); test(approxEqual(closestSeg2.y, 5.0, 0.000001)); test(approxEqual(closestSeg2.z, -5.0, 0.000001)); // Test computePlaneSegmentIntersection(); - test(approxEqual(computePlaneSegmentIntersection(Vector3(-6, 3, 0), Vector3(6, 3, 0), 0.0, Vector3(-1, 0, 0)), 0.5, 0.000001)); + test(approxEqual(computePlaneSegmentIntersection(Vector3(-6, 3, 0), Vector3(6, 3, 0), 0.0, Vector3(-1, 0, 0)), 0.5, 0.000001)); test(approxEqual(computePlaneSegmentIntersection(Vector3(-6, 3, 0), Vector3(6, 3, 0), 0.0, Vector3(1, 0, 0)), 0.5, 0.000001)); test(approxEqual(computePlaneSegmentIntersection(Vector3(5, 12, 0), Vector3(5, 4, 0), 6, Vector3(0, 1, 0)), 0.75, 0.000001)); test(approxEqual(computePlaneSegmentIntersection(Vector3(5, 4, 8), Vector3(9, 14, 8), 4, Vector3(0, 1, 0)), 0.0, 0.000001)); decimal tIntersect = computePlaneSegmentIntersection(Vector3(5, 4, 0), Vector3(9, 4, 0), 4, Vector3(0, 1, 0)); - test(tIntersect < 0.0 && tIntersect > 1.0); + test(tIntersect < 0.0 || tIntersect > 1.0); // Test computeDistancePointToLineDistance() test(approxEqual(computeDistancePointToLineDistance(Vector3(6, 0, 0), Vector3(14, 0, 0), Vector3(5, 3, 0)), 3.0, 0.000001)); From b21a6bb59b104e54364ddf6a004484a1c5824f25 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 26 Feb 2017 13:48:50 +0200 Subject: [PATCH 059/248] Refactor contact manifold and contact point creation --- CMakeLists.txt | 2 + src/collision/CollisionDetection.cpp | 216 ++------------- src/collision/ContactManifold.cpp | 254 ++++-------------- src/collision/ContactManifold.h | 27 +- src/collision/ContactManifoldInfo.h | 130 +++++++++ src/collision/ContactManifoldSet.cpp | 217 +++++++++------ src/collision/ContactManifoldSet.h | 17 +- src/collision/ContactPointInfo.h | 88 ++++++ .../narrowphase/CapsuleVsCapsuleAlgorithm.cpp | 25 +- .../narrowphase/CapsuleVsCapsuleAlgorithm.h | 2 +- .../narrowphase/DefaultCollisionDispatch.cpp | 2 +- .../narrowphase/GJK/GJKAlgorithm.cpp | 6 +- src/collision/narrowphase/GJK/GJKAlgorithm.h | 5 +- .../narrowphase/NarrowPhaseAlgorithm.h | 4 +- .../narrowphase/SAT/SATAlgorithm.cpp | 2 +- src/collision/narrowphase/SAT/SATAlgorithm.h | 5 +- .../narrowphase/SphereVsCapsuleAlgorithm.cpp | 11 +- .../narrowphase/SphereVsCapsuleAlgorithm.h | 2 +- .../SphereVsConvexMeshAlgorithm.cpp | 6 +- .../narrowphase/SphereVsConvexMeshAlgorithm.h | 2 +- .../narrowphase/SphereVsSphereAlgorithm.cpp | 11 +- .../narrowphase/SphereVsSphereAlgorithm.h | 2 +- src/collision/shapes/CollisionShape.h | 2 +- src/constraint/ContactPoint.cpp | 32 ++- src/constraint/ContactPoint.h | 86 ++---- src/engine/CollisionWorld.h | 6 +- src/engine/EventListener.h | 6 +- src/engine/OverlappingPair.h | 16 +- 28 files changed, 543 insertions(+), 641 deletions(-) create mode 100644 src/collision/ContactManifoldInfo.h create mode 100644 src/collision/ContactPointInfo.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 37b8febe..58ea37d7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -60,6 +60,8 @@ SET (REACTPHYSICS3D_SOURCES "src/body/CollisionBody.cpp" "src/body/RigidBody.h" "src/body/RigidBody.cpp" + "src/collision/ContactPointInfo.h" + "src/collision/ContactManifoldInfo.h" "src/collision/broadphase/BroadPhaseAlgorithm.h" "src/collision/broadphase/BroadPhaseAlgorithm.cpp" "src/collision/broadphase/DynamicAABBTree.h" diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 96f683d7..4a0ef718 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -72,66 +72,6 @@ void CollisionDetection::computeCollisionDetection() { mNarrowPhaseInfoList = nullptr; } -// TODO : Remove this method -// Report collision between two sets of shapes -/* -void CollisionDetection::reportCollisionBetweenShapes(CollisionCallback* callback, - const std::set& shapes1, - const std::set& shapes2) { - - // For each possible collision pair of bodies - map::iterator it; - for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ++it) { - - OverlappingPair* pair = it->second; - - const ProxyShape* shape1 = pair->getShape1(); - const ProxyShape* shape2 = pair->getShape2(); - - assert(shape1->mBroadPhaseID != shape2->mBroadPhaseID); - - // If both shapes1 and shapes2 sets are non-empty, we check that - // shape1 is among on set and shape2 is among the other one - if (!shapes1.empty() && !shapes2.empty() && - (shapes1.count(shape1->mBroadPhaseID) == 0 || shapes2.count(shape2->mBroadPhaseID) == 0) && - (shapes1.count(shape2->mBroadPhaseID) == 0 || shapes2.count(shape1->mBroadPhaseID) == 0)) { - continue; - } - if (!shapes1.empty() && shapes2.empty() && - shapes1.count(shape1->mBroadPhaseID) == 0 && shapes1.count(shape2->mBroadPhaseID) == 0) - { - continue; - } - if (!shapes2.empty() && shapes1.empty() && - shapes2.count(shape1->mBroadPhaseID) == 0 && shapes2.count(shape2->mBroadPhaseID) == 0) - { - continue; - } - - // For each contact manifold set of the overlapping pair - const ContactManifoldSet& manifoldSet = pair->getContactManifoldSet(); - for (int j=0; jgetNbContactPoints(); i++) { - - ContactPoint* contactPoint = manifold->getContactPoint(i); - - // Create the contact info object for the contact - ContactPointInfo contactInfo; - contactInfo.init(contactPoint->getNormal(), contactPoint->getPenetrationDepth(), - contactPoint->getLocalPointOnBody1(), contactPoint->getLocalPointOnBody2()); - - // Notify the collision callback about this new contact - if (callback != nullptr) callback->notifyContact(contactInfo); - } - } - } -} -*/ - // Compute the broad-phase collision detection void CollisionDetection::computeBroadPhase() { @@ -191,9 +131,6 @@ void CollisionDetection::computeMiddlePhase() { CollisionBody* const body1 = shape1->getBody(); CollisionBody* const body2 = shape2->getBody(); - // Update the contact cache of the overlapping pair - pair->update(); - // Check that at least one body is awake and not static bool isBody1Active = !body1->isSleeping() && body1->getType() != BodyType::STATIC; bool isBody2Active = !body2->isSleeping() && body2->getType() != BodyType::STATIC; @@ -308,25 +245,21 @@ void CollisionDetection::computeNarrowPhase() { // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - ContactPointInfo contactPointInfo; - if (narrowPhaseAlgorithm->testCollision(currentNarrowPhaseInfo, contactPointInfo)) { + ContactManifoldInfo contactManifoldInfo(mSingleFrameAllocator); + if (narrowPhaseAlgorithm->testCollision(currentNarrowPhaseInfo, contactManifoldInfo)) { + + // Reduce the number of points in the contact manifold + contactManifoldInfo.reduce(); // If it is the first contact since the pairs are overlapping if (currentNarrowPhaseInfo->overlappingPair->getNbContactPoints() == 0) { // Trigger a callback event - if (mWorld->mEventListener != nullptr) mWorld->mEventListener->beginContact(contactPointInfo); + if (mWorld->mEventListener != nullptr) mWorld->mEventListener->beginContact(contactManifoldInfo); } - // Create a new contact - ContactPoint* contact = new (mWorld->mPoolAllocator.allocate(sizeof(ContactPoint))) - ContactPoint(contactPointInfo); - - contact->updateWorldContactPoints(currentNarrowPhaseInfo->shape1ToWorldTransform, - currentNarrowPhaseInfo->shape2ToWorldTransform); - - // Add the contact to the contact manifold set of the corresponding overlapping pair - currentNarrowPhaseInfo->overlappingPair->addContact(contact); + // Add the contact manifold to the corresponding overlapping pair + currentNarrowPhaseInfo->overlappingPair->addContactManifold(contactManifoldInfo); // Add the overlapping pair into the set of pairs in contact during narrow-phase overlappingpairid pairId = OverlappingPair::computeID(currentNarrowPhaseInfo->overlappingPair->getShape1(), @@ -334,7 +267,7 @@ void CollisionDetection::computeNarrowPhase() { mContactOverlappingPairs[pairId] = currentNarrowPhaseInfo->overlappingPair; // Trigger a callback event for the new contact - if (mWorld->mEventListener != nullptr) mWorld->mEventListener->newContact(contactPointInfo); + if (mWorld->mEventListener != nullptr) mWorld->mEventListener->newContact(contactManifoldInfo); } } @@ -345,111 +278,6 @@ void CollisionDetection::computeNarrowPhase() { addAllContactManifoldsToBodies(); } -// TODO : Remove this method -// Compute the narrow-phase collision detection -/* -void CollisionDetection::computeNarrowPhaseBetweenShapes(CollisionCallback* callback, - const std::set& shapes1, - const std::set& shapes2) { - - mContactOverlappingPairs.clear(); - - // For each possible collision pair of bodies - map::iterator it; - for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ) { - - OverlappingPair* pair = it->second; - - ProxyShape* shape1 = pair->getShape1(); - ProxyShape* shape2 = pair->getShape2(); - - assert(shape1->mBroadPhaseID != shape2->mBroadPhaseID); - - // If both shapes1 and shapes2 sets are non-empty, we check that - // shape1 is among on set and shape2 is among the other one - if (!shapes1.empty() && !shapes2.empty() && - (shapes1.count(shape1->mBroadPhaseID) == 0 || shapes2.count(shape2->mBroadPhaseID) == 0) && - (shapes1.count(shape2->mBroadPhaseID) == 0 || shapes2.count(shape1->mBroadPhaseID) == 0)) { - ++it; - continue; - } - if (!shapes1.empty() && shapes2.empty() && - shapes1.count(shape1->mBroadPhaseID) == 0 && shapes1.count(shape2->mBroadPhaseID) == 0) - { - ++it; - continue; - } - if (!shapes2.empty() && shapes1.empty() && - shapes2.count(shape1->mBroadPhaseID) == 0 && shapes2.count(shape2->mBroadPhaseID) == 0) - { - ++it; - continue; - } - - // Check if the collision filtering allows collision between the two shapes and - // that the two shapes are still overlapping. Otherwise, we destroy the - // overlapping pair - if (((shape1->getCollideWithMaskBits() & shape2->getCollisionCategoryBits()) == 0 || - (shape1->getCollisionCategoryBits() & shape2->getCollideWithMaskBits()) == 0) || - !mBroadPhaseAlgorithm.testOverlappingShapes(shape1, shape2)) { - - std::map::iterator itToRemove = it; - ++it; - - // TODO : Remove all the contact manifold of the overlapping pair from the contact manifolds list of the two bodies involved - - // Destroy the overlapping pair - itToRemove->second->~OverlappingPair(); - mWorld->mPoolAllocator.release(itToRemove->second, sizeof(OverlappingPair)); - mOverlappingPairs.erase(itToRemove); - continue; - } - else { - ++it; - } - - CollisionBody* const body1 = shape1->getBody(); - CollisionBody* const body2 = shape2->getBody(); - - // Update the contact cache of the overlapping pair - pair->update(); - - // Check if the two bodies are allowed to collide, otherwise, we do not test for collision - if (body1->getType() != BodyType::DYNAMIC && body2->getType() != BodyType::DYNAMIC) continue; - bodyindexpair bodiesIndex = OverlappingPair::computeBodiesIndexPair(body1, body2); - if (mNoCollisionPairs.count(bodiesIndex) > 0) continue; - - // Check if the two bodies are sleeping, if so, we do no test collision between them - if (body1->isSleeping() && body2->isSleeping()) continue; - - // Select the narrow phase algorithm to use according to the two collision shapes - const CollisionShapeType shape1Type = shape1->getCollisionShape()->getType(); - const CollisionShapeType shape2Type = shape2->getCollisionShape()->getType(); - const int shape1Index = static_cast(shape1Type); - const int shape2Index = static_cast(shape2Type); - NarrowPhaseAlgorithm* narrowPhaseAlgorithm = mCollisionMatrix[shape1Index][shape2Index]; - - // If there is no collision algorithm between those two kinds of shapes - if (narrowPhaseAlgorithm == nullptr) continue; - - // Create the CollisionShapeInfo objects - CollisionShapeInfo shape1Info(shape1, shape1->getCollisionShape(), shape1->getLocalToWorldTransform(), - pair, shape1->getCachedCollisionData()); - CollisionShapeInfo shape2Info(shape2, shape2->getCollisionShape(), shape2->getLocalToWorldTransform(), - pair, shape2->getCachedCollisionData()); - - TestCollisionBetweenShapesCallback narrowPhaseCallback(callback); - - // Use the narrow-phase collision detection algorithm to check - // if there really is a collision - narrowPhaseAlgorithm->testCollision(shape1Info, shape2Info, &narrowPhaseCallback); - } - - // Add all the contact manifolds (between colliding bodies) to the bodies - addAllContactManifoldsToBodies(); -} -*/ - // Allow the broadphase to notify the collision detection about an overlapping pair. /// This method is called by the broad-phase collision detection algorithm void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, ProxyShape* shape2) { @@ -698,8 +526,8 @@ bool CollisionDetection::testOverlap(CollisionBody* body1, CollisionBody* body2) // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - ContactPointInfo contactPointInfo; - isColliding |= narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactPointInfo); + ContactManifoldInfo contactManifoldInfo(mMemoryAllocator); + isColliding |= narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactManifoldInfo); } } @@ -786,8 +614,8 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - ContactPointInfo contactPointInfo; - isColliding |= narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactPointInfo); + ContactManifoldInfo contactManifoldInfo(mMemoryAllocator); + isColliding |= narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactManifoldInfo); } } @@ -859,10 +687,10 @@ void CollisionDetection::testCollision(CollisionBody* body1, CollisionBody* body // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - ContactPointInfo contactPointInfo; - if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactPointInfo)) { + ContactManifoldInfo contactManifoldInfo(mMemoryAllocator); + if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactManifoldInfo)) { - CollisionCallback::CollisionCallbackInfo collisionInfo(contactPointInfo, body1, body2, + CollisionCallback::CollisionCallbackInfo collisionInfo(contactManifoldInfo, body1, body2, body1ProxyShape, body2ProxyShape); // Report the contact to the user @@ -937,10 +765,10 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - ContactPointInfo contactPointInfo; - if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactPointInfo)) { + ContactManifoldInfo contactManifoldInfo(mMemoryAllocator); + if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactManifoldInfo)) { - CollisionCallback::CollisionCallbackInfo collisionInfo(contactPointInfo, body, + CollisionCallback::CollisionCallbackInfo collisionInfo(contactManifoldInfo, body, proxyShape->getBody(), bodyProxyShape, proxyShape); @@ -1008,10 +836,10 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - ContactPointInfo contactPointInfo; - if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactPointInfo)) { + ContactManifoldInfo contactManifoldInfo(mMemoryAllocator); + if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactManifoldInfo)) { - CollisionCallback::CollisionCallbackInfo collisionInfo(contactPointInfo, shape1->getBody(), + CollisionCallback::CollisionCallbackInfo collisionInfo(contactManifoldInfo, shape1->getBody(), shape2->getBody(), shape1, shape2); // Report the contact to the user diff --git a/src/collision/ContactManifold.cpp b/src/collision/ContactManifold.cpp index dc40774b..36103642 100644 --- a/src/collision/ContactManifold.cpp +++ b/src/collision/ContactManifold.cpp @@ -30,13 +30,30 @@ using namespace reactphysics3d; // Constructor -ContactManifold::ContactManifold(ProxyShape* shape1, ProxyShape* shape2, +ContactManifold::ContactManifold(const ContactManifoldInfo& manifoldInfo, ProxyShape* shape1, ProxyShape* shape2, PoolAllocator& memoryAllocator, short normalDirectionId) : mShape1(shape1), mShape2(shape2), mNormalDirectionId(normalDirectionId), mNbContactPoints(0), mFrictionImpulse1(0.0), mFrictionImpulse2(0.0), mFrictionTwistImpulse(0.0), mIsAlreadyInIsland(false), mMemoryAllocator(memoryAllocator) { + // For each contact point info in the manifold + const ContactPointInfo* pointInfo = manifoldInfo.getFirstContactPointInfo(); + while(pointInfo != nullptr) { + + // Create the new contact point + ContactPoint* contact = new (mMemoryAllocator.allocate(sizeof(ContactPoint))) + ContactPoint(pointInfo, mShape1->getLocalToWorldTransform(), mShape2->getLocalToWorldTransform()); + + // Add the new contact point into the manifold + mContactPoints[mNbContactPoints] = contact; + mNbContactPoints++; + + pointInfo = pointInfo->next; + } + + assert(mNbContactPoints <= MAX_CONTACT_POINTS_IN_MANIFOLD); + assert(mNbContactPoints > 0); } // Destructor @@ -44,209 +61,6 @@ ContactManifold::~ContactManifold() { clear(); } -// Add a contact point in the manifold -void ContactManifold::addContactPoint(ContactPoint* contact) { - - // For contact already in the manifold - for (uint i=0; igetWorldPointOnBody1() - - contact->getWorldPointOnBody1()).lengthSquare(); - if (distance <= PERSISTENT_CONTACT_DIST_THRESHOLD*PERSISTENT_CONTACT_DIST_THRESHOLD) { - - // Delete the new contact - contact->~ContactPoint(); - mMemoryAllocator.release(contact, sizeof(ContactPoint)); - - assert(mNbContactPoints > 0); - - return; - } - } - - // If the contact manifold is full - if (mNbContactPoints == MAX_CONTACT_POINTS_IN_MANIFOLD) { - int indexMaxPenetration = getIndexOfDeepestPenetration(contact); - int indexToRemove = getIndexToRemove(indexMaxPenetration, contact->getLocalPointOnBody1()); - removeContactPoint(indexToRemove); - } - - // Add the new contact point in the manifold - mContactPoints[mNbContactPoints] = contact; - mNbContactPoints++; - - assert(mNbContactPoints > 0); -} - -// Remove a contact point from the manifold -void ContactManifold::removeContactPoint(uint index) { - assert(index < mNbContactPoints); - assert(mNbContactPoints > 0); - - // Call the destructor explicitly and tell the memory allocator that - // the corresponding memory block is now free - mContactPoints[index]->~ContactPoint(); - mMemoryAllocator.release(mContactPoints[index], sizeof(ContactPoint)); - - // If we don't remove the last index - if (index < mNbContactPoints - 1) { - mContactPoints[index] = mContactPoints[mNbContactPoints - 1]; - } - - mNbContactPoints--; -} - -// Update the contact manifold -/// First the world space coordinates of the current contacts in the manifold are recomputed from -/// the corresponding transforms of the bodies because they have moved. Then we remove the contacts -/// with a negative penetration depth (meaning that the bodies are not penetrating anymore) and also -/// the contacts with a too large distance between the contact points in the plane orthogonal to the -/// contact normal. -void ContactManifold::update(const Transform& transform1, const Transform& transform2) { - - if (mNbContactPoints == 0) return; - - // Update the world coordinates and penetration depth of the contact points in the manifold - for (uint i=0; iupdateWorldContactPoints(transform1, transform2); - mContactPoints[i]->updatePenetrationDepth(); - } - - const decimal squarePersistentContactThreshold = PERSISTENT_CONTACT_DIST_THRESHOLD * - PERSISTENT_CONTACT_DIST_THRESHOLD; - - // Remove the contact points that don't represent very well the contact manifold - for (int i=static_cast(mNbContactPoints)-1; i>=0; i--) { - assert(i < static_cast(mNbContactPoints)); - - // Compute the distance between contact points in the normal direction - decimal distanceNormal = -mContactPoints[i]->getPenetrationDepth(); - - // If the contacts points are too far from each other in the normal direction - if (distanceNormal > squarePersistentContactThreshold) { - removeContactPoint(i); - } - else { - // Compute the distance of the two contact points in the plane - // orthogonal to the contact normal - Vector3 projOfPoint1 = mContactPoints[i]->getWorldPointOnBody1() + - mContactPoints[i]->getNormal() * distanceNormal; - Vector3 projDifference = mContactPoints[i]->getWorldPointOnBody2() - projOfPoint1; - - // If the orthogonal distance is larger than the valid distance - // threshold, we remove the contact - if (projDifference.lengthSquare() > squarePersistentContactThreshold) { - removeContactPoint(i); - } - } - } -} - -// Return the index of the contact point with the larger penetration depth. -/// This corresponding contact will be kept in the cache. The method returns -1 is -/// the new contact is the deepest. -int ContactManifold::getIndexOfDeepestPenetration(ContactPoint* newContact) const { - assert(mNbContactPoints == MAX_CONTACT_POINTS_IN_MANIFOLD); - int indexMaxPenetrationDepth = -1; - decimal maxPenetrationDepth = newContact->getPenetrationDepth(); - - // For each contact in the cache - for (uint i=0; igetPenetrationDepth() > maxPenetrationDepth) { - maxPenetrationDepth = mContactPoints[i]->getPenetrationDepth(); - indexMaxPenetrationDepth = i; - } - } - - // Return the index of largest penetration depth - return indexMaxPenetrationDepth; -} - -// Return the index that will be removed. -/// The index of the contact point with the larger penetration -/// depth is given as a parameter. This contact won't be removed. Given this contact, we compute -/// the different area and we want to keep the contacts with the largest area. The new point is also -/// kept. In order to compute the area of a quadrilateral, we use the formula : -/// Area = 0.5 * | AC x BD | where AC and BD form the diagonals of the quadrilateral. Note that -/// when we compute this area, we do not calculate it exactly but we -/// only estimate it because we do not compute the actual diagonals of the quadrialteral. Therefore, -/// this is only a guess that is faster to compute. This idea comes from the Bullet Physics library -/// by Erwin Coumans (http://wwww.bulletphysics.org). -int ContactManifold::getIndexToRemove(int indexMaxPenetration, const Vector3& newPoint) const { - - assert(mNbContactPoints == MAX_CONTACT_POINTS_IN_MANIFOLD); - - decimal area0 = 0.0; // Area with contact 1,2,3 and newPoint - decimal area1 = 0.0; // Area with contact 0,2,3 and newPoint - decimal area2 = 0.0; // Area with contact 0,1,3 and newPoint - decimal area3 = 0.0; // Area with contact 0,1,2 and newPoint - - if (indexMaxPenetration != 0) { - // Compute the area - Vector3 vector1 = newPoint - mContactPoints[1]->getLocalPointOnBody1(); - Vector3 vector2 = mContactPoints[3]->getLocalPointOnBody1() - - mContactPoints[2]->getLocalPointOnBody1(); - Vector3 crossProduct = vector1.cross(vector2); - area0 = crossProduct.lengthSquare(); - } - if (indexMaxPenetration != 1) { - // Compute the area - Vector3 vector1 = newPoint - mContactPoints[0]->getLocalPointOnBody1(); - Vector3 vector2 = mContactPoints[3]->getLocalPointOnBody1() - - mContactPoints[2]->getLocalPointOnBody1(); - Vector3 crossProduct = vector1.cross(vector2); - area1 = crossProduct.lengthSquare(); - } - if (indexMaxPenetration != 2) { - // Compute the area - Vector3 vector1 = newPoint - mContactPoints[0]->getLocalPointOnBody1(); - Vector3 vector2 = mContactPoints[3]->getLocalPointOnBody1() - - mContactPoints[1]->getLocalPointOnBody1(); - Vector3 crossProduct = vector1.cross(vector2); - area2 = crossProduct.lengthSquare(); - } - if (indexMaxPenetration != 3) { - // Compute the area - Vector3 vector1 = newPoint - mContactPoints[0]->getLocalPointOnBody1(); - Vector3 vector2 = mContactPoints[2]->getLocalPointOnBody1() - - mContactPoints[1]->getLocalPointOnBody1(); - Vector3 crossProduct = vector1.cross(vector2); - area3 = crossProduct.lengthSquare(); - } - - // Return the index of the contact to remove - return getMaxArea(area0, area1, area2, area3); -} - -// Return the index of maximum area -int ContactManifold::getMaxArea(decimal area0, decimal area1, decimal area2, decimal area3) const { - if (area0 < area1) { - if (area1 < area2) { - if (area2 < area3) return 3; - else return 2; - } - else { - if (area1 < area3) return 3; - else return 1; - } - } - else { - if (area0 < area2) { - if (area2 < area3) return 3; - else return 2; - } - else { - if (area0 < area3) return 3; - else return 0; - } - } -} - // Clear the contact manifold void ContactManifold::clear() { for (uint i=0; igetLocalToWorldTransform(), mShape2->getLocalToWorldTransform()); + + // Add the new contact point into the manifold + mContactPoints[mNbContactPoints] = contactPoint; + mNbContactPoints++; + +} + +// Remove a contact point +void ContactManifold::removeContactPoint(int index) { + + assert(mNbContactPoints > 0); + assert(index >= 0 && index < mNbContactPoints); + + // Delete the contact + mContactPoints[index]->~ContactPoint(); + mMemoryAllocator.release(mContactPoints[index], sizeof(ContactPoint)); + + for (int i=index; (i+1) < mNbContactPoints; i++) { + mContactPoints[i] = mContactPoints[i+1]; + } + + mNbContactPoints--; +} diff --git a/src/collision/ContactManifold.h b/src/collision/ContactManifold.h index c36c1476..da323c0f 100644 --- a/src/collision/ContactManifold.h +++ b/src/collision/ContactManifold.h @@ -31,6 +31,7 @@ #include "body/CollisionBody.h" #include "collision/ProxyShape.h" #include "constraint/ContactPoint.h" +#include "collision/ContactManifoldInfo.h" #include "memory/PoolAllocator.h" /// ReactPhysics3D namespace @@ -130,18 +131,6 @@ class ContactManifold { // -------------------- Methods -------------------- // - /// Return the index of maximum area - int getMaxArea(decimal area0, decimal area1, decimal area2, decimal area3) const; - - /// Return the index of the contact with the larger penetration depth. - int getIndexOfDeepestPenetration(ContactPoint* newContact) const; - - /// Return the index that will be removed. - int getIndexToRemove(int indexMaxPenetration, const Vector3& newPoint) const; - - /// Remove a contact point from the manifold - void removeContactPoint(uint index); - /// Return true if the contact manifold has already been added into an island bool isAlreadyInIsland() const; @@ -150,7 +139,7 @@ class ContactManifold { // -------------------- Methods -------------------- // /// Constructor - ContactManifold(ProxyShape* shape1, ProxyShape* shape2, + ContactManifold(const ContactManifoldInfo& manifoldInfo, ProxyShape* shape1, ProxyShape* shape2, PoolAllocator& memoryAllocator, short int normalDirectionId); /// Destructor @@ -177,12 +166,6 @@ class ContactManifold { /// Return the normal direction Id short int getNormalDirectionId() const; - /// Add a contact point to the manifold - void addContactPoint(ContactPoint* contact); - - /// Update the contact manifold. - void update(const Transform& transform1, const Transform& transform2); - /// Clear the contact manifold void clear(); @@ -231,6 +214,12 @@ class ContactManifold { /// Return the largest depth of all the contact points decimal getLargestContactDepth() const; + /// Add a contact point + void addContactPoint(const ContactPointInfo* contactPointInfo); + + /// Remove a contact point + void removeContactPoint(int index); + // -------------------- Friendship -------------------- // friend class DynamicsWorld; diff --git a/src/collision/ContactManifoldInfo.h b/src/collision/ContactManifoldInfo.h new file mode 100644 index 00000000..d4afc590 --- /dev/null +++ b/src/collision/ContactManifoldInfo.h @@ -0,0 +1,130 @@ +/******************************************************************************** +* 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_CONTACT_MANIFOLD_INFO_H +#define REACTPHYSICS3D_CONTACT_MANIFOLD_INFO_H + +// Libraries +#include "collision/ContactPointInfo.h" +#include "memory/Allocator.h" + +/// ReactPhysics3D namespace +namespace reactphysics3d { + + +// Class ContactManifoldInfo +/** + * This class is used to collect the list of ContactPointInfo that come + * from a collision test between two shapes. + */ +class ContactManifoldInfo { + + private: + + // -------------------- Attributes -------------------- // + + /// Linked list with all the contact points + ContactPointInfo* mContactPointsList; + + /// Memory allocator used to allocate contact points + Allocator& mAllocator; + + // -------------------- Methods -------------------- // + + + public: + + // -------------------- Methods -------------------- // + + /// Constructor + ContactManifoldInfo(Allocator& allocator) : mContactPointsList(nullptr), mAllocator(allocator) {} + + /// Destructor + ~ContactManifoldInfo() { + + // Delete all the contact points in the linked list + ContactPointInfo* element = mContactPointsList; + while(element != nullptr) { + ContactPointInfo* elementToDelete = element; + element = element->next; + + // Delete the current element + mAllocator.release(elementToDelete, sizeof(ContactPointInfo)); + } + } + + /// Deleted copy-constructor + ContactManifoldInfo(const ContactManifoldInfo& contactManifold) = delete; + + /// Deleted assignment operator + ContactManifoldInfo& operator=(const ContactManifoldInfo& contactManifold) = delete; + + /// Add a new contact point into the manifold + void addContactPoint(const Vector3& contactNormal, decimal penDepth, + const Vector3& localPt1, const Vector3& localPt2) { + + assert(penDepth > decimal(0.0)); + + // Create the contact point info + ContactPointInfo* contactPointInfo = new (mAllocator.allocate(sizeof(ContactPointInfo))) + ContactPointInfo(contactNormal, penDepth, localPt1, localPt2); + + // Add it into the linked list of contact points + contactPointInfo->next = mContactPointsList; + mContactPointsList = contactPointInfo; + } + + /// Get the first contact point info of the linked list of contact points + ContactPointInfo* getFirstContactPointInfo() const { + return mContactPointsList; + } + + /// Reduce the number of points in the contact manifold + void reduce() { + + // TODO : Implement this (do not forget to deallocate removed points) + } + + /// Return the largest penetration depth among the contact points + decimal getLargestPenetrationDepth() const { + + decimal maxDepth = decimal(0.0); + ContactPointInfo* element = mContactPointsList; + while(element != nullptr) { + + if (element->penetrationDepth > maxDepth) { + maxDepth = element->penetrationDepth; + } + + element = element->next; + } + + return maxDepth; + } +}; + +} +#endif + diff --git a/src/collision/ContactManifoldSet.cpp b/src/collision/ContactManifoldSet.cpp index a7dc9d2e..c9b0d5bb 100644 --- a/src/collision/ContactManifoldSet.cpp +++ b/src/collision/ContactManifoldSet.cpp @@ -43,92 +43,147 @@ ContactManifoldSet::~ContactManifoldSet() { clear(); } -// Add a contact point to the manifold set -void ContactManifoldSet::addContactPoint(ContactPoint* contact) { +void ContactManifoldSet::addContactManifold(const ContactManifoldInfo& contactManifoldInfo) { - // Compute an Id corresponding to the normal direction (using a cubemap) - short int normalDirectionId = computeCubemapNormalId(contact->getNormal()); + assert(contactManifoldInfo.getFirstContactPointInfo() != nullptr); // If there is no contact manifold yet if (mNbManifolds == 0) { - createManifold(normalDirectionId); - mManifolds[0]->addContactPoint(contact); - assert(mManifolds[mNbManifolds-1]->getNbContactPoints() > 0); - for (int i=0; igetNbContactPoints() > 0); + // If the maximum number of manifold is 1 + if (mNbMaxManifolds == 1) { + createManifold(contactManifoldInfo, 0); + } + else { + + // Compute an Id corresponding to the normal direction (using a cubemap) + short int normalDirectionId = computeCubemapNormalId(contactManifoldInfo.getFirstContactPointInfo()->normal); + + createManifold(contactManifoldInfo, normalDirectionId); + } + } + else { // If there is already at least one contact manifold in the set + + // If the maximum number of manifold is 1 + if (mNbMaxManifolds == 1) { + + // Replace the old manifold with the new one + updateManifoldWithNewOne(0, contactManifoldInfo); + } + else { + + // Compute an Id corresponding to the normal direction (using a cubemap) + short int normalDirectionId = computeCubemapNormalId(contactManifoldInfo.getFirstContactPointInfo()->normal); + + // Select the manifold with the most similar normal (if exists) + int similarManifoldIndex = 0; + if (mNbMaxManifolds > 1) { + similarManifoldIndex = selectManifoldWithSimilarNormal(normalDirectionId); + } + + // If a similar manifold has been found + if (similarManifoldIndex != -1) { + + // Replace the old manifold with the new one + updateManifoldWithNewOne(similarManifoldIndex, contactManifoldInfo); + } + else { + + // If we have not reach the maximum number of manifolds + if (mNbManifolds < mNbMaxManifolds) { + + // Create the new contact manifold + createManifold(contactManifoldInfo, normalDirectionId); + } + else { + + decimal newManifoldPenDepth = contactManifoldInfo.getLargestPenetrationDepth(); + + // We have reached the maximum number of manifold, we do not + // want to keep the manifold with the smallest penetration detph + int smallestPenDepthManifoldIndex = getManifoldWithSmallestContactPenetrationDepth(newManifoldPenDepth); + + // If the manifold with the smallest penetration depth is not the new one, + // we have to keep the new manifold and remove the one with the smallest depth + if (smallestPenDepthManifoldIndex >= 0) { + removeManifold(smallestPenDepthManifoldIndex); + createManifold(contactManifoldInfo, normalDirectionId); + } + } + } + } + } +} + +// Update a previous similar manifold with a new one +void ContactManifoldSet::updateManifoldWithNewOne(int oldManifoldIndex, const ContactManifoldInfo& newManifold) { + + // For each contact point of the previous manifold + for (int i=0; igetNbContactPoints(); ) { + + ContactPoint* contactPoint = mManifolds[oldManifoldIndex]->getContactPoint(i); + + // For each contact point in the new manifold + ContactPointInfo* newPoint = newManifold.getFirstContactPointInfo(); + bool needToRemovePoint = true; + while (newPoint != nullptr) { + + // If the new contact point is similar (very close) to the old contact point + if (!newPoint->isUsed && contactPoint->isSimilarWithContactPoint(newPoint)) { + + // Replace (update) the old contact point with the new one + contactPoint->update(newPoint, mManifolds[oldManifoldIndex]->getShape1()->getLocalToWorldTransform(), + mManifolds[oldManifoldIndex]->getShape2()->getLocalToWorldTransform()); + needToRemovePoint = false; + newPoint->isUsed = true; + break; + } + + newPoint = newPoint->next; + } + + // If no new contact point is similar to the old one + if (needToRemovePoint) { + + // Remove the old contact point + mManifolds[oldManifoldIndex]->removeContactPoint(i); + } + else { + i++; + } + } + + // For each point of the new manifold that have not been used yet (to update + // an existing point in the previous manifold), add it into the previous manifold + const ContactPointInfo* newPointInfo = newManifold.getFirstContactPointInfo(); + while (newPointInfo != nullptr) { + + if (!newPointInfo->isUsed) { + mManifolds[oldManifoldIndex]->addContactPoint(newPointInfo); } - return; - } + newPointInfo = newPointInfo->next; + } +} - // Select the manifold with the most similar normal (if exists) - int similarManifoldIndex = 0; - if (mNbMaxManifolds > 1) { - similarManifoldIndex = selectManifoldWithSimilarNormal(normalDirectionId); - } - - // If a similar manifold has been found - if (similarManifoldIndex != -1) { - - // Add the contact point to that similar manifold - mManifolds[similarManifoldIndex]->addContactPoint(contact); - assert(mManifolds[similarManifoldIndex]->getNbContactPoints() > 0); - - return; - } - - // If the maximum number of manifold has not been reached yet - if (mNbManifolds < mNbMaxManifolds) { - - // Create a new manifold for the contact point - createManifold(normalDirectionId); - mManifolds[mNbManifolds-1]->addContactPoint(contact); - for (int i=0; igetNbContactPoints() > 0); - } - - return; - } +// Return the manifold with the smallest contact penetration depth +int ContactManifoldSet::getManifoldWithSmallestContactPenetrationDepth(decimal initDepth) const { // The contact point will be in a new contact manifold, we now have too much - // manifolds condidates. We need to remove one. We choose to keep the manifolds - // with the largest contact depth among their points - int smallestDepthIndex = -1; - decimal minDepth = contact->getPenetrationDepth(); + // manifolds condidates. We need to remove one. We choose to remove the manifold + // with the smallest contact depth among their points + int smallestDepthManifoldIndex = -1; + decimal minDepth = initDepth; assert(mNbManifolds == mNbMaxManifolds); for (int i=0; igetLargestContactDepth(); if (depth < minDepth) { minDepth = depth; - smallestDepthIndex = i; + smallestDepthManifoldIndex = i; } } - // If we do not want to keep to new manifold (not created yet) with the - // new contact point - if (smallestDepthIndex == -1) { - - // Delete the new contact - contact->~ContactPoint(); - mMemoryAllocator.release(contact, sizeof(ContactPoint)); - - return; - } - - assert(smallestDepthIndex >= 0 && smallestDepthIndex < mNbManifolds); - - // Here we need to replace an existing manifold with a new one (that contains - // the new contact point) - removeManifold(smallestDepthIndex); - createManifold(normalDirectionId); - mManifolds[mNbManifolds-1]->addContactPoint(contact); - assert(mManifolds[mNbManifolds-1]->getNbContactPoints() > 0); - for (int i=0; igetNbContactPoints() > 0); - } - - return; + return smallestDepthManifoldIndex; } // Return the index of the contact manifold with a similar average normal. @@ -154,7 +209,7 @@ short int ContactManifoldSet::computeCubemapNormalId(const Vector3& normal) cons int faceNo; decimal u, v; - decimal max = max3(fabs(normal.x), fabs(normal.y), fabs(normal.z)); + decimal max = max3(std::fabs(normal.x), std::fabs(normal.y), std::fabs(normal.z)); Vector3 normalScaled = normal / max; if (normalScaled.x >= normalScaled.y && normalScaled.x >= normalScaled.z) { @@ -173,8 +228,8 @@ short int ContactManifoldSet::computeCubemapNormalId(const Vector3& normal) cons v = normalScaled.y; } - int indexU = floor(((u + 1)/2) * CONTACT_CUBEMAP_FACE_NB_SUBDIVISIONS); - int indexV = floor(((v + 1)/2) * CONTACT_CUBEMAP_FACE_NB_SUBDIVISIONS); + int indexU = std::floor(((u + 1)/2) * CONTACT_CUBEMAP_FACE_NB_SUBDIVISIONS); + int indexV = std::floor(((v + 1)/2) * CONTACT_CUBEMAP_FACE_NB_SUBDIVISIONS); if (indexU == CONTACT_CUBEMAP_FACE_NB_SUBDIVISIONS) indexU--; if (indexV == CONTACT_CUBEMAP_FACE_NB_SUBDIVISIONS) indexV--; @@ -182,22 +237,6 @@ short int ContactManifoldSet::computeCubemapNormalId(const Vector3& normal) cons return faceNo * 200 + indexU * nbSubDivInFace + indexV; } -// Update the contact manifolds -void ContactManifoldSet::update() { - - for (int i=mNbManifolds-1; i>=0; i--) { - - // Update the contact manifold - mManifolds[i]->update(mShape1->getBody()->getTransform() * mShape1->getLocalToBodyTransform(), - mShape2->getBody()->getTransform() * mShape2->getLocalToBodyTransform()); - - // Remove the contact manifold if has no contact points anymore - if (mManifolds[i]->getNbContactPoints() == 0) { - removeManifold(i); - } - } -} - // Clear the contact manifold set void ContactManifoldSet::clear() { @@ -210,11 +249,11 @@ void ContactManifoldSet::clear() { } // Create a new contact manifold and add it to the set -void ContactManifoldSet::createManifold(short int normalDirectionId) { +void ContactManifoldSet::createManifold(const ContactManifoldInfo& manifoldInfo, short int normalDirectionId) { assert(mNbManifolds < mNbMaxManifolds); mManifolds[mNbManifolds] = new (mMemoryAllocator.allocate(sizeof(ContactManifold))) - ContactManifold(mShape1, mShape2, mMemoryAllocator, normalDirectionId); + ContactManifold(manifoldInfo, mShape1, mShape2, mMemoryAllocator, normalDirectionId); mNbManifolds++; } diff --git a/src/collision/ContactManifoldSet.h b/src/collision/ContactManifoldSet.h index 21944e36..1a2bac97 100644 --- a/src/collision/ContactManifoldSet.h +++ b/src/collision/ContactManifoldSet.h @@ -69,7 +69,7 @@ class ContactManifoldSet { // -------------------- Methods -------------------- // /// Create a new contact manifold and add it to the set - void createManifold(short normalDirectionId); + void createManifold(const ContactManifoldInfo& manifoldInfo, short normalDirectionId); /// Remove a contact manifold from the set void removeManifold(int index); @@ -82,6 +82,12 @@ class ContactManifoldSet { // normal vector into of the of the bucket and returns a unique Id for the bucket short int computeCubemapNormalId(const Vector3& normal) const; + /// Return the manifold with the smallest contact penetration depth + int getManifoldWithSmallestContactPenetrationDepth(decimal initDepth) const; + + /// Update a previous similar manifold with a new one + void updateManifoldWithNewOne(int oldManifoldIndex, const ContactManifoldInfo& newManifold); + public: // -------------------- Methods -------------------- // @@ -93,18 +99,15 @@ class ContactManifoldSet { /// Destructor ~ContactManifoldSet(); + /// Add a contact manifold in the set + void addContactManifold(const ContactManifoldInfo& contactManifoldInfo); + /// Return the first proxy shape ProxyShape* getShape1() const; /// Return the second proxy shape ProxyShape* getShape2() const; - /// Add a contact point to the manifold set - void addContactPoint(ContactPoint* contact); - - /// Update the contact manifolds - void update(); - /// Clear the contact manifold set void clear(); diff --git a/src/collision/ContactPointInfo.h b/src/collision/ContactPointInfo.h new file mode 100644 index 00000000..1ff8bfdd --- /dev/null +++ b/src/collision/ContactPointInfo.h @@ -0,0 +1,88 @@ +/******************************************************************************** +* 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_CONTACT_POINT_INFO_H +#define REACTPHYSICS3D_CONTACT_POINT_INFO_H + +// Libraries +#include "body/CollisionBody.h" +#include "mathematics/mathematics.h" +#include "configuration.h" + +/// ReactPhysics3D namespace +namespace reactphysics3d { + +// Structure ContactPointInfo +/** + * This structure contains informations about a collision contact + * computed during the narrow-phase collision detection. Those + * informations are used to compute the contact set for a contact + * between two bodies. + */ +struct ContactPointInfo { + + private: + + // -------------------- Methods -------------------- // + + public: + + // -------------------- Attributes -------------------- // + + /// Normalized normal vector of the collision contact in world space + Vector3 normal; + + /// Penetration depth of the contact + decimal penetrationDepth; + + /// Contact point of body 1 in local space of body 1 + Vector3 localPoint1; + + /// Contact point of body 2 in local space of body 2 + Vector3 localPoint2; + + /// Pointer to the next contact point info + ContactPointInfo* next; + + /// True if the contact point has already been inserted into a manifold + bool isUsed; + + // -------------------- Methods -------------------- // + + /// Constructor + ContactPointInfo(const Vector3& contactNormal, decimal penDepth, + const Vector3& localPt1, const Vector3& localPt2) + : normal(contactNormal), penetrationDepth(penDepth), + localPoint1(localPt1), localPoint2(localPt2), next(nullptr), isUsed(false) { + + } + + /// Destructor + ~ContactPointInfo() = default; +}; + +} + +#endif diff --git a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp index 2f9f8703..e83d694c 100644 --- a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp @@ -30,8 +30,11 @@ // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; -bool CapsuleVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactPointInfo& contactPointInfo) { +bool CapsuleVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) { + assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE); + assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CAPSULE); + const decimal parallelEpsilon = decimal(0.001); // Get the capsule collision shapes @@ -39,7 +42,7 @@ bool CapsuleVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhase const CapsuleShape* capsuleShape2 = static_cast(narrowPhaseInfo->collisionShape2); // Get the transform from capsule 1 local-space to capsule 2 local-space - const Transform capsule1ToCapsule2SpaceTransform = narrowPhaseInfo->shape1ToWorldTransform * narrowPhaseInfo->shape2ToWorldTransform.getInverse(); + const Transform capsule1ToCapsule2SpaceTransform = narrowPhaseInfo->shape2ToWorldTransform.getInverse() * narrowPhaseInfo->shape1ToWorldTransform; // Compute the end-points of the inner segment of the first capsule Vector3 capsule1SegA(0, -capsuleShape1->getHeight() * decimal(0.5), 0); @@ -63,7 +66,7 @@ bool CapsuleVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhase // If the distance between the two segments is larger than the sum of the capsules radius (we do not have overlapping) const decimal segmentsDistance = computeDistancePointToLineDistance(capsule1SegA, capsule1SegB, capsule2SegA); - if (segmentsDistance > sumRadius || segmentsDistance < MACHINE_EPSILON) { + if (segmentsDistance >= sumRadius || segmentsDistance < MACHINE_EPSILON) { // The capsule are parallel but their inner segment distance is larger than the sum of the capsules radius. // Therefore, we do not have overlap. If the inner segments overlap, we do not report any collision. @@ -102,8 +105,9 @@ bool CapsuleVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhase Vector3 segment1ToSegment2 = (capsule2SegA - capsule1SegA); Vector3 segment1ToSegment2Normalized = segment1ToSegment2.getUnit(); - const Vector3 contactPointACapsule1Local = capsule1ToCapsule2SpaceTransform.getInverse() * (clipPointA - segment1ToSegment2 + segment1ToSegment2Normalized * capsuleShape1->getRadius()); - const Vector3 contactPointBCapsule1Local = capsule1ToCapsule2SpaceTransform.getInverse() * (clipPointB - segment1ToSegment2 + segment1ToSegment2Normalized * capsuleShape1->getRadius()); + Transform capsule2ToCapsule1SpaceTransform = capsule1ToCapsule2SpaceTransform.getInverse(); + const Vector3 contactPointACapsule1Local = capsule2ToCapsule1SpaceTransform * (clipPointA - segment1ToSegment2 + segment1ToSegment2Normalized * capsuleShape1->getRadius()); + const Vector3 contactPointBCapsule1Local = capsule2ToCapsule1SpaceTransform * (clipPointB - segment1ToSegment2 + segment1ToSegment2Normalized * capsuleShape1->getRadius()); const Vector3 contactPointACapsule2Local = clipPointA - segment1ToSegment2Normalized * capsuleShape2->getRadius(); const Vector3 contactPointBCapsule2Local = clipPointB - segment1ToSegment2Normalized * capsuleShape2->getRadius(); @@ -112,9 +116,10 @@ bool CapsuleVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhase decimal penetrationDepth = sumRadius - segmentsDistance; // Create the contact info object - // TODO : Make sure we create two contact points at the same time (same method here) - contactPointInfo.init(normalWorld, penetrationDepth, contactPointACapsule1Local, contactPointBCapsule1Local); - contactPointInfo.init(normalWorld, penetrationDepth, contactPointACapsule2Local, contactPointBCapsule2Local); + contactManifoldInfo.addContactPoint(normalWorld, penetrationDepth, contactPointACapsule1Local, contactPointACapsule2Local); + contactManifoldInfo.addContactPoint(normalWorld, penetrationDepth, contactPointBCapsule1Local, contactPointBCapsule2Local); + + return true; } } @@ -129,7 +134,7 @@ bool CapsuleVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhase const decimal closestPointsDistanceSquare = closestPointsSeg1ToSeg2.lengthSquare(); // If the collision shapes overlap - if (closestPointsDistanceSquare <= sumRadius * sumRadius && closestPointsDistanceSquare > MACHINE_EPSILON) { + if (closestPointsDistanceSquare < sumRadius * sumRadius && closestPointsDistanceSquare > MACHINE_EPSILON) { decimal closestPointsDistance = std::sqrt(closestPointsDistanceSquare); closestPointsSeg1ToSeg2 /= closestPointsDistance; @@ -142,7 +147,7 @@ bool CapsuleVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhase decimal penetrationDepth = sumRadius - closestPointsDistance; // Create the contact info object - contactPointInfo.init(normalWorld, penetrationDepth, contactPointCapsule1Local, contactPointCapsule2Local); + contactManifoldInfo.addContactPoint(normalWorld, penetrationDepth, contactPointCapsule1Local, contactPointCapsule2Local); return true; } diff --git a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h index 7a46f73a..898d6337 100644 --- a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h +++ b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h @@ -62,7 +62,7 @@ class CapsuleVsCapsuleAlgorithm : public NarrowPhaseAlgorithm { /// Compute a contact info if the two bounding volume collide virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactPointInfo& contactPointInfo) override; + ContactManifoldInfo& contactManifoldInfo) override; }; } diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.cpp b/src/collision/narrowphase/DefaultCollisionDispatch.cpp index 88d4b9b2..5fdd485b 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.cpp +++ b/src/collision/narrowphase/DefaultCollisionDispatch.cpp @@ -45,7 +45,7 @@ NarrowPhaseAlgorithm* DefaultCollisionDispatch::selectAlgorithm(int type1, int t return &mSphereVsSphereAlgorithm; } // Sphere vs Capsule algorithm - if (shape1Type == CollisionShapeType::CAPSULE && shape2Type == CollisionShapeType::SPHERE) { + if (shape1Type == CollisionShapeType::SPHERE && shape2Type == CollisionShapeType::CAPSULE) { return &mSphereVsCapsuleAlgorithm; } // Capsule vs Capsule algorithm diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp index 4ea55ba4..6be90769 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp @@ -47,7 +47,7 @@ using namespace reactphysics3d; /// origin, they we give that simplex polytope to the EPA algorithm which will compute /// the correct penetration depth and contact points between the enlarged objects. GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactPointInfo& contactPointInfo) { + ContactManifoldInfo& contactManifoldInfo) { PROFILE("GJKAlgorithm::testCollision()"); @@ -201,8 +201,8 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(const NarrowPhaseInfo* narro return GJKResult::INTERPENETRATE; } - // Create the contact info object - contactPointInfo.init(normal, penetrationDepth, pA, pB); + // Add a new contact point + contactManifoldInfo.addContactPoint(normal, penetrationDepth, pA, pB); return GJKResult::COLLIDE_IN_MARGIN; } diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.h b/src/collision/narrowphase/GJK/GJKAlgorithm.h index 8ca25e33..f40592c4 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.h +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.h @@ -27,7 +27,8 @@ #define REACTPHYSICS3D_GJK_ALGORITHM_H // Libraries -#include "constraint/ContactPoint.h" +#include "collision/ContactManifoldInfo.h" +#include "collision/NarrowPhaseInfo.h" #include "collision/shapes/ConvexShape.h" #include "VoronoiSimplex.h" @@ -87,7 +88,7 @@ class GJKAlgorithm { /// Compute a contact info if the two bounding volumes collide. GJKResult testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactPointInfo& contactPointInfo); + ContactManifoldInfo& contactManifoldInfo); /// Use the GJK Algorithm to find if a point is inside a convex collision shape bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape); diff --git a/src/collision/narrowphase/NarrowPhaseAlgorithm.h b/src/collision/narrowphase/NarrowPhaseAlgorithm.h index f7f68907..f665181b 100644 --- a/src/collision/narrowphase/NarrowPhaseAlgorithm.h +++ b/src/collision/narrowphase/NarrowPhaseAlgorithm.h @@ -28,7 +28,7 @@ // Libraries #include "body/Body.h" -#include "constraint/ContactPoint.h" +#include "collision/ContactManifoldInfo.h" #include "memory/PoolAllocator.h" #include "engine/OverlappingPair.h" #include "collision/NarrowPhaseInfo.h" @@ -84,7 +84,7 @@ class NarrowPhaseAlgorithm { NarrowPhaseAlgorithm& operator=(const NarrowPhaseAlgorithm& algorithm) = delete; /// Compute a contact info if the two bounding volume collide - virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactPointInfo& contactPointInfo)=0; + virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo)=0; }; } diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index d74faf09..b46ca386 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -37,7 +37,7 @@ using namespace reactphysics3d; bool SATAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactPointInfo& contactPointInfo) { + ContactManifoldInfo& contactManifoldInfo) { } diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.h b/src/collision/narrowphase/SAT/SATAlgorithm.h index 30156cc2..80feece1 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.h +++ b/src/collision/narrowphase/SAT/SATAlgorithm.h @@ -27,7 +27,8 @@ #define REACTPHYSICS3D_SAT_ALGORITHM_H // Libraries -#include "constraint/ContactPoint.h" +#include "collision/ContactManifoldInfo.h" +#include "collision/NarrowPhaseInfo.h" /// ReactPhysics3D namespace namespace reactphysics3d { @@ -59,7 +60,7 @@ class SATAlgorithm { /// Compute a contact info if the two bounding volumes collide. bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactPointInfo& contactPointInfo); + ContactManifoldInfo& contactManifoldInfo); }; } diff --git a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp index 24cb4e96..aace17fd 100644 --- a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp @@ -31,14 +31,17 @@ // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; -bool SphereVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactPointInfo& contactPointInfo) { +bool SphereVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) { + assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE); + assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CAPSULE); + // Get the collision shapes const SphereShape* sphereShape = static_cast(narrowPhaseInfo->collisionShape1); const CapsuleShape* capsuleShape = static_cast(narrowPhaseInfo->collisionShape2); // Get the transform from sphere local-space to capsule local-space - const Transform sphereToCapsuleSpaceTransform = narrowPhaseInfo->shape1ToWorldTransform * narrowPhaseInfo->shape2ToWorldTransform.getInverse(); + const Transform sphereToCapsuleSpaceTransform = narrowPhaseInfo->shape2ToWorldTransform.getInverse() * narrowPhaseInfo->shape1ToWorldTransform; // Transform the center of the sphere into the local-space of the capsule shape const Vector3 sphereCenter = sphereToCapsuleSpaceTransform.getPosition(); @@ -58,7 +61,7 @@ bool SphereVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseI decimal sumRadius = sphereShape->getRadius() + capsuleShape->getRadius(); // If the collision shapes overlap - if (sphereSegmentDistanceSquare <= sumRadius * sumRadius && sphereSegmentDistanceSquare > MACHINE_EPSILON) { + if (sphereSegmentDistanceSquare < sumRadius * sumRadius && sphereSegmentDistanceSquare > MACHINE_EPSILON) { decimal sphereSegmentDistance = std::sqrt(sphereSegmentDistanceSquare); sphereCenterToSegment /= sphereSegmentDistance; @@ -71,7 +74,7 @@ bool SphereVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseI decimal penetrationDepth = sumRadius - sphereSegmentDistance; // Create the contact info object - contactPointInfo.init(normalWorld, penetrationDepth, contactPointSphereLocal, contactPointCapsuleLocal); + contactManifoldInfo.addContactPoint(normalWorld, penetrationDepth, contactPointSphereLocal, contactPointCapsuleLocal); return true; } diff --git a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h index 98eaf894..784df6f9 100644 --- a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h +++ b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h @@ -62,7 +62,7 @@ class SphereVsCapsuleAlgorithm : public NarrowPhaseAlgorithm { /// Compute a contact info if the two bounding volume collide virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactPointInfo& contactPointInfo) override; + ContactManifoldInfo& contactManifoldInfo) override; }; } diff --git a/src/collision/narrowphase/SphereVsConvexMeshAlgorithm.cpp b/src/collision/narrowphase/SphereVsConvexMeshAlgorithm.cpp index 65371e4f..06dbc615 100644 --- a/src/collision/narrowphase/SphereVsConvexMeshAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsConvexMeshAlgorithm.cpp @@ -33,7 +33,7 @@ using namespace reactphysics3d; bool SphereVsConvexMeshAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactPointInfo& contactPointInfo) { + ContactManifoldInfo& contactManifoldInfo) { // Get the local-space to world-space transforms const Transform& transform1 = narrowPhaseInfo->shape1ToWorldTransform; @@ -41,7 +41,7 @@ bool SphereVsConvexMeshAlgorithm::testCollision(const NarrowPhaseInfo* narrowPha // First, we run the GJK algorithm GJKAlgorithm gjkAlgorithm; - GJKAlgorithm::GJKResult result = gjkAlgorithm.testCollision(narrowPhaseInfo, contactPointInfo); + GJKAlgorithm::GJKResult result = gjkAlgorithm.testCollision(narrowPhaseInfo, contactManifoldInfo); // If we have found a contact point inside the margins (shallow penetration) if (result == GJKAlgorithm::GJKResult::COLLIDE_IN_MARGIN) { @@ -55,7 +55,7 @@ bool SphereVsConvexMeshAlgorithm::testCollision(const NarrowPhaseInfo* narrowPha // Run the SAT algorithm to find the separating axis and compute contact point SATAlgorithm satAlgorithm; - return satAlgorithm.testCollision(narrowPhaseInfo, contactPointInfo); + return satAlgorithm.testCollision(narrowPhaseInfo, contactManifoldInfo); } return false; diff --git a/src/collision/narrowphase/SphereVsConvexMeshAlgorithm.h b/src/collision/narrowphase/SphereVsConvexMeshAlgorithm.h index 448b8a5d..f0046545 100644 --- a/src/collision/narrowphase/SphereVsConvexMeshAlgorithm.h +++ b/src/collision/narrowphase/SphereVsConvexMeshAlgorithm.h @@ -62,7 +62,7 @@ class SphereVsConvexMeshAlgorithm : public NarrowPhaseAlgorithm { /// Compute a contact info if the two bounding volume collide virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactPointInfo& contactPointInfo) override; + ContactManifoldInfo& contactManifoldInfo) override; }; } diff --git a/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp b/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp index e80688d5..54e51e52 100644 --- a/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp @@ -31,8 +31,11 @@ using namespace reactphysics3d; bool SphereVsSphereAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactPointInfo& contactPointInfo) { + ContactManifoldInfo& contactManifoldInfo) { + assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE); + assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::SPHERE); + // Get the sphere collision shapes const SphereShape* sphereShape1 = static_cast(narrowPhaseInfo->collisionShape1); const SphereShape* sphereShape2 = static_cast(narrowPhaseInfo->collisionShape2); @@ -49,7 +52,7 @@ bool SphereVsSphereAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseIn decimal sumRadius = sphereShape1->getRadius() + sphereShape2->getRadius(); // If the sphere collision shapes intersect - if (squaredDistanceBetweenCenters <= sumRadius * sumRadius) { + if (squaredDistanceBetweenCenters < sumRadius * sumRadius) { Vector3 centerSphere2InBody1LocalSpace = transform1.getInverse() * transform2.getPosition(); Vector3 centerSphere1InBody2LocalSpace = transform2.getInverse() * transform1.getPosition(); Vector3 intersectionOnBody1 = sphereShape1->getRadius() * @@ -59,8 +62,8 @@ bool SphereVsSphereAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseIn decimal penetrationDepth = sumRadius - std::sqrt(squaredDistanceBetweenCenters); // Create the contact info object - contactPointInfo.init(vectorBetweenCenters.getUnit(), penetrationDepth, - intersectionOnBody1, intersectionOnBody2); + contactManifoldInfo.addContactPoint(vectorBetweenCenters.getUnit(), penetrationDepth, + intersectionOnBody1, intersectionOnBody2); return true; } diff --git a/src/collision/narrowphase/SphereVsSphereAlgorithm.h b/src/collision/narrowphase/SphereVsSphereAlgorithm.h index be10d5a1..b70befd2 100644 --- a/src/collision/narrowphase/SphereVsSphereAlgorithm.h +++ b/src/collision/narrowphase/SphereVsSphereAlgorithm.h @@ -62,7 +62,7 @@ class SphereVsSphereAlgorithm : public NarrowPhaseAlgorithm { /// Compute a contact info if the two bounding volume collide virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactPointInfo& contactPointInfo) override; + ContactManifoldInfo& contactManifoldInfo) override; }; } diff --git a/src/collision/shapes/CollisionShape.h b/src/collision/shapes/CollisionShape.h index 464c1bd5..c2db3466 100644 --- a/src/collision/shapes/CollisionShape.h +++ b/src/collision/shapes/CollisionShape.h @@ -40,7 +40,7 @@ namespace reactphysics3d { /// Type of the collision shape -enum class CollisionShapeType {TRIANGLE, BOX, CAPSULE, SPHERE, CONVEX_MESH, CONCAVE_MESH, HEIGHTFIELD}; +enum class CollisionShapeType {TRIANGLE, SPHERE, CAPSULE, BOX, CONVEX_MESH, CONCAVE_MESH, HEIGHTFIELD}; const int NB_COLLISION_SHAPE_TYPES = 9; // Declarations diff --git a/src/constraint/ContactPoint.cpp b/src/constraint/ContactPoint.cpp index 00ed60d7..f420bbff 100644 --- a/src/constraint/ContactPoint.cpp +++ b/src/constraint/ContactPoint.cpp @@ -31,13 +31,35 @@ using namespace reactphysics3d; using namespace std; // Constructor -ContactPoint::ContactPoint(const ContactPointInfo& contactInfo) - : mNormal(contactInfo.normal), - mPenetrationDepth(contactInfo.penetrationDepth), - mLocalPointOnBody1(contactInfo.localPoint1), - mLocalPointOnBody2(contactInfo.localPoint2), +ContactPoint::ContactPoint(const ContactPointInfo* contactInfo, const Transform& body1Transform, + const Transform& body2Transform) + : mNormal(contactInfo->normal), + mPenetrationDepth(contactInfo->penetrationDepth), + mLocalPointOnBody1(contactInfo->localPoint1), + mLocalPointOnBody2(contactInfo->localPoint2), mIsRestingContact(false) { assert(mPenetrationDepth > decimal(0.0)); + // Compute the world position of the contact points + mWorldPointOnBody1 = body1Transform * mLocalPointOnBody1; + mWorldPointOnBody2 = body2Transform * mLocalPointOnBody2; +} + +// Update the contact point with a new one that is similar (very close) +/// The idea is to keep the cache impulse (for warm starting the contact solver) +void ContactPoint::update(const ContactPointInfo* contactInfo, const Transform& body1Transform, + const Transform& body2Transform) { + + assert(isSimilarWithContactPoint(contactInfo)); + assert(contactInfo->penetrationDepth > decimal(0.0)); + + mNormal = contactInfo->normal; + mPenetrationDepth = contactInfo->penetrationDepth; + mLocalPointOnBody1 = contactInfo->localPoint1; + mLocalPointOnBody2 = contactInfo->localPoint2; + + // Compute the world position of the contact points + mWorldPointOnBody1 = body1Transform * mLocalPointOnBody1; + mWorldPointOnBody2 = body2Transform * mLocalPointOnBody2; } diff --git a/src/constraint/ContactPoint.h b/src/constraint/ContactPoint.h index 4028ed8f..ec4c6556 100644 --- a/src/constraint/ContactPoint.h +++ b/src/constraint/ContactPoint.h @@ -29,60 +29,13 @@ // Libraries #include "body/CollisionBody.h" #include "collision/NarrowPhaseInfo.h" +#include "collision/ContactPointInfo.h" #include "configuration.h" #include "mathematics/mathematics.h" -#include "configuration.h" /// ReactPhysics3D namespace namespace reactphysics3d { -// Structure ContactPointInfo -/** - * This structure contains informations about a collision contact - * computed during the narrow-phase collision detection. Those - * informations are used to compute the contact set for a contact - * between two bodies. - */ -struct ContactPointInfo { - - private: - - // -------------------- Methods -------------------- // - - public: - - // -------------------- Attributes -------------------- // - - /// Normalized normal vector of the collision contact in world space - Vector3 normal; - - /// Penetration depth of the contact - decimal penetrationDepth; - - /// Contact point of body 1 in local space of body 1 - Vector3 localPoint1; - - /// Contact point of body 2 in local space of body 2 - Vector3 localPoint2; - - // -------------------- Methods -------------------- // - - /// Constructor - ContactPointInfo() = default; - - /// Destructor - ~ContactPointInfo() = default; - - /// Initialize the contact point info - void init(const Vector3& contactNormal, decimal penDepth, - const Vector3& localPt1, const Vector3& localPt2) { - normal = contactNormal; - penetrationDepth = penDepth; - localPoint1 = localPt1; - localPoint2 = localPt2; - } -}; - // Class ContactPoint /** * This class represents a collision contact point between two @@ -95,16 +48,16 @@ class ContactPoint { // -------------------- Attributes -------------------- // /// Normalized normal vector of the contact (from body1 toward body2) in world space - const Vector3 mNormal; + Vector3 mNormal; /// Penetration depth decimal mPenetrationDepth; /// Contact point on body 1 in local space of body 1 - const Vector3 mLocalPointOnBody1; + Vector3 mLocalPointOnBody1; /// Contact point on body 2 in local space of body 2 - const Vector3 mLocalPointOnBody2; + Vector3 mLocalPointOnBody2; /// Contact point on body 1 in world space Vector3 mWorldPointOnBody1; @@ -123,7 +76,8 @@ class ContactPoint { // -------------------- Methods -------------------- // /// Constructor - ContactPoint(const ContactPointInfo& contactInfo); + ContactPoint(const ContactPointInfo* contactInfo, const Transform& body1Transform, + const Transform& body2Transform); /// Destructor ~ContactPoint() = default; @@ -134,11 +88,9 @@ class ContactPoint { /// Deleted assignment operator ContactPoint& operator=(const ContactPoint& contact) = delete; - /// Update the world contact points - void updateWorldContactPoints(const Transform& body1Transform, const Transform& body2Transform); - - /// Update the penetration depth - void updatePenetrationDepth(); + /// Update the contact point with a new one that is similar (very close) + void update(const ContactPointInfo* contactInfo, const Transform& body1Transform, + const Transform& body2Transform); /// Return the normal vector of the contact Vector3 getNormal() const; @@ -158,6 +110,9 @@ class ContactPoint { /// Return the cached penetration impulse decimal getPenetrationImpulse() const; + /// Return true if the contact point is similar (close enougth) to another given contact point + bool isSimilarWithContactPoint(const ContactPointInfo* contactPoint) const; + /// Set the cached penetration impulse void setPenetrationImpulse(decimal impulse); @@ -174,17 +129,6 @@ class ContactPoint { size_t getSizeInBytes() const; }; -// Update the world contact points -inline void ContactPoint::updateWorldContactPoints(const Transform& body1Transform, const Transform& body2Transform) { - mWorldPointOnBody1 = body1Transform * mLocalPointOnBody1; - mWorldPointOnBody2 = body2Transform * mLocalPointOnBody2; -} - -// Update the penetration depth -inline void ContactPoint::updatePenetrationDepth() { - mPenetrationDepth = (mWorldPointOnBody1 - mWorldPointOnBody2).dot(mNormal); -} - // Return the normal vector of the contact inline Vector3 ContactPoint::getNormal() const { return mNormal; @@ -215,6 +159,12 @@ inline decimal ContactPoint::getPenetrationImpulse() const { return mPenetrationImpulse; } +// Return true if the contact point is similar (close enougth) to another given contact point +inline bool ContactPoint::isSimilarWithContactPoint(const ContactPointInfo* localContactPointBody1) const { + return (localContactPointBody1->localPoint1 - mLocalPointOnBody1).lengthSquare() <= (PERSISTENT_CONTACT_DIST_THRESHOLD * + PERSISTENT_CONTACT_DIST_THRESHOLD); +} + // Set the cached penetration impulse inline void ContactPoint::setPenetrationImpulse(decimal impulse) { mPenetrationImpulse = impulse; diff --git a/src/engine/CollisionWorld.h b/src/engine/CollisionWorld.h index dc162716..0e24f0c8 100644 --- a/src/engine/CollisionWorld.h +++ b/src/engine/CollisionWorld.h @@ -247,16 +247,16 @@ class CollisionCallback { struct CollisionCallbackInfo { public: - const ContactPointInfo& contactPoint; + const ContactManifoldInfo& contactManifold; CollisionBody* body1; CollisionBody* body2; const ProxyShape* proxyShape1; const ProxyShape* proxyShape2; // Constructor - CollisionCallbackInfo(const ContactPointInfo& point, CollisionBody* b1, CollisionBody* b2, + CollisionCallbackInfo(const ContactManifoldInfo& manifold, CollisionBody* b1, CollisionBody* b2, const ProxyShape* proxShape1, const ProxyShape* proxShape2) : - contactPoint(point), body1(b1), body2(b2), + contactManifold(manifold), body1(b1), body2(b2), proxyShape1(proxShape1), proxyShape2(proxShape2) { } diff --git a/src/engine/EventListener.h b/src/engine/EventListener.h index 562e8ac7..e8594255 100644 --- a/src/engine/EventListener.h +++ b/src/engine/EventListener.h @@ -27,7 +27,7 @@ #define REACTPHYSICS3D_EVENT_LISTENER_H // Libraries -#include "constraint/ContactPoint.h" +#include "collision/ContactManifoldInfo.h" namespace reactphysics3d { @@ -53,13 +53,13 @@ class EventListener { /** * @param contact Information about the contact */ - virtual void beginContact(const ContactPointInfo& contact) {} + virtual void beginContact(const ContactManifoldInfo& contactManifold) {} /// Called when a new contact point is found between two bodies /** * @param contact Information about the contact */ - virtual void newContact(const ContactPointInfo& contact) {} + virtual void newContact(const ContactManifoldInfo& contactManifold) {} /// Called at the beginning of an internal tick of the simulation step. /// Each time the DynamicsWorld::update() method is called, the physics diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index 70ee1c3f..c34b91b7 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -80,11 +80,8 @@ class OverlappingPair { /// Return the pointer to second body ProxyShape* getShape2() const; - /// Add a contact to the contact cache - void addContact(ContactPoint* contact); - - /// Update the contact cache - void update(); + /// Add a contact manifold + void addContactManifold(const ContactManifoldInfo& contactManifoldInfo); /// Return the cached separating axis Vector3 getCachedSeparatingAxis() const; @@ -123,13 +120,8 @@ inline ProxyShape* OverlappingPair::getShape2() const { } // Add a contact to the contact manifold -inline void OverlappingPair::addContact(ContactPoint* contact) { - mContactManifoldSet.addContactPoint(contact); -} - -// Update the contact manifold -inline void OverlappingPair::update() { - mContactManifoldSet.update(); +inline void OverlappingPair::addContactManifold(const ContactManifoldInfo& contactManifoldInfo) { + mContactManifoldSet.addContactManifold(contactManifoldInfo); } // Return the cached separating axis From 0ecd554f500c4e292560091c04d085004a8c8050 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 27 Feb 2017 19:06:28 +0100 Subject: [PATCH 060/248] Update collision detection scene in testbed application --- .../CollisionDetectionScene.cpp | 18 +++++++++ .../CollisionDetectionScene.h | 38 +++++++++++-------- 2 files changed, 41 insertions(+), 15 deletions(-) diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp index 3d692501..8c0196b3 100644 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp @@ -82,6 +82,17 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mCapsule1->setColor(mGreyColorDemo); mCapsule1->setSleepingColor(mRedColorDemo); + // ---------- Capsule 2 ---------- // + openglframework::Vector3 position4(-4, 0, 0); + + // Create a cylinder and a corresponding collision body in the dynamics world + mCapsule2 = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, position4, mCollisionWorld, mMeshFolderPath); + mAllShapes.push_back(mCapsule2); + + // Set the color + mCapsule2->setColor(mGreyColorDemo); + mCapsule2->setSleepingColor(mRedColorDemo); + // ---------- Cone ---------- // //openglframework::Vector3 position4(0, 0, 0); @@ -163,6 +174,12 @@ CollisionDetectionScene::~CollisionDetectionScene() { mCollisionWorld->destroyCollisionBody(mSphere2->getCollisionBody()); delete mSphere2; + mCollisionWorld->destroyCollisionBody(mCapsule1->getCollisionBody()); + delete mCapsule1; + + mCollisionWorld->destroyCollisionBody(mCapsule2->getCollisionBody()); + delete mCapsule2; + /* // Destroy the corresponding rigid body from the dynamics world mCollisionWorld->destroyCollisionBody(mCone->getCollisionBody()); @@ -285,6 +302,7 @@ void CollisionDetectionScene::renderSinglePass(openglframework::Shader& shader, if (mSphere1->getCollisionBody()->isActive()) mSphere1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); if (mSphere2->getCollisionBody()->isActive()) mSphere2->render(shader, worldToCameraMatrix, mIsWireframeEnabled); if (mCapsule1->getCollisionBody()->isActive()) mCapsule1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + if (mCapsule2->getCollisionBody()->isActive()) mCapsule2->render(shader, worldToCameraMatrix, mIsWireframeEnabled); /* if (mBox->getCollisionBody()->isActive()) mBox->render(shader, worldToCameraMatrix); diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.h b/testbed/scenes/collisiondetection/CollisionDetectionScene.h index c2aec0cd..2c33b3ac 100644 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.h +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.h @@ -51,8 +51,8 @@ const float CONE_RADIUS = 3.0f; const float CONE_HEIGHT = 5.0f; const float CYLINDER_RADIUS = 3.0f; const float CYLINDER_HEIGHT = 5.0f; -const float CAPSULE_RADIUS = 3.0f; -const float CAPSULE_HEIGHT = 5.0f; +const float CAPSULE_RADIUS = 1.0f; +const float CAPSULE_HEIGHT = 1.0f; const float DUMBBELL_HEIGHT = 5.0f; const int NB_RAYS = 100; const float RAY_LENGTH = 30.0f; @@ -83,21 +83,29 @@ class ContactManager : public rp3d::CollisionCallback { /// This method will be called for each reported contact point virtual void notifyContact(const CollisionCallbackInfo& collisionCallbackInfo) override { - rp3d::Vector3 point1 = collisionCallbackInfo.contactPoint.localPoint1; - point1 = collisionCallbackInfo.proxyShape1->getLocalToWorldTransform() * point1; - openglframework::Vector3 position1(point1.x, point1.y, point1.z); - mContactPoints.push_back(ContactPoint(position1)); + // For each contact point + rp3d::ContactPointInfo* contactPointInfo = collisionCallbackInfo.contactManifold.getFirstContactPointInfo(); + while (contactPointInfo != nullptr) { - rp3d::Vector3 point2 = collisionCallbackInfo.contactPoint.localPoint2; - point2 = collisionCallbackInfo.proxyShape2->getLocalToWorldTransform() * point2; - openglframework::Vector3 position2(point2.x, point2.y, point2.z); - mContactPoints.push_back(ContactPoint(position2)); + rp3d::Vector3 point1 = contactPointInfo->localPoint1; + point1 = collisionCallbackInfo.proxyShape1->getLocalToWorldTransform() * point1; + openglframework::Vector3 position1(point1.x, point1.y, point1.z); + mContactPoints.push_back(ContactPoint(position1)); - // Create a line to display the normal at hit point - rp3d::Vector3 n = collisionCallbackInfo.contactPoint.normal; - openglframework::Vector3 normal(n.x, n.y, n.z); - Line* normalLine = new Line(position1, position1 + normal); - mNormals.push_back(normalLine); + + rp3d::Vector3 point2 = contactPointInfo->localPoint2; + point2 = collisionCallbackInfo.proxyShape2->getLocalToWorldTransform() * point2; + openglframework::Vector3 position2(point2.x, point2.y, point2.z); + mContactPoints.push_back(ContactPoint(position2)); + + // Create a line to display the normal at hit point + rp3d::Vector3 n = contactPointInfo->normal; + openglframework::Vector3 normal(n.x, n.y, n.z); + Line* normalLine = new Line(position1, position1 + normal); + mNormals.push_back(normalLine); + + contactPointInfo = contactPointInfo->next; + } } void resetPoints() { From 050e8b36dcfc921a19007548a932470a29ab59d3 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 22 Mar 2017 19:07:31 +0100 Subject: [PATCH 061/248] Refactor convex mesh shape (create PolyhedronMesh, ConvexPolyhedron classes) --- CMakeLists.txt | 4 + src/collision/HalfEdgeStructure.cpp | 29 +-- src/collision/HalfEdgeStructure.h | 37 +++- src/collision/PolygonVertexArray.cpp | 75 +++++++ src/collision/PolygonVertexArray.h | 188 +++++++++++++++++ src/collision/PolyhedronMesh.cpp | 79 +++++-- src/collision/PolyhedronMesh.h | 39 ++-- .../narrowphase/SAT/SATAlgorithm.cpp | 57 ++++- src/collision/narrowphase/SAT/SATAlgorithm.h | 16 ++ src/collision/shapes/BoxShape.cpp | 2 +- src/collision/shapes/BoxShape.h | 4 +- src/collision/shapes/CollisionShape.h | 2 +- src/collision/shapes/ConvexMeshShape.cpp | 198 +++--------------- src/collision/shapes/ConvexMeshShape.h | 110 +--------- src/collision/shapes/ConvexPolyhedron.cpp | 37 ++++ src/collision/shapes/ConvexPolyhedron.h | 68 ++++++ src/reactphysics3d.h | 2 + test/tests/collision/TestHalfEdgeStructure.h | 141 +++++++------ test/tests/collision/TestPointInside.h | 10 +- test/tests/collision/TestRaycast.h | 10 +- testbed/common/ConvexMesh.cpp | 58 +++-- testbed/common/ConvexMesh.h | 6 +- 22 files changed, 751 insertions(+), 421 deletions(-) create mode 100644 src/collision/PolygonVertexArray.cpp create mode 100644 src/collision/PolygonVertexArray.h create mode 100644 src/collision/shapes/ConvexPolyhedron.cpp create mode 100644 src/collision/shapes/ConvexPolyhedron.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 58ea37d7..4f6ab0bc 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -90,6 +90,8 @@ SET (REACTPHYSICS3D_SOURCES "src/collision/shapes/AABB.cpp" "src/collision/shapes/ConvexShape.h" "src/collision/shapes/ConvexShape.cpp" + "src/collision/shapes/ConvexPolyhedron.h" + "src/collision/shapes/ConvexPolyhedron.cpp" "src/collision/shapes/ConcaveShape.h" "src/collision/shapes/ConcaveShape.cpp" "src/collision/shapes/BoxShape.h" @@ -114,6 +116,8 @@ SET (REACTPHYSICS3D_SOURCES "src/collision/ProxyShape.cpp" "src/collision/TriangleVertexArray.h" "src/collision/TriangleVertexArray.cpp" + "src/collision/PolygonVertexArray.h" + "src/collision/PolygonVertexArray.cpp" "src/collision/TriangleMesh.h" "src/collision/TriangleMesh.cpp" "src/collision/PolyhedronMesh.h" diff --git a/src/collision/HalfEdgeStructure.cpp b/src/collision/HalfEdgeStructure.cpp index 6393acb0..0f7b8f6e 100644 --- a/src/collision/HalfEdgeStructure.cpp +++ b/src/collision/HalfEdgeStructure.cpp @@ -29,8 +29,8 @@ using namespace reactphysics3d; -// Initialize the structure -void HalfEdgeStructure::init(std::vector vertices, std::vector> faces) { +// Initialize the structure (when all vertices and faces have been added) +void HalfEdgeStructure::init() { using edgeKey = std::pair; @@ -41,30 +41,19 @@ void HalfEdgeStructure::init(std::vector vertices, std::vector mapEdgeIndexToKey; std::map mapFaceIndexToEdgeKey; - // For each vertices - for (uint v=0; v& faceVertices = faces[f]; + Face face = mFaces[f]; std::vector currentFaceEdges; edgeKey firstEdgeKey; // For each vertex of the face - for (uint v=0; v < faceVertices.size(); v++) { - uint v1Index = faceVertices[v]; - uint v2Index = faceVertices[v == (faceVertices.size() - 1) ? 0 : v + 1]; + for (uint v=0; v < face.faceVertices.size(); v++) { + uint v1Index = face.faceVertices[v]; + uint v2Index = face.faceVertices[v == (face.faceVertices.size() - 1) ? 0 : v + 1]; const edgeKey pairV1V2 = std::make_pair(v1Index, v2Index); @@ -78,7 +67,7 @@ void HalfEdgeStructure::init(std::vector vertices, std::vector= 1) { nextEdges.insert(std::make_pair(currentFaceEdges[currentFaceEdges.size() - 1], pairV1V2)); } - if (v == (faceVertices.size() - 1)) { + if (v == (face.faceVertices.size() - 1)) { nextEdges.insert(std::make_pair(pairV1V2, firstEdgeKey)); } edges.insert(std::make_pair(pairV1V2, edge)); @@ -121,7 +110,7 @@ void HalfEdgeStructure::init(std::vector vertices, std::vector faceVertices; // Index of the vertices of the face + + /// Constructor + Face(std::vector vertices) : faceVertices(vertices) {} }; struct Vertex { - Vector3 point; // Coordinates of the vertex + uint vertexPointIndex; // Index of the vertex point in the origin vertex array uint edgeIndex; // Index of one edge emanting from this vertex /// Constructor - Vertex(Vector3& p) { point = p;} + Vertex(uint vertexCoordsIndex) : vertexPointIndex(vertexCoordsIndex) { } }; private: @@ -80,8 +84,14 @@ class HalfEdgeStructure { /// Destructor ~HalfEdgeStructure() = default; - /// Initialize the structure - void init(std::vector vertices, std::vector> faces); + /// Initialize the structure (when all vertices and faces have been added) + void init(); + + /// Add a vertex + uint addVertex(uint vertexPointIndex); + + /// Add a face + void addFace(std::vector faceVertices); /// Return the number of faces uint getNbFaces() const; @@ -98,11 +108,26 @@ class HalfEdgeStructure { /// Return a given edge Edge getHalfEdge(uint index) const; - /// Retunr a given vertex + /// Return a given vertex Vertex getVertex(uint index) const; }; +// Add a vertex +inline uint HalfEdgeStructure::addVertex(uint vertexPointIndex) { + Vertex vertex(vertexPointIndex); + mVertices.push_back(vertex); + return mVertices.size() - 1; +} + +// Add a face +inline void HalfEdgeStructure::addFace(std::vector faceVertices) { + + // Create a new face + Face face(faceVertices); + mFaces.push_back(face); +} + // Return the number of faces inline uint HalfEdgeStructure::getNbFaces() const { return mFaces.size(); diff --git a/src/collision/PolygonVertexArray.cpp b/src/collision/PolygonVertexArray.cpp new file mode 100644 index 00000000..309a0d62 --- /dev/null +++ b/src/collision/PolygonVertexArray.cpp @@ -0,0 +1,75 @@ +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "PolygonVertexArray.h" + +using namespace reactphysics3d; + +// Constructor +/// Note that your data will not be copied into the PolygonVertexArray and +/// therefore, you need to make sure that those data are always valid during +/// the lifetime of the PolygonVertexArray. +/** + */ +PolygonVertexArray::PolygonVertexArray(uint nbVertices, void* verticesStart, int verticesStride, + void* indexesStart, int indexesStride, + uint nbFaces, PolygonFace* facesStart, + VertexDataType vertexDataType, IndexDataType indexDataType) { + mNbVertices = nbVertices; + mVerticesStart = reinterpret_cast(verticesStart); + mVerticesStride = verticesStride; + mIndicesStart = reinterpret_cast(indexesStart); + mIndicesStride = indexesStride; + mNbFaces = nbFaces; + mPolygonFacesStart = facesStart; + mVertexDataType = vertexDataType; + mIndexDataType = indexDataType; +} + +// Return the vertex index of a given vertex in a face +uint PolygonVertexArray::getVertexIndexInFace(uint faceIndex, uint noVertexInFace) const { + + assert(faceIndex < mNbFaces); + + // Get the face + PolygonFace* face = getPolygonFace(faceIndex); + + assert(noVertexInFace < face->nbVertices); + + void* vertexIndexPointer = mIndicesStart + (face->indexBase + noVertexInFace) * mIndicesStride; + + if (mIndexDataType == PolygonVertexArray::IndexDataType::INDEX_INTEGER_TYPE) { + return *((uint*)vertexIndexPointer); + } + else if (mIndexDataType == PolygonVertexArray::IndexDataType::INDEX_SHORT_TYPE) { + return *((unsigned short*)vertexIndexPointer); + } + else { + assert(false); + } + + return 0; +} diff --git a/src/collision/PolygonVertexArray.h b/src/collision/PolygonVertexArray.h new file mode 100644 index 00000000..5ae02e0e --- /dev/null +++ b/src/collision/PolygonVertexArray.h @@ -0,0 +1,188 @@ +/******************************************************************************** +* 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_POLYGON_VERTEX_ARRAY_H +#define REACTPHYSICS3D_POLYGON_VERTEX_ARRAY_H + +// Libraries +#include "configuration.h" +#include + +namespace reactphysics3d { + +// Class PolygonVertexArray +/** + * This class is used to describe the vertices and faces of a polyhedron mesh. + * A PolygonVertexArray represents an array of vertices and polygon faces + * of a polyhedron mesh. When you create a PolygonVertexArray, no data is copied + * into the array. It only stores pointer to the data. The purpose is to allow + * the user to share vertices data between the physics engine and the rendering + * part. Therefore, make sure that the data pointed by a PolygonVertexArray + * remains valid during the PolygonVertexArray life. + */ +class PolygonVertexArray { + + public: + + /// Data type for the vertices in the array + enum class VertexDataType {VERTEX_FLOAT_TYPE, VERTEX_DOUBLE_TYPE}; + + /// Data type for the indices in the array + enum class IndexDataType {INDEX_INTEGER_TYPE, INDEX_SHORT_TYPE}; + + /// Represent a polygon face of the polyhedron + struct PolygonFace { + + /// Number of vertices in the polygon face + uint nbVertices; + + /// Index of the first vertex of the polygon face + /// inside the array with all vertex indices + uint indexBase; + }; + + protected: + + /// Number of vertices in the array + uint mNbVertices; + + /// Pointer to the first vertex value in the array + unsigned char* mVerticesStart; + + /// Stride (number of bytes) between the beginning of two vertices + /// values in the array + int mVerticesStride; + + /// Pointer to the first vertex index of the array + unsigned char* mIndicesStart; + + /// Stride (number of bytes) between the beginning of two indices in + /// the array + int mIndicesStride; + + /// Number of polygon faces in the array + uint mNbFaces; + + /// Pointer to the first polygon face in the polyhedron + PolygonFace* mPolygonFacesStart; + + /// Data type of the vertices in the array + VertexDataType mVertexDataType; + + /// Data type of the indices in the array + IndexDataType mIndexDataType; + + public: + + /// Constructor + PolygonVertexArray(uint nbVertices, void* verticesStart, int verticesStride, + void* indexesStart, int indexesStride, + uint nbFaces, PolygonFace* facesStart, + VertexDataType vertexDataType, IndexDataType indexDataType); + + /// Destructor + ~PolygonVertexArray() = default; + + /// Return the vertex data type + VertexDataType getVertexDataType() const; + + /// Return the index data type + IndexDataType getIndexDataType() const; + + /// Return the number of vertices + uint getNbVertices() const; + + /// Return the number of faces + uint getNbFaces() const; + + /// Return the vertices stride (number of bytes) + int getVerticesStride() const; + + /// Return the indices stride (number of bytes) + int getIndicesStride() const; + + /// Return the vertex index of a given vertex in a face + uint getVertexIndexInFace(uint faceIndex, uint noVertexInFace) const; + + /// Return a polygon face of the polyhedron + PolygonFace* getPolygonFace(uint faceIndex) const; + + /// Return the pointer to the start of the vertices array + unsigned char* getVerticesStart() const; + + /// Return the pointer to the start of the indices array + unsigned char* getIndicesStart() const; +}; + +// Return the vertex data type +inline PolygonVertexArray::VertexDataType PolygonVertexArray::getVertexDataType() const { + return mVertexDataType; +} + +// Return the index data type +inline PolygonVertexArray::IndexDataType PolygonVertexArray::getIndexDataType() const { + return mIndexDataType; +} + +// Return the number of vertices +inline uint PolygonVertexArray::getNbVertices() const { + return mNbVertices; +} + +// Return the number of faces +inline uint PolygonVertexArray::getNbFaces() const { + return mNbFaces; +} + +// Return the vertices stride (number of bytes) +inline int PolygonVertexArray::getVerticesStride() const { + return mVerticesStride; +} + +// Return the indices stride (number of bytes) +inline int PolygonVertexArray::getIndicesStride() const { + return mIndicesStride; +} + +// Return a polygon face of the polyhedron +inline PolygonVertexArray::PolygonFace* PolygonVertexArray::getPolygonFace(uint faceIndex) const { + assert(faceIndex < mNbFaces); + return &mPolygonFacesStart[faceIndex]; +} + +// Return the pointer to the start of the vertices array +inline unsigned char* PolygonVertexArray::getVerticesStart() const { + return mVerticesStart; +} + +// Return the pointer to the start of the indices array +inline unsigned char* PolygonVertexArray::getIndicesStart() const { + return mIndicesStart; +} + +} + +#endif + diff --git a/src/collision/PolyhedronMesh.cpp b/src/collision/PolyhedronMesh.cpp index 891a2f47..df43a47a 100644 --- a/src/collision/PolyhedronMesh.cpp +++ b/src/collision/PolyhedronMesh.cpp @@ -30,33 +30,70 @@ using namespace reactphysics3d; // Constructor -PolyhedronMesh::PolyhedronMesh() : mIsFinalized(false) { +PolyhedronMesh::PolyhedronMesh(PolygonVertexArray* polygonVertexArray) { + mPolygonVertexArray = polygonVertexArray; + + // Create the half-edge structure of the mesh + createHalfEdgeStructure(); } -// Add a vertex into the polyhedron. -// This method returns the index of the vertex that you need to use -// to add faces. -uint PolyhedronMesh::addVertex(const Vector3& vertex) { - mVertices.push_back(vertex); - return mVertices.size() - 1; -} +// Create the half-edge structure of the mesh +void PolyhedronMesh::createHalfEdgeStructure() { -// Add a face into the polyhedron. -// A face is a list of vertices indices (returned by addVertex() method). -// The order of the indices are important. You need to specify the vertices of -// of the face sorted counter-clockwise as seen from the outside of the polyhedron. -void PolyhedronMesh::addFace(std::vector faceVertices) { - mFaces.push_back(faceVertices); -} + // For each vertex of the mesh + for (uint v=0; v < mPolygonVertexArray->getNbVertices(); v++) { + mHalfEdgeStructure.addVertex(v); + } -// Call this method when you are done adding vertices and faces -void PolyhedronMesh::finalize() { + // For each polygon face of the mesh + for (uint f=0; f < mPolygonVertexArray->getNbFaces(); f++) { - if (mIsFinalized) return; + // Get the polygon face + PolygonVertexArray::PolygonFace* face = mPolygonVertexArray->getPolygonFace(f); + + std::vector faceVertices; + + // For each vertex of the face + for (uint v=0; v < face->nbVertices; v++) { + faceVertices.push_back(mPolygonVertexArray->getVertexIndexInFace(f, v)); + } + + // Addd the face into the half-edge structure + mHalfEdgeStructure.addFace(faceVertices); + } // Initialize the half-edge structure - mHalfEdgeStructure.init(mVertices, mFaces); - - mIsFinalized = true; + mHalfEdgeStructure.init(); +} + +/// Return a vertex +Vector3 PolyhedronMesh::getVertex(uint index) const { + assert(index < getNbVertices()); + + // Get the vertex index in the array with all vertices + uint vertexIndex = mHalfEdgeStructure.getVertex(index).vertexPointIndex; + + PolygonVertexArray::VertexDataType vertexType = mPolygonVertexArray->getVertexDataType(); + unsigned char* verticesStart = mPolygonVertexArray->getVerticesStart(); + int vertexStride = mPolygonVertexArray->getVerticesStride(); + + Vector3 vertex; + if (vertexType == PolygonVertexArray::VertexDataType::VERTEX_FLOAT_TYPE) { + const float* vertices = (float*)(verticesStart + vertexIndex * vertexStride); + vertex.x = decimal(vertices[0]); + vertex.y = decimal(vertices[1]); + vertex.z = decimal(vertices[2]); + } + else if (vertexType == PolygonVertexArray::VertexDataType::VERTEX_DOUBLE_TYPE) { + const double* vertices = (double*)(verticesStart + vertexIndex * vertexStride); + vertex.x = decimal(vertices[0]); + vertex.y = decimal(vertices[1]); + vertex.z = decimal(vertices[2]); + } + else { + assert(false); + } + + return vertex; } diff --git a/src/collision/PolyhedronMesh.h b/src/collision/PolyhedronMesh.h index c7182bd8..f842cae1 100644 --- a/src/collision/PolyhedronMesh.h +++ b/src/collision/PolyhedronMesh.h @@ -29,6 +29,7 @@ // Libraries #include "mathematics/mathematics.h" #include "HalfEdgeStructure.h" +#include "collision/PolygonVertexArray.h" #include namespace reactphysics3d { @@ -36,45 +37,51 @@ namespace reactphysics3d { // Class PolyhedronMesh /** * This class describes a polyhedron mesh made of faces and vertices. - * The faces do not have to be triangle + * The faces do not have to be triangles. */ class PolyhedronMesh { private: + // -------------------- Attributes -------------------- // + + /// Pointer the the polygon vertex array with vertices and faces + /// of the mesh + PolygonVertexArray* mPolygonVertexArray; + /// Half-edge structure of the mesh HalfEdgeStructure mHalfEdgeStructure; - /// True if the half-edge structure has been generated - bool mIsFinalized; + // -------------------- Methods -------------------- // - /// All the vertices - std::vector mVertices; - - /// All the indexes of the face vertices - std::vector> mFaces; + /// Create the half-edge structure of the mesh + void createHalfEdgeStructure(); public: + // -------------------- Methods -------------------- // + /// Constructor - PolyhedronMesh(); + PolyhedronMesh(PolygonVertexArray* polygonVertexArray); /// Destructor ~PolyhedronMesh() = default; - /// Add a vertex into the polyhedron - uint addVertex(const Vector3& vertex); + /// Return the number of vertices + uint getNbVertices() const; - /// Add a face into the polyhedron - void addFace(std::vector faceVertices); - - /// Call this method when you are done adding vertices and faces - void finalize(); + /// Return a vertex + Vector3 getVertex(uint index) const; /// Return the half-edge structure of the mesh const HalfEdgeStructure& getHalfEdgeStructure() const; }; +// Return the number of vertices +inline uint PolyhedronMesh::getNbVertices() const { + return mHalfEdgeStructure.getNbVertices(); +} + // Return the half-edge structure of the mesh inline const HalfEdgeStructure& PolyhedronMesh::getHalfEdgeStructure() const { return mHalfEdgeStructure; diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index b46ca386..61910acc 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -26,6 +26,7 @@ // Libraries #include "SATAlgorithm.h" #include "constraint/ContactPoint.h" +#include "collision/PolyhedronMesh.h" #include "configuration.h" #include "engine/Profiler.h" #include @@ -36,8 +37,60 @@ // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; -bool SATAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactManifoldInfo& contactManifoldInfo) { +bool SATAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) { + assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); + + switch (narrowPhaseInfo->collisionShape1->getType()) { + case CollisionShapeType::CONVEX_POLYHEDRON: + return testCollisionConvexMeshVsConvexMesh(narrowPhaseInfo, contactManifoldInfo); + case CollisionShapeType::SPHERE: + return testCollisionSphereVsConvexMesh(narrowPhaseInfo, contactManifoldInfo); + case CollisionShapeType::CAPSULE: + return testCollisionCapsuleVsConvexMesh(narrowPhaseInfo, contactManifoldInfo); + case CollisionShapeType::TRIANGLE: + return testCollisionTriangleVsConvexMesh(narrowPhaseInfo, contactManifoldInfo); + default: assert(false); + } + + return false; +} + +// Test collision between a sphere and a convex mesh +bool SATAlgorithm::testCollisionSphereVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { } + +// Test collision between a capsule and a convex mesh +bool SATAlgorithm::testCollisionCapsuleVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { + +} + +// Test collision between a triangle and a convex mesh +bool SATAlgorithm::testCollisionTriangleVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { + +} + +// Test collision between two convex meshes +bool SATAlgorithm::testCollisionConvexMeshVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { + +} + + +// Return true if the arcs AB and CD on the Gauss Map (unit sphere) intersect +/// This is used to know if the edge between faces with normal A and B on first polyhedron +/// and edge between faces with normal C and D on second polygon create a face on the Minkowski +/// sum of both polygons. If this is the case, it means that the cross product of both edges +/// might be a separating axis. +bool SATAlgorithm::testGaussMapArcsIntersect(const Vector3& a, const Vector3& b, + const Vector3& c, const Vector3& d) const { + const Vector3 bCrossA = b.cross(a); + const Vector3 dCrossC = d.cross(c); + + const decimal cba = c.dot(bCrossA); + const decimal dba = d.dot(bCrossA); + const decimal adc = a.dot(dCrossC); + const decimal bdc = b.dot(dCrossC); + + return cba * dba < decimal(0.0) && adc * bdc < decimal(0.0) && cba * bdc > decimal(0.0); +} diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.h b/src/collision/narrowphase/SAT/SATAlgorithm.h index 80feece1..dc5bc5f2 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.h +++ b/src/collision/narrowphase/SAT/SATAlgorithm.h @@ -42,6 +42,22 @@ class SATAlgorithm { // -------------------- Methods -------------------- // + /// Return true if the arcs AB and CD on the Gauss Map intersect + bool testGaussMapArcsIntersect(const Vector3& a, const Vector3& b, + const Vector3& c, const Vector3& d) const; + + /// Test collision between a sphere and a convex mesh + bool testCollisionSphereVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; + + /// Test collision between a capsule and a convex mesh + bool testCollisionCapsuleVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; + + /// Test collision between a triangle and a convex mesh + bool testCollisionTriangleVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; + + /// Test collision between two convex meshes + bool testCollisionConvexMeshVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; + public : // -------------------- Methods -------------------- // diff --git a/src/collision/shapes/BoxShape.cpp b/src/collision/shapes/BoxShape.cpp index ce3197e3..ba5dfa1a 100644 --- a/src/collision/shapes/BoxShape.cpp +++ b/src/collision/shapes/BoxShape.cpp @@ -38,7 +38,7 @@ using namespace reactphysics3d; * @param margin The collision margin (in meters) around the collision shape */ BoxShape::BoxShape(const Vector3& extent, decimal margin) - : ConvexShape(CollisionShapeType::BOX, margin), mExtent(extent - Vector3(margin, margin, margin)) { + : ConvexPolyhedron(margin), mExtent(extent - Vector3(margin, margin, margin)) { assert(extent.x > decimal(0.0) && extent.x > margin); assert(extent.y > decimal(0.0) && extent.y > margin); assert(extent.z > decimal(0.0) && extent.z > margin); diff --git a/src/collision/shapes/BoxShape.h b/src/collision/shapes/BoxShape.h index 776356ba..c3d5caf2 100644 --- a/src/collision/shapes/BoxShape.h +++ b/src/collision/shapes/BoxShape.h @@ -28,7 +28,7 @@ // Libraries #include -#include "ConvexShape.h" +#include "ConvexPolyhedron.h" #include "body/CollisionBody.h" #include "mathematics/mathematics.h" @@ -50,7 +50,7 @@ namespace reactphysics3d { * constructor of the box shape. Otherwise, it is recommended to use the * default margin distance by not using the "margin" parameter in the constructor. */ -class BoxShape : public ConvexShape { +class BoxShape : public ConvexPolyhedron { protected : diff --git a/src/collision/shapes/CollisionShape.h b/src/collision/shapes/CollisionShape.h index c2db3466..28e724fd 100644 --- a/src/collision/shapes/CollisionShape.h +++ b/src/collision/shapes/CollisionShape.h @@ -40,7 +40,7 @@ namespace reactphysics3d { /// Type of the collision shape -enum class CollisionShapeType {TRIANGLE, SPHERE, CAPSULE, BOX, CONVEX_MESH, CONCAVE_MESH, HEIGHTFIELD}; +enum class CollisionShapeType {TRIANGLE, SPHERE, CAPSULE, CONVEX_POLYHEDRON, CONCAVE_MESH, HEIGHTFIELD}; const int NB_COLLISION_SHAPE_TYPES = 9; // Declarations diff --git a/src/collision/shapes/ConvexMeshShape.cpp b/src/collision/shapes/ConvexMeshShape.cpp index cc880a25..40382aeb 100644 --- a/src/collision/shapes/ConvexMeshShape.cpp +++ b/src/collision/shapes/ConvexMeshShape.cpp @@ -30,6 +30,9 @@ using namespace reactphysics3d; +// TODO : Check in every collision shape that localScalling is used correctly and even with SAT +// algorithm (not only in getLocalSupportPoint***() methods) + // Constructor to initialize with an array of 3D vertices. /// This method creates an internal copy of the input vertices. /** @@ -38,108 +41,13 @@ using namespace reactphysics3d; * @param stride Stride between the beginning of two elements in the vertices array * @param margin Collision margin (in meters) around the collision shape */ -ConvexMeshShape::ConvexMeshShape(const decimal* arrayVertices, uint nbVertices, int stride, decimal margin) - : ConvexShape(CollisionShapeType::CONVEX_MESH, margin), mNbVertices(nbVertices), mMinBounds(0, 0, 0), - mMaxBounds(0, 0, 0), mIsEdgesInformationUsed(false) { - assert(nbVertices > 0); - assert(stride > 0); - - const unsigned char* vertexPointer = (const unsigned char*) arrayVertices; - - // Copy all the vertices into the internal array - for (uint i=0; igetVertexDataType(); - TriangleVertexArray::IndexDataType indexType = triangleVertexArray->getIndexDataType(); - unsigned char* verticesStart = triangleVertexArray->getVerticesStart(); - unsigned char* indicesStart = triangleVertexArray->getIndicesStart(); - int vertexStride = triangleVertexArray->getVerticesStride(); - int indexStride = triangleVertexArray->getIndicesStride(); - - // For each vertex of the mesh - for (uint v = 0; v < triangleVertexArray->getNbVertices(); v++) { - - // Get the vertices components of the triangle - if (vertexType == TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE) { - const float* vertices = (float*)(verticesStart + v * vertexStride); - - Vector3 vertex(vertices[0], vertices[1], vertices[2] ); - vertex = vertex * mScaling; - mVertices.push_back(vertex); - } - else if (vertexType == TriangleVertexArray::VertexDataType::VERTEX_DOUBLE_TYPE) { - const double* vertices = (double*)(verticesStart + v * vertexStride); - - Vector3 vertex(vertices[0], vertices[1], vertices[2] ); - vertex = vertex * mScaling; - mVertices.push_back(vertex); - } - } - - // If we need to use the edges information of the mesh - if (mIsEdgesInformationUsed) { - - // For each triangle of the mesh - for (uint triangleIndex=0; triangleIndexgetNbTriangles(); triangleIndex++) { - - void* vertexIndexPointer = (indicesStart + triangleIndex * 3 * indexStride); - - uint vertexIndex[3] = {0, 0, 0}; - - // For each vertex of the triangle - for (int k=0; k < 3; k++) { - - // Get the index of the current vertex in the triangle - if (indexType == TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE) { - vertexIndex[k] = ((uint*)vertexIndexPointer)[k]; - } - else if (indexType == TriangleVertexArray::IndexDataType::INDEX_SHORT_TYPE) { - vertexIndex[k] = ((unsigned short*)vertexIndexPointer)[k]; - } - else { - assert(false); - } - } - - // Add information about the edges - addEdge(vertexIndex[0], vertexIndex[1]); - addEdge(vertexIndex[0], vertexIndex[2]); - addEdge(vertexIndex[1], vertexIndex[2]); - } - } - - mNbVertices = mVertices.size(); - recalculateBounds(); -} - -// Constructor. -/// If you use this constructor, you will need to set the vertices manually one by one using -/// the addVertex() method. -ConvexMeshShape::ConvexMeshShape(decimal margin) - : ConvexShape(CollisionShapeType::CONVEX_MESH, margin), mNbVertices(0), mMinBounds(0, 0, 0), - mMaxBounds(0, 0, 0), mIsEdgesInformationUsed(false) { - -} - // Return a local support point in a given direction without the object margin. /// If the edges information is not used for collision detection, this method will go through /// the whole vertices list and pick up the vertex with the largest dot product in the support @@ -151,78 +59,28 @@ ConvexMeshShape::ConvexMeshShape(decimal margin) Vector3 ConvexMeshShape::getLocalSupportPointWithoutMargin(const Vector3& direction, void** cachedCollisionData) const { - assert(mNbVertices == mVertices.size()); - assert(cachedCollisionData != nullptr); + // TODO : Do we still need to have cachedCollisionData or we can remove it from everywhere ? - // Allocate memory for the cached collision data if not allocated yet - if ((*cachedCollisionData) == nullptr) { - *cachedCollisionData = (int*) malloc(sizeof(int)); - *((int*)(*cachedCollisionData)) = 0; - } + double maxDotProduct = DECIMAL_SMALLEST; + uint indexMaxDotProduct = 0; - // If the edges information is used to speed up the collision detection - if (mIsEdgesInformationUsed) { + // For each vertex of the mesh + for (uint i=0; igetNbVertices(); i++) { - assert(mEdgesAdjacencyList.size() == mNbVertices); + // Compute the dot product of the current vertex + double dotProduct = direction.dot(mPolyhedronMesh->getVertex(i)); - uint maxVertex = *((int*)(*cachedCollisionData)); - decimal maxDotProduct = direction.dot(mVertices[maxVertex]); - bool isOptimal; - - // Perform hill-climbing (local search) - do { - isOptimal = true; - - assert(mEdgesAdjacencyList.at(maxVertex).size() > 0); - - // For all neighbors of the current vertex - std::set::const_iterator it; - std::set::const_iterator itBegin = mEdgesAdjacencyList.at(maxVertex).begin(); - std::set::const_iterator itEnd = mEdgesAdjacencyList.at(maxVertex).end(); - for (it = itBegin; it != itEnd; ++it) { - - // Compute the dot product - decimal dotProduct = direction.dot(mVertices[*it]); - - // If the current vertex is a better vertex (larger dot product) - if (dotProduct > maxDotProduct) { - maxVertex = *it; - maxDotProduct = dotProduct; - isOptimal = false; - } - } - - } while(!isOptimal); - - // Cache the support vertex - *((int*)(*cachedCollisionData)) = maxVertex; - - // Return the support vertex - return mVertices[maxVertex] * mScaling; - } - else { // If the edges information is not used - - double maxDotProduct = DECIMAL_SMALLEST; - uint indexMaxDotProduct = 0; - - // For each vertex of the mesh - for (uint i=0; i maxDotProduct) { - indexMaxDotProduct = i; - maxDotProduct = dotProduct; - } + // If the current dot product is larger than the maximum one + if (dotProduct > maxDotProduct) { + indexMaxDotProduct = i; + maxDotProduct = dotProduct; } - - assert(maxDotProduct >= decimal(0.0)); - - // Return the vertex with the largest dot product in the support direction - return mVertices[indexMaxDotProduct] * mScaling; } + + assert(maxDotProduct >= decimal(0.0)); + + // Return the vertex with the largest dot product in the support direction + return mPolyhedronMesh->getVertex(indexMaxDotProduct) * mScaling; } // Recompute the bounds of the mesh @@ -235,16 +93,16 @@ void ConvexMeshShape::recalculateBounds() { mMaxBounds.setToZero(); // For each vertex of the mesh - for (uint i=0; igetNbVertices(); i++) { - if (mVertices[i].x > mMaxBounds.x) mMaxBounds.x = mVertices[i].x; - if (mVertices[i].x < mMinBounds.x) mMinBounds.x = mVertices[i].x; + if (mPolyhedronMesh->getVertex(i).x > mMaxBounds.x) mMaxBounds.x = mPolyhedronMesh->getVertex(i).x; + if (mPolyhedronMesh->getVertex(i).x < mMinBounds.x) mMinBounds.x = mPolyhedronMesh->getVertex(i).x; - if (mVertices[i].y > mMaxBounds.y) mMaxBounds.y = mVertices[i].y; - if (mVertices[i].y < mMinBounds.y) mMinBounds.y = mVertices[i].y; + if (mPolyhedronMesh->getVertex(i).y > mMaxBounds.y) mMaxBounds.y = mPolyhedronMesh->getVertex(i).y; + if (mPolyhedronMesh->getVertex(i).y < mMinBounds.y) mMinBounds.y = mPolyhedronMesh->getVertex(i).y; - if (mVertices[i].z > mMaxBounds.z) mMaxBounds.z = mVertices[i].z; - if (mVertices[i].z < mMinBounds.z) mMinBounds.z = mVertices[i].z; + if (mPolyhedronMesh->getVertex(i).z > mMaxBounds.z) mMaxBounds.z = mPolyhedronMesh->getVertex(i).z; + if (mPolyhedronMesh->getVertex(i).z < mMinBounds.z) mMinBounds.z = mPolyhedronMesh->getVertex(i).z; } // Apply the local scaling factor diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index 66b624aa..c33fd5bd 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -1,4 +1,4 @@ -/******************************************************************************** + /******************************************************************************** * ReactPhysics3D physics library, http://www.reactphysics3d.com * * Copyright (c) 2010-2016 Daniel Chappuis * ********************************************************************************* @@ -27,10 +27,11 @@ #define REACTPHYSICS3D_CONVEX_MESH_SHAPE_H // Libraries -#include "ConvexShape.h" +#include "ConvexPolyhedron.h" #include "engine/CollisionWorld.h" #include "mathematics/mathematics.h" #include "collision/TriangleMesh.h" +#include "collision/PolyhedronMesh.h" #include "collision/narrowphase/GJK/GJKAlgorithm.h" #include #include @@ -58,17 +59,14 @@ class CollisionWorld; * with the addEdge() method. Then, you must use the setIsEdgesInformationUsed(true) method * in order to use the edges information for collision detection. */ -class ConvexMeshShape : public ConvexShape { +class ConvexMeshShape : public ConvexPolyhedron { protected : // -------------------- Attributes -------------------- // - /// Array with the vertices of the mesh - std::vector mVertices; - - /// Number of vertices in the mesh - uint mNbVertices; + /// Polyhedron structure of the mesh + PolyhedronMesh* mPolyhedronMesh; /// Mesh minimum bounds in the three local x, y and z directions Vector3 mMinBounds; @@ -76,13 +74,6 @@ class ConvexMeshShape : public ConvexShape { /// Mesh maximum bounds in the three local x, y and z directions Vector3 mMaxBounds; - /// True if the shape contains the edges of the convex mesh in order to - /// make the collision detection faster - bool mIsEdgesInformationUsed; - - /// Adjacency list representing the edges of the mesh - std::map > mEdgesAdjacencyList; - // -------------------- Methods -------------------- // /// Recompute the bounds of the mesh @@ -108,16 +99,10 @@ class ConvexMeshShape : public ConvexShape { // -------------------- Methods -------------------- // - /// Constructor to initialize with an array of 3D vertices. - ConvexMeshShape(const decimal* arrayVertices, uint nbVertices, int stride, - decimal margin = OBJECT_MARGIN); - - /// Constructor to initialize with a triangle vertex array - ConvexMeshShape(TriangleVertexArray* triangleVertexArray, bool isEdgesInformationUsed = true, - decimal margin = OBJECT_MARGIN); - - /// Constructor. - ConvexMeshShape(decimal margin = OBJECT_MARGIN); + /// Constructor + // TODO : Do we really need to use the margin anymore ? Maybe for raycasting ? If not, remove all the + // comments documentation about margin + ConvexMeshShape(PolyhedronMesh* polyhedronMesh, decimal margin = OBJECT_MARGIN); /// Destructor virtual ~ConvexMeshShape() override = default; @@ -134,21 +119,8 @@ class ConvexMeshShape : public ConvexShape { /// Return the local inertia tensor of the collision shape. virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; - /// Add a vertex into the convex mesh - void addVertex(const Vector3& vertex); - - /// Add an edge into the convex mesh by specifying the two vertex indices of the edge. - void addEdge(uint v1, uint v2); - /// Return true if the collision shape is a polyhedron virtual bool isPolyhedron() const override; - - /// Return true if the edges information is used to speed up the collision detection - bool isEdgesInformationUsed() const; - - /// Set the variable to know if the edges information is used to speed up the - /// collision detection - void setIsEdgesInformationUsed(bool isEdgesUsed); }; /// Set the scaling vector of the collision shape @@ -197,68 +169,6 @@ inline void ConvexMeshShape::computeLocalInertiaTensor(Matrix3x3& tensor, decima 0.0, 0.0, factor * (xSquare + ySquare)); } -// Add a vertex into the convex mesh -/** - * @param vertex Vertex to be added - */ -inline void ConvexMeshShape::addVertex(const Vector3& vertex) { - - // Add the vertex in to vertices array - mVertices.push_back(vertex); - mNbVertices++; - - // Update the bounds of the mesh - if (vertex.x * mScaling.x > mMaxBounds.x) mMaxBounds.x = vertex.x * mScaling.x; - if (vertex.x * mScaling.x < mMinBounds.x) mMinBounds.x = vertex.x * mScaling.x; - if (vertex.y * mScaling.y > mMaxBounds.y) mMaxBounds.y = vertex.y * mScaling.y; - if (vertex.y * mScaling.y < mMinBounds.y) mMinBounds.y = vertex.y * mScaling.y; - if (vertex.z * mScaling.z > mMaxBounds.z) mMaxBounds.z = vertex.z * mScaling.z; - if (vertex.z * mScaling.z < mMinBounds.z) mMinBounds.z = vertex.z * mScaling.z; -} - -// Add an edge into the convex mesh by specifying the two vertex indices of the edge. -/// Note that the vertex indices start at zero and need to correspond to the order of -/// the vertices in the vertices array in the constructor or the order of the calls -/// of the addVertex() methods that you use to add vertices into the convex mesh. -/** -* @param v1 Index of the first vertex of the edge to add -* @param v2 Index of the second vertex of the edge to add -*/ -inline void ConvexMeshShape::addEdge(uint v1, uint v2) { - - // If the entry for vertex v1 does not exist in the adjacency list - if (mEdgesAdjacencyList.count(v1) == 0) { - mEdgesAdjacencyList.insert(std::make_pair(v1, std::set())); - } - - // If the entry for vertex v2 does not exist in the adjacency list - if (mEdgesAdjacencyList.count(v2) == 0) { - mEdgesAdjacencyList.insert(std::make_pair(v2, std::set())); - } - - // Add the edge in the adjacency list - mEdgesAdjacencyList[v1].insert(v2); - mEdgesAdjacencyList[v2].insert(v1); -} - -// Return true if the edges information is used to speed up the collision detection -/** - * @return True if the edges information is used and false otherwise - */ -inline bool ConvexMeshShape::isEdgesInformationUsed() const { - return mIsEdgesInformationUsed; -} - -// Set the variable to know if the edges information is used to speed up the -// collision detection -/** - * @param isEdgesUsed True if you want to use the edges information to speed up - * the collision detection with the convex mesh shape - */ -inline void ConvexMeshShape::setIsEdgesInformationUsed(bool isEdgesUsed) { - mIsEdgesInformationUsed = isEdgesUsed; -} - // Return true if a point is inside the collision shape inline bool ConvexMeshShape::testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const { diff --git a/src/collision/shapes/ConvexPolyhedron.cpp b/src/collision/shapes/ConvexPolyhedron.cpp new file mode 100644 index 00000000..26964554 --- /dev/null +++ b/src/collision/shapes/ConvexPolyhedron.cpp @@ -0,0 +1,37 @@ +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "ConvexPolyhedron.h" + + +// We want to use the ReactPhysics3D namespace +using namespace reactphysics3d; + +// Constructor +ConvexPolyhedron::ConvexPolyhedron(decimal margin) + : ConvexShape(CollisionShapeType::CONVEX_POLYHEDRON, margin) { + +} diff --git a/src/collision/shapes/ConvexPolyhedron.h b/src/collision/shapes/ConvexPolyhedron.h new file mode 100644 index 00000000..27bbc0b5 --- /dev/null +++ b/src/collision/shapes/ConvexPolyhedron.h @@ -0,0 +1,68 @@ +/******************************************************************************** +* 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_CONVEX_POLYHEDRON_H +#define REACTPHYSICS3D_CONVEX_POLYHEDRON_H + +// Libraries +#include "ConvexShape.h" + +/// ReactPhysics3D namespace +namespace reactphysics3d { + +// Class ConvexPolyhedron +/** + * This abstract class represents a convex polyhedron collision shape associated with a + * body that is used during the narrow-phase collision detection. + */ +class ConvexPolyhedron : public ConvexShape { + + protected : + + // -------------------- Attributes -------------------- // + + // -------------------- Methods -------------------- // + + public : + + // -------------------- Methods -------------------- // + + /// Constructor + ConvexPolyhedron(decimal margin); + + /// Destructor + virtual ~ConvexPolyhedron() override = default; + + /// Deleted copy-constructor + ConvexPolyhedron(const ConvexPolyhedron& shape) = delete; + + /// Deleted assignment operator + ConvexPolyhedron& operator=(const ConvexPolyhedron& shape) = delete; +}; + +} + +#endif + diff --git a/src/reactphysics3d.h b/src/reactphysics3d.h index 3dbbd302..f6b8b8bf 100644 --- a/src/reactphysics3d.h +++ b/src/reactphysics3d.h @@ -55,7 +55,9 @@ #include "collision/ProxyShape.h" #include "collision/RaycastInfo.h" #include "collision/TriangleMesh.h" +#include "collision/PolyhedronMesh.h" #include "collision/TriangleVertexArray.h" +#include "collision/PolygonVertexArray.h" #include "constraint/BallAndSocketJoint.h" #include "constraint/SliderJoint.h" #include "constraint/HingeJoint.h" diff --git a/test/tests/collision/TestHalfEdgeStructure.h b/test/tests/collision/TestHalfEdgeStructure.h index 871a8ed1..4c4a2b39 100644 --- a/test/tests/collision/TestHalfEdgeStructure.h +++ b/test/tests/collision/TestHalfEdgeStructure.h @@ -43,19 +43,28 @@ class TestHalfEdgeStructure : public Test { void testCube() { // Create the half-edge structure for a cube - std::vector vertices; - std::vector> faces; rp3d::HalfEdgeStructure cubeStructure; + rp3d::Vector3 vertices[8] = { + rp3d::Vector3(-0.5, -0.5, 0.5), + rp3d::Vector3(0.5, -0.5, 0.5), + rp3d::Vector3(0.5, 0.5, 0.5), + rp3d::Vector3(-0.5, 0.5, 0.5), + rp3d::Vector3(-0.5, -0.5, -0.5), + rp3d::Vector3(0.5, -0.5, -0.5), + rp3d::Vector3(0.5, 0.5, -0.5), + rp3d::Vector3(-0.5, 0.5, -0.5) + }; + // Vertices - vertices.push_back(rp3d::Vector3(-0.5, -0.5, 0.5)); - vertices.push_back(rp3d::Vector3(0.5, -0.5, 0.5)); - vertices.push_back(rp3d::Vector3(0.5, 0.5, 0.5)); - vertices.push_back(rp3d::Vector3(-0.5, 0.5, 0.5)); - vertices.push_back(rp3d::Vector3(-0.5, -0.5, -0.5)); - vertices.push_back(rp3d::Vector3(0.5, -0.5, -0.5)); - vertices.push_back(rp3d::Vector3(0.5, 0.5, -0.5)); - vertices.push_back(rp3d::Vector3(-0.5, 0.5, -0.5)); + cubeStructure.addVertex(0); + cubeStructure.addVertex(1); + cubeStructure.addVertex(2); + cubeStructure.addVertex(3); + cubeStructure.addVertex(4); + cubeStructure.addVertex(5); + cubeStructure.addVertex(6); + cubeStructure.addVertex(7); // Faces std::vector face0; @@ -71,14 +80,14 @@ class TestHalfEdgeStructure : public Test { std::vector face5; face5.push_back(2); face5.push_back(6); face5.push_back(7); face5.push_back(3); - faces.push_back(face0); - faces.push_back(face1); - faces.push_back(face2); - faces.push_back(face3); - faces.push_back(face4); - faces.push_back(face5); + cubeStructure.addFace(face0); + cubeStructure.addFace(face1); + cubeStructure.addFace(face2); + cubeStructure.addFace(face3); + cubeStructure.addFace(face4); + cubeStructure.addFace(face5); - cubeStructure.init(vertices, faces); + cubeStructure.init(); // --- Test that the half-edge structure of the cube is valid --- // @@ -87,44 +96,44 @@ class TestHalfEdgeStructure : public Test { test(cubeStructure.getNbHalfEdges() == 24); // Test vertices - test(cubeStructure.getVertex(0).point.x == -0.5); - test(cubeStructure.getVertex(0).point.y == -0.5); - test(cubeStructure.getVertex(0).point.z == 0.5); + test(vertices[cubeStructure.getVertex(0).vertexPointIndex].x == -0.5); + test(vertices[cubeStructure.getVertex(0).vertexPointIndex].y == -0.5); + test(vertices[cubeStructure.getVertex(0).vertexPointIndex].z == 0.5); test(cubeStructure.getHalfEdge(cubeStructure.getVertex(0).edgeIndex).vertexIndex == 0); - test(cubeStructure.getVertex(1).point.x == 0.5); - test(cubeStructure.getVertex(1).point.y == -0.5); - test(cubeStructure.getVertex(1).point.z == 0.5); + test(vertices[cubeStructure.getVertex(1).vertexPointIndex].x == 0.5); + test(vertices[cubeStructure.getVertex(1).vertexPointIndex].y == -0.5); + test(vertices[cubeStructure.getVertex(1).vertexPointIndex].z == 0.5); test(cubeStructure.getHalfEdge(cubeStructure.getVertex(1).edgeIndex).vertexIndex == 1); - test(cubeStructure.getVertex(2).point.x == 0.5); - test(cubeStructure.getVertex(2).point.y == 0.5); - test(cubeStructure.getVertex(2).point.z == 0.5); + test(vertices[cubeStructure.getVertex(2).vertexPointIndex].x == 0.5); + test(vertices[cubeStructure.getVertex(2).vertexPointIndex].y == 0.5); + test(vertices[cubeStructure.getVertex(2).vertexPointIndex].z == 0.5); test(cubeStructure.getHalfEdge(cubeStructure.getVertex(2).edgeIndex).vertexIndex == 2); - test(cubeStructure.getVertex(3).point.x == -0.5); - test(cubeStructure.getVertex(3).point.y == 0.5); - test(cubeStructure.getVertex(3).point.z == 0.5); + test(vertices[cubeStructure.getVertex(3).vertexPointIndex].x == -0.5); + test(vertices[cubeStructure.getVertex(3).vertexPointIndex].y == 0.5); + test(vertices[cubeStructure.getVertex(3).vertexPointIndex].z == 0.5); test(cubeStructure.getHalfEdge(cubeStructure.getVertex(3).edgeIndex).vertexIndex == 3); - test(cubeStructure.getVertex(4).point.x == -0.5); - test(cubeStructure.getVertex(4).point.y == -0.5); - test(cubeStructure.getVertex(4).point.z == -0.5); + test(vertices[cubeStructure.getVertex(4).vertexPointIndex].x == -0.5); + test(vertices[cubeStructure.getVertex(4).vertexPointIndex].y == -0.5); + test(vertices[cubeStructure.getVertex(4).vertexPointIndex].z == -0.5); test(cubeStructure.getHalfEdge(cubeStructure.getVertex(4).edgeIndex).vertexIndex == 4); - test(cubeStructure.getVertex(5).point.x == 0.5); - test(cubeStructure.getVertex(5).point.y == -0.5); - test(cubeStructure.getVertex(5).point.z == -0.5); + test(vertices[cubeStructure.getVertex(5).vertexPointIndex].x == 0.5); + test(vertices[cubeStructure.getVertex(5).vertexPointIndex].y == -0.5); + test(vertices[cubeStructure.getVertex(5).vertexPointIndex].z == -0.5); test(cubeStructure.getHalfEdge(cubeStructure.getVertex(5).edgeIndex).vertexIndex == 5); - test(cubeStructure.getVertex(6).point.x == 0.5); - test(cubeStructure.getVertex(6).point.y == 0.5); - test(cubeStructure.getVertex(6).point.z == -0.5); + test(vertices[cubeStructure.getVertex(6).vertexPointIndex].x == 0.5); + test(vertices[cubeStructure.getVertex(6).vertexPointIndex].y == 0.5); + test(vertices[cubeStructure.getVertex(6).vertexPointIndex].z == -0.5); test(cubeStructure.getHalfEdge(cubeStructure.getVertex(6).edgeIndex).vertexIndex == 6); - test(cubeStructure.getVertex(7).point.x == -0.5); - test(cubeStructure.getVertex(7).point.y == 0.5); - test(cubeStructure.getVertex(7).point.z == -0.5); + test(vertices[cubeStructure.getVertex(7).vertexPointIndex].x == -0.5); + test(vertices[cubeStructure.getVertex(7).vertexPointIndex].y == 0.5); + test(vertices[cubeStructure.getVertex(7).vertexPointIndex].z == -0.5); test(cubeStructure.getHalfEdge(cubeStructure.getVertex(7).edgeIndex).vertexIndex == 7); // Test faces @@ -158,15 +167,21 @@ class TestHalfEdgeStructure : public Test { void testTetrahedron() { // Create the half-edge structure for a tetrahedron - std::vector vertices; std::vector> faces; rp3d::HalfEdgeStructure tetrahedron; // Vertices - vertices.push_back(rp3d::Vector3(1, -1, -1)); - vertices.push_back(rp3d::Vector3(-1, -1, -1)); - vertices.push_back(rp3d::Vector3(0, -1, 1)); - vertices.push_back(rp3d::Vector3(0, 1, 0)); + rp3d::Vector3 vertices[4] = { + rp3d::Vector3(1, -1, -1), + rp3d::Vector3(-1, -1, -1), + rp3d::Vector3(0, -1, 1), + rp3d::Vector3(0, 1, 0) + }; + + tetrahedron.addVertex(0); + tetrahedron.addVertex(1); + tetrahedron.addVertex(2); + tetrahedron.addVertex(3); // Faces std::vector face0; @@ -178,12 +193,12 @@ class TestHalfEdgeStructure : public Test { std::vector face3; face3.push_back(0); face3.push_back(2); face3.push_back(3); - faces.push_back(face0); - faces.push_back(face1); - faces.push_back(face2); - faces.push_back(face3); + tetrahedron.addFace(face0); + tetrahedron.addFace(face1); + tetrahedron.addFace(face2); + tetrahedron.addFace(face3); - tetrahedron.init(vertices, faces); + tetrahedron.init(); // --- Test that the half-edge structure of the tetrahedron is valid --- // @@ -192,24 +207,24 @@ class TestHalfEdgeStructure : public Test { test(tetrahedron.getNbHalfEdges() == 12); // Test vertices - test(tetrahedron.getVertex(0).point.x == 1); - test(tetrahedron.getVertex(0).point.y == -1); - test(tetrahedron.getVertex(0).point.z == -1); + test(vertices[tetrahedron.getVertex(0).vertexPointIndex].x == 1); + test(vertices[tetrahedron.getVertex(0).vertexPointIndex].y == -1); + test(vertices[tetrahedron.getVertex(0).vertexPointIndex].z == -1); test(tetrahedron.getHalfEdge(tetrahedron.getVertex(0).edgeIndex).vertexIndex == 0); - test(tetrahedron.getVertex(1).point.x == -1); - test(tetrahedron.getVertex(1).point.y == -1); - test(tetrahedron.getVertex(1).point.z == -1); + test(vertices[tetrahedron.getVertex(1).vertexPointIndex].x == -1); + test(vertices[tetrahedron.getVertex(1).vertexPointIndex].y == -1); + test(vertices[tetrahedron.getVertex(1).vertexPointIndex].z == -1); test(tetrahedron.getHalfEdge(tetrahedron.getVertex(1).edgeIndex).vertexIndex == 1); - test(tetrahedron.getVertex(2).point.x == 0); - test(tetrahedron.getVertex(2).point.y == -1); - test(tetrahedron.getVertex(2).point.z == 1); + test(vertices[tetrahedron.getVertex(2).vertexPointIndex].x == 0); + test(vertices[tetrahedron.getVertex(2).vertexPointIndex].y == -1); + test(vertices[tetrahedron.getVertex(2).vertexPointIndex].z == 1); test(tetrahedron.getHalfEdge(tetrahedron.getVertex(2).edgeIndex).vertexIndex == 2); - test(tetrahedron.getVertex(3).point.x == 0); - test(tetrahedron.getVertex(3).point.y == 1); - test(tetrahedron.getVertex(3).point.z == 0); + test(vertices[tetrahedron.getVertex(3).vertexPointIndex].x == 0); + test(vertices[tetrahedron.getVertex(3).vertexPointIndex].y == 1); + test(vertices[tetrahedron.getVertex(3).vertexPointIndex].z == 0); test(tetrahedron.getHalfEdge(tetrahedron.getVertex(3).edgeIndex).vertexIndex == 3); // Test faces diff --git a/test/tests/collision/TestPointInside.h b/test/tests/collision/TestPointInside.h index 9fd20110..abb54791 100644 --- a/test/tests/collision/TestPointInside.h +++ b/test/tests/collision/TestPointInside.h @@ -124,7 +124,8 @@ class TestPointInside : public Test { mCapsuleShape = new CapsuleShape(2, 10); mCapsuleProxyShape = mCapsuleBody->addCollisionShape(mCapsuleShape, mShapeTransform); - mConvexMeshShape = new ConvexMeshShape(0.0); // Box of dimension (2, 3, 4) + // TODO : Create convex mesh shape with new way (polyhedron mesh) to add test again + /*mConvexMeshShape = new ConvexMeshShape(0.0); // Box of dimension (2, 3, 4) mConvexMeshShape->addVertex(Vector3(-2, -3, -4)); mConvexMeshShape->addVertex(Vector3(2, -3, -4)); mConvexMeshShape->addVertex(Vector3(2, -3, 4)); @@ -160,6 +161,7 @@ class TestPointInside : public Test { mConvexMeshProxyShapeEdgesInfo = mConvexMeshBodyEdgesInfo->addCollisionShape( mConvexMeshShapeBodyEdgesInfo, mShapeTransform); + */ // Compound shape is a capsule and a sphere Vector3 positionShape2(Vector3(4, 2, -3)); @@ -175,8 +177,8 @@ class TestPointInside : public Test { delete mBoxShape; delete mSphereShape; delete mCapsuleShape; - delete mConvexMeshShape; - delete mConvexMeshShapeBodyEdgesInfo; + //delete mConvexMeshShape; + //delete mConvexMeshShapeBodyEdgesInfo; } /// Run the tests @@ -399,6 +401,7 @@ class TestPointInside : public Test { // ----- Tests without using edges information ----- // + /* // Tests with CollisionBody test(mConvexMeshBody->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 0))); test(mConvexMeshBody->testPointInside(mLocalShapeToWorld * Vector3(-1.9, 0, 0))); @@ -504,6 +507,7 @@ class TestPointInside : public Test { test(!mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(-10, -2, -1.5))); test(!mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(-1, 4, -2.5))); test(!mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(1, -2, 4.5))); + */ } /// Test the CollisionBody::testPointInside() method diff --git a/test/tests/collision/TestRaycast.h b/test/tests/collision/TestRaycast.h index 852455c2..fe8926d5 100644 --- a/test/tests/collision/TestRaycast.h +++ b/test/tests/collision/TestRaycast.h @@ -206,8 +206,9 @@ class TestRaycast : public Test { mCapsuleShape = new CapsuleShape(2, 5); mCapsuleProxyShape = mCapsuleBody->addCollisionShape(mCapsuleShape, mShapeTransform); + // TODO : Create convex mesh shape with new way (polyhedron mesh) to add test again // Box of dimension (2, 3, 4) - mConvexMeshShape = new ConvexMeshShape(0.0); + /*mConvexMeshShape = new ConvexMeshShape(0.0); mConvexMeshShape->addVertex(Vector3(-2, -3, -4)); mConvexMeshShape->addVertex(Vector3(2, -3, -4)); mConvexMeshShape->addVertex(Vector3(2, -3, 4)); @@ -243,6 +244,7 @@ class TestRaycast : public Test { mConvexMeshProxyShapeEdgesInfo = mConvexMeshBodyEdgesInfo->addCollisionShape( mConvexMeshShapeEdgesInfo, mShapeTransform); + */ // Compound shape is a cylinder and a sphere Vector3 positionShape2(Vector3(4, 2, -3)); @@ -312,8 +314,8 @@ class TestRaycast : public Test { delete mBoxShape; delete mSphereShape; delete mCapsuleShape; - delete mConvexMeshShape; - delete mConvexMeshShapeEdgesInfo; + //delete mConvexMeshShape; + //delete mConvexMeshShapeEdgesInfo; delete mTriangleShape; delete mConcaveMeshShape; delete mHeightFieldShape; @@ -1297,6 +1299,7 @@ class TestRaycast : public Test { /// CollisionWorld::raycast() methods. void testConvexMesh() { + /* // ----- Test feedback data ----- // Vector3 point1 = mLocalShapeToWorld * Vector3(1 , 2, 6); Vector3 point2 = mLocalShapeToWorld * Vector3(1, 2, -4); @@ -1555,6 +1558,7 @@ class TestRaycast : public Test { mCallback.reset(); mWorld->raycast(Ray(ray16.point1, ray16.point2, decimal(0.8)), &mCallback); test(mCallback.isHit); + */ } /// Test the CollisionBody::raycast() and diff --git a/testbed/common/ConvexMesh.cpp b/testbed/common/ConvexMesh.cpp index 7842c529..11be5732 100644 --- a/testbed/common/ConvexMesh.cpp +++ b/testbed/common/ConvexMesh.cpp @@ -40,17 +40,36 @@ ConvexMesh::ConvexMesh(const openglframework::Vector3 &position, // Compute the scaling matrix mScalingMatrix = openglframework::Matrix4::identity(); - // Vertex and Indices array for the triangle mesh (data in shared and not copied) - mPhysicsTriangleVertexArray = + /*mPolygonVertexArray = new rp3d::TriangleVertexArray(getNbVertices(), &(mVertices[0]), sizeof(openglframework::Vector3), getNbFaces(0), &(mIndices[0][0]), sizeof(int), rp3d::TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE, - rp3d::TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE); + rp3d::TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE);*/ + + // Polygon faces descriptions for the polyhedron + mPolygonFaces = new rp3d::PolygonVertexArray::PolygonFace[getNbFaces(0)]; + rp3d::PolygonVertexArray::PolygonFace* face = mPolygonFaces; + for (int f=0; f < getNbFaces(0); f++) { + face->indexBase = f * 3; + face->nbVertices = 3; + face++; + } + + // Create the polygon vertex array + mPolygonVertexArray = + new rp3d::PolygonVertexArray(getNbVertices(), &(mVertices[0]), sizeof(openglframework::Vector3), + &(mIndices[0][0]), sizeof(int), + getNbFaces(0), mPolygonFaces, + rp3d::PolygonVertexArray::VertexDataType::VERTEX_FLOAT_TYPE, + rp3d::PolygonVertexArray::IndexDataType::INDEX_INTEGER_TYPE); + + // Create the polyhedron mesh + mPolyhedronMesh = new rp3d::PolyhedronMesh(mPolygonVertexArray); // Create the collision shape for the rigid body (convex mesh shape) and // do not forget to delete it at the end - mConvexShape = new rp3d::ConvexMeshShape(mPhysicsTriangleVertexArray); + mConvexShape = new rp3d::ConvexMeshShape(mPolyhedronMesh); // Initial position and orientation of the rigid body rp3d::Vector3 initPosition(position.x, position.y, position.z); @@ -85,16 +104,29 @@ ConvexMesh::ConvexMesh(const openglframework::Vector3 &position, float mass, // Compute the scaling matrix mScalingMatrix = openglframework::Matrix4::identity(); - // Vertex and Indices array for the triangle mesh (data in shared and not copied) - mPhysicsTriangleVertexArray = - new rp3d::TriangleVertexArray(getNbVertices(), &(mVertices[0]), sizeof(openglframework::Vector3), - getNbFaces(0), &(mIndices[0][0]), sizeof(int), - rp3d::TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE, - rp3d::TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE); + // Polygon faces descriptions for the polyhedron + mPolygonFaces = new rp3d::PolygonVertexArray::PolygonFace[getNbFaces(0)]; + rp3d::PolygonVertexArray::PolygonFace* face = mPolygonFaces; + for (int f=0; f < getNbFaces(0); f++) { + face->indexBase = f * 3; + face->nbVertices = 3; + face++; + } + + // Create the polygon vertex array + mPolygonVertexArray = + new rp3d::PolygonVertexArray(getNbVertices(), &(mVertices[0]), sizeof(openglframework::Vector3), + &(mIndices[0][0]), sizeof(int), + getNbFaces(0), mPolygonFaces, + rp3d::PolygonVertexArray::VertexDataType::VERTEX_FLOAT_TYPE, + rp3d::PolygonVertexArray::IndexDataType::INDEX_INTEGER_TYPE); + + // Create the polyhedron mesh + mPolyhedronMesh = new rp3d::PolyhedronMesh(mPolygonVertexArray); // Create the collision shape for the rigid body (convex mesh shape) and do // not forget to delete it at the end - mConvexShape = new rp3d::ConvexMeshShape(mPhysicsTriangleVertexArray); + mConvexShape = new rp3d::ConvexMeshShape(mPolyhedronMesh); // Initial position and orientation of the rigid body rp3d::Vector3 initPosition(position.x, position.y, position.z); @@ -128,7 +160,9 @@ ConvexMesh::~ConvexMesh() { mVBOTextureCoords.destroy(); mVAO.destroy(); - delete mPhysicsTriangleVertexArray; + delete mPolyhedronMesh; + delete mPolygonVertexArray; + delete[] mPolygonFaces; delete mConvexShape; } diff --git a/testbed/common/ConvexMesh.h b/testbed/common/ConvexMesh.h index b6cb90c1..e2ba5836 100644 --- a/testbed/common/ConvexMesh.h +++ b/testbed/common/ConvexMesh.h @@ -41,7 +41,11 @@ class ConvexMesh : public PhysicsObject { /// Previous transform (for interpolation) rp3d::Transform mPreviousTransform; - rp3d::TriangleVertexArray* mPhysicsTriangleVertexArray; + rp3d::PolygonVertexArray::PolygonFace* mPolygonFaces; + + rp3d::PolygonVertexArray* mPolygonVertexArray; + + rp3d::PolyhedronMesh* mPolyhedronMesh; /// Collision shape rp3d::ConvexMeshShape* mConvexShape; From a9b3afae59f092a75755e6edb767d079303c31bf Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 28 Mar 2017 23:07:10 +0200 Subject: [PATCH 062/248] Finish implementing capsule vs capsule narrow-phase algorithm --- .../narrowphase/CapsuleVsCapsuleAlgorithm.cpp | 74 +++++++++---------- 1 file changed, 37 insertions(+), 37 deletions(-) diff --git a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp index e83d694c..11160b8c 100644 --- a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp @@ -66,60 +66,60 @@ bool CapsuleVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhase // If the distance between the two segments is larger than the sum of the capsules radius (we do not have overlapping) const decimal segmentsDistance = computeDistancePointToLineDistance(capsule1SegA, capsule1SegB, capsule2SegA); - if (segmentsDistance >= sumRadius || segmentsDistance < MACHINE_EPSILON) { + if (segmentsDistance >= sumRadius) { // The capsule are parallel but their inner segment distance is larger than the sum of the capsules radius. // Therefore, we do not have overlap. If the inner segments overlap, we do not report any collision. return false; } - // Compute the planes that goes through the extrem points of the inner segment of capsule 1 - decimal d1 = seg1.dot(capsule1SegA); - decimal d2 = -seg1.dot(capsule1SegB); + // If the distance between the two segments is larger than zero (inner segments of capsules are not overlapping) + // If the inner segments are overlapping, we cannot compute a contact normal (unknown direction). In this case, + // we skip the parallel contact points calculation (there might still be contact in the spherical caps of the capsules) + if (segmentsDistance > MACHINE_EPSILON) { - // Clip the inner segment of capsule 2 with the two planes that go through extreme points of inner - // segment of capsule 1 - decimal t1 = computePlaneSegmentIntersection(capsule2SegB, capsule2SegA, d1, seg1); - decimal t2 = computePlaneSegmentIntersection(capsule2SegA, capsule2SegB, d2, -seg1); + // Compute the planes that goes through the extreme points of the inner segment of capsule 1 + decimal d1 = seg1.dot(capsule1SegA); + decimal d2 = -seg1.dot(capsule1SegB); - bool isClipValid = false; // True if the segments were overlapping (the clip segment is valid) + // Clip the inner segment of capsule 2 with the two planes that go through extreme points of inner + // segment of capsule 1 + decimal t1 = computePlaneSegmentIntersection(capsule2SegB, capsule2SegA, d1, seg1); + decimal t2 = computePlaneSegmentIntersection(capsule2SegA, capsule2SegB, d2, -seg1); - // Clip the inner segment of capsule 2 - Vector3 clipPointA, clipPointB; - if (t1 >= decimal(0.0)) { + // If the segments were overlapping (the clip segment is valid) + if (t1 > decimal(0.0) && t2 > decimal(0.0)) { - if (t1 > decimal(1.0)) t1 = decimal(1.0); - clipPointA = capsule2SegB - t1 * seg2; - isClipValid = true; - } - if (t2 >= decimal(0.0) && t2 <= decimal(1.0)) { + // Clip the inner segment of capsule 2 + if (t1 > decimal(1.0)) t1 = decimal(1.0); + const Vector3 clipPointA = capsule2SegB - t1 * seg2; + if (t2 > decimal(1.0)) t2 = decimal(1.0); + const Vector3 clipPointB = capsule2SegA + t2 * seg2; - if (t2 > decimal(1.0)) t2 = decimal(1.0); - clipPointB = capsule2SegA + t2 * seg2; - isClipValid = true; - } + // Project point capsule2SegA onto line of innner segment of capsule 1 + const Vector3 seg1Normalized = seg1.getUnit(); + Vector3 pointOnInnerSegCapsule1 = capsule1SegA + seg1Normalized.dot(capsule2SegA - capsule1SegA) * seg1Normalized; - // If we have a valid clip segment - if (isClipValid) { + // Compute a perpendicular vector from segment 1 to segment 2 + Vector3 segment1ToSegment2 = (capsule2SegA - pointOnInnerSegCapsule1); + Vector3 segment1ToSegment2Normalized = segment1ToSegment2.getUnit(); - Vector3 segment1ToSegment2 = (capsule2SegA - capsule1SegA); - Vector3 segment1ToSegment2Normalized = segment1ToSegment2.getUnit(); + Transform capsule2ToCapsule1SpaceTransform = capsule1ToCapsule2SpaceTransform.getInverse(); + const Vector3 contactPointACapsule1Local = capsule2ToCapsule1SpaceTransform * (clipPointA - segment1ToSegment2 + segment1ToSegment2Normalized * capsuleShape1->getRadius()); + const Vector3 contactPointBCapsule1Local = capsule2ToCapsule1SpaceTransform * (clipPointB - segment1ToSegment2 + segment1ToSegment2Normalized * capsuleShape1->getRadius()); + const Vector3 contactPointACapsule2Local = clipPointA - segment1ToSegment2Normalized * capsuleShape2->getRadius(); + const Vector3 contactPointBCapsule2Local = clipPointB - segment1ToSegment2Normalized * capsuleShape2->getRadius(); - Transform capsule2ToCapsule1SpaceTransform = capsule1ToCapsule2SpaceTransform.getInverse(); - const Vector3 contactPointACapsule1Local = capsule2ToCapsule1SpaceTransform * (clipPointA - segment1ToSegment2 + segment1ToSegment2Normalized * capsuleShape1->getRadius()); - const Vector3 contactPointBCapsule1Local = capsule2ToCapsule1SpaceTransform * (clipPointB - segment1ToSegment2 + segment1ToSegment2Normalized * capsuleShape1->getRadius()); - const Vector3 contactPointACapsule2Local = clipPointA - segment1ToSegment2Normalized * capsuleShape2->getRadius(); - const Vector3 contactPointBCapsule2Local = clipPointB - segment1ToSegment2Normalized * capsuleShape2->getRadius(); + const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * segment1ToSegment2Normalized; - const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * segment1ToSegment2Normalized; + decimal penetrationDepth = sumRadius - segmentsDistance; - decimal penetrationDepth = sumRadius - segmentsDistance; + // Create the contact info object + contactManifoldInfo.addContactPoint(normalWorld, penetrationDepth, contactPointACapsule1Local, contactPointACapsule2Local); + contactManifoldInfo.addContactPoint(normalWorld, penetrationDepth, contactPointBCapsule1Local, contactPointBCapsule2Local); - // Create the contact info object - contactManifoldInfo.addContactPoint(normalWorld, penetrationDepth, contactPointACapsule1Local, contactPointACapsule2Local); - contactManifoldInfo.addContactPoint(normalWorld, penetrationDepth, contactPointBCapsule1Local, contactPointBCapsule2Local); - - return true; + return true; + } } } From 951ba3e42c3680f42e8204ca4b3f9a01d1d28c07 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 30 Mar 2017 22:39:06 +0200 Subject: [PATCH 063/248] Working on ConvexPolyhedron class --- src/collision/PolyhedronMesh.cpp | 27 +++++++ src/collision/PolyhedronMesh.h | 17 +++- src/collision/shapes/BoxShape.cpp | 31 ++++++++ src/collision/shapes/BoxShape.h | 100 ++++++++++++++++++++++-- src/collision/shapes/ConvexMeshShape.h | 75 ++++++++++++++++-- src/collision/shapes/ConvexPolyhedron.h | 33 ++++++++ src/collision/shapes/ConvexShape.h | 2 +- 7 files changed, 268 insertions(+), 17 deletions(-) diff --git a/src/collision/PolyhedronMesh.cpp b/src/collision/PolyhedronMesh.cpp index df43a47a..50ef5bab 100644 --- a/src/collision/PolyhedronMesh.cpp +++ b/src/collision/PolyhedronMesh.cpp @@ -36,6 +36,17 @@ PolyhedronMesh::PolyhedronMesh(PolygonVertexArray* polygonVertexArray) { // Create the half-edge structure of the mesh createHalfEdgeStructure(); + + // Create the face normals array + mFacesNormals = new Vector3[mHalfEdgeStructure.getNbFaces()]; + + // Compute the faces normals + computeFacesNormals(); +} + +// Destructor +PolyhedronMesh::~PolyhedronMesh() { + delete[] mFacesNormals; } // Create the half-edge structure of the mesh @@ -59,6 +70,8 @@ void PolyhedronMesh::createHalfEdgeStructure() { faceVertices.push_back(mPolygonVertexArray->getVertexIndexInFace(f, v)); } + assert(faceVertices.size() >= 3); + // Addd the face into the half-edge structure mHalfEdgeStructure.addFace(faceVertices); } @@ -97,3 +110,17 @@ Vector3 PolyhedronMesh::getVertex(uint index) const { return vertex; } + +void PolyhedronMesh::computeFacesNormals() { + + // For each face + for (uint f=0; f < mHalfEdgeStructure.getNbFaces(); f++) { + HalfEdgeStructure::Face face = mHalfEdgeStructure.getFace(f); + + assert(face.faceVertices.size() >= 3); + + const Vector3 vec1 = getVertex(face.faceVertices[1]) - getVertex(face.faceVertices[0]); + const Vector3 vec2 = getVertex(face.faceVertices[2]) - getVertex(face.faceVertices[0]); + mFacesNormals[f] = vec1.cross(vec2); + } +} diff --git a/src/collision/PolyhedronMesh.h b/src/collision/PolyhedronMesh.h index f842cae1..940b2db0 100644 --- a/src/collision/PolyhedronMesh.h +++ b/src/collision/PolyhedronMesh.h @@ -52,11 +52,17 @@ class PolyhedronMesh { /// Half-edge structure of the mesh HalfEdgeStructure mHalfEdgeStructure; + /// Array with the face normals + Vector3* mFacesNormals; + // -------------------- Methods -------------------- // /// Create the half-edge structure of the mesh void createHalfEdgeStructure(); + /// Compute the faces normals + void computeFacesNormals(); + public: // -------------------- Methods -------------------- // @@ -65,7 +71,7 @@ class PolyhedronMesh { PolyhedronMesh(PolygonVertexArray* polygonVertexArray); /// Destructor - ~PolyhedronMesh() = default; + ~PolyhedronMesh(); /// Return the number of vertices uint getNbVertices() const; @@ -73,6 +79,9 @@ class PolyhedronMesh { /// Return a vertex Vector3 getVertex(uint index) const; + /// Return a face normal + Vector3 getFaceNormal(uint faceIndex) const; + /// Return the half-edge structure of the mesh const HalfEdgeStructure& getHalfEdgeStructure() const; }; @@ -82,6 +91,12 @@ inline uint PolyhedronMesh::getNbVertices() const { return mHalfEdgeStructure.getNbVertices(); } +// Return a face normal +inline Vector3 PolyhedronMesh::getFaceNormal(uint faceIndex) const { + assert(faceIndex < mHalfEdgeStructure.getNbFaces()); + return mFacesNormals[faceIndex]; +} + // Return the half-edge structure of the mesh inline const HalfEdgeStructure& PolyhedronMesh::getHalfEdgeStructure() const { return mHalfEdgeStructure; diff --git a/src/collision/shapes/BoxShape.cpp b/src/collision/shapes/BoxShape.cpp index ba5dfa1a..f00210c2 100644 --- a/src/collision/shapes/BoxShape.cpp +++ b/src/collision/shapes/BoxShape.cpp @@ -42,6 +42,37 @@ BoxShape::BoxShape(const Vector3& extent, decimal margin) assert(extent.x > decimal(0.0) && extent.x > margin); assert(extent.y > decimal(0.0) && extent.y > margin); assert(extent.z > decimal(0.0) && extent.z > margin); + + // Vertices + mHalfEdgeStructure.addVertex(0); + mHalfEdgeStructure.addVertex(1); + mHalfEdgeStructure.addVertex(2); + mHalfEdgeStructure.addVertex(3); + mHalfEdgeStructure.addVertex(4); + mHalfEdgeStructure.addVertex(5); + mHalfEdgeStructure.addVertex(6); + mHalfEdgeStructure.addVertex(7); + + // Faces + std::vector face0; + face0.push_back(0); face0.push_back(1); face0.push_back(2); face0.push_back(3); + std::vector face1; + face0.push_back(1); face0.push_back(5); face0.push_back(6); face0.push_back(2); + std::vector face2; + face0.push_back(4); face0.push_back(7); face0.push_back(6); face0.push_back(5); + std::vector face3; + face0.push_back(4); face0.push_back(0); face0.push_back(3); face0.push_back(7); + std::vector face4; + face0.push_back(4); face0.push_back(5); face0.push_back(1); face0.push_back(0); + std::vector face5; + face0.push_back(2); face0.push_back(6); face0.push_back(7); face0.push_back(3); + + mHalfEdgeStructure.addFace(face0); + mHalfEdgeStructure.addFace(face1); + mHalfEdgeStructure.addFace(face2); + mHalfEdgeStructure.addFace(face3); + mHalfEdgeStructure.addFace(face4); + mHalfEdgeStructure.addFace(face5); } // Return the local inertia tensor of the collision shape diff --git a/src/collision/shapes/BoxShape.h b/src/collision/shapes/BoxShape.h index c3d5caf2..d78bda25 100644 --- a/src/collision/shapes/BoxShape.h +++ b/src/collision/shapes/BoxShape.h @@ -59,6 +59,9 @@ class BoxShape : public ConvexPolyhedron { /// Extent sizes of the box in the x, y and z direction Vector3 mExtent; + /// Half-edge structure of the polyhedron + HalfEdgeStructure mHalfEdgeStructure; + // -------------------- Methods -------------------- // /// Return a local support point in a given direction without the object margin @@ -99,11 +102,32 @@ class BoxShape : public ConvexPolyhedron { /// Return the local bounds of the shape in x, y and z directions virtual void getLocalBounds(Vector3& min, Vector3& max) const override; - /// Return true if the collision shape is a polyhedron - virtual bool isPolyhedron() const override; - /// Return the local inertia tensor of the collision shape virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; + + /// Return the number of faces of the polyhedron + virtual uint getNbFaces() const override; + + /// Return a given face of the polyhedron + virtual HalfEdgeStructure::Face getFace(uint faceIndex) const override; + + /// Return the number of vertices of the polyhedron + virtual uint getNbVertices() const override; + + /// Return a given vertex of the polyhedron + virtual HalfEdgeStructure::Vertex getVertex(uint vertexIndex) const override; + + /// Return the number of half-edges of the polyhedron + virtual uint getNbHalfEdges() const override; + + /// Return a given half-edge of the polyhedron + virtual HalfEdgeStructure::Edge getHalfEdge(uint edgeIndex) const override; + + /// Return the position of a given vertex + virtual Vector3 getVertexPosition(uint vertexIndex) const override; + + /// Return the normal vector of a given face of the polyhedron + virtual Vector3 getFaceNormal(uint faceIndex) const override; }; // Return the extents of the box @@ -137,11 +161,6 @@ inline void BoxShape::getLocalBounds(Vector3& min, Vector3& max) const { min = -max; } -// Return true if the collision shape is a polyhedron -inline bool BoxShape::isPolyhedron() const { - return true; -} - // Return the number of bytes used by the collision shape inline size_t BoxShape::getSizeInBytes() const { return sizeof(BoxShape); @@ -163,6 +182,71 @@ inline bool BoxShape::testPointInside(const Vector3& localPoint, ProxyShape* pro localPoint.z < mExtent[2] && localPoint.z > -mExtent[2]); } +// Return the number of faces of the polyhedron +inline uint BoxShape::getNbFaces() const { + return 6; +} + +// Return a given face of the polyhedron +inline HalfEdgeStructure::Face BoxShape::getFace(uint faceIndex) const { + assert(faceIndex < mHalfEdgeStructure.getNbFaces()); + return mHalfEdgeStructure.getFace(faceIndex); +} + +// Return the number of vertices of the polyhedron +inline uint BoxShape::getNbVertices() const { + return 8; +} + +// Return a given vertex of the polyhedron +inline HalfEdgeStructure::Vertex BoxShape::getVertex(uint vertexIndex) const { + assert(vertexIndex < getNbVertices()); + return mHalfEdgeStructure.getVertex(vertexIndex); +} + +// Return the position of a given vertex +inline Vector3 BoxShape::getVertexPosition(uint vertexIndex) const { + assert(vertexIndex < getNbVertices()); + + Vector3 extent = getExtent(); + + switch(vertexIndex) { + case 0: return Vector3(-extent.x, -extent.y, extent.z); + case 1: return Vector3(extent.x, -extent.y, extent.z); + case 2: return Vector3(extent.x, extent.y, extent.z); + case 3: return Vector3(-extent.x, extent.y, extent.z); + case 4: return Vector3(-extent.x, -extent.y, -extent.z); + case 5: return Vector3(extent.x, -extent.y, -extent.z); + case 6: return Vector3(extent.x, extent.y, -extent.z); + case 7: return Vector3(-extent.x, extent.y, -extent.z); + } +} + +// Return the normal vector of a given face of the polyhedron +inline Vector3 BoxShape::getFaceNormal(uint faceIndex) const { + assert(faceIndex < getNbFaces()); + + switch(faceIndex) { + case 0: return Vector3(0, 0, 1); + case 1: return Vector3(1, 0, 0); + case 2: return Vector3(0, 0, -1); + case 3: return Vector3(-1, 0, 0); + case 4: return Vector3(0, -1, 0); + case 5: return Vector3(0, 1, 0); + } +} + +// Return the number of half-edges of the polyhedron +inline uint BoxShape::getNbHalfEdges() const { + return 24; +} + +// Return a given half-edge of the polyhedron +inline HalfEdgeStructure::Edge BoxShape::getHalfEdge(uint edgeIndex) const { + assert(edgeIndex < getNbHalfEdges()); + return mHalfEdgeStructure.getHalfEdge(edgeIndex); +} + } #endif diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index c33fd5bd..cc88d38d 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -119,8 +119,29 @@ class ConvexMeshShape : public ConvexPolyhedron { /// Return the local inertia tensor of the collision shape. virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; - /// Return true if the collision shape is a polyhedron - virtual bool isPolyhedron() const override; + /// Return the number of faces of the polyhedron + virtual uint getNbFaces() const override; + + /// Return a given face of the polyhedron + virtual HalfEdgeStructure::Face getFace(uint faceIndex) const override; + + /// Return the number of vertices of the polyhedron + virtual uint getNbVertices() const override; + + /// Return a given vertex of the polyhedron + virtual HalfEdgeStructure::Vertex getVertex(uint vertexIndex) const override; + + /// Return the number of half-edges of the polyhedron + virtual uint getNbHalfEdges() const override; + + /// Return a given half-edge of the polyhedron + virtual HalfEdgeStructure::Edge getHalfEdge(uint edgeIndex) const override; + + /// Return the position of a given vertex + virtual Vector3 getVertexPosition(uint vertexIndex) const override; + + /// Return the normal vector of a given face of the polyhedron + virtual Vector3 getFaceNormal(uint faceIndex) const override; }; /// Set the scaling vector of the collision shape @@ -134,11 +155,6 @@ inline size_t ConvexMeshShape::getSizeInBytes() const { return sizeof(ConvexMeshShape); } -// Return true if the collision shape is a polyhedron -inline bool ConvexMeshShape::isPolyhedron() const { - return true; -} - // Return the local bounds of the shape in x, y and z directions /** * @param min The minimum bounds of the shape in local-space coordinates @@ -178,6 +194,51 @@ inline bool ConvexMeshShape::testPointInside(const Vector3& localPoint, mNarrowPhaseGJKAlgorithm.testPointInside(localPoint, proxyShape); } +// Return the number of faces of the polyhedron +inline uint ConvexMeshShape::getNbFaces() const { + return mPolyhedronMesh->getHalfEdgeStructure().getNbFaces(); +} + +// Return a given face of the polyhedron +inline HalfEdgeStructure::Face ConvexMeshShape::getFace(uint faceIndex) const { + assert(faceIndex < getNbFaces()); + return mPolyhedronMesh->getHalfEdgeStructure().getFace(faceIndex); +} + +// Return the number of vertices of the polyhedron +inline uint ConvexMeshShape::getNbVertices() const { + return mPolyhedronMesh->getHalfEdgeStructure().getNbVertices(); +} + +// Return a given vertex of the polyhedron +inline HalfEdgeStructure::Vertex ConvexMeshShape::getVertex(uint vertexIndex) const { + assert(vertexIndex < getNbVertices()); + return mPolyhedronMesh->getHalfEdgeStructure().getVertex(vertexIndex); +} + +// Return the number of half-edges of the polyhedron +inline uint ConvexMeshShape::getNbHalfEdges() const { + return mPolyhedronMesh->getHalfEdgeStructure().getNbHalfEdges(); +} + +// Return a given half-edge of the polyhedron +inline HalfEdgeStructure::Edge ConvexMeshShape::getHalfEdge(uint edgeIndex) const { + assert(edgeIndex < getNbHalfEdges()); + return mPolyhedronMesh->getHalfEdgeStructure().getHalfEdge(edgeIndex); +} + +// Return the position of a given vertex +inline Vector3 ConvexMeshShape::getVertexPosition(uint vertexIndex) const { + assert(vertexIndex < getNbVertices()); + return mPolyhedronMesh->getVertex(vertexIndex); +} + +// Return the normal vector of a given face of the polyhedron +inline Vector3 ConvexMeshShape::getFaceNormal(uint faceIndex) const { + assert(faceIndex < getNbFaces()); + return mPolyhedronMesh->getFaceNormal(faceIndex); +} + } #endif diff --git a/src/collision/shapes/ConvexPolyhedron.h b/src/collision/shapes/ConvexPolyhedron.h index 27bbc0b5..2a544077 100644 --- a/src/collision/shapes/ConvexPolyhedron.h +++ b/src/collision/shapes/ConvexPolyhedron.h @@ -28,6 +28,7 @@ // Libraries #include "ConvexShape.h" +#include "collision/HalfEdgeStructure.h" /// ReactPhysics3D namespace namespace reactphysics3d { @@ -60,8 +61,40 @@ class ConvexPolyhedron : public ConvexShape { /// Deleted assignment operator ConvexPolyhedron& operator=(const ConvexPolyhedron& shape) = delete; + + /// Return the number of faces of the polyhedron + virtual uint getNbFaces() const=0; + + /// Return a given face of the polyhedron + virtual HalfEdgeStructure::Face getFace(uint faceIndex) const=0; + + /// Return the number of vertices of the polyhedron + virtual uint getNbVertices() const=0; + + /// Return a given vertex of the polyhedron + virtual HalfEdgeStructure::Vertex getVertex(uint vertexIndex) const=0; + + /// Return the position of a given vertex + virtual Vector3 getVertexPosition(uint vertexIndex) const=0; + + /// Return the normal vector of a given face of the polyhedron + virtual Vector3 getFaceNormal(uint faceIndex) const=0; + + /// Return the number of half-edges of the polyhedron + virtual uint getNbHalfEdges() const=0; + + /// Return a given half-edge of the polyhedron + virtual HalfEdgeStructure::Edge getHalfEdge(uint edgeIndex) const=0; + + /// Return true if the collision shape is a polyhedron + virtual bool isPolyhedron() const override; }; +// Return true if the collision shape is a polyhedron +inline bool ConvexPolyhedron::isPolyhedron() const { + return true; +} + } #endif diff --git a/src/collision/shapes/ConvexShape.h b/src/collision/shapes/ConvexShape.h index 4b12cae4..9180fefe 100644 --- a/src/collision/shapes/ConvexShape.h +++ b/src/collision/shapes/ConvexShape.h @@ -84,7 +84,7 @@ class ConvexShape : public CollisionShape { friend class EPAAlgorithm; }; -/// Return true if the collision shape is convex, false if it is concave +// Return true if the collision shape is convex, false if it is concave inline bool ConvexShape::isConvex() const { return true; } From 57da79492f3cfc99e5758fb650988a4c778dcf4e Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 2 Apr 2017 00:33:29 +0200 Subject: [PATCH 064/248] Add sphere vs convex polyhedron test in SAT algorithm --- CMakeLists.txt | 8 +-- src/collision/PolyhedronMesh.cpp | 2 + .../narrowphase/DefaultCollisionDispatch.cpp | 4 ++ .../narrowphase/DefaultCollisionDispatch.h | 4 +- .../narrowphase/SAT/SATAlgorithm.cpp | 64 ++++++++++++++++++- src/collision/narrowphase/SAT/SATAlgorithm.h | 2 +- ... => SphereVsConvexPolyhedronAlgorithm.cpp} | 4 +- ....h => SphereVsConvexPolyhedronAlgorithm.h} | 14 ++-- src/collision/shapes/BoxShape.cpp | 12 ++-- src/collision/shapes/BoxShape.h | 4 +- src/collision/shapes/CollisionShape.h | 2 +- src/collision/shapes/ConvexMeshShape.cpp | 2 +- src/collision/shapes/ConvexMeshShape.h | 4 +- ...lyhedron.cpp => ConvexPolyhedronShape.cpp} | 4 +- ...exPolyhedron.h => ConvexPolyhedronShape.h} | 14 ++-- 15 files changed, 105 insertions(+), 39 deletions(-) rename src/collision/narrowphase/{SphereVsConvexMeshAlgorithm.cpp => SphereVsConvexPolyhedronAlgorithm.cpp} (95%) rename src/collision/narrowphase/{SphereVsConvexMeshAlgorithm.h => SphereVsConvexPolyhedronAlgorithm.h} (84%) rename src/collision/shapes/{ConvexPolyhedron.cpp => ConvexPolyhedronShape.cpp} (95%) rename src/collision/shapes/{ConvexPolyhedron.h => ConvexPolyhedronShape.h} (90%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4f6ab0bc..0a30f8c2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -84,14 +84,14 @@ SET (REACTPHYSICS3D_SOURCES "src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp" "src/collision/narrowphase/ConcaveVsConvexAlgorithm.h" "src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp" - "src/collision/narrowphase/SphereVsConvexMeshAlgorithm.h" - "src/collision/narrowphase/SphereVsConvexMeshAlgorithm.cpp" + "src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h" + "src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp" "src/collision/shapes/AABB.h" "src/collision/shapes/AABB.cpp" "src/collision/shapes/ConvexShape.h" "src/collision/shapes/ConvexShape.cpp" - "src/collision/shapes/ConvexPolyhedron.h" - "src/collision/shapes/ConvexPolyhedron.cpp" + "src/collision/shapes/ConvexPolyhedronShape.h" + "src/collision/shapes/ConvexPolyhedronShape.cpp" "src/collision/shapes/ConcaveShape.h" "src/collision/shapes/ConcaveShape.cpp" "src/collision/shapes/BoxShape.h" diff --git a/src/collision/PolyhedronMesh.cpp b/src/collision/PolyhedronMesh.cpp index 50ef5bab..60a3be9f 100644 --- a/src/collision/PolyhedronMesh.cpp +++ b/src/collision/PolyhedronMesh.cpp @@ -111,6 +111,7 @@ Vector3 PolyhedronMesh::getVertex(uint index) const { return vertex; } +// Compute the faces normals void PolyhedronMesh::computeFacesNormals() { // For each face @@ -122,5 +123,6 @@ void PolyhedronMesh::computeFacesNormals() { const Vector3 vec1 = getVertex(face.faceVertices[1]) - getVertex(face.faceVertices[0]); const Vector3 vec2 = getVertex(face.faceVertices[2]) - getVertex(face.faceVertices[0]); mFacesNormals[f] = vec1.cross(vec2); + mFacesNormals[f].normalize(); } } diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.cpp b/src/collision/narrowphase/DefaultCollisionDispatch.cpp index 5fdd485b..0a1e498c 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.cpp +++ b/src/collision/narrowphase/DefaultCollisionDispatch.cpp @@ -52,6 +52,10 @@ NarrowPhaseAlgorithm* DefaultCollisionDispatch::selectAlgorithm(int type1, int t if (shape1Type == CollisionShapeType::CAPSULE && shape2Type == CollisionShapeType::CAPSULE) { return &mCapsuleVsCapsuleAlgorithm; } + // Sphere vs Convex Polyhedron algorithm + if (shape1Type == CollisionShapeType::SPHERE && shape2Type == CollisionShapeType::CONVEX_POLYHEDRON) { + return &mSphereVsConvexPolyhedronAlgorithm; + } return nullptr; } diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.h b/src/collision/narrowphase/DefaultCollisionDispatch.h index 65e05497..7c5d77ea 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.h +++ b/src/collision/narrowphase/DefaultCollisionDispatch.h @@ -30,7 +30,7 @@ #include "CollisionDispatch.h" #include "ConcaveVsConvexAlgorithm.h" #include "SphereVsSphereAlgorithm.h" -#include "SphereVsConvexMeshAlgorithm.h" +#include "SphereVsConvexPolyhedronAlgorithm.h" #include "SphereVsCapsuleAlgorithm.h" #include "CapsuleVsCapsuleAlgorithm.h" #include "GJK/GJKAlgorithm.h" @@ -51,7 +51,7 @@ class DefaultCollisionDispatch : public CollisionDispatch { SphereVsSphereAlgorithm mSphereVsSphereAlgorithm; /// Sphere vs Convex Mesh collision algorithm - SphereVsConvexMeshAlgorithm mSphereVsConvexMeshAlgorithm; + SphereVsConvexPolyhedronAlgorithm mSphereVsConvexPolyhedronAlgorithm; /// Sphere vs Capsule collision algorithm SphereVsCapsuleAlgorithm mSphereVsCapsuleAlgorithm; diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 61910acc..ee241c77 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -27,6 +27,8 @@ #include "SATAlgorithm.h" #include "constraint/ContactPoint.h" #include "collision/PolyhedronMesh.h" +#include "collision/shapes/ConvexPolyhedronShape.h" +#include "collision/shapes/SphereShape.h" #include "configuration.h" #include "engine/Profiler.h" #include @@ -45,7 +47,7 @@ bool SATAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, Contact case CollisionShapeType::CONVEX_POLYHEDRON: return testCollisionConvexMeshVsConvexMesh(narrowPhaseInfo, contactManifoldInfo); case CollisionShapeType::SPHERE: - return testCollisionSphereVsConvexMesh(narrowPhaseInfo, contactManifoldInfo); + return testCollisionSphereVsConvexPolyhedron(narrowPhaseInfo, contactManifoldInfo); case CollisionShapeType::CAPSULE: return testCollisionCapsuleVsConvexMesh(narrowPhaseInfo, contactManifoldInfo); case CollisionShapeType::TRIANGLE: @@ -57,23 +59,81 @@ bool SATAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, Contact } // Test collision between a sphere and a convex mesh -bool SATAlgorithm::testCollisionSphereVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { +bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { + assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE); + assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); + + // Get the capsule collision shapes + const SphereShape* sphere = static_cast(narrowPhaseInfo->collisionShape1); + const ConvexPolyhedronShape* polyhedron = static_cast(narrowPhaseInfo->collisionShape2); + + + // Get the transform from sphere local-space to polyhedron local-space + const Transform sphereToPolyhedronSpaceTransform = narrowPhaseInfo->shape2ToWorldTransform.getInverse() * + narrowPhaseInfo->shape1ToWorldTransform; + + // Transform the center of the sphere into the local-space of the convex polyhedron + const Vector3 sphereCenter = sphereToPolyhedronSpaceTransform.getPosition(); + + // Minimum penetration depth + decimal minPenetrationDepth = DECIMAL_LARGEST; + uint minFaceIndex = 0; + + // For each face of the convex mesh + for (uint f = 0; f < polyhedron->getNbFaces(); f++) { + + // Get the face + HalfEdgeStructure::Face face = polyhedron->getFace(f); + + // Get the face normal + const Vector3 faceNormal = polyhedron->getFaceNormal(f); + + Vector3 sphereCenterToFacePoint = polyhedron->getVertexPosition(face.faceVertices[0]) - sphereCenter; + decimal penetrationDepth = sphereCenterToFacePoint.dot(faceNormal) + sphere->getRadius(); + + // If the penetration depth is negative, we have found a separating axis + if (penetrationDepth <= decimal(0.0)) { + return false; + } + + // Check if we have found a new minimum penetration axis + if (penetrationDepth < minPenetrationDepth) { + minPenetrationDepth = penetrationDepth; + minFaceIndex = f; + } + } + + const Vector3 minFaceNormal = polyhedron->getFaceNormal(minFaceIndex); + const Vector3 normalWorld = -(narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * minFaceNormal); + const Vector3 contactPointSphereLocal = narrowPhaseInfo->shape1ToWorldTransform.getInverse() * normalWorld * sphere->getRadius(); + const Vector3 contactPointPolyhedronLocal = sphereCenter + minFaceNormal * (minPenetrationDepth - sphere->getRadius()); + + // Create the contact info object + contactManifoldInfo.addContactPoint(normalWorld, minPenetrationDepth, contactPointSphereLocal, contactPointPolyhedronLocal); + + return true; } // Test collision between a capsule and a convex mesh bool SATAlgorithm::testCollisionCapsuleVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { + assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE); + assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); } // Test collision between a triangle and a convex mesh bool SATAlgorithm::testCollisionTriangleVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { + assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::TRIANGLE); + assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); } // Test collision between two convex meshes bool SATAlgorithm::testCollisionConvexMeshVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { + assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON); + assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); } diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.h b/src/collision/narrowphase/SAT/SATAlgorithm.h index dc5bc5f2..f3ae2ab2 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.h +++ b/src/collision/narrowphase/SAT/SATAlgorithm.h @@ -47,7 +47,7 @@ class SATAlgorithm { const Vector3& c, const Vector3& d) const; /// Test collision between a sphere and a convex mesh - bool testCollisionSphereVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; + bool testCollisionSphereVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; /// Test collision between a capsule and a convex mesh bool testCollisionCapsuleVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; diff --git a/src/collision/narrowphase/SphereVsConvexMeshAlgorithm.cpp b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp similarity index 95% rename from src/collision/narrowphase/SphereVsConvexMeshAlgorithm.cpp rename to src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp index 06dbc615..107348db 100644 --- a/src/collision/narrowphase/SphereVsConvexMeshAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp @@ -24,7 +24,7 @@ ********************************************************************************/ // Libraries -#include "SphereVsConvexMeshAlgorithm.h" +#include "SphereVsConvexPolyhedronAlgorithm.h" #include "SAT/SATAlgorithm.h" #include "collision/shapes/SphereShape.h" #include "collision/shapes/ConvexMeshShape.h" @@ -32,7 +32,7 @@ // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; -bool SphereVsConvexMeshAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, +bool SphereVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) { // Get the local-space to world-space transforms diff --git a/src/collision/narrowphase/SphereVsConvexMeshAlgorithm.h b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h similarity index 84% rename from src/collision/narrowphase/SphereVsConvexMeshAlgorithm.h rename to src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h index f0046545..0bdac19a 100644 --- a/src/collision/narrowphase/SphereVsConvexMeshAlgorithm.h +++ b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h @@ -35,12 +35,12 @@ /// Namespace ReactPhysics3D namespace reactphysics3d { -// Class SphereVsConvexMeshAlgorithm +// Class SphereVsConvexPolyhedronAlgorithm /** * This class is used to compute the narrow-phase collision detection - * between a sphere and a convex mesh. + * between a sphere and a convex polyhedron. */ -class SphereVsConvexMeshAlgorithm : public NarrowPhaseAlgorithm { +class SphereVsConvexPolyhedronAlgorithm : public NarrowPhaseAlgorithm { protected : @@ -49,16 +49,16 @@ class SphereVsConvexMeshAlgorithm : public NarrowPhaseAlgorithm { // -------------------- Methods -------------------- // /// Constructor - SphereVsConvexMeshAlgorithm() = default; + SphereVsConvexPolyhedronAlgorithm() = default; /// Destructor - virtual ~SphereVsConvexMeshAlgorithm() override = default; + virtual ~SphereVsConvexPolyhedronAlgorithm() override = default; /// Deleted copy-constructor - SphereVsConvexMeshAlgorithm(const SphereVsConvexMeshAlgorithm& algorithm) = delete; + SphereVsConvexPolyhedronAlgorithm(const SphereVsConvexPolyhedronAlgorithm& algorithm) = delete; /// Deleted assignment operator - SphereVsConvexMeshAlgorithm& operator=(const SphereVsConvexMeshAlgorithm& algorithm) = delete; + SphereVsConvexPolyhedronAlgorithm& operator=(const SphereVsConvexPolyhedronAlgorithm& algorithm) = delete; /// Compute a contact info if the two bounding volume collide virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, diff --git a/src/collision/shapes/BoxShape.cpp b/src/collision/shapes/BoxShape.cpp index f00210c2..e1c97844 100644 --- a/src/collision/shapes/BoxShape.cpp +++ b/src/collision/shapes/BoxShape.cpp @@ -38,7 +38,7 @@ using namespace reactphysics3d; * @param margin The collision margin (in meters) around the collision shape */ BoxShape::BoxShape(const Vector3& extent, decimal margin) - : ConvexPolyhedron(margin), mExtent(extent - Vector3(margin, margin, margin)) { + : ConvexPolyhedronShape(margin), mExtent(extent - Vector3(margin, margin, margin)) { assert(extent.x > decimal(0.0) && extent.x > margin); assert(extent.y > decimal(0.0) && extent.y > margin); assert(extent.z > decimal(0.0) && extent.z > margin); @@ -57,15 +57,15 @@ BoxShape::BoxShape(const Vector3& extent, decimal margin) std::vector face0; face0.push_back(0); face0.push_back(1); face0.push_back(2); face0.push_back(3); std::vector face1; - face0.push_back(1); face0.push_back(5); face0.push_back(6); face0.push_back(2); + face1.push_back(1); face0.push_back(5); face0.push_back(6); face0.push_back(2); std::vector face2; - face0.push_back(4); face0.push_back(7); face0.push_back(6); face0.push_back(5); + face2.push_back(4); face0.push_back(7); face0.push_back(6); face0.push_back(5); std::vector face3; - face0.push_back(4); face0.push_back(0); face0.push_back(3); face0.push_back(7); + face3.push_back(4); face0.push_back(0); face0.push_back(3); face0.push_back(7); std::vector face4; - face0.push_back(4); face0.push_back(5); face0.push_back(1); face0.push_back(0); + face4.push_back(4); face0.push_back(5); face0.push_back(1); face0.push_back(0); std::vector face5; - face0.push_back(2); face0.push_back(6); face0.push_back(7); face0.push_back(3); + face5.push_back(2); face0.push_back(6); face0.push_back(7); face0.push_back(3); mHalfEdgeStructure.addFace(face0); mHalfEdgeStructure.addFace(face1); diff --git a/src/collision/shapes/BoxShape.h b/src/collision/shapes/BoxShape.h index d78bda25..be79e3dd 100644 --- a/src/collision/shapes/BoxShape.h +++ b/src/collision/shapes/BoxShape.h @@ -28,7 +28,7 @@ // Libraries #include -#include "ConvexPolyhedron.h" +#include "ConvexPolyhedronShape.h" #include "body/CollisionBody.h" #include "mathematics/mathematics.h" @@ -50,7 +50,7 @@ namespace reactphysics3d { * constructor of the box shape. Otherwise, it is recommended to use the * default margin distance by not using the "margin" parameter in the constructor. */ -class BoxShape : public ConvexPolyhedron { +class BoxShape : public ConvexPolyhedronShape { protected : diff --git a/src/collision/shapes/CollisionShape.h b/src/collision/shapes/CollisionShape.h index 28e724fd..2b1fa576 100644 --- a/src/collision/shapes/CollisionShape.h +++ b/src/collision/shapes/CollisionShape.h @@ -41,7 +41,7 @@ namespace reactphysics3d { /// Type of the collision shape enum class CollisionShapeType {TRIANGLE, SPHERE, CAPSULE, CONVEX_POLYHEDRON, CONCAVE_MESH, HEIGHTFIELD}; -const int NB_COLLISION_SHAPE_TYPES = 9; +const int NB_COLLISION_SHAPE_TYPES = 6; // Declarations class ProxyShape; diff --git a/src/collision/shapes/ConvexMeshShape.cpp b/src/collision/shapes/ConvexMeshShape.cpp index 40382aeb..263bb736 100644 --- a/src/collision/shapes/ConvexMeshShape.cpp +++ b/src/collision/shapes/ConvexMeshShape.cpp @@ -42,7 +42,7 @@ using namespace reactphysics3d; * @param margin Collision margin (in meters) around the collision shape */ ConvexMeshShape::ConvexMeshShape(PolyhedronMesh* polyhedronMesh, decimal margin) - : ConvexPolyhedron(margin), mPolyhedronMesh(polyhedronMesh), mMinBounds(0, 0, 0), mMaxBounds(0, 0, 0) { + : ConvexPolyhedronShape(margin), mPolyhedronMesh(polyhedronMesh), mMinBounds(0, 0, 0), mMaxBounds(0, 0, 0) { // Recalculate the bounds of the mesh recalculateBounds(); diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index cc88d38d..ff11c232 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -27,7 +27,7 @@ #define REACTPHYSICS3D_CONVEX_MESH_SHAPE_H // Libraries -#include "ConvexPolyhedron.h" +#include "ConvexPolyhedronShape.h" #include "engine/CollisionWorld.h" #include "mathematics/mathematics.h" #include "collision/TriangleMesh.h" @@ -59,7 +59,7 @@ class CollisionWorld; * with the addEdge() method. Then, you must use the setIsEdgesInformationUsed(true) method * in order to use the edges information for collision detection. */ -class ConvexMeshShape : public ConvexPolyhedron { +class ConvexMeshShape : public ConvexPolyhedronShape { protected : diff --git a/src/collision/shapes/ConvexPolyhedron.cpp b/src/collision/shapes/ConvexPolyhedronShape.cpp similarity index 95% rename from src/collision/shapes/ConvexPolyhedron.cpp rename to src/collision/shapes/ConvexPolyhedronShape.cpp index 26964554..e73a7cd7 100644 --- a/src/collision/shapes/ConvexPolyhedron.cpp +++ b/src/collision/shapes/ConvexPolyhedronShape.cpp @@ -24,14 +24,14 @@ ********************************************************************************/ // Libraries -#include "ConvexPolyhedron.h" +#include "ConvexPolyhedronShape.h" // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; // Constructor -ConvexPolyhedron::ConvexPolyhedron(decimal margin) +ConvexPolyhedronShape::ConvexPolyhedronShape(decimal margin) : ConvexShape(CollisionShapeType::CONVEX_POLYHEDRON, margin) { } diff --git a/src/collision/shapes/ConvexPolyhedron.h b/src/collision/shapes/ConvexPolyhedronShape.h similarity index 90% rename from src/collision/shapes/ConvexPolyhedron.h rename to src/collision/shapes/ConvexPolyhedronShape.h index 2a544077..059e5a3b 100644 --- a/src/collision/shapes/ConvexPolyhedron.h +++ b/src/collision/shapes/ConvexPolyhedronShape.h @@ -33,12 +33,12 @@ /// ReactPhysics3D namespace namespace reactphysics3d { -// Class ConvexPolyhedron +// Class ConvexPolyhedronShape /** * This abstract class represents a convex polyhedron collision shape associated with a * body that is used during the narrow-phase collision detection. */ -class ConvexPolyhedron : public ConvexShape { +class ConvexPolyhedronShape : public ConvexShape { protected : @@ -51,16 +51,16 @@ class ConvexPolyhedron : public ConvexShape { // -------------------- Methods -------------------- // /// Constructor - ConvexPolyhedron(decimal margin); + ConvexPolyhedronShape(decimal margin); /// Destructor - virtual ~ConvexPolyhedron() override = default; + virtual ~ConvexPolyhedronShape() override = default; /// Deleted copy-constructor - ConvexPolyhedron(const ConvexPolyhedron& shape) = delete; + ConvexPolyhedronShape(const ConvexPolyhedronShape& shape) = delete; /// Deleted assignment operator - ConvexPolyhedron& operator=(const ConvexPolyhedron& shape) = delete; + ConvexPolyhedronShape& operator=(const ConvexPolyhedronShape& shape) = delete; /// Return the number of faces of the polyhedron virtual uint getNbFaces() const=0; @@ -91,7 +91,7 @@ class ConvexPolyhedron : public ConvexShape { }; // Return true if the collision shape is a polyhedron -inline bool ConvexPolyhedron::isPolyhedron() const { +inline bool ConvexPolyhedronShape::isPolyhedron() const { return true; } From f61fea8b8ab3d592c42a3074200307ebd7014d36 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 16 Apr 2017 22:09:59 +0200 Subject: [PATCH 065/248] Add clippling segment/polygons methods, fix issues and add convex vs capsule algorithm --- CMakeLists.txt | 2 + src/collision/CollisionDetection.cpp | 11 -- src/collision/CollisionDetection.h | 11 +- .../CapsuleVsConvexPolyhedronAlgorithm.cpp | 61 ++++++++ .../CapsuleVsConvexPolyhedronAlgorithm.h | 71 +++++++++ .../narrowphase/SAT/SATAlgorithm.cpp | 50 +++--- src/collision/narrowphase/SAT/SATAlgorithm.h | 27 ++-- .../narrowphase/SphereVsCapsuleAlgorithm.cpp | 33 ++-- .../SphereVsConvexPolyhedronAlgorithm.cpp | 7 +- .../SphereVsConvexPolyhedronAlgorithm.h | 4 +- src/engine/OverlappingPair.cpp | 2 - src/mathematics/mathematics_functions.cpp | 147 +++++++++++++++++- src/mathematics/mathematics_functions.h | 11 +- test/Test.h | 2 +- test/tests/collision/TestRaycast.h | 6 +- .../mathematics/TestMathematicsFunctions.h | 90 ++++++++++- 16 files changed, 452 insertions(+), 83 deletions(-) create mode 100644 src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp create mode 100644 src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 0a30f8c2..5cacac60 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -86,6 +86,8 @@ SET (REACTPHYSICS3D_SOURCES "src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp" "src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h" "src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp" + "src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h" + "src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp" "src/collision/shapes/AABB.h" "src/collision/shapes/AABB.cpp" "src/collision/shapes/ConvexShape.h" diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 4a0ef718..908c5bf5 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -288,17 +288,6 @@ void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, Pro if ((shape1->getCollideWithMaskBits() & shape2->getCollisionCategoryBits()) == 0 || (shape1->getCollisionCategoryBits() & shape2->getCollideWithMaskBits()) == 0) return; - // Make sure the shape with the smallest collision shape type comes first - const uint shape1TypeIndex = static_cast(shape1->getCollisionShape()->getType()); - const uint shape2TypeIndex = static_cast(shape2->getCollisionShape()->getType()); - if (shape1TypeIndex > shape2TypeIndex) { - - // Swap the two shapes - ProxyShape* temp = shape1; - shape1 = shape2; - shape2 = temp; - } - // Compute the overlapping pair ID overlappingpairid pairID = OverlappingPair::computeID(shape1, shape2); diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index 9444b319..29200ec7 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -266,8 +266,15 @@ inline void CollisionDetection::updateProxyCollisionShape(ProxyShape* shape, con inline NarrowPhaseAlgorithm* CollisionDetection::selectNarrowPhaseAlgorithm(const CollisionShapeType& shape1Type, const CollisionShapeType& shape2Type) const { - const unsigned int shape1Index = static_cast(shape1Type); - const unsigned int shape2Index = static_cast(shape2Type); + uint shape1Index = static_cast(shape1Type); + uint shape2Index = static_cast(shape2Type); + + // Swap the shape types if necessary + if (shape1Index > shape2Index) { + const uint tempIndex = shape1Index; + shape1Index = shape2Index; + shape2Index = tempIndex; + } assert(shape1Index <= shape2Index); diff --git a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp new file mode 100644 index 00000000..8deb17e5 --- /dev/null +++ b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp @@ -0,0 +1,61 @@ +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "CapsuleVsConvexPolyhedronAlgorithm.h" +#include "SAT/SATAlgorithm.h" +#include "GJK/GJKAlgorithm.h" + +// We want to use the ReactPhysics3D namespace +using namespace reactphysics3d; + +bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + ContactManifoldInfo& contactManifoldInfo) { + + // Get the local-space to world-space transforms + const Transform& transform1 = narrowPhaseInfo->shape1ToWorldTransform; + const Transform& transform2 = narrowPhaseInfo->shape2ToWorldTransform; + + // First, we run the GJK algorithm + GJKAlgorithm gjkAlgorithm; + GJKAlgorithm::GJKResult result = gjkAlgorithm.testCollision(narrowPhaseInfo, contactManifoldInfo); + + // If we have found a contact point inside the margins (shallow penetration) + if (result == GJKAlgorithm::GJKResult::COLLIDE_IN_MARGIN) { + + // Return true + return true; + } + + // If we have overlap even without the margins (deep penetration) + if (result == GJKAlgorithm::GJKResult::INTERPENETRATE) { + + // Run the SAT algorithm to find the separating axis and compute contact point + SATAlgorithm satAlgorithm; + return satAlgorithm.testCollisionCapsuleVsConvexPolyhedron(narrowPhaseInfo, contactManifoldInfo); + } + + return false; +} diff --git a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h new file mode 100644 index 00000000..e9905596 --- /dev/null +++ b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h @@ -0,0 +1,71 @@ +/******************************************************************************** +* 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_CAPSULE_VS_CONVEX_POLYHEDRON_ALGORITHM_H +#define REACTPHYSICS3D_CAPSULE_VS_CONVEX_POLYHEDRON_ALGORITHM_H + +// Libraries +#include "body/Body.h" +#include "constraint/ContactPoint.h" +#include "NarrowPhaseAlgorithm.h" + + +/// Namespace ReactPhysics3D +namespace reactphysics3d { + +// Class CapsuleVsConvexPolyhedronAlgorithm +/** + * This class is used to compute the narrow-phase collision detection + * between a capsule and a convex polyhedron. + */ +class CapsuleVsConvexPolyhedronAlgorithm : public NarrowPhaseAlgorithm { + + protected : + + public : + + // -------------------- Methods -------------------- // + + /// Constructor + CapsuleVsConvexPolyhedronAlgorithm() = default; + + /// Destructor + virtual ~CapsuleVsConvexPolyhedronAlgorithm() override = default; + + /// Deleted copy-constructor + CapsuleVsConvexPolyhedronAlgorithm(const CapsuleVsConvexPolyhedronAlgorithm& algorithm) = delete; + + /// Deleted assignment operator + CapsuleVsConvexPolyhedronAlgorithm& operator=(const CapsuleVsConvexPolyhedronAlgorithm& algorithm) = delete; + + /// Compute a contact info if the two bounding volume collide + virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + ContactManifoldInfo& contactManifoldInfo) override; +}; + +} + +#endif + diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index ee241c77..1b57e36f 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -39,39 +39,25 @@ // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; -bool SATAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) { - - assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); - - switch (narrowPhaseInfo->collisionShape1->getType()) { - case CollisionShapeType::CONVEX_POLYHEDRON: - return testCollisionConvexMeshVsConvexMesh(narrowPhaseInfo, contactManifoldInfo); - case CollisionShapeType::SPHERE: - return testCollisionSphereVsConvexPolyhedron(narrowPhaseInfo, contactManifoldInfo); - case CollisionShapeType::CAPSULE: - return testCollisionCapsuleVsConvexMesh(narrowPhaseInfo, contactManifoldInfo); - case CollisionShapeType::TRIANGLE: - return testCollisionTriangleVsConvexMesh(narrowPhaseInfo, contactManifoldInfo); - default: assert(false); - } - - return false; -} - // Test collision between a sphere and a convex mesh bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { - assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE); - assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); + bool isSphereShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE; + + assert(isSphereShape1 || narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON); + assert(!isSphereShape1 || narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON); + assert(!isSphereShape1 || narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::SPHERE); // Get the capsule collision shapes - const SphereShape* sphere = static_cast(narrowPhaseInfo->collisionShape1); - const ConvexPolyhedronShape* polyhedron = static_cast(narrowPhaseInfo->collisionShape2); + const SphereShape* sphere = static_cast(isSphereShape1 ? narrowPhaseInfo->collisionShape1 : narrowPhaseInfo->collisionShape2); + const ConvexPolyhedronShape* polyhedron = static_cast(isSphereShape1 ? narrowPhaseInfo->collisionShape2 : narrowPhaseInfo->collisionShape1); + const Transform& sphereToWorldTransform = isSphereShape1 ? narrowPhaseInfo->shape1ToWorldTransform : narrowPhaseInfo->shape2ToWorldTransform; + const Transform& polyhedronToWorldTransform = isSphereShape1 ? narrowPhaseInfo->shape2ToWorldTransform : narrowPhaseInfo->shape1ToWorldTransform; // Get the transform from sphere local-space to polyhedron local-space - const Transform sphereToPolyhedronSpaceTransform = narrowPhaseInfo->shape2ToWorldTransform.getInverse() * - narrowPhaseInfo->shape1ToWorldTransform; + const Transform worldToPolyhedronTransform = polyhedronToWorldTransform.getInverse(); + const Transform sphereToPolyhedronSpaceTransform = worldToPolyhedronTransform * sphereToWorldTransform; // Transform the center of the sphere into the local-space of the convex polyhedron const Vector3 sphereCenter = sphereToPolyhedronSpaceTransform.getPosition(); @@ -105,18 +91,24 @@ bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(const NarrowPhaseInfo* } const Vector3 minFaceNormal = polyhedron->getFaceNormal(minFaceIndex); - const Vector3 normalWorld = -(narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * minFaceNormal); - const Vector3 contactPointSphereLocal = narrowPhaseInfo->shape1ToWorldTransform.getInverse() * normalWorld * sphere->getRadius(); + Vector3 normalWorld = -(polyhedronToWorldTransform.getOrientation() * minFaceNormal); + const Vector3 contactPointSphereLocal = sphereToWorldTransform.getInverse() * normalWorld * sphere->getRadius(); const Vector3 contactPointPolyhedronLocal = sphereCenter + minFaceNormal * (minPenetrationDepth - sphere->getRadius()); + if (!isSphereShape1) { + normalWorld = -normalWorld; + } + // Create the contact info object - contactManifoldInfo.addContactPoint(normalWorld, minPenetrationDepth, contactPointSphereLocal, contactPointPolyhedronLocal); + contactManifoldInfo.addContactPoint(normalWorld, minPenetrationDepth, + isSphereShape1 ? contactPointSphereLocal : contactPointPolyhedronLocal, + isSphereShape1 ? contactPointPolyhedronLocal : contactPointSphereLocal); return true; } // Test collision between a capsule and a convex mesh -bool SATAlgorithm::testCollisionCapsuleVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { +bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE); assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.h b/src/collision/narrowphase/SAT/SATAlgorithm.h index f3ae2ab2..b779d711 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.h +++ b/src/collision/narrowphase/SAT/SATAlgorithm.h @@ -46,18 +46,6 @@ class SATAlgorithm { bool testGaussMapArcsIntersect(const Vector3& a, const Vector3& b, const Vector3& c, const Vector3& d) const; - /// Test collision between a sphere and a convex mesh - bool testCollisionSphereVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; - - /// Test collision between a capsule and a convex mesh - bool testCollisionCapsuleVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; - - /// Test collision between a triangle and a convex mesh - bool testCollisionTriangleVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; - - /// Test collision between two convex meshes - bool testCollisionConvexMeshVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; - public : // -------------------- Methods -------------------- // @@ -74,9 +62,18 @@ class SATAlgorithm { /// Deleted assignment operator SATAlgorithm& operator=(const SATAlgorithm& algorithm) = delete; - /// Compute a contact info if the two bounding volumes collide. - bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactManifoldInfo& contactManifoldInfo); + /// Test collision between a sphere and a convex mesh + bool testCollisionSphereVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; + + /// Test collision between a capsule and a convex mesh + bool testCollisionCapsuleVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; + + /// Test collision between a triangle and a convex mesh + bool testCollisionTriangleVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; + + /// Test collision between two convex meshes + bool testCollisionConvexMeshVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; + }; } diff --git a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp index aace17fd..a311b2bf 100644 --- a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp @@ -32,23 +32,30 @@ using namespace reactphysics3d; bool SphereVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) { - - assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE); - assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CAPSULE); + + bool isSphereShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE; + + assert(isSphereShape1 || narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE); + assert(!isSphereShape1 || narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE); + assert(!isSphereShape1 || narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::SPHERE); // Get the collision shapes - const SphereShape* sphereShape = static_cast(narrowPhaseInfo->collisionShape1); - const CapsuleShape* capsuleShape = static_cast(narrowPhaseInfo->collisionShape2); + const SphereShape* sphereShape = static_cast(isSphereShape1 ? narrowPhaseInfo->collisionShape1 : narrowPhaseInfo->collisionShape2); + const CapsuleShape* capsuleShape = static_cast(isSphereShape1 ? narrowPhaseInfo->collisionShape2 : narrowPhaseInfo->collisionShape1); // Get the transform from sphere local-space to capsule local-space - const Transform sphereToCapsuleSpaceTransform = narrowPhaseInfo->shape2ToWorldTransform.getInverse() * narrowPhaseInfo->shape1ToWorldTransform; + const Transform& sphereToWorldTransform = isSphereShape1 ? narrowPhaseInfo->shape1ToWorldTransform : narrowPhaseInfo->shape2ToWorldTransform; + const Transform& capsuleToWorldTransform = isSphereShape1 ? narrowPhaseInfo->shape2ToWorldTransform : narrowPhaseInfo->shape1ToWorldTransform; + const Transform worldToCapsuleTransform = capsuleToWorldTransform.getInverse(); + const Transform sphereToCapsuleSpaceTransform = worldToCapsuleTransform * sphereToWorldTransform; // Transform the center of the sphere into the local-space of the capsule shape const Vector3 sphereCenter = sphereToCapsuleSpaceTransform.getPosition(); // Compute the end-points of the inner segment of the capsule - const Vector3 capsuleSegA(0, -capsuleShape->getHeight() * decimal(0.5), 0); - const Vector3 capsuleSegB(0, capsuleShape->getHeight() * decimal(0.5), 0); + const decimal capsuleHalfHeight = capsuleShape->getHeight() * decimal(0.5); + const Vector3 capsuleSegA(0, -capsuleHalfHeight, 0); + const Vector3 capsuleSegB(0, capsuleHalfHeight, 0); // Compute the point on the inner capsule segment that is the closes to center of sphere const Vector3 closestPointOnSegment = computeClosestPointOnSegment(capsuleSegA, capsuleSegB, sphereCenter); @@ -69,12 +76,18 @@ bool SphereVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseI const Vector3 contactPointSphereLocal = sphereToCapsuleSpaceTransform.getInverse() * (sphereCenter + sphereCenterToSegment * sphereShape->getRadius()); const Vector3 contactPointCapsuleLocal = closestPointOnSegment - sphereCenterToSegment * capsuleShape->getRadius(); - const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * sphereCenterToSegment; + Vector3 normalWorld = capsuleToWorldTransform.getOrientation() * sphereCenterToSegment; decimal penetrationDepth = sumRadius - sphereSegmentDistance; + + if (!isSphereShape1) { + normalWorld = -normalWorld; + } // Create the contact info object - contactManifoldInfo.addContactPoint(normalWorld, penetrationDepth, contactPointSphereLocal, contactPointCapsuleLocal); + contactManifoldInfo.addContactPoint(normalWorld, penetrationDepth, + isSphereShape1 ? contactPointSphereLocal : contactPointCapsuleLocal, + isSphereShape1 ? contactPointCapsuleLocal : contactPointSphereLocal); return true; } diff --git a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp index 107348db..44959971 100644 --- a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp @@ -25,15 +25,14 @@ // Libraries #include "SphereVsConvexPolyhedronAlgorithm.h" +#include "GJK/GJKAlgorithm.h" #include "SAT/SATAlgorithm.h" -#include "collision/shapes/SphereShape.h" -#include "collision/shapes/ConvexMeshShape.h" // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; bool SphereVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactManifoldInfo& contactManifoldInfo) { + ContactManifoldInfo& contactManifoldInfo) { // Get the local-space to world-space transforms const Transform& transform1 = narrowPhaseInfo->shape1ToWorldTransform; @@ -55,7 +54,7 @@ bool SphereVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* nar // Run the SAT algorithm to find the separating axis and compute contact point SATAlgorithm satAlgorithm; - return satAlgorithm.testCollision(narrowPhaseInfo, contactManifoldInfo); + return satAlgorithm.testCollisionSphereVsConvexPolyhedron(narrowPhaseInfo, contactManifoldInfo); } return false; diff --git a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h index 0bdac19a..591ebd44 100644 --- a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h +++ b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h @@ -23,8 +23,8 @@ * * ********************************************************************************/ -#ifndef REACTPHYSICS3D_SPHERE_VS_CONVEX_MESH_ALGORITHM_H -#define REACTPHYSICS3D_SPHERE_VS_CONVEX_MESH_ALGORITHM_H +#ifndef REACTPHYSICS3D_SPHERE_VS_CONVEX_POLYHEDRON_ALGORITHM_H +#define REACTPHYSICS3D_SPHERE_VS_CONVEX_POLYHEDRON_ALGORITHM_H // Libraries #include "body/Body.h" diff --git a/src/engine/OverlappingPair.cpp b/src/engine/OverlappingPair.cpp index 6df4bf4e..1f5d894e 100644 --- a/src/engine/OverlappingPair.cpp +++ b/src/engine/OverlappingPair.cpp @@ -35,6 +35,4 @@ OverlappingPair::OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, : mContactManifoldSet(shape1, shape2, memoryAllocator, nbMaxContactManifolds), mCachedSeparatingAxis(0.0, 1.0, 0.0) { - assert(static_cast(shape1->getCollisionShape()->getType()) <= - static_cast(shape2->getCollisionShape()->getType())); } diff --git a/src/mathematics/mathematics_functions.cpp b/src/mathematics/mathematics_functions.cpp index 7de898ae..07e3530f 100644 --- a/src/mathematics/mathematics_functions.cpp +++ b/src/mathematics/mathematics_functions.cpp @@ -27,6 +27,7 @@ #include "mathematics_functions.h" #include "Vector3.h" #include +#include using namespace reactphysics3d; @@ -187,7 +188,7 @@ decimal reactphysics3d::computePlaneSegmentIntersection(const Vector3& segA, con return t; } -/// Compute the distance between a point "point" and a line given by the points "linePointA" and "linePointB" +// Compute the distance between a point "point" and a line given by the points "linePointA" and "linePointB" decimal reactphysics3d::computeDistancePointToLineDistance(const Vector3& linePointA, const Vector3& linePointB, const Vector3& point) { decimal distAB = (linePointB - linePointA).length(); @@ -199,4 +200,148 @@ decimal reactphysics3d::computeDistancePointToLineDistance(const Vector3& linePo return ((point - linePointA).cross(point - linePointB)).length() / distAB; } +// Clip a segment against multiple planes and return the clipped segment vertices +// This method implements the Sutherland–Hodgman clipping algorithm +std::vector reactphysics3d::clipSegmentWithPlanes(const Vector3& segA, const Vector3& segB, + const std::vector& planesPoints, + const std::vector& planesNormals) { + + assert(planesPoints.size() == planesNormals.size()); + + std::vector inputVertices = {segA, segB}; + std::vector outputVertices; + + // For each clipping plane + for (uint p=0; p= decimal(0.0)) { + + // If the first vertex is not in front of the clippling plane + if (v1DotN < decimal(0.0)) { + + // The second point we keep is the intersection between the segment v1, v2 and the clipping plane + decimal t = computePlaneSegmentIntersection(v1, v2, planesNormals[p].dot(planesPoints[p]), planesNormals[p]); + + if (t >= decimal(0) && t <= decimal(1.0)) { + outputVertices.push_back(v1 + t * (v2 - v1)); + } + else { + outputVertices.push_back(v2); + } + } + else { + outputVertices.push_back(v1); + } + + // Add the second vertex + outputVertices.push_back(v2); + } + else { // If the second vertex is behind the clipping plane + + // If the first vertex is in front of the clippling plane + if (v1DotN >= decimal(0.0)) { + + outputVertices.push_back(v1); + + // The first point we keep is the intersection between the segment v1, v2 and the clipping plane + decimal t = computePlaneSegmentIntersection(v1, v2, -planesNormals[p].dot(planesPoints[p]), -planesNormals[p]); + + if (t >= decimal(0.0) && t <= decimal(1.0)) { + outputVertices.push_back(v1 + t * (v2 - v1)); + } + } + } + + inputVertices = outputVertices; + } + + return outputVertices; +} + +/// Clip a polygon against multiple planes and return the clipped polygon vertices +/// This method implements the Sutherland–Hodgman clipping algorithm +std::vector reactphysics3d::clipPolygonWithPlanes(const std::vector& polygonVertices, const std::vector& planesPoints, + const std::vector& planesNormals) { + + assert(planesPoints.size() == planesNormals.size()); + + std::vector inputVertices(polygonVertices); + std::vector outputVertices; + + // For each clipping plane + for (uint p=0; p= decimal(0.0)) { + + // If the first vertex is not in front of the clippling plane + if (v1DotN < decimal(0.0)) { + + // The second point we keep is the intersection between the segment v1, v2 and the clipping plane + decimal t = computePlaneSegmentIntersection(v1, v2, planesNormals[p].dot(planesPoints[p]), planesNormals[p]); + + if (t >= decimal(0) && t <= decimal(1.0)) { + outputVertices.push_back(v1 + t * (v2 - v1)); + } + else { + outputVertices.push_back(v2); + } + } + + // Add the second vertex + outputVertices.push_back(v2); + } + else { // If the second vertex is behind the clipping plane + + // If the first vertex is in front of the clippling plane + if (v1DotN >= decimal(0.0)) { + + // The first point we keep is the intersection between the segment v1, v2 and the clipping plane + decimal t = computePlaneSegmentIntersection(v1, v2, -planesNormals[p].dot(planesPoints[p]), -planesNormals[p]); + + if (t >= decimal(0.0) && t <= decimal(1.0)) { + outputVertices.push_back(v1 + t * (v2 - v1)); + } + else { + outputVertices.push_back(v1); + } + } + } + + vStart = vEnd; + } + + inputVertices = outputVertices; + } + + return outputVertices; +} + diff --git a/src/mathematics/mathematics_functions.h b/src/mathematics/mathematics_functions.h index 315de65c..639e8d3b 100644 --- a/src/mathematics/mathematics_functions.h +++ b/src/mathematics/mathematics_functions.h @@ -32,6 +32,7 @@ #include #include #include +#include /// ReactPhysics3D namespace namespace reactphysics3d { @@ -96,8 +97,16 @@ decimal computePlaneSegmentIntersection(const Vector3& segA, const Vector3& segB /// Compute the distance between a point and a line decimal computeDistancePointToLineDistance(const Vector3& linePointA, const Vector3& linePointB, const Vector3& point); +/// Clip a segment against multiple planes and return the clipped segment vertices +std::vector clipSegmentWithPlanes(const Vector3& segA, const Vector3& segB, + const std::vector& planesPoints, + const std::vector& planesNormals); + +/// Clip a polygon against multiple planes and return the clipped polygon vertices +std::vector clipPolygonWithPlanes(const std::vector& polygonVertices, const std::vector& planesPoints, + const std::vector& planesNormals); + } - #endif diff --git a/test/Test.h b/test/Test.h index 37fa9dee..1288813d 100644 --- a/test/Test.h +++ b/test/Test.h @@ -35,7 +35,7 @@ namespace reactphysics3d { // Macros -#define test(condition) applyTest(condition, #condition, __FILE__, __LINE__) +#define test(condition) applyTest(condition, #condition, __FILE__, __LINE__); #define fail(text) applyFail(text, __FILE__, __LINE__); // Class Test diff --git a/test/tests/collision/TestRaycast.h b/test/tests/collision/TestRaycast.h index fe8926d5..0f25ab94 100644 --- a/test/tests/collision/TestRaycast.h +++ b/test/tests/collision/TestRaycast.h @@ -300,8 +300,8 @@ class TestRaycast : public Test { mBoxProxyShape->setCollisionCategoryBits(CATEGORY1); mSphereProxyShape->setCollisionCategoryBits(CATEGORY1); mCapsuleProxyShape->setCollisionCategoryBits(CATEGORY1); - mConvexMeshProxyShape->setCollisionCategoryBits(CATEGORY2); - mConvexMeshProxyShapeEdgesInfo->setCollisionCategoryBits(CATEGORY2); + //mConvexMeshProxyShape->setCollisionCategoryBits(CATEGORY2); + //mConvexMeshProxyShapeEdgesInfo->setCollisionCategoryBits(CATEGORY2); mCompoundSphereProxyShape->setCollisionCategoryBits(CATEGORY2); mCompoundCapsuleProxyShape->setCollisionCategoryBits(CATEGORY2); mTriangleProxyShape->setCollisionCategoryBits(CATEGORY1); @@ -1787,7 +1787,7 @@ class TestRaycast : public Test { // ----- Test raycast miss ----- // test(!mConcaveMeshBody->raycast(ray1, raycastInfo3)); - test(!mConvexMeshProxyShape->raycast(ray1, raycastInfo3)); + //test(!mConvexMeshProxyShape->raycast(ray1, raycastInfo3)); mCallback.reset(); mWorld->raycast(ray1, &mCallback); test(!mCallback.isHit); diff --git a/test/tests/mathematics/TestMathematicsFunctions.h b/test/tests/mathematics/TestMathematicsFunctions.h index 42e1065c..04a81a69 100644 --- a/test/tests/mathematics/TestMathematicsFunctions.h +++ b/test/tests/mathematics/TestMathematicsFunctions.h @@ -27,8 +27,6 @@ #define TEST_MATHEMATICS_FUNCTIONS_H // Libraries -#include "Test.h" -#include "mathematics/mathematics_functions.h" /// Reactphysics3D namespace namespace reactphysics3d { @@ -170,6 +168,94 @@ class TestMathematicsFunctions : public Test { test(approxEqual(computeDistancePointToLineDistance(Vector3(6, -5, 0), Vector3(10, -5, 0), Vector3(-43, 254, 0)), 259.0, 0.000001)); test(approxEqual(computeDistancePointToLineDistance(Vector3(6, -5, 8), Vector3(10, -5, -5), Vector3(6, -5, 8)), 0.0, 0.000001)); test(approxEqual(computeDistancePointToLineDistance(Vector3(6, -5, 8), Vector3(10, -5, -5), Vector3(10, -5, -5)), 0.0, 0.000001)); + + + // Test clipSegmentWithPlanes() + std::vector segmentVertices; + segmentVertices.push_back(Vector3(-6, 3, 0)); + segmentVertices.push_back(Vector3(8, 3, 0)); + + std::vector planesNormals; + std::vector planesPoints; + planesNormals.push_back(Vector3(-1, 0, 0)); + planesPoints.push_back(Vector3(4, 0, 0)); + + std::vector clipSegmentVertices = clipSegmentWithPlanes(segmentVertices[0], segmentVertices[1], + planesPoints, planesNormals); + test(clipSegmentVertices.size() == 2); + test(approxEqual(clipSegmentVertices[0].x, -6, 0.000001)); + test(approxEqual(clipSegmentVertices[0].y, 3, 0.000001)); + test(approxEqual(clipSegmentVertices[0].z, 0, 0.000001)); + test(approxEqual(clipSegmentVertices[1].x, 4, 0.000001)); + test(approxEqual(clipSegmentVertices[1].y, 3, 0.000001)); + test(approxEqual(clipSegmentVertices[1].z, 0, 0.000001)); + + segmentVertices.clear(); + segmentVertices.push_back(Vector3(8, 3, 0)); + segmentVertices.push_back(Vector3(-6, 3, 0)); + + clipSegmentVertices = clipSegmentWithPlanes(segmentVertices[0], segmentVertices[1], planesPoints, planesNormals); + test(clipSegmentVertices.size() == 2); + test(approxEqual(clipSegmentVertices[0].x, 4, 0.000001)); + test(approxEqual(clipSegmentVertices[0].y, 3, 0.000001)); + test(approxEqual(clipSegmentVertices[0].z, 0, 0.000001)); + test(approxEqual(clipSegmentVertices[1].x, -6, 0.000001)); + test(approxEqual(clipSegmentVertices[1].y, 3, 0.000001)); + test(approxEqual(clipSegmentVertices[1].z, 0, 0.000001)); + + segmentVertices.clear(); + segmentVertices.push_back(Vector3(-6, 3, 0)); + segmentVertices.push_back(Vector3(3, 3, 0)); + + clipSegmentVertices = clipSegmentWithPlanes(segmentVertices[0], segmentVertices[1], planesPoints, planesNormals); + test(clipSegmentVertices.size() == 2); + test(approxEqual(clipSegmentVertices[0].x, -6, 0.000001)); + test(approxEqual(clipSegmentVertices[0].y, 3, 0.000001)); + test(approxEqual(clipSegmentVertices[0].z, 0, 0.000001)); + test(approxEqual(clipSegmentVertices[1].x, 3, 0.000001)); + test(approxEqual(clipSegmentVertices[1].y, 3, 0.000001)); + test(approxEqual(clipSegmentVertices[1].z, 0, 0.000001)); + + segmentVertices.clear(); + segmentVertices.push_back(Vector3(5, 3, 0)); + segmentVertices.push_back(Vector3(8, 3, 0)); + + clipSegmentVertices = clipSegmentWithPlanes(segmentVertices[0], segmentVertices[1], planesPoints, planesNormals); + test(clipSegmentVertices.size() == 0); + + // Test clipPolygonWithPlanes() + std::vector polygonVertices; + polygonVertices.push_back(Vector3(-4, 2, 0)); + polygonVertices.push_back(Vector3(7, 2, 0)); + polygonVertices.push_back(Vector3(7, 4, 0)); + polygonVertices.push_back(Vector3(-4, 4, 0)); + + planesNormals.clear(); + planesPoints.clear(); + planesNormals.push_back(Vector3(1, 0, 0)); + planesPoints.push_back(Vector3(0, 0, 0)); + planesNormals.push_back(Vector3(0, 1, 0)); + planesPoints.push_back(Vector3(0, 0, 0)); + planesNormals.push_back(Vector3(-1, 0, 0)); + planesPoints.push_back(Vector3(10, 0, 0)); + planesNormals.push_back(Vector3(0, -1, 0)); + planesPoints.push_back(Vector3(10, 5, 0)); + + clipSegmentVertices = clipPolygonWithPlanes(polygonVertices, planesPoints, planesNormals); + test(clipSegmentVertices.size() == 4); + test(approxEqual(clipSegmentVertices[0].x, 0, 0.000001)); + test(approxEqual(clipSegmentVertices[0].y, 2, 0.000001)); + test(approxEqual(clipSegmentVertices[0].z, 0, 0.000001)); + test(approxEqual(clipSegmentVertices[1].x, 7, 0.000001)); + test(approxEqual(clipSegmentVertices[1].y, 2, 0.000001)); + test(approxEqual(clipSegmentVertices[1].z, 0, 0.000001)); + test(approxEqual(clipSegmentVertices[2].x, 7, 0.000001)); + test(approxEqual(clipSegmentVertices[2].y, 4, 0.000001)); + test(approxEqual(clipSegmentVertices[2].z, 0, 0.000001)); + test(approxEqual(clipSegmentVertices[3].x, 0, 0.000001)); + test(approxEqual(clipSegmentVertices[3].y, 4, 0.000001)); + test(approxEqual(clipSegmentVertices[3].z, 0, 0.000001)); + } }; From 7fb6f49149b04f5303735394ab568af726c03cbf Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Fri, 28 Apr 2017 21:40:16 +0200 Subject: [PATCH 066/248] Working on capsule vs polyhedron narrow-phase algorithm --- src/collision/ContactManifoldInfo.h | 27 ++- src/collision/PolyhedronMesh.cpp | 15 ++ src/collision/PolyhedronMesh.h | 14 ++ src/collision/ProxyShape.h | 1 - .../narrowphase/CapsuleVsCapsuleAlgorithm.cpp | 7 +- .../narrowphase/CapsuleVsCapsuleAlgorithm.h | 2 +- .../CapsuleVsConvexPolyhedronAlgorithm.cpp | 71 +++++- .../CapsuleVsConvexPolyhedronAlgorithm.h | 2 +- .../narrowphase/SAT/SATAlgorithm.cpp | 218 +++++++++++++++++- src/collision/narrowphase/SAT/SATAlgorithm.h | 12 + .../narrowphase/SphereVsCapsuleAlgorithm.cpp | 3 + .../narrowphase/SphereVsCapsuleAlgorithm.h | 2 +- .../SphereVsConvexPolyhedronAlgorithm.cpp | 7 +- .../SphereVsConvexPolyhedronAlgorithm.h | 2 +- src/collision/shapes/BoxShape.h | 8 + src/collision/shapes/ConvexMeshShape.h | 8 + src/collision/shapes/ConvexPolyhedronShape.h | 3 + src/collision/shapes/ConvexShape.h | 2 +- src/mathematics/mathematics_functions.cpp | 5 + src/mathematics/mathematics_functions.h | 3 + 20 files changed, 382 insertions(+), 30 deletions(-) diff --git a/src/collision/ContactManifoldInfo.h b/src/collision/ContactManifoldInfo.h index d4afc590..f631b9fc 100644 --- a/src/collision/ContactManifoldInfo.h +++ b/src/collision/ContactManifoldInfo.h @@ -64,15 +64,8 @@ class ContactManifoldInfo { /// Destructor ~ContactManifoldInfo() { - // Delete all the contact points in the linked list - ContactPointInfo* element = mContactPointsList; - while(element != nullptr) { - ContactPointInfo* elementToDelete = element; - element = element->next; - - // Delete the current element - mAllocator.release(elementToDelete, sizeof(ContactPointInfo)); - } + // Remove all the contact points + reset(); } /// Deleted copy-constructor @@ -96,6 +89,22 @@ class ContactManifoldInfo { mContactPointsList = contactPointInfo; } + /// Remove all the contact points + void reset() { + + // Delete all the contact points in the linked list + ContactPointInfo* element = mContactPointsList; + while(element != nullptr) { + ContactPointInfo* elementToDelete = element; + element = element->next; + + // Delete the current element + mAllocator.release(elementToDelete, sizeof(ContactPointInfo)); + } + + mContactPointsList = nullptr; + } + /// Get the first contact point info of the linked list of contact points ContactPointInfo* getFirstContactPointInfo() const { return mContactPointsList; diff --git a/src/collision/PolyhedronMesh.cpp b/src/collision/PolyhedronMesh.cpp index 60a3be9f..61b1e3c8 100644 --- a/src/collision/PolyhedronMesh.cpp +++ b/src/collision/PolyhedronMesh.cpp @@ -42,6 +42,9 @@ PolyhedronMesh::PolyhedronMesh(PolygonVertexArray* polygonVertexArray) { // Compute the faces normals computeFacesNormals(); + + // Compute the centroid + computeCentroid(); } // Destructor @@ -126,3 +129,15 @@ void PolyhedronMesh::computeFacesNormals() { mFacesNormals[f].normalize(); } } + +// Compute the centroid of the polyhedron +void PolyhedronMesh::computeCentroid() { + + mCentroid.setToZero(); + + for (uint v=0; v < getNbVertices(); v++) { + mCentroid += getVertex(v); + } + + mCentroid /= getNbVertices(); +} diff --git a/src/collision/PolyhedronMesh.h b/src/collision/PolyhedronMesh.h index 940b2db0..a64db670 100644 --- a/src/collision/PolyhedronMesh.h +++ b/src/collision/PolyhedronMesh.h @@ -55,6 +55,9 @@ class PolyhedronMesh { /// Array with the face normals Vector3* mFacesNormals; + /// Centroid of the polyhedron + Vector3 mCentroid; + // -------------------- Methods -------------------- // /// Create the half-edge structure of the mesh @@ -63,6 +66,9 @@ class PolyhedronMesh { /// Compute the faces normals void computeFacesNormals(); + /// Compute the centroid of the polyhedron + void computeCentroid() ; + public: // -------------------- Methods -------------------- // @@ -84,6 +90,9 @@ class PolyhedronMesh { /// Return the half-edge structure of the mesh const HalfEdgeStructure& getHalfEdgeStructure() const; + + /// Return the centroid of the polyhedron + Vector3 getCentroid() const; }; // Return the number of vertices @@ -102,6 +111,11 @@ inline const HalfEdgeStructure& PolyhedronMesh::getHalfEdgeStructure() const { return mHalfEdgeStructure; } +// Return the centroid of the polyhedron +inline Vector3 PolyhedronMesh::getCentroid() const { + return mCentroid; +} + } #endif diff --git a/src/collision/ProxyShape.h b/src/collision/ProxyShape.h index 45c0add2..d9575b3d 100644 --- a/src/collision/ProxyShape.h +++ b/src/collision/ProxyShape.h @@ -175,7 +175,6 @@ class ProxyShape { friend class CollisionDetection; friend class CollisionWorld; friend class DynamicsWorld; - friend class EPAAlgorithm; friend class GJKAlgorithm; friend class ConvexMeshShape; diff --git a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp index 11160b8c..a6c7a020 100644 --- a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp @@ -30,13 +30,14 @@ // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; +// Compute the narrow-phase collision detection between two capsules +// This technique is based on the "Robust Contact Creation for Physics Simulations" presentation +// by Dirk Gregorius. bool CapsuleVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) { assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE); assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CAPSULE); - const decimal parallelEpsilon = decimal(0.001); - // Get the capsule collision shapes const CapsuleShape* capsuleShape1 = static_cast(narrowPhaseInfo->collisionShape1); const CapsuleShape* capsuleShape2 = static_cast(narrowPhaseInfo->collisionShape2); @@ -62,7 +63,7 @@ bool CapsuleVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhase decimal sumRadius = capsuleShape2->getRadius() + capsuleShape1->getRadius(); // If the two capsules are parallel (we create two contact points) - if (seg1.cross(seg2).lengthSquare() < parallelEpsilon * parallelEpsilon) { + if (areParallelVectors(seg1, seg2)) { // If the distance between the two segments is larger than the sum of the capsules radius (we do not have overlapping) const decimal segmentsDistance = computeDistancePointToLineDistance(capsule1SegA, capsule1SegB, capsule2SegA); diff --git a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h index 898d6337..9d8393c9 100644 --- a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h +++ b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h @@ -60,7 +60,7 @@ class CapsuleVsCapsuleAlgorithm : public NarrowPhaseAlgorithm { /// Deleted assignment operator CapsuleVsCapsuleAlgorithm& operator=(const CapsuleVsCapsuleAlgorithm& algorithm) = delete; - /// Compute a contact info if the two bounding volume collide + /// Compute the narrow-phase collision detection between two capsules virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) override; }; diff --git a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp index 8deb17e5..5e8dd5f9 100644 --- a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp @@ -27,24 +27,86 @@ #include "CapsuleVsConvexPolyhedronAlgorithm.h" #include "SAT/SATAlgorithm.h" #include "GJK/GJKAlgorithm.h" +#include "collision/shapes/CapsuleShape.h" +#include "collision/shapes/ConvexPolyhedronShape.h" // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; +// Compute the narrow-phase collision detection between a capsule and a polyhedron +// This technique is based on the "Robust Contact Creation for Physics Simulations" presentation +// by Dirk Gregorius. bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) { - // Get the local-space to world-space transforms - const Transform& transform1 = narrowPhaseInfo->shape1ToWorldTransform; - const Transform& transform2 = narrowPhaseInfo->shape2ToWorldTransform; - // First, we run the GJK algorithm GJKAlgorithm gjkAlgorithm; + SATAlgorithm satAlgorithm; GJKAlgorithm::GJKResult result = gjkAlgorithm.testCollision(narrowPhaseInfo, contactManifoldInfo); // If we have found a contact point inside the margins (shallow penetration) if (result == GJKAlgorithm::GJKResult::COLLIDE_IN_MARGIN) { + // GJK has found a shallow contact. If the contact normal is parallel to a face of the + // polyhedron mesh, we would like to create two contact points instead of a single one + // (as in the deep contact case with SAT algorithm) + + // Get the contact point created by GJK + ContactPointInfo* contactPoint = contactManifoldInfo.getFirstContactPointInfo(); + + bool isCapsuleShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE; + assert(isCapsuleShape1 || narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON); + assert(!isCapsuleShape1 || narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON); + assert(!isCapsuleShape1 || narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CAPSULE); + + // Get the collision shapes + const CapsuleShape* capsuleShape = static_cast(isCapsuleShape1 ? narrowPhaseInfo->collisionShape1 : narrowPhaseInfo->collisionShape2); + const ConvexPolyhedronShape* polyhedron = static_cast(isCapsuleShape1 ? narrowPhaseInfo->collisionShape2 : narrowPhaseInfo->collisionShape1); + + // For each face of the polyhedron + // For each face of the convex mesh + for (uint f = 0; f < polyhedron->getNbFaces(); f++) { + + // Get the face + HalfEdgeStructure::Face face = polyhedron->getFace(f); + + const Transform polyhedronToWorld = isCapsuleShape1 ? narrowPhaseInfo->shape2ToWorldTransform : narrowPhaseInfo->shape1ToWorldTransform; + + // Get the face normal + const Vector3 faceNormal = polyhedron->getFaceNormal(f); + const Vector3 faceNormalWorld = polyhedronToWorld.getOrientation() * faceNormal; + + // If the polyhedron face normal is parallel to the computed GJK contact normal + if (areParallelVectors(faceNormalWorld, contactPoint->normal)) { + + // Remove the previous contact point computed by GJK + contactManifoldInfo.reset(); + + const Transform capsuleToWorld = isCapsuleShape1 ? narrowPhaseInfo->shape1ToWorldTransform : narrowPhaseInfo->shape2ToWorldTransform; + const Transform polyhedronToCapsuleTransform = capsuleToWorld.getInverse() * polyhedronToWorld; + + // Compute the end-points of the inner segment of the capsule + const Vector3 capsuleSegA(0, -capsuleShape->getHeight() * decimal(0.5), 0); + const Vector3 capsuleSegB(0, capsuleShape->getHeight() * decimal(0.5), 0); + + // Convert the inner capsule segment points into the polyhedron local-space + const Transform capsuleToPolyhedronTransform = polyhedronToCapsuleTransform.getInverse(); + const Vector3 capsuleSegAPolyhedronSpace = capsuleToPolyhedronTransform * capsuleSegA; + const Vector3 capsuleSegBPolyhedronSpace = capsuleToPolyhedronTransform * capsuleSegB; + + const Vector3 separatingAxisCapsuleSpace = polyhedronToCapsuleTransform.getOrientation() * faceNormal; + + // Compute and create two contact points + satAlgorithm.computeCapsulePolyhedronFaceContactPoints(f, capsuleShape->getRadius(), polyhedron, contactPoint->penetrationDepth, + polyhedronToCapsuleTransform, faceNormalWorld, separatingAxisCapsuleSpace, + capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, + contactManifoldInfo, isCapsuleShape1); + + break; + } + + } + // Return true return true; } @@ -53,7 +115,6 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* na if (result == GJKAlgorithm::GJKResult::INTERPENETRATE) { // Run the SAT algorithm to find the separating axis and compute contact point - SATAlgorithm satAlgorithm; return satAlgorithm.testCollisionCapsuleVsConvexPolyhedron(narrowPhaseInfo, contactManifoldInfo); } diff --git a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h index e9905596..6b3f504f 100644 --- a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h +++ b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h @@ -60,7 +60,7 @@ class CapsuleVsConvexPolyhedronAlgorithm : public NarrowPhaseAlgorithm { /// Deleted assignment operator CapsuleVsConvexPolyhedronAlgorithm& operator=(const CapsuleVsConvexPolyhedronAlgorithm& algorithm) = delete; - /// Compute a contact info if the two bounding volume collide + /// Compute the narrow-phase collision detection between a capsule and a polyhedron virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) override; }; diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 1b57e36f..3637b3dc 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -27,7 +27,7 @@ #include "SATAlgorithm.h" #include "constraint/ContactPoint.h" #include "collision/PolyhedronMesh.h" -#include "collision/shapes/ConvexPolyhedronShape.h" +#include "collision/shapes/CapsuleShape.h" #include "collision/shapes/SphereShape.h" #include "configuration.h" #include "engine/Profiler.h" @@ -110,8 +110,220 @@ bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(const NarrowPhaseInfo* // Test collision between a capsule and a convex mesh bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { - assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE); - assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); + bool isCapsuleShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE; + + assert(isCapsuleShape1 || narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON); + assert(!isCapsuleShape1 || narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON); + assert(!isCapsuleShape1 || narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CAPSULE); + + // Get the collision shapes + const CapsuleShape* capsuleShape = static_cast(isCapsuleShape1 ? narrowPhaseInfo->collisionShape1 : narrowPhaseInfo->collisionShape2); + const ConvexPolyhedronShape* polyhedron = static_cast(isCapsuleShape1 ? narrowPhaseInfo->collisionShape2 : narrowPhaseInfo->collisionShape1); + + const Transform capsuleToWorld = isCapsuleShape1 ? narrowPhaseInfo->shape1ToWorldTransform : narrowPhaseInfo->shape2ToWorldTransform; + const Transform polyhedronToWorld = isCapsuleShape1 ? narrowPhaseInfo->shape2ToWorldTransform : narrowPhaseInfo->shape1ToWorldTransform; + + const Transform polyhedronToCapsuleTransform = capsuleToWorld.getInverse() * polyhedronToWorld; + + // Minimum penetration depth + decimal minPenetrationDepth = DECIMAL_LARGEST; + uint minFaceIndex = 0; + uint minEdgeIndex = 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++) { + + // Get the face + HalfEdgeStructure::Face face = polyhedron->getFace(f); + + // Get the face normal + const Vector3 faceNormal = polyhedron->getFaceNormal(f); + + // Compute the penetration depth (using the capsule support in the direction opposite to the face normal) + const Vector3 faceNormalCapsuleSpace = polyhedronToCapsuleTransform.getOrientation() * faceNormal; + const Vector3 capsuleSupportPoint = capsuleShape->getLocalSupportPointWithMargin(-faceNormalCapsuleSpace, nullptr); + const Vector3 pointOnPolyhedronFace = polyhedronToCapsuleTransform * polyhedron->getVertexPosition(face.faceVertices[0]); + const Vector3 capsuleSupportPointToFacePoint = pointOnPolyhedronFace - capsuleSupportPoint; + const decimal penetrationDepth = capsuleSupportPointToFacePoint.dot(faceNormal); + + // If the penetration depth is negative, we have found a separating axis + if (penetrationDepth <= decimal(0.0)) { + return false; + } + + // Check if we have found a new minimum penetration axis + if (penetrationDepth < minPenetrationDepth) { + minPenetrationDepth = penetrationDepth; + minFaceIndex = f; + isMinPenetrationFaceNormal = true; + separatingAxisCapsuleSpace = faceNormalCapsuleSpace; + } + } + + // Compute the end-points of the inner segment of the capsule + const Vector3 capsuleSegA(0, -capsuleShape->getHeight() * decimal(0.5), 0); + const Vector3 capsuleSegB(0, capsuleShape->getHeight() * decimal(0.5), 0); + const Vector3 capsuleSegmentAxis = capsuleSegB - capsuleSegA; + + // 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) { + + // Get an edge from the polyhedron (convert it into the capsule local-space) + HalfEdgeStructure::Edge edge = polyhedron->getHalfEdge(e); + const Vector3 edgeVertex1 = polyhedron->getVertexPosition(edge.vertexIndex); + const Vector3 edgeVertex2 = polyhedron->getVertexPosition(polyhedron->getHalfEdge(edge.nextEdgeIndex).vertexIndex); + const Vector3 edgeDirectionCapsuleSpace = polyhedronToCapsuleTransform.getOrientation() * (edgeVertex2 - edgeVertex1); + + HalfEdgeStructure::Edge twinEdge = polyhedron->getHalfEdge(edge.twinEdgeIndex); + const Vector3 adjacentFace1Normal = polyhedronToCapsuleTransform.getOrientation() * polyhedron->getFaceNormal(edge.faceIndex); + const Vector3 adjacentFace2Normal = polyhedronToCapsuleTransform.getOrientation() * polyhedron->getFaceNormal(twinEdge.faceIndex); + + // Check using the Gauss Map if this edge cross product can be as separating axis + if (isMinkowskiFaceCapsuleVsEdge(capsuleSegmentAxis, adjacentFace1Normal, adjacentFace2Normal)) { + + // Compute the axis to test (cross product between capsule inner segment and polyhedron edge) + Vector3 axis = capsuleSegmentAxis.cross(edgeDirectionCapsuleSpace); + + // Skip separating axis test if polyhedron edge is parallel to the capsule inner segment + if (axis.lengthSquare() >= decimal(0.00001)) { + + const Vector3 polyhedronCentroid = polyhedronToCapsuleTransform * polyhedron->getCentroid(); + const Vector3 pointOnPolyhedronEdge = polyhedronToCapsuleTransform * edgeVertex1; + + // Swap axis direction if necessary such that it points out of the polyhedron + if (axis.dot(pointOnPolyhedronEdge - polyhedronCentroid) < 0) { + axis = -axis; + } + + axis.normalize(); + + // Compute the penetration depth + const Vector3 capsuleSupportPoint = capsuleShape->getLocalSupportPointWithMargin(-axis, nullptr); + const Vector3 capsuleSupportPointToEdgePoint = pointOnPolyhedronEdge - capsuleSupportPoint; + const decimal penetrationDepth = capsuleSupportPointToEdgePoint.dot(axis); + + // If the penetration depth is negative, we have found a separating axis + if (penetrationDepth <= decimal(0.0)) { + return false; + } + + // Check if we have found a new minimum penetration axis + if (penetrationDepth < minPenetrationDepth) { + minPenetrationDepth = penetrationDepth; + minEdgeIndex = e; + isMinPenetrationFaceNormal = false; + separatingAxisCapsuleSpace = axis; + separatingPolyhedronEdgeVertex1 = edgeVertex1; + separatingPolyhedronEdgeVertex2 = edgeVertex2; + } + } + } + } + + // Convert the inner capsule segment points into the polyhedron local-space + const Transform capsuleToPolyhedronTransform = polyhedronToCapsuleTransform.getInverse(); + const Vector3 capsuleSegAPolyhedronSpace = capsuleToPolyhedronTransform * capsuleSegA; + const Vector3 capsuleSegBPolyhedronSpace = capsuleToPolyhedronTransform * capsuleSegB; + + const Vector3 normalWorld = capsuleToWorld.getOrientation() * separatingAxisCapsuleSpace; + const decimal capsuleRadius = capsuleShape->getRadius(); + + // If the separating axis is a face normal + // We need to clip the inner capsule segment with the adjacent faces of the separating face + if (isMinPenetrationFaceNormal) { + + computeCapsulePolyhedronFaceContactPoints(minFaceIndex, capsuleRadius, polyhedron, minPenetrationDepth, + polyhedronToCapsuleTransform, normalWorld, separatingAxisCapsuleSpace, + capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, + contactManifoldInfo, isCapsuleShape1); + } + else { // The separating axis is the cross product of a polyhedron edge and the inner capsule segment + + // Compute the closest points between the inner capsule segment and the + // edge of the polyhedron in polyhedron local-space + Vector3 closestPointPolyhedronEdge, closestPointCapsuleInnerSegment; + computeClosestPointBetweenTwoSegments(capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, + separatingPolyhedronEdgeVertex1, separatingPolyhedronEdgeVertex2, + closestPointCapsuleInnerSegment, closestPointPolyhedronEdge); + + + // Project closest capsule inner segment point into the capsule bounds + const Vector3 contactPointCapsule = (polyhedronToCapsuleTransform * closestPointCapsuleInnerSegment) - separatingAxisCapsuleSpace * capsuleRadius; + + // Create the contact point + contactManifoldInfo.addContactPoint(normalWorld, minPenetrationDepth, + isCapsuleShape1 ? contactPointCapsule : closestPointPolyhedronEdge, + isCapsuleShape1 ? closestPointPolyhedronEdge : contactPointCapsule); + } + + return true; +} + +// Compute the two contact points between a polyhedron and a capsule when the separating +// axis is a face normal of the polyhedron +void SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceIndex, decimal capsuleRadius, const ConvexPolyhedronShape* polyhedron, + decimal penetrationDepth, const Transform& polyhedronToCapsuleTransform, + const Vector3& normalWorld, const Vector3& separatingAxisCapsuleSpace, + const Vector3& capsuleSegAPolyhedronSpace, const Vector3& capsuleSegBPolyhedronSpace, + ContactManifoldInfo& contactManifoldInfo, bool isCapsuleShape1) const { + + HalfEdgeStructure::Face face = polyhedron->getFace(referenceFaceIndex); + uint firstEdgeIndex = face.edgeIndex; + uint edgeIndex = firstEdgeIndex; + + std::vector planesPoints; + std::vector planesNormals; + + // For each adjacent edge of the separating face of the polyhedron + do { + HalfEdgeStructure::Edge edge = polyhedron->getHalfEdge(edgeIndex); + HalfEdgeStructure::Edge twinEdge = polyhedron->getHalfEdge(edge.twinEdgeIndex); + + // Construct a clippling plane for each adjacent edge of the separting face of the polyhedron + planesPoints.push_back(polyhedron->getVertexPosition(edge.vertexIndex)); + planesNormals.push_back(polyhedron->getFaceNormal(twinEdge.faceIndex)); + + edgeIndex = edge.nextEdgeIndex; + + } while(edgeIndex != firstEdgeIndex); + + // First we clip the inner segment of the capsule with the four planes of the adjacent faces + std::vector clipSegment = clipSegmentWithPlanes(capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, + planesPoints, planesNormals); + + // Project the two clipped points into the polyhedron face + const Vector3 faceNormal = polyhedron->getFaceNormal(referenceFaceIndex); + const Vector3 contactPoint1Polyhedron = clipSegment[0] + faceNormal * (penetrationDepth - capsuleRadius); + const Vector3 contactPoint2Polyhedron = clipSegment[1] + faceNormal * (penetrationDepth - capsuleRadius); + + // Project the two clipped points into the capsule bounds + const Vector3 contactPoint1Capsule = (polyhedronToCapsuleTransform * clipSegment[0]) - separatingAxisCapsuleSpace * capsuleRadius; + const Vector3 contactPoint2Capsule = (polyhedronToCapsuleTransform * clipSegment[1]) - separatingAxisCapsuleSpace * capsuleRadius; + + // Create the contact points + contactManifoldInfo.addContactPoint(normalWorld, penetrationDepth, + isCapsuleShape1 ? contactPoint1Capsule : contactPoint1Polyhedron, + isCapsuleShape1 ? contactPoint1Polyhedron : contactPoint1Capsule); + contactManifoldInfo.addContactPoint(normalWorld, penetrationDepth, + isCapsuleShape1 ? contactPoint2Capsule : contactPoint2Polyhedron, + isCapsuleShape1 ? contactPoint2Polyhedron : contactPoint2Capsule); +} + +// This method returns true if an edge of a polyhedron and a capsule forms a +// face of the Minkowski Difference. This test is used to know if two edges +// (one edge of the polyhedron vs the inner segment of the capsule in this case) +// have to be test as a possible separating axis +bool SATAlgorithm::isMinkowskiFaceCapsuleVsEdge(const Vector3& capsuleSegment, const Vector3& edgeAdjacentFace1Normal, + const Vector3& edgeAdjacentFace2Normal) const { + + // Return true if the arc on the Gauss Map corresponding to the polyhedron edge + // intersect the unit circle plane corresponding to capsule Gauss Map + return capsuleSegment.dot(edgeAdjacentFace1Normal) * capsuleSegment.dot(edgeAdjacentFace2Normal) < decimal(0.0); } // Test collision between a triangle and a convex mesh diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.h b/src/collision/narrowphase/SAT/SATAlgorithm.h index b779d711..42e380f2 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.h +++ b/src/collision/narrowphase/SAT/SATAlgorithm.h @@ -29,6 +29,7 @@ // Libraries #include "collision/ContactManifoldInfo.h" #include "collision/NarrowPhaseInfo.h" +#include "collision/shapes/ConvexPolyhedronShape.h" /// ReactPhysics3D namespace namespace reactphysics3d { @@ -68,6 +69,17 @@ class SATAlgorithm { /// Test collision between a capsule and a convex mesh bool testCollisionCapsuleVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; + /// Compute the two contact points between a polyhedron and a capsule when the separating axis is a face normal of the polyhedron + void computeCapsulePolyhedronFaceContactPoints(uint referenceFaceIndex, decimal capsuleRadius, const ConvexPolyhedronShape* polyhedron, + decimal penetrationDepth, const Transform& polyhedronToCapsuleTransform, + const Vector3& normalWorld, const Vector3& separatingAxisCapsuleSpace, + const Vector3& capsuleSegAPolyhedronSpace, const Vector3& capsuleSegBPolyhedronSpace, + ContactManifoldInfo& contactManifoldInfo, 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 a triangle and a convex mesh bool testCollisionTriangleVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; diff --git a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp index a311b2bf..cd437d6e 100644 --- a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp @@ -31,6 +31,9 @@ // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; +// Compute the narrow-phase collision detection between a sphere and a capsule +// This technique is based on the "Robust Contact Creation for Physics Simulations" presentation +// by Dirk Gregorius. bool SphereVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) { bool isSphereShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE; diff --git a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h index 784df6f9..154f6e4c 100644 --- a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h +++ b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h @@ -60,7 +60,7 @@ class SphereVsCapsuleAlgorithm : public NarrowPhaseAlgorithm { /// Deleted assignment operator SphereVsCapsuleAlgorithm& operator=(const SphereVsCapsuleAlgorithm& algorithm) = delete; - /// Compute a contact info if the two bounding volume collide + /// Compute the narrow-phase collision detection between a sphere and a capsule virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) override; }; diff --git a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp index 44959971..708d9f8d 100644 --- a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp @@ -31,13 +31,12 @@ // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; +// Compute the narrow-phase collision detection a sphere and a convex polyhedron +// This technique is based on the "Robust Contact Creation for Physics Simulations" presentation +// by Dirk Gregorius. bool SphereVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) { - // Get the local-space to world-space transforms - const Transform& transform1 = narrowPhaseInfo->shape1ToWorldTransform; - const Transform& transform2 = narrowPhaseInfo->shape2ToWorldTransform; - // First, we run the GJK algorithm GJKAlgorithm gjkAlgorithm; GJKAlgorithm::GJKResult result = gjkAlgorithm.testCollision(narrowPhaseInfo, contactManifoldInfo); diff --git a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h index 591ebd44..c1fd3e55 100644 --- a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h +++ b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h @@ -60,7 +60,7 @@ class SphereVsConvexPolyhedronAlgorithm : public NarrowPhaseAlgorithm { /// Deleted assignment operator SphereVsConvexPolyhedronAlgorithm& operator=(const SphereVsConvexPolyhedronAlgorithm& algorithm) = delete; - /// Compute a contact info if the two bounding volume collide + /// Compute the narrow-phase collision detection a sphere and a convex polyhedron virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) override; }; diff --git a/src/collision/shapes/BoxShape.h b/src/collision/shapes/BoxShape.h index be79e3dd..d2b92dcc 100644 --- a/src/collision/shapes/BoxShape.h +++ b/src/collision/shapes/BoxShape.h @@ -128,6 +128,9 @@ class BoxShape : public ConvexPolyhedronShape { /// Return the normal vector of a given face of the polyhedron virtual Vector3 getFaceNormal(uint faceIndex) const override; + + /// Return the centroid of the polyhedron + virtual Vector3 getCentroid() const override; }; // Return the extents of the box @@ -236,6 +239,11 @@ inline Vector3 BoxShape::getFaceNormal(uint faceIndex) const { } } +// Return the centroid of the box +inline Vector3 BoxShape::getCentroid() const { + return Vector3::zero(); +} + // Return the number of half-edges of the polyhedron inline uint BoxShape::getNbHalfEdges() const { return 24; diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index ff11c232..28ba9c86 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -142,6 +142,9 @@ class ConvexMeshShape : public ConvexPolyhedronShape { /// Return the normal vector of a given face of the polyhedron virtual Vector3 getFaceNormal(uint faceIndex) const override; + + /// Return the centroid of the polyhedron + virtual Vector3 getCentroid() const override; }; /// Set the scaling vector of the collision shape @@ -239,6 +242,11 @@ inline Vector3 ConvexMeshShape::getFaceNormal(uint faceIndex) const { return mPolyhedronMesh->getFaceNormal(faceIndex); } +// Return the centroid of the polyhedron +inline Vector3 ConvexMeshShape::getCentroid() const { + return mPolyhedronMesh->getCentroid(); +} + } #endif diff --git a/src/collision/shapes/ConvexPolyhedronShape.h b/src/collision/shapes/ConvexPolyhedronShape.h index 059e5a3b..f6d2a34b 100644 --- a/src/collision/shapes/ConvexPolyhedronShape.h +++ b/src/collision/shapes/ConvexPolyhedronShape.h @@ -88,6 +88,9 @@ class ConvexPolyhedronShape : public ConvexShape { /// Return true if the collision shape is a polyhedron virtual bool isPolyhedron() const override; + + /// Return the centroid of the polyhedron + virtual Vector3 getCentroid() const=0; }; // Return true if the collision shape is a polyhedron diff --git a/src/collision/shapes/ConvexShape.h b/src/collision/shapes/ConvexShape.h index 9180fefe..4b98c9fa 100644 --- a/src/collision/shapes/ConvexShape.h +++ b/src/collision/shapes/ConvexShape.h @@ -81,7 +81,7 @@ class ConvexShape : public CollisionShape { // -------------------- Friendship -------------------- // friend class GJKAlgorithm; - friend class EPAAlgorithm; + friend class SATAlgorithm; }; // Return true if the collision shape is convex, false if it is concave diff --git a/src/mathematics/mathematics_functions.cpp b/src/mathematics/mathematics_functions.cpp index 07e3530f..36ba113a 100644 --- a/src/mathematics/mathematics_functions.cpp +++ b/src/mathematics/mathematics_functions.cpp @@ -60,6 +60,11 @@ Vector3 reactphysics3d::clamp(const Vector3& vector, decimal maxLength) { return vector; } +/// Return true if two vectors are parallel +bool reactphysics3d::areParallelVectors(const Vector3& vector1, const Vector3& vector2) { + return vector1.cross(vector2).lengthSquare() < decimal(0.00001); +} + /// Compute and return a point on segment from "segPointA" and "segPointB" that is closest to point "pointC" Vector3 reactphysics3d::computeClosestPointOnSegment(const Vector3& segPointA, const Vector3& segPointB, const Vector3& pointC) { diff --git a/src/mathematics/mathematics_functions.h b/src/mathematics/mathematics_functions.h index 639e8d3b..44ce9cf4 100644 --- a/src/mathematics/mathematics_functions.h +++ b/src/mathematics/mathematics_functions.h @@ -76,6 +76,9 @@ inline bool sameSign(decimal a, decimal b) { return a * b >= decimal(0.0); } +/// Return true if two vectors are parallel +bool areParallelVectors(const Vector3& vector1, const Vector3& vector2); + /// Clamp a vector such that it is no longer than a given maximum length Vector3 clamp(const Vector3& vector, decimal maxLength); From 0ec21e36b9e823aefed5c03949758af41bf240ea Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 16 May 2017 07:10:44 +0200 Subject: [PATCH 067/248] Working on SAT algorithm between two polyhedra --- .../narrowphase/CapsuleVsCapsuleAlgorithm.cpp | 2 +- .../narrowphase/SAT/SATAlgorithm.cpp | 336 +++++++++++++++++- src/collision/narrowphase/SAT/SATAlgorithm.h | 24 +- src/mathematics/mathematics_functions.cpp | 2 +- src/mathematics/mathematics_functions.h | 2 +- .../mathematics/TestMathematicsFunctions.h | 13 +- 6 files changed, 349 insertions(+), 30 deletions(-) diff --git a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp index a6c7a020..17008622 100644 --- a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp @@ -66,7 +66,7 @@ bool CapsuleVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhase if (areParallelVectors(seg1, seg2)) { // If the distance between the two segments is larger than the sum of the capsules radius (we do not have overlapping) - const decimal segmentsDistance = computeDistancePointToLineDistance(capsule1SegA, capsule1SegB, capsule2SegA); + const decimal segmentsDistance = computePointToLineDistance(capsule1SegA, capsule1SegB, capsule2SegA); if (segmentsDistance >= sumRadius) { // The capsule are parallel but their inner segment distance is larger than the sum of the capsules radius. diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 3637b3dc..fd09db27 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -169,8 +169,7 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(const NarrowPhaseInfo* const Vector3 capsuleSegB(0, capsuleShape->getHeight() * decimal(0.5), 0); const Vector3 capsuleSegmentAxis = capsuleSegB - capsuleSegA; - // For each direction that is the cross product of the capsule inner segment and - // an edge of the polyhedron + // 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) { // Get an edge from the polyhedron (convert it into the capsule local-space) @@ -326,18 +325,327 @@ bool SATAlgorithm::isMinkowskiFaceCapsuleVsEdge(const Vector3& capsuleSegment, c return capsuleSegment.dot(edgeAdjacentFace1Normal) * capsuleSegment.dot(edgeAdjacentFace2Normal) < decimal(0.0); } -// Test collision between a triangle and a convex mesh -bool SATAlgorithm::testCollisionTriangleVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { - - assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::TRIANGLE); - assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); -} - -// Test collision between two convex meshes -bool SATAlgorithm::testCollisionConvexMeshVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { +// Test collision between two convex polyhedrons +bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON); assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); + + const ConvexPolyhedronShape* polyhedron1 = static_cast(narrowPhaseInfo->collisionShape1); + const ConvexPolyhedronShape* polyhedron2 = static_cast(narrowPhaseInfo->collisionShape2); + + const Transform polyhedron1ToPolyhedron2 = narrowPhaseInfo->shape2ToWorldTransform.getInverse() * narrowPhaseInfo->shape1ToWorldTransform; + const Transform polyhedron2ToPolyhedron1 = polyhedron1ToPolyhedron2.getInverse(); + + decimal minPenetrationDepth = DECIMAL_LARGEST; + uint minFaceIndex = 0; + bool isMinPenetrationFaceNormal = false; + bool isMinPenetrationFaceNormalPolyhedron1 = false; + Vector3 separatingEdge1A, separatingEdge1B; + Vector3 separatingEdge2A, separatingEdge2B; + Vector3 minEdgeVsEdgeSeparatingAxisPolyhedron2Space; + + // Test all the face normals of the polyhedron 1 for separating axis + uint faceIndex; + decimal penetrationDepth = testFaceDirectionPolyhedronVsPolyhedron(polyhedron1, polyhedron2, polyhedron1ToPolyhedron2, faceIndex); + if (penetrationDepth <= decimal(0.0)) { + + // We have found a separating axis + return false; + } + if (penetrationDepth < minPenetrationDepth) { + isMinPenetrationFaceNormal = true; + minPenetrationDepth = penetrationDepth; + minFaceIndex = faceIndex; + isMinPenetrationFaceNormalPolyhedron1 = true; + } + + // Test all the face normals of the polyhedron 2 for separating axis + penetrationDepth = testFaceDirectionPolyhedronVsPolyhedron(polyhedron2, polyhedron1, polyhedron2ToPolyhedron1, faceIndex); + if (penetrationDepth <= decimal(0.0)) { + + // We have found a separating axis + return false; + } + if (penetrationDepth < minPenetrationDepth) { + isMinPenetrationFaceNormal = true; + minPenetrationDepth = penetrationDepth; + minFaceIndex = faceIndex; + isMinPenetrationFaceNormalPolyhedron1 = 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) { + + // Get an edge of polyhedron 1 + HalfEdgeStructure::Edge edge1 = polyhedron1->getHalfEdge(i); + + const Vector3 edge1A = polyhedron1ToPolyhedron2 * polyhedron1->getVertexPosition(edge1.vertexIndex); + 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) { + + // Get an edge of polyhedron 2 + HalfEdgeStructure::Edge edge2 = polyhedron2->getHalfEdge(j); + + const Vector3 edge2A = polyhedron2->getVertexPosition(edge2.vertexIndex); + const Vector3 edge2B = polyhedron2->getVertexPosition(polyhedron2->getHalfEdge(edge2.nextEdgeIndex).vertexIndex); + const Vector3 edge2Direction = edge2B - edge2A; + + // If the two edges build a minkowski face (and the cross product is + // therefore a candidate for separating axis + if (testEdgesBuildMinkowskiFace(polyhedron1, edge1, polyhedron2, edge2, polyhedron1ToPolyhedron2)) { + + Vector3 separatingAxisPolyhedron2Space; + + // Compute the penetration depth + decimal penetrationDepth = computeDistanceBetweenEdges(edge1A, edge2A, polyhedron2->getCentroid(), + edge1Direction, edge2Direction, separatingAxisPolyhedron2Space); + + if (penetrationDepth <= decimal(0.0)) { + + // We have found a separating axis + return false; + } + + if (penetrationDepth < minPenetrationDepth) { + minPenetrationDepth = penetrationDepth; + isMinPenetrationFaceNormalPolyhedron1 = false; + isMinPenetrationFaceNormal = false; + separatingEdge1A = edge1A; + separatingEdge1B = edge1B; + separatingEdge2A = edge2A; + separatingEdge2B = edge2B; + minEdgeVsEdgeSeparatingAxisPolyhedron2Space = separatingAxisPolyhedron2Space; + } + + } + } + } + + assert(minPenetrationDepth > decimal(0.0)); + assert((isMinPenetrationFaceNormal && minFaceIndex >= 0) || !isMinPenetrationFaceNormal); + + // If the separation axis is a face normal + if (isMinPenetrationFaceNormal) { + + const ConvexPolyhedronShape* referencePolyhedron = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron1 : polyhedron2; + const ConvexPolyhedronShape* incidentPolyhedron = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron2 : polyhedron1; + const Transform& referenceToIncidentTransform = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron1ToPolyhedron2 : polyhedron2ToPolyhedron1; + const Transform& incidentToReferenceTransform = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron2ToPolyhedron1 : polyhedron1ToPolyhedron2; + + const Vector3 axisReferenceSpace = referencePolyhedron->getFaceNormal(minFaceIndex); + const Vector3 axisIncidentSpace = referenceToIncidentTransform.getOrientation() * axisReferenceSpace; + + // Compute the world normal + const Vector3 normalWorld = isMinPenetrationFaceNormalPolyhedron1 ? narrowPhaseInfo->shape1ToWorldTransform.getOrientation() * axisReferenceSpace : + -(narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * axisReferenceSpace); + + // Get the reference face + HalfEdgeStructure::Face referenceFace = referencePolyhedron->getFace(minFaceIndex); + + // Find the incident face on the other polyhedron (most anti-parallel face) + uint incidentFaceIndex = findMostAntiParallelFaceOnPolyhedron(incidentPolyhedron, axisIncidentSpace); + + // Get the incident face + HalfEdgeStructure::Face incidentFace = incidentPolyhedron->getFace(incidentFaceIndex); + + std::vector polygonVertices; // Vertices to clip of the incident face + std::vector planesNormals; // Normals of the clipping planes + std::vector planesPoints; // Points on the clipping planes + + // Get all the vertices of the incident face (in the reference local-space) + std::vector::const_iterator it; + for (it = incidentFace.faceVertices.begin(); it != incidentFace.faceVertices.end(); ++it) { + const Vector3 faceVertexIncidentSpace = incidentPolyhedron->getVertexPosition(*it); + polygonVertices.push_back(incidentToReferenceTransform * faceVertexIncidentSpace); + } + + // Get the reference face clipping planes + uint currentEdgeIndex = referenceFace.edgeIndex; + uint firstEdgeIndex = currentEdgeIndex; + do { + + // Get the adjacent edge + HalfEdgeStructure::Edge edge = referencePolyhedron->getHalfEdge(currentEdgeIndex); + + // Get the twin edge + HalfEdgeStructure::Edge twinEdge = referencePolyhedron->getHalfEdge(edge.twinEdgeIndex); + + // Get the adjacent face normal (and negate it to have a clipping plane) + Vector3 faceNormal = -referencePolyhedron->getFaceNormal(twinEdge.faceIndex); + + // Get a vertex of the clipping plane (vertex of the adjacent edge) + Vector3 faceVertex = referencePolyhedron->getVertexPosition(edge.vertexIndex); + + planesNormals.push_back(faceNormal); + planesPoints.push_back(faceVertex); + + // Go to the next adjacent edge of the reference face + currentEdgeIndex = edge.nextEdgeIndex; + + } while (currentEdgeIndex != firstEdgeIndex); + + // Clip the reference faces with the adjacent planes of the reference face + std::vector clipPolygonVertices = clipPolygonWithPlanes(polygonVertices, planesPoints, planesNormals); + + // We only keep the clipped points that are below the reference face + const Vector3 referenceFaceVertex = referencePolyhedron->getVertexPosition(firstEdgeIndex); + std::vector::const_iterator itPoints; + for (itPoints = clipPolygonVertices.begin(); itPoints != clipPolygonVertices.end(); ++itPoints) { + + // If the clip point is bellow the reference face + if (((*itPoints) - referenceFaceVertex).dot(axisReferenceSpace) < decimal(0.0)) { + + // Convert the clip incident polyhedron vertex into the incident polyhedron local-space + const Vector3 contactPointIncidentPolyhedron = referenceToIncidentTransform * (*itPoints); + + // Project the contact point onto the reference face + Vector3 contactPointReferencePolyhedron = (*itPoints) + axisReferenceSpace * minPenetrationDepth; + + // Create a new contact point + contactManifoldInfo.addContactPoint(normalWorld, minPenetrationDepth, + isMinPenetrationFaceNormalPolyhedron1 ? contactPointReferencePolyhedron : contactPointIncidentPolyhedron, + isMinPenetrationFaceNormalPolyhedron1 ? contactPointIncidentPolyhedron : contactPointReferencePolyhedron); + } + } + } + else { // If we have an edge vs edge contact + + // Compute the closest points between the two edges (in the local-space of poylhedron 2) + Vector3 closestPointPolyhedron1Edge, closestPointPolyhedron2Edge; + computeClosestPointBetweenTwoSegments(separatingEdge1A, separatingEdge1B, separatingEdge2A, separatingEdge2B, + closestPointPolyhedron1Edge, closestPointPolyhedron2Edge); + + // Compute the contact point on polyhedron 1 edge in the local-space of polyhedron 1 + const Vector3 closestPointPolyhedron1EdgeLocalSpace = polyhedron2ToPolyhedron1 * closestPointPolyhedron1Edge; + + // Compute the world normal + const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * minEdgeVsEdgeSeparatingAxisPolyhedron2Space; + + // Create the contact point + contactManifoldInfo.addContactPoint(normalWorld, minPenetrationDepth, + closestPointPolyhedron1EdgeLocalSpace, closestPointPolyhedron2Edge); + } + + return true; +} + +// Find and return the index of the polyhedron face with the most anti-parallel face normal given a direction vector +// This is used to find the incident face on a polyhedron of a given reference face of another polyhedron +uint SATAlgorithm::findMostAntiParallelFaceOnPolyhedron(const ConvexPolyhedronShape* polyhedron, const Vector3& direction) const { + + decimal minDotProduct = DECIMAL_LARGEST; + uint mostAntiParallelFace = 0; + + // For each face of the polyhedron + for (uint i=0; i < polyhedron->getNbFaces(); i++) { + + // Get the face normal + decimal dotProduct = polyhedron->getFaceNormal(i).dot(direction); + if (dotProduct < minDotProduct) { + minDotProduct = dotProduct; + mostAntiParallelFace = i; + } + } + + return mostAntiParallelFace; +} + +// Compute and return the distance between the two edges in the direction of the candidate separating axis +decimal SATAlgorithm::computeDistanceBetweenEdges(const Vector3& edge1A, const Vector3& edge2A, const Vector3& polyhedron2Centroid, + const Vector3& edge1Direction, const Vector3& edge2Direction, + Vector3& outSeparatingAxisPolyhedron2Space) const { + + // If the two edges are parallel + if (areParallelVectors(edge1Direction, edge2Direction)) { + + // Return a large penetration depth to skip those edges + return DECIMAL_LARGEST; + } + + // Compute the candidate separating axis (cross product between two polyhedrons edges) + Vector3 axis = edge1Direction.cross(edge2Direction).getUnit(); + + // Make sure the axis direction is going from first to second polyhedron + if (axis.dot(edge2A - polyhedron2Centroid) > decimal(0.0)) { + axis = -axis; + } + + outSeparatingAxisPolyhedron2Space = axis; + + // Compute and return the distance between the edges + return -axis.dot(edge2A - edge1A); +} + +// Test all the normals of a polyhedron for separating axis in the polyhedron vs polyhedron case +decimal SATAlgorithm::testFaceDirectionPolyhedronVsPolyhedron(const ConvexPolyhedronShape* polyhedron1, + const ConvexPolyhedronShape* polyhedron2, + const Transform& polyhedron1ToPolyhedron2, + uint& minFaceIndex) const { + + decimal minPenetrationDepth = DECIMAL_LARGEST; + + // For each face of the first polyhedron + for (uint f = 0; f < polyhedron1->getNbFaces(); f++) { + + HalfEdgeStructure::Face face = polyhedron1->getFace(f); + + // Get the face normal + const Vector3 faceNormal = polyhedron1->getFaceNormal(f); + + // Convert the face normal into the local-space of polyhedron 2 + const Vector3 faceNormalPolyhedron2Space = polyhedron1ToPolyhedron2.getOrientation() * faceNormal; + + // Get the support point of polyhedron 2 in the inverse direction of face normal + const Vector3 supportPoint = polyhedron2->getLocalSupportPointWithoutMargin(-faceNormalPolyhedron2Space, nullptr); + + // Compute the penetration depth + const Vector3 faceVertex = polyhedron1ToPolyhedron2 * polyhedron1->getVertexPosition(face.faceVertices[0]); + decimal penetrationDepth = (faceVertex - supportPoint).dot(faceNormalPolyhedron2Space); + + // If the penetration depth is negative, we have found a separating axis + if (penetrationDepth <= decimal(0.0)) { + return penetrationDepth; + } + + // Check if we have found a new minimum penetration axis + if (penetrationDepth < minPenetrationDepth) { + minPenetrationDepth = penetrationDepth; + minFaceIndex = f; + } + } + + return minPenetrationDepth; +} + + +// Return true if two edges of two polyhedrons build a minkowski face (and can therefore be a separating axis) +bool SATAlgorithm::testEdgesBuildMinkowskiFace(const ConvexPolyhedronShape* polyhedron1, const HalfEdgeStructure::Edge& edge1, + const ConvexPolyhedronShape* polyhedron2, const HalfEdgeStructure::Edge& edge2, + const Transform& polyhedron1ToPolyhedron2) const { + + const Vector3 a = polyhedron1ToPolyhedron2 * polyhedron1->getFaceNormal(edge1.faceIndex); + const Vector3 b = polyhedron1ToPolyhedron2 * polyhedron1->getFaceNormal(polyhedron1->getHalfEdge(edge1.twinEdgeIndex).faceIndex); + + const Vector3 c = polyhedron2->getFaceNormal(edge2.faceIndex); + const Vector3 d = polyhedron2->getFaceNormal(polyhedron2->getHalfEdge(edge2.twinEdgeIndex).faceIndex); + + // Compute b.cross(a) using the edge direction + const Vector3 edge1Vertex1 = polyhedron1->getVertexPosition(edge1.vertexIndex); + const Vector3 edge1Vertex2 = polyhedron1->getVertexPosition(polyhedron1->getHalfEdge(edge1.twinEdgeIndex).vertexIndex); + const Vector3 bCrossA = polyhedron1ToPolyhedron2.getOrientation() * (edge1Vertex2 - edge1Vertex1); + + // Compute d.cross(c) using the edge direction + const Vector3 edge2Vertex1 = polyhedron2->getVertexPosition(edge2.vertexIndex); + const Vector3 edge2Vertex2 = polyhedron2->getVertexPosition(polyhedron2->getHalfEdge(edge2.twinEdgeIndex).vertexIndex); + const Vector3 dCrossC = edge2Vertex2 - edge2Vertex1; + + // Test if the two arcs of the Gauss Map intersect (therefore forming a minkowski face) + // Note that we negate the normals of the second polyhedron because we are looking at the + // Gauss map of the minkowski difference of the polyhedrons + return testGaussMapArcsIntersect(a, b, -c, -d, bCrossA, dCrossC); } @@ -346,10 +654,8 @@ bool SATAlgorithm::testCollisionConvexMeshVsConvexMesh(const NarrowPhaseInfo* na /// and edge between faces with normal C and D on second polygon create a face on the Minkowski /// sum of both polygons. If this is the case, it means that the cross product of both edges /// might be a separating axis. -bool SATAlgorithm::testGaussMapArcsIntersect(const Vector3& a, const Vector3& b, - const Vector3& c, const Vector3& d) const { - const Vector3 bCrossA = b.cross(a); - const Vector3 dCrossC = d.cross(c); +bool SATAlgorithm::testGaussMapArcsIntersect(const Vector3& a, const Vector3& b, const Vector3& c, const Vector3& d, + const Vector3& bCrossA, const Vector3& dCrossC) const { const decimal cba = c.dot(bCrossA); const decimal dba = d.dot(bCrossA); diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.h b/src/collision/narrowphase/SAT/SATAlgorithm.h index 42e380f2..ae5da16e 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.h +++ b/src/collision/narrowphase/SAT/SATAlgorithm.h @@ -43,9 +43,23 @@ class SATAlgorithm { // -------------------- Methods -------------------- // + /// Return true if two edges of two polyhedrons build a minkowski face (and can therefore be a separating axis) + bool testEdgesBuildMinkowskiFace(const ConvexPolyhedronShape* polyhedron1, const HalfEdgeStructure::Edge& edge1, + const ConvexPolyhedronShape* polyhedron2, const HalfEdgeStructure::Edge& edge2, + const Transform& polyhedron1ToPolyhedron2) const; + /// Return true if the arcs AB and CD on the Gauss Map intersect bool testGaussMapArcsIntersect(const Vector3& a, const Vector3& b, - const Vector3& c, const Vector3& d) const; + const Vector3& c, const Vector3& d, + const Vector3& bCrossA, const Vector3& dCrossC) const; + + // Find and return the index of the polyhedron face with the most anti-parallel face normal given a direction vector + uint findMostAntiParallelFaceOnPolyhedron(const ConvexPolyhedronShape* polyhedron, const Vector3& direction) const; + + /// Compute and return the distance between the two edges in the direction of the candidate separating axis + decimal computeDistanceBetweenEdges(const Vector3& edge1A, const Vector3& edge2A, const Vector3& polyhedron2Centroid, + const Vector3& edge1Direction, const Vector3& edge2Direction, + Vector3& outSeparatingAxis) const; public : @@ -80,12 +94,12 @@ class SATAlgorithm { bool isMinkowskiFaceCapsuleVsEdge(const Vector3& capsuleSegment, const Vector3& edgeAdjacentFace1Normal, const Vector3& edgeAdjacentFace2Normal) const; - /// Test collision between a triangle and a convex mesh - bool testCollisionTriangleVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; - /// Test collision between two convex meshes - bool testCollisionConvexMeshVsConvexMesh(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; + bool testCollisionConvexPolyhedronVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; + /// Test all the normals of a polyhedron for separating axis in the polyhedron vs polyhedron case + decimal testFaceDirectionPolyhedronVsPolyhedron(const ConvexPolyhedronShape* polyhedron1, const ConvexPolyhedronShape* polyhedron2, + const Transform& polyhedron1ToPolyhedron2, uint& minFaceIndex) const; }; } diff --git a/src/mathematics/mathematics_functions.cpp b/src/mathematics/mathematics_functions.cpp index 36ba113a..e01c749a 100644 --- a/src/mathematics/mathematics_functions.cpp +++ b/src/mathematics/mathematics_functions.cpp @@ -194,7 +194,7 @@ decimal reactphysics3d::computePlaneSegmentIntersection(const Vector3& segA, con } // Compute the distance between a point "point" and a line given by the points "linePointA" and "linePointB" -decimal reactphysics3d::computeDistancePointToLineDistance(const Vector3& linePointA, const Vector3& linePointB, const Vector3& point) { +decimal reactphysics3d::computePointToLineDistance(const Vector3& linePointA, const Vector3& linePointB, const Vector3& point) { decimal distAB = (linePointB - linePointA).length(); diff --git a/src/mathematics/mathematics_functions.h b/src/mathematics/mathematics_functions.h index 44ce9cf4..c695f342 100644 --- a/src/mathematics/mathematics_functions.h +++ b/src/mathematics/mathematics_functions.h @@ -98,7 +98,7 @@ void computeBarycentricCoordinatesInTriangle(const Vector3& a, const Vector3& b, decimal computePlaneSegmentIntersection(const Vector3& segA, const Vector3& segB, const decimal planeD, const Vector3& planeNormal); /// Compute the distance between a point and a line -decimal computeDistancePointToLineDistance(const Vector3& linePointA, const Vector3& linePointB, const Vector3& point); +decimal computePointToLineDistance(const Vector3& linePointA, const Vector3& linePointB, const Vector3& point); /// Clip a segment against multiple planes and return the clipped segment vertices std::vector clipSegmentWithPlanes(const Vector3& segA, const Vector3& segB, diff --git a/test/tests/mathematics/TestMathematicsFunctions.h b/test/tests/mathematics/TestMathematicsFunctions.h index 04a81a69..b45415ee 100644 --- a/test/tests/mathematics/TestMathematicsFunctions.h +++ b/test/tests/mathematics/TestMathematicsFunctions.h @@ -162,13 +162,12 @@ class TestMathematicsFunctions : public Test { decimal tIntersect = computePlaneSegmentIntersection(Vector3(5, 4, 0), Vector3(9, 4, 0), 4, Vector3(0, 1, 0)); test(tIntersect < 0.0 || tIntersect > 1.0); - // Test computeDistancePointToLineDistance() - test(approxEqual(computeDistancePointToLineDistance(Vector3(6, 0, 0), Vector3(14, 0, 0), Vector3(5, 3, 0)), 3.0, 0.000001)); - test(approxEqual(computeDistancePointToLineDistance(Vector3(6, -5, 0), Vector3(10, -5, 0), Vector3(4, 3, 0)), 8.0, 0.000001)); - test(approxEqual(computeDistancePointToLineDistance(Vector3(6, -5, 0), Vector3(10, -5, 0), Vector3(-43, 254, 0)), 259.0, 0.000001)); - test(approxEqual(computeDistancePointToLineDistance(Vector3(6, -5, 8), Vector3(10, -5, -5), Vector3(6, -5, 8)), 0.0, 0.000001)); - test(approxEqual(computeDistancePointToLineDistance(Vector3(6, -5, 8), Vector3(10, -5, -5), Vector3(10, -5, -5)), 0.0, 0.000001)); - + // Test computePointToLineDistance() + test(approxEqual(computePointToLineDistance(Vector3(6, 0, 0), Vector3(14, 0, 0), Vector3(5, 3, 0)), 3.0, 0.000001)); + test(approxEqual(computePointToLineDistance(Vector3(6, -5, 0), Vector3(10, -5, 0), Vector3(4, 3, 0)), 8.0, 0.000001)); + test(approxEqual(computePointToLineDistance(Vector3(6, -5, 0), Vector3(10, -5, 0), Vector3(-43, 254, 0)), 259.0, 0.000001)); + test(approxEqual(computePointToLineDistance(Vector3(6, -5, 8), Vector3(10, -5, -5), Vector3(6, -5, 8)), 0.0, 0.000001)); + test(approxEqual(computePointToLineDistance(Vector3(6, -5, 8), Vector3(10, -5, -5), Vector3(10, -5, -5)), 0.0, 0.000001)); // Test clipSegmentWithPlanes() std::vector segmentVertices; From 678c88d3bd5be850a3ec354e742b8002363120e6 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 16 May 2017 07:11:18 +0200 Subject: [PATCH 068/248] Add box in collision detection scene for the testbed application --- .../CollisionDetectionScene.cpp | 20 +++++++++++++++++++ .../CollisionDetectionScene.h | 1 + 2 files changed, 21 insertions(+) diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp index 8c0196b3..b96620b6 100644 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp @@ -60,6 +60,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mSphere1->setColor(mGreyColorDemo); mSphere1->setSleepingColor(mRedColorDemo); + /* // ---------- Sphere 2 ---------- // openglframework::Vector3 position2(4, 0, 0); @@ -92,6 +93,17 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) // Set the color mCapsule2->setColor(mGreyColorDemo); mCapsule2->setSleepingColor(mRedColorDemo); +*/ + // ---------- Box 1 ---------- // + openglframework::Vector3 position5(4, 5, 0); + + // Create a box and a corresponding collision body in the dynamics world + mBox1 = new Box(BOX_SIZE, position5, mCollisionWorld, mMeshFolderPath); + mAllShapes.push_back(mBox1); + + // Set the color + mBox1->setColor(mGreyColorDemo); + mBox1->setSleepingColor(mRedColorDemo); // ---------- Cone ---------- // //openglframework::Vector3 position4(0, 0, 0); @@ -171,6 +183,7 @@ CollisionDetectionScene::~CollisionDetectionScene() { mCollisionWorld->destroyCollisionBody(mSphere1->getCollisionBody()); delete mSphere1; + /* mCollisionWorld->destroyCollisionBody(mSphere2->getCollisionBody()); delete mSphere2; @@ -179,6 +192,10 @@ CollisionDetectionScene::~CollisionDetectionScene() { mCollisionWorld->destroyCollisionBody(mCapsule2->getCollisionBody()); delete mCapsule2; + */ + + mCollisionWorld->destroyCollisionBody(mBox1->getCollisionBody()); + delete mBox1; /* // Destroy the corresponding rigid body from the dynamics world @@ -300,9 +317,12 @@ void CollisionDetectionScene::renderSinglePass(openglframework::Shader& shader, // Render the shapes if (mSphere1->getCollisionBody()->isActive()) mSphere1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + /* if (mSphere2->getCollisionBody()->isActive()) mSphere2->render(shader, worldToCameraMatrix, mIsWireframeEnabled); if (mCapsule1->getCollisionBody()->isActive()) mCapsule1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); if (mCapsule2->getCollisionBody()->isActive()) mCapsule2->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + */ + if (mBox1->getCollisionBody()->isActive()) mBox1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); /* if (mBox->getCollisionBody()->isActive()) mBox->render(shader, worldToCameraMatrix); diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.h b/testbed/scenes/collisiondetection/CollisionDetectionScene.h index 2c33b3ac..01df3df8 100644 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.h +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.h @@ -146,6 +146,7 @@ class CollisionDetectionScene : public SceneDemo { Sphere* mSphere2; Capsule* mCapsule1; Capsule* mCapsule2; + Box* mBox1; //Cone* mCone; //Cylinder* mCylinder; //Capsule* mCapsule; From 2af87d48045d97b266d2cddaff5085f58e20dcc6 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 16 May 2017 07:42:04 +0200 Subject: [PATCH 069/248] Add bias to prefer some axis when penetration depths are the same in SAT algorithm --- src/collision/narrowphase/SAT/SATAlgorithm.cpp | 10 +++++++--- src/collision/narrowphase/SAT/SATAlgorithm.h | 5 +++++ 2 files changed, 12 insertions(+), 3 deletions(-) diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index fd09db27..c82256f3 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -39,6 +39,9 @@ // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; +// Static variables initialization +const decimal SATAlgorithm::SAME_SEPARATING_AXIS_BIAS = decimal(0.001); + // Test collision between a sphere and a convex mesh bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { @@ -353,7 +356,7 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(const NarrowP // We have found a separating axis return false; } - if (penetrationDepth < minPenetrationDepth) { + if (penetrationDepth < minPenetrationDepth - SAME_SEPARATING_AXIS_BIAS) { isMinPenetrationFaceNormal = true; minPenetrationDepth = penetrationDepth; minFaceIndex = faceIndex; @@ -367,7 +370,7 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(const NarrowP // We have found a separating axis return false; } - if (penetrationDepth < minPenetrationDepth) { + if (penetrationDepth < minPenetrationDepth - SAME_SEPARATING_AXIS_BIAS) { isMinPenetrationFaceNormal = true; minPenetrationDepth = penetrationDepth; minFaceIndex = faceIndex; @@ -409,7 +412,8 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(const NarrowP return false; } - if (penetrationDepth < minPenetrationDepth) { + if (penetrationDepth < minPenetrationDepth - SAME_SEPARATING_AXIS_BIAS) { + minPenetrationDepth = penetrationDepth; isMinPenetrationFaceNormalPolyhedron1 = false; isMinPenetrationFaceNormal = false; diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.h b/src/collision/narrowphase/SAT/SATAlgorithm.h index ae5da16e..a95abe31 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.h +++ b/src/collision/narrowphase/SAT/SATAlgorithm.h @@ -41,6 +41,11 @@ class SATAlgorithm { // -------------------- Attributes -------------------- // + /// Bias used to make sure the SAT algorithm returns the same penetration axis between frames + /// when there are multiple separating axis with the same penetration depth. The goal is to + /// make sure the contact manifold does not change too much between frames. + static const decimal SAME_SEPARATING_AXIS_BIAS; + // -------------------- Methods -------------------- // /// Return true if two edges of two polyhedrons build a minkowski face (and can therefore be a separating axis) From 9d55255c56aa171654395c4a77b81efdaa88c086 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 17 May 2017 23:40:17 +0200 Subject: [PATCH 070/248] Add contact point normals and constant color shader in testbed application --- testbed/common/VisualContactPoint.cpp | 96 ++++++++++++++-- testbed/common/VisualContactPoint.h | 24 +++- .../CollisionDetectionScene.cpp | 103 +----------------- .../CollisionDetectionScene.h | 44 ++------ testbed/scenes/raycast/RaycastScene.cpp | 40 ++----- testbed/scenes/raycast/RaycastScene.h | 13 ++- testbed/shaders/color.frag | 38 +++++++ testbed/shaders/color.vert | 43 ++++++++ testbed/src/Scene.h | 5 +- testbed/src/SceneDemo.cpp | 25 ++++- testbed/src/SceneDemo.h | 3 + 11 files changed, 240 insertions(+), 194 deletions(-) mode change 100644 => 100755 testbed/scenes/collisiondetection/CollisionDetectionScene.cpp mode change 100644 => 100755 testbed/scenes/collisiondetection/CollisionDetectionScene.h create mode 100644 testbed/shaders/color.frag create mode 100644 testbed/shaders/color.vert diff --git a/testbed/common/VisualContactPoint.cpp b/testbed/common/VisualContactPoint.cpp index 7661587e..03ed864b 100644 --- a/testbed/common/VisualContactPoint.cpp +++ b/testbed/common/VisualContactPoint.cpp @@ -36,17 +36,24 @@ openglframework::Mesh VisualContactPoint::mMesh; bool VisualContactPoint::mStaticDataCreated = false; // Constructor -VisualContactPoint::VisualContactPoint(const openglframework::Vector3& position, - const std::string& meshFolderPath) - : mColor(1.0f, 0.0f, 0.0f, 1.0f) { +VisualContactPoint::VisualContactPoint(const openglframework::Vector3& position, const std::string& meshFolderPath, + const openglframework::Vector3& normalLineEndPointLocal, const openglframework::Color& color) + : mColor(color), mVBOVerticesNormalLine(GL_ARRAY_BUFFER) { + + mContactNormalLinePoints[0] = openglframework::Vector3(0, 0, 0); + mContactNormalLinePoints[1] = (normalLineEndPointLocal - position) * 0.5f; // Initialize the position where the mesh will be rendered translateWorld(position); + + // Create the VBO and VAO to render the contact normal line + createContactNormalLineVBOAndVAO(); } // Destructor VisualContactPoint::~VisualContactPoint() { - + mVAONormalLine.destroy(); + mVBOVerticesNormalLine.destroy(); } // Load and initialize the mesh for all the contact points @@ -84,8 +91,7 @@ void VisualContactPoint::destroyStaticData() { } // Render the sphere at the correct position and with the correct orientation -void VisualContactPoint::render(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix) { +void VisualContactPoint::render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) { // Bind the VAO mVAO.bind(); @@ -93,6 +99,10 @@ void VisualContactPoint::render(openglframework::Shader& shader, // Bind the shader shader.bind(); + // Set the vertex color + openglframework::Vector4 color(mColor.r, mColor.g, mColor.b, mColor.a); + shader.setVector4Uniform("vertexColor", color, false); + mVBOVertices.bind(); // Set the model to camera matrix @@ -106,10 +116,6 @@ void VisualContactPoint::render(openglframework::Shader& shader, localToCameraMatrix.getUpperLeft3x3Matrix().getInverse().getTranspose(); shader.setMatrix3x3Uniform("normalMatrix", normalMatrix, false); - // Set the vertex color - openglframework::Vector4 color(mColor.r, mColor.g, mColor.b, mColor.a); - shader.setVector4Uniform("vertexColor", color, false); - // Get the location of shader attribute variables GLint vertexPositionLoc = shader.getAttribLocation("vertexPosition"); GLint vertexNormalLoc = shader.getAttribLocation("vertexNormal", false); @@ -138,9 +144,56 @@ void VisualContactPoint::render(openglframework::Shader& shader, // Unbind the shader shader.unbind(); + + // Render the contact normal line + renderContactNormalLine(shader, worldToCameraMatrix); } -// Create the Vertex Buffer Objects used to render with OpenGL. +void VisualContactPoint::renderContactNormalLine(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) { + + // Bind the VAO + mVAONormalLine.bind(); + + // Bind the shader + shader.bind(); + + mVBOVerticesNormalLine.bind(); + + // Set the model to camera matrix + const openglframework::Matrix4 localToCameraMatrix = worldToCameraMatrix * mTransformMatrix; + shader.setMatrix4x4Uniform("localToWorldMatrix", mTransformMatrix); + shader.setMatrix4x4Uniform("worldToCameraMatrix", worldToCameraMatrix); + + // Set the normal matrix (inverse transpose of the 3x3 upper-left sub matrix of the + // model-view matrix) + const openglframework::Matrix3 normalMatrix = + localToCameraMatrix.getUpperLeft3x3Matrix().getInverse().getTranspose(); + shader.setMatrix3x3Uniform("normalMatrix", normalMatrix, false); + + // Set the vertex color + openglframework::Vector4 color(0, 1, 0, 1); + shader.setVector4Uniform("vertexColor", color, false); + + // Get the location of shader attribute variables + GLint vertexPositionLoc = shader.getAttribLocation("vertexPosition"); + + glEnableVertexAttribArray(vertexPositionLoc); + glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)NULL); + + // Draw the lines + glDrawArrays(GL_LINES, 0, 2); + + glDisableVertexAttribArray(vertexPositionLoc); + + mVBOVerticesNormalLine.unbind(); + + // Unbind the VAO + mVAONormalLine.unbind(); + + shader.unbind(); +} + +// Create the Vertex Buffer Objects used to render the contact point sphere with OpenGL. /// We create two VBOs (one for vertices and one for indices) void VisualContactPoint::createVBOAndVAO() { @@ -181,3 +234,24 @@ void VisualContactPoint::createVBOAndVAO() { // Unbind the VAO mVAO.unbind(); } + +// Create the Vertex Buffer Objects used to render the contact normal line +void VisualContactPoint::createContactNormalLineVBOAndVAO() { + + // Create the VBO for the vertices data + mVBOVerticesNormalLine.create(); + mVBOVerticesNormalLine.bind(); + size_t sizeNormalLineVertices = 2 * sizeof(openglframework::Vector3); + mVBOVerticesNormalLine.copyDataIntoVBO(sizeNormalLineVertices, &mContactNormalLinePoints[0], GL_STATIC_DRAW); + mVBOVerticesNormalLine.unbind(); + + // Create the VAO for both VBOs + mVAONormalLine.create(); + mVAONormalLine.bind(); + + // Bind the VBO of vertices + mVBOVerticesNormalLine.bind(); + + // Unbind the VAO + mVAONormalLine.unbind(); +} diff --git a/testbed/common/VisualContactPoint.h b/testbed/common/VisualContactPoint.h index 944caf21..b540e751 100644 --- a/testbed/common/VisualContactPoint.h +++ b/testbed/common/VisualContactPoint.h @@ -28,6 +28,7 @@ // Libraries #include "openglframework.h" +#include "Line.h" const float VISUAL_CONTACT_POINT_RADIUS = 0.2f; @@ -56,15 +57,30 @@ class VisualContactPoint : public openglframework::Object3D { /// Vertex Array Object for the vertex data static openglframework::VertexArrayObject mVAO; + /// Vertex Buffer Object for the vertices data + openglframework::VertexBufferObject mVBOVerticesNormalLine; + + /// Vertex Array Object for the vertex data + openglframework::VertexArrayObject mVAONormalLine; + /// True if static data (VBO, VAO) has been created already static bool mStaticDataCreated; + // Two end-points of the contact normal line + openglframework::Vector3 mContactNormalLinePoints[2]; + /// Color openglframework::Color mColor; - // Create the Vertex Buffer Objects used to render with OpenGL. + // Create the Vertex Buffer Objects used to render the contact point sphere with OpenGL. static void createVBOAndVAO(); + // Create the Vertex Buffer Objects used to render the contact normal line with OpenGL. + void createContactNormalLineVBOAndVAO(); + + /// Render the contact normal line + void renderContactNormalLine(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix); + // -------------------- Methods -------------------- // public : @@ -72,8 +88,8 @@ class VisualContactPoint : public openglframework::Object3D { // -------------------- Methods -------------------- // /// Constructor - VisualContactPoint(const openglframework::Vector3& position, - const std::string &meshFolderPath); + VisualContactPoint(const openglframework::Vector3& position, const std::string &meshFolderPath, + const openglframework::Vector3& normalLineEndPointLocal, const openglframework::Color& color); /// Destructor ~VisualContactPoint(); @@ -84,7 +100,7 @@ class VisualContactPoint : public openglframework::Object3D { /// Destroy the mesh for the contact points static void destroyStaticData(); - /// Render the sphere at the correct position and with the correct orientation + /// Render the sphere contact point at the correct position and with the correct orientation void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix); }; diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp old mode 100644 new mode 100755 index b96620b6..21a0b51a --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp @@ -34,7 +34,7 @@ using namespace collisiondetectionscene; CollisionDetectionScene::CollisionDetectionScene(const std::string& name) : SceneDemo(name, SCENE_RADIUS, false), mMeshFolderPath("meshes/"), mContactManager(mPhongShader, mMeshFolderPath), - mAreNormalsDisplayed(false), mVBOVertices(GL_ARRAY_BUFFER) { + mAreNormalsDisplayed(false) { mSelectedShapeIndex = 0; mIsContactPointsDisplayed = true; @@ -60,7 +60,6 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mSphere1->setColor(mGreyColorDemo); mSphere1->setSleepingColor(mRedColorDemo); - /* // ---------- Sphere 2 ---------- // openglframework::Vector3 position2(4, 0, 0); @@ -93,17 +92,6 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) // Set the color mCapsule2->setColor(mGreyColorDemo); mCapsule2->setSleepingColor(mRedColorDemo); -*/ - // ---------- Box 1 ---------- // - openglframework::Vector3 position5(4, 5, 0); - - // Create a box and a corresponding collision body in the dynamics world - mBox1 = new Box(BOX_SIZE, position5, mCollisionWorld, mMeshFolderPath); - mAllShapes.push_back(mBox1); - - // Set the color - mBox1->setColor(mGreyColorDemo); - mBox1->setSleepingColor(mRedColorDemo); // ---------- Cone ---------- // //openglframework::Vector3 position4(0, 0, 0); @@ -158,9 +146,6 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) //mHeightField->setColor(mGreyColorDemo); //mHeightField->setSleepingColor(mRedColorDemo); - // Create the VBO and VAO to render the lines - //createVBOAndVAO(mPhongShader); - mAllShapes[mSelectedShapeIndex]->setColor(mBlueColorDemo); } @@ -172,9 +157,6 @@ void CollisionDetectionScene::reset() { // Destructor CollisionDetectionScene::~CollisionDetectionScene() { - // Destroy the shader - mPhongShader.destroy(); - // Destroy the box rigid body from the dynamics world //mCollisionWorld->destroyCollisionBody(mBox->getCollisionBody()); //delete mBox; @@ -183,7 +165,6 @@ CollisionDetectionScene::~CollisionDetectionScene() { mCollisionWorld->destroyCollisionBody(mSphere1->getCollisionBody()); delete mSphere1; - /* mCollisionWorld->destroyCollisionBody(mSphere2->getCollisionBody()); delete mSphere2; @@ -192,10 +173,6 @@ CollisionDetectionScene::~CollisionDetectionScene() { mCollisionWorld->destroyCollisionBody(mCapsule2->getCollisionBody()); delete mCapsule2; - */ - - mCollisionWorld->destroyCollisionBody(mBox1->getCollisionBody()); - delete mBox1; /* // Destroy the corresponding rigid body from the dynamics world @@ -246,10 +223,6 @@ CollisionDetectionScene::~CollisionDetectionScene() { // Destroy the collision world delete mCollisionWorld; - - // Destroy the VBOs and VAO - mVBOVertices.destroy(); - mVAO.destroy(); } // Update the physics world (take a simulation step) @@ -272,57 +245,11 @@ void CollisionDetectionScene::update() { void CollisionDetectionScene::renderSinglePass(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) { - /* - // Bind the VAO - mVAO.bind(); - - // Bind the shader - shader.bind(); - - mVBOVertices.bind(); - - // Set the model to camera matrix - const Matrix4 localToCameraMatrix = Matrix4::identity(); - shader.setMatrix4x4Uniform("localToWorldMatrix", localToCameraMatrix); - shader.setMatrix4x4Uniform("worldToCameraMatrix", worldToCameraMatrix); - - // Set the normal matrix (inverse transpose of the 3x3 upper-left sub matrix of the - // model-view matrix) - const openglframework::Matrix3 normalMatrix = - localToCameraMatrix.getUpperLeft3x3Matrix().getInverse().getTranspose(); - shader.setMatrix3x3Uniform("normalMatrix", normalMatrix, false); - - // Set the vertex color - openglframework::Vector4 color(1, 0, 0, 1); - shader.setVector4Uniform("vertexColor", color, false); - - // Get the location of shader attribute variables - GLint vertexPositionLoc = shader.getAttribLocation("vertexPosition"); - - glEnableVertexAttribArray(vertexPositionLoc); - glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)NULL); - - // Draw the lines - glDrawArrays(GL_LINES, 0, NB_RAYS); - - glDisableVertexAttribArray(vertexPositionLoc); - - mVBOVertices.unbind(); - - // Unbind the VAO - mVAO.unbind(); - - shader.unbind(); - */ - // Render the shapes if (mSphere1->getCollisionBody()->isActive()) mSphere1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - /* if (mSphere2->getCollisionBody()->isActive()) mSphere2->render(shader, worldToCameraMatrix, mIsWireframeEnabled); if (mCapsule1->getCollisionBody()->isActive()) mCapsule1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); if (mCapsule2->getCollisionBody()->isActive()) mCapsule2->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - */ - if (mBox1->getCollisionBody()->isActive()) mBox1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); /* if (mBox->getCollisionBody()->isActive()) mBox->render(shader, worldToCameraMatrix); @@ -338,34 +265,6 @@ void CollisionDetectionScene::renderSinglePass(openglframework::Shader& shader, shader.unbind(); } -// Create the Vertex Buffer Objects used to render with OpenGL. -/// We create two VBOs (one for vertices and one for indices) -void CollisionDetectionScene::createVBOAndVAO(openglframework::Shader& shader) { - - // Bind the shader - shader.bind(); - - // Create the VBO for the vertices data - mVBOVertices.create(); - mVBOVertices.bind(); - size_t sizeVertices = mLinePoints.size() * sizeof(openglframework::Vector3); - mVBOVertices.copyDataIntoVBO(sizeVertices, &mLinePoints[0], GL_STATIC_DRAW); - mVBOVertices.unbind(); - - // Create the VAO for both VBOs - mVAO.create(); - mVAO.bind(); - - // Bind the VBO of vertices - mVBOVertices.bind(); - - // Unbind the VAO - mVAO.unbind(); - - // Unbind the shader - shader.unbind(); -} - void CollisionDetectionScene::selectNextShape() { int previousIndex = mSelectedShapeIndex; diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.h b/testbed/scenes/collisiondetection/CollisionDetectionScene.h old mode 100644 new mode 100755 index 01df3df8..6eeeb25b --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.h +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.h @@ -58,7 +58,7 @@ const int NB_RAYS = 100; const float RAY_LENGTH = 30.0f; const int NB_BODIES = 9; -// Raycast manager +// Contact manager class ContactManager : public rp3d::CollisionCallback { private: @@ -66,16 +66,12 @@ class ContactManager : public rp3d::CollisionCallback { /// All the visual contact points std::vector mContactPoints; - /// All the normals at contact points - std::vector mNormals; - /// Contact point mesh folder path std::string mMeshFolderPath; public: - ContactManager(openglframework::Shader& shader, - const std::string& meshFolderPath) + ContactManager(openglframework::Shader& shader, const std::string& meshFolderPath) : mMeshFolderPath(meshFolderPath) { } @@ -87,22 +83,20 @@ class ContactManager : public rp3d::CollisionCallback { rp3d::ContactPointInfo* contactPointInfo = collisionCallbackInfo.contactManifold.getFirstContactPointInfo(); while (contactPointInfo != nullptr) { + // Contact normal + rp3d::Vector3 normal = contactPointInfo->normal; + openglframework::Vector3 contactNormal(normal.x, normal.y, normal.z); + rp3d::Vector3 point1 = contactPointInfo->localPoint1; point1 = collisionCallbackInfo.proxyShape1->getLocalToWorldTransform() * point1; + openglframework::Vector3 position1(point1.x, point1.y, point1.z); - mContactPoints.push_back(ContactPoint(position1)); - + mContactPoints.push_back(ContactPoint(position1, contactNormal, openglframework::Color::red())); rp3d::Vector3 point2 = contactPointInfo->localPoint2; point2 = collisionCallbackInfo.proxyShape2->getLocalToWorldTransform() * point2; openglframework::Vector3 position2(point2.x, point2.y, point2.z); - mContactPoints.push_back(ContactPoint(position2)); - - // Create a line to display the normal at hit point - rp3d::Vector3 n = contactPointInfo->normal; - openglframework::Vector3 normal(n.x, n.y, n.z); - Line* normalLine = new Line(position1, position1 + normal); - mNormals.push_back(normalLine); + mContactPoints.push_back(ContactPoint(position2, contactNormal, openglframework::Color::blue())); contactPointInfo = contactPointInfo->next; } @@ -111,13 +105,6 @@ class ContactManager : public rp3d::CollisionCallback { void resetPoints() { mContactPoints.clear(); - - // Destroy all the normals - for (std::vector::iterator it = mNormals.begin(); - it != mNormals.end(); ++it) { - delete (*it); - } - mNormals.clear(); } std::vector getContactPoints() const { @@ -146,7 +133,6 @@ class CollisionDetectionScene : public SceneDemo { Sphere* mSphere2; Capsule* mCapsule1; Capsule* mCapsule2; - Box* mBox1; //Cone* mCone; //Cylinder* mCylinder; //Capsule* mCapsule; @@ -162,18 +148,6 @@ class CollisionDetectionScene : public SceneDemo { /// Collision world used for the physics simulation rp3d::CollisionWorld* mCollisionWorld; - /// All the points to render the lines - std::vector mLinePoints; - - /// Vertex Buffer Object for the vertices data - openglframework::VertexBufferObject mVBOVertices; - - /// Vertex Array Object for the vertex data - openglframework::VertexArrayObject mVAO; - - /// Create the Vertex Buffer Objects used to render with OpenGL. - void createVBOAndVAO(openglframework::Shader& shader); - /// Select the next shape void selectNextShape(); diff --git a/testbed/scenes/raycast/RaycastScene.cpp b/testbed/scenes/raycast/RaycastScene.cpp index c403ebb2..d420073f 100644 --- a/testbed/scenes/raycast/RaycastScene.cpp +++ b/testbed/scenes/raycast/RaycastScene.cpp @@ -124,7 +124,7 @@ RaycastScene::RaycastScene(const std::string& name) createLines(); // Create the VBO and VAO to render the lines - createVBOAndVAO(mPhongShader); + createVBOAndVAO(); changeBody(); } @@ -199,9 +199,6 @@ void RaycastScene::reset() { // Destructor RaycastScene::~RaycastScene() { - // Destroy the shader - mPhongShader.destroy(); - // Destroy the box rigid body from the dynamics world mCollisionWorld->destroyCollisionBody(mBox->getCollisionBody()); delete mBox; @@ -293,40 +290,33 @@ void RaycastScene::update() { } // Render the scene -void RaycastScene::renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix) { +void RaycastScene::renderSinglePass(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) { // Bind the VAO mVAO.bind(); // Bind the shader - shader.bind(); + mColorShader.bind(); mVBOVertices.bind(); // Set the model to camera matrix const Matrix4 localToCameraMatrix = Matrix4::identity(); - shader.setMatrix4x4Uniform("localToWorldMatrix", localToCameraMatrix); - shader.setMatrix4x4Uniform("worldToCameraMatrix", worldToCameraMatrix); - - // Set the normal matrix (inverse transpose of the 3x3 upper-left sub matrix of the - // model-view matrix) - const openglframework::Matrix3 normalMatrix = - localToCameraMatrix.getUpperLeft3x3Matrix().getInverse().getTranspose(); - shader.setMatrix3x3Uniform("normalMatrix", normalMatrix, false); + mColorShader.setMatrix4x4Uniform("localToWorldMatrix", localToCameraMatrix); + mColorShader.setMatrix4x4Uniform("worldToCameraMatrix", worldToCameraMatrix); // Set the vertex color - openglframework::Vector4 color(1, 0, 0, 1); - shader.setVector4Uniform("vertexColor", color, false); + openglframework::Vector4 color(1, 0.55, 0, 1); + mColorShader.setVector4Uniform("vertexColor", color, false); // Get the location of shader attribute variables - GLint vertexPositionLoc = shader.getAttribLocation("vertexPosition"); + GLint vertexPositionLoc = mColorShader.getAttribLocation("vertexPosition"); glEnableVertexAttribArray(vertexPositionLoc); glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)NULL); // Draw the lines - glDrawArrays(GL_LINES, 0, NB_RAYS); + glDrawArrays(GL_LINES, 0, mLinePoints.size() * 2); glDisableVertexAttribArray(vertexPositionLoc); @@ -335,7 +325,7 @@ void RaycastScene::renderSinglePass(openglframework::Shader& shader, // Unbind the VAO mVAO.unbind(); - shader.unbind(); + mColorShader.unbind(); // Render the shapes if (mBox->getCollisionBody()->isActive()) mBox->render(shader, worldToCameraMatrix, mIsWireframeEnabled); @@ -345,16 +335,11 @@ void RaycastScene::renderSinglePass(openglframework::Shader& shader, if (mDumbbell->getCollisionBody()->isActive()) mDumbbell->render(shader, worldToCameraMatrix, mIsWireframeEnabled); if (mConcaveMesh->getCollisionBody()->isActive()) mConcaveMesh->render(shader, worldToCameraMatrix, mIsWireframeEnabled); if (mHeightField->getCollisionBody()->isActive()) mHeightField->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - - shader.unbind(); } // Create the Vertex Buffer Objects used to render with OpenGL. /// We create two VBOs (one for vertices and one for indices) -void RaycastScene::createVBOAndVAO(openglframework::Shader& shader) { - - // Bind the shader - shader.bind(); +void RaycastScene::createVBOAndVAO() { // Create the VBO for the vertices data mVBOVertices.create(); @@ -372,9 +357,6 @@ void RaycastScene::createVBOAndVAO(openglframework::Shader& shader) { // Unbind the VAO mVAO.unbind(); - - // Unbind the shader - shader.unbind(); } // Called when a keyboard event occurs diff --git a/testbed/scenes/raycast/RaycastScene.h b/testbed/scenes/raycast/RaycastScene.h index be698e53..39b73799 100644 --- a/testbed/scenes/raycast/RaycastScene.h +++ b/testbed/scenes/raycast/RaycastScene.h @@ -82,13 +82,16 @@ class RaycastManager : public rp3d::RaycastCallback { } virtual rp3d::decimal notifyRaycastHit(const rp3d::RaycastInfo& raycastInfo) override { + + rp3d::Vector3 n = raycastInfo.worldNormal; + openglframework::Vector3 normal(n.x, n.y, n.z); + rp3d::Vector3 hitPos = raycastInfo.worldPoint; openglframework::Vector3 position(hitPos.x, hitPos.y, hitPos.z); - mHitPoints.push_back(ContactPoint(position)); + mHitPoints.push_back(ContactPoint(position, normal, openglframework::Color::red())); // Create a line to display the normal at hit point - rp3d::Vector3 n = raycastInfo.worldNormal; - openglframework::Vector3 normal(n.x, n.y, n.z); + // TODO : Remove the mNormals because the VisualContactPoint is now able to display the contact normal on its own Line* normalLine = new Line(position, position + normal); mNormals.push_back(normalLine); @@ -134,8 +137,6 @@ class RaycastScene : public SceneDemo { /// True if the hit points normals are displayed bool mAreNormalsDisplayed; - /// Raycast manager - /// All objects on the scene Box* mBox; Sphere* mSphere; @@ -161,7 +162,7 @@ class RaycastScene : public SceneDemo { void createLines(); // Create the Vertex Buffer Objects used to render with OpenGL. - void createVBOAndVAO(openglframework::Shader& shader); + void createVBOAndVAO(); public: diff --git a/testbed/shaders/color.frag b/testbed/shaders/color.frag new file mode 100644 index 00000000..7ba710f0 --- /dev/null +++ b/testbed/shaders/color.frag @@ -0,0 +1,38 @@ +#version 330 + +/******************************************************************************** +* OpenGL-Framework * +* Copyright (c) 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. * +* * +********************************************************************************/ + +// Uniform variables +uniform vec4 vertexColor; // Vertex color + +// Out variable +out vec4 color; // Output color + +void main() { + + // Compute the final color + color = vertexColor; +} diff --git a/testbed/shaders/color.vert b/testbed/shaders/color.vert new file mode 100644 index 00000000..72083abc --- /dev/null +++ b/testbed/shaders/color.vert @@ -0,0 +1,43 @@ +#version 330 + +/******************************************************************************** +* OpenGL-Framework * +* Copyright (c) 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. * +* * +********************************************************************************/ + +// Uniform variables +uniform mat4 localToWorldMatrix; // Local-space to world-space matrix +uniform mat4 worldToCameraMatrix; // World-space to camera-space matrix +uniform mat4 projectionMatrix; // Projection matrix + +// In variables +in vec4 vertexPosition; + +void main() { + + // Compute the vertex position + vec4 positionCameraSpace = worldToCameraMatrix * localToWorldMatrix * vertexPosition; + + // Compute the clip-space vertex coordinates + gl_Position = projectionMatrix * positionCameraSpace; +} diff --git a/testbed/src/Scene.h b/testbed/src/Scene.h index d51ffec1..aa29b9e5 100644 --- a/testbed/src/Scene.h +++ b/testbed/src/Scene.h @@ -34,9 +34,12 @@ struct ContactPoint { public: openglframework::Vector3 point; + openglframework::Vector3 normal; + openglframework::Color color; /// Constructor - ContactPoint(const openglframework::Vector3& pointWorld) : point(pointWorld) { + ContactPoint(const openglframework::Vector3& pointWorld, const openglframework::Vector3& normalWorld, const openglframework::Color colorPoint) + : point(pointWorld), normal(normalWorld), color(colorPoint) { } }; diff --git a/testbed/src/SceneDemo.cpp b/testbed/src/SceneDemo.cpp index 1906d9f4..2cb3e440 100644 --- a/testbed/src/SceneDemo.cpp +++ b/testbed/src/SceneDemo.cpp @@ -46,6 +46,7 @@ SceneDemo::SceneDemo(const std::string& name, float sceneRadius, bool isShadowMa mDepthShader("shaders/depth.vert", "shaders/depth.frag"), mPhongShader("shaders/phong.vert", "shaders/phong.frag"), mQuadShader("shaders/quad.vert", "shaders/quad.frag"), + mColorShader("shaders/color.vert", "shaders/color.frag"), mVBOQuad(GL_ARRAY_BUFFER), mMeshFolderPath("meshes/") { shadowMapTextureLevel++; @@ -84,6 +85,11 @@ SceneDemo::~SceneDemo() { mFBOShadowMap.destroy(); mVBOQuad.destroy(); + mDepthShader.destroy(); + mPhongShader.destroy(); + mQuadShader.destroy(); + mColorShader.destroy(); + // Destroy the contact points removeAllContactPoints(); @@ -156,7 +162,7 @@ void SceneDemo::render() { if (mIsShadowMappingEnabled) mShadowMapTexture.bind(); const GLuint textureUnit = 0; - // Set the variables of the shader + // Set the variables of the phong shader mPhongShader.setMatrix4x4Uniform("projectionMatrix", mCamera.getProjectionMatrix()); mPhongShader.setMatrix4x4Uniform("shadowMapProjectionMatrix", mShadowMapBiasMatrix * shadowMapProjMatrix); mPhongShader.setMatrix4x4Uniform("worldToLight0CameraMatrix", worldToLightCameraMatrix); @@ -166,6 +172,12 @@ void SceneDemo::render() { mPhongShader.setIntUniform("shadowMapSampler", textureUnit); mPhongShader.setIntUniform("isShadowEnabled", mIsShadowMappingEnabled); mPhongShader.setVector2Uniform("shadowMapDimension", Vector2(SHADOWMAP_WIDTH, SHADOWMAP_HEIGHT)); + mPhongShader.unbind(); + + // Set the variables of the color shader + mColorShader.bind(); + mColorShader.setMatrix4x4Uniform("projectionMatrix", mCamera.getProjectionMatrix()); + mColorShader.unbind(); // Set the viewport to render the scene glViewport(mViewportX, mViewportY, mViewportWidth, mViewportHeight); @@ -289,20 +301,19 @@ void SceneDemo::updateContactPoints() { for (it = contactPoints.begin(); it != contactPoints.end(); ++it) { // Create a visual contact point for rendering - VisualContactPoint* point = new VisualContactPoint(it->point, mMeshFolderPath); + VisualContactPoint* point = new VisualContactPoint(it->point, mMeshFolderPath, it->point + it->normal, it->color); mContactPoints.push_back(point); } } } // Render the contact points -void SceneDemo::renderContactPoints(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix) { +void SceneDemo::renderContactPoints(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) { // Render all the raycast hit points for (std::vector::iterator it = mContactPoints.begin(); it != mContactPoints.end(); ++it) { - (*it)->render(shader, worldToCameraMatrix); + (*it)->render(mColorShader, worldToCameraMatrix); } } @@ -335,7 +346,9 @@ std::vector SceneDemo::computeContactPointsOfWorld(const rp3d::Dyn rp3d::ContactPoint* contactPoint = manifold->getContactPoint(i); rp3d::Vector3 point = contactPoint->getWorldPointOnBody1(); - ContactPoint contact(openglframework::Vector3(point.x, point.y, point.z)); + rp3d::Vector3 normalWorld = contactPoint->getNormal(); + openglframework::Vector3 normal = openglframework::Vector3(normalWorld.x, normalWorld.y, normalWorld.z); + ContactPoint contact(openglframework::Vector3(point.x, point.y, point.z), normal, openglframework::Color::red()); contactPoints.push_back(contact); } diff --git a/testbed/src/SceneDemo.h b/testbed/src/SceneDemo.h index c64c8a9b..f7b5f7ce 100644 --- a/testbed/src/SceneDemo.h +++ b/testbed/src/SceneDemo.h @@ -73,6 +73,9 @@ class SceneDemo : public Scene { /// Phong shader openglframework::Shader mPhongShader; + /// Constant color shader + openglframework::Shader mColorShader; + // TODO : Delete this openglframework::Shader mQuadShader; From 730b68787735cf246a23b18c1ed78332520b026c Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 29 May 2017 08:32:10 +0200 Subject: [PATCH 071/248] Working on temporal coherence in SAT (polyhedron vs polyhedron) --- CMakeLists.txt | 2 + src/collision/CollisionDetection.cpp | 13 +- .../CapsuleVsConvexPolyhedronAlgorithm.cpp | 14 +- ...xPolyhedronVsConvexPolyhedronAlgorithm.cpp | 48 +++ ...vexPolyhedronVsConvexPolyhedronAlgorithm.h | 71 ++++ .../narrowphase/DefaultCollisionDispatch.cpp | 9 + .../narrowphase/DefaultCollisionDispatch.h | 16 +- .../narrowphase/GJK/GJKAlgorithm.cpp | 11 +- .../narrowphase/SAT/SATAlgorithm.cpp | 333 +++++++++++++----- src/collision/narrowphase/SAT/SATAlgorithm.h | 15 +- .../SphereVsConvexPolyhedronAlgorithm.cpp | 12 +- .../SphereVsConvexPolyhedronAlgorithm.h | 2 +- src/engine/OverlappingPair.cpp | 3 +- src/engine/OverlappingPair.h | 68 +++- 14 files changed, 502 insertions(+), 115 deletions(-) create mode 100644 src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp create mode 100644 src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 5cacac60..2e3be144 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -88,6 +88,8 @@ SET (REACTPHYSICS3D_SOURCES "src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp" "src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h" "src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp" + "src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.h" + "src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp" "src/collision/shapes/AABB.h" "src/collision/shapes/AABB.cpp" "src/collision/shapes/ConvexShape.h" diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 908c5bf5..9ce02f9d 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -241,7 +241,7 @@ void CollisionDetection::computeNarrowPhase() { // If there is no collision algorithm between those two kinds of shapes, skip it if (narrowPhaseAlgorithm != nullptr) { - + // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. @@ -268,7 +268,15 @@ void CollisionDetection::computeNarrowPhase() { // Trigger a callback event for the new contact if (mWorld->mEventListener != nullptr) mWorld->mEventListener->newContact(contactManifoldInfo); + + currentNarrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasColliding = true; } + else { + currentNarrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasColliding = false; + } + + // The previous frame collision info is now valid + currentNarrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().isValid = true; } currentNarrowPhaseInfo = currentNarrowPhaseInfo->next; @@ -834,6 +842,9 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { // Report the contact to the user callback->notifyContact(collisionInfo); } + + // The previous frame collision info is now valid + narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().isValid = true; } NarrowPhaseInfo* currentNarrowPhaseInfo = narrowPhaseInfo; diff --git a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp index 5e8dd5f9..142a7fc9 100644 --- a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp @@ -44,6 +44,9 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* na SATAlgorithm satAlgorithm; GJKAlgorithm::GJKResult result = gjkAlgorithm.testCollision(narrowPhaseInfo, contactManifoldInfo); + narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = true; + narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = false; + // If we have found a contact point inside the margins (shallow penetration) if (result == GJKAlgorithm::GJKResult::COLLIDE_IN_MARGIN) { @@ -104,9 +107,11 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* na break; } - } + narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = false; + narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = false; + // Return true return true; } @@ -115,7 +120,12 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* na if (result == GJKAlgorithm::GJKResult::INTERPENETRATE) { // Run the SAT algorithm to find the separating axis and compute contact point - return satAlgorithm.testCollisionCapsuleVsConvexPolyhedron(narrowPhaseInfo, contactManifoldInfo); + bool isColliding = satAlgorithm.testCollisionCapsuleVsConvexPolyhedron(narrowPhaseInfo, contactManifoldInfo); + + narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = false; + narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = true; + + return isColliding; } return false; diff --git a/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp new file mode 100644 index 00000000..16b9edf5 --- /dev/null +++ b/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp @@ -0,0 +1,48 @@ +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "ConvexPolyhedronVsConvexPolyhedronAlgorithm.h" +#include "GJK/GJKAlgorithm.h" +#include "SAT/SATAlgorithm.h" + +// We want to use the ReactPhysics3D namespace +using namespace reactphysics3d; + +// Compute the narrow-phase collision detection between two convex polyhedra +// This technique is based on the "Robust Contact Creation for Physics Simulations" presentation +// by Dirk Gregorius. +bool ConvexPolyhedronVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + ContactManifoldInfo& contactManifoldInfo) { + + // Run the SAT algorithm to find the separating axis and compute contact point + SATAlgorithm satAlgorithm; + bool isColliding = satAlgorithm.testCollisionConvexPolyhedronVsConvexPolyhedron(narrowPhaseInfo, contactManifoldInfo); + + narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = true; + narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = false; + + return isColliding; +} diff --git a/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.h b/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.h new file mode 100644 index 00000000..ed76d6fc --- /dev/null +++ b/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.h @@ -0,0 +1,71 @@ +/******************************************************************************** +* 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_CONVEX_POLYHEDRON_VS_CONVEX_POLYHEDRON_ALGORITHM_H +#define REACTPHYSICS3D_CONVEX_POLYHEDRON_VS_CONVEX_POLYHEDRON_ALGORITHM_H + +// Libraries +#include "body/Body.h" +#include "constraint/ContactPoint.h" +#include "NarrowPhaseAlgorithm.h" + + +/// Namespace ReactPhysics3D +namespace reactphysics3d { + +// Class ConvexPolyhedronVsConvexPolyhedronAlgorithm +/** + * This class is used to compute the narrow-phase collision detection + * between two convex polyhedra. + */ +class ConvexPolyhedronVsConvexPolyhedronAlgorithm : public NarrowPhaseAlgorithm { + + protected : + + public : + + // -------------------- Methods -------------------- // + + /// Constructor + ConvexPolyhedronVsConvexPolyhedronAlgorithm() = default; + + /// Destructor + virtual ~ConvexPolyhedronVsConvexPolyhedronAlgorithm() override = default; + + /// Deleted copy-constructor + ConvexPolyhedronVsConvexPolyhedronAlgorithm(const ConvexPolyhedronVsConvexPolyhedronAlgorithm& algorithm) = delete; + + /// Deleted assignment operator + ConvexPolyhedronVsConvexPolyhedronAlgorithm& operator=(const ConvexPolyhedronVsConvexPolyhedronAlgorithm& algorithm) = delete; + + /// Compute the narrow-phase collision detection between two convex polyhedra + virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, + ContactManifoldInfo& contactManifoldInfo) override; +}; + +} + +#endif + diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.cpp b/src/collision/narrowphase/DefaultCollisionDispatch.cpp index 0a1e498c..df1828ad 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.cpp +++ b/src/collision/narrowphase/DefaultCollisionDispatch.cpp @@ -56,6 +56,15 @@ NarrowPhaseAlgorithm* DefaultCollisionDispatch::selectAlgorithm(int type1, int t if (shape1Type == CollisionShapeType::SPHERE && shape2Type == CollisionShapeType::CONVEX_POLYHEDRON) { return &mSphereVsConvexPolyhedronAlgorithm; } + // Capsule vs Convex Polyhedron algorithm + if (shape1Type == CollisionShapeType::CAPSULE && shape2Type == CollisionShapeType::CONVEX_POLYHEDRON) { + return &mCapsuleVsConvexPolyhedronAlgorithm; + } + // Convex Polyhedron vs Convex Polyhedron algorithm + if (shape1Type == CollisionShapeType::CONVEX_POLYHEDRON && + shape2Type == CollisionShapeType::CONVEX_POLYHEDRON) { + return &mConvexPolyhedronVsConvexPolyhedronAlgorithm; + } return nullptr; } diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.h b/src/collision/narrowphase/DefaultCollisionDispatch.h index 7c5d77ea..7b3945d3 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.h +++ b/src/collision/narrowphase/DefaultCollisionDispatch.h @@ -33,6 +33,8 @@ #include "SphereVsConvexPolyhedronAlgorithm.h" #include "SphereVsCapsuleAlgorithm.h" #include "CapsuleVsCapsuleAlgorithm.h" +#include "CapsuleVsConvexPolyhedronAlgorithm.h" +#include "ConvexPolyhedronVsConvexPolyhedronAlgorithm.h" #include "GJK/GJKAlgorithm.h" namespace reactphysics3d { @@ -50,14 +52,20 @@ class DefaultCollisionDispatch : public CollisionDispatch { /// Sphere vs Sphere collision algorithm SphereVsSphereAlgorithm mSphereVsSphereAlgorithm; - /// Sphere vs Convex Mesh collision algorithm - SphereVsConvexPolyhedronAlgorithm mSphereVsConvexPolyhedronAlgorithm; + /// Capsule vs Capsule collision algorithm + CapsuleVsCapsuleAlgorithm mCapsuleVsCapsuleAlgorithm; /// Sphere vs Capsule collision algorithm SphereVsCapsuleAlgorithm mSphereVsCapsuleAlgorithm; - /// Capsule vs Capsule collision algorithm - CapsuleVsCapsuleAlgorithm mCapsuleVsCapsuleAlgorithm; + /// Sphere vs Convex Polyhedron collision algorithm + SphereVsConvexPolyhedronAlgorithm mSphereVsConvexPolyhedronAlgorithm; + + /// Capsule vs Convex Polyhedron collision algorithm + CapsuleVsConvexPolyhedronAlgorithm mCapsuleVsConvexPolyhedronAlgorithm; + + /// Convex Polyhedron vs Convex Polyhedron collision algorithm + ConvexPolyhedronVsConvexPolyhedronAlgorithm mConvexPolyhedronVsConvexPolyhedronAlgorithm; public: diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp index 6be90769..4f7e1177 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp @@ -93,7 +93,14 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(const NarrowPhaseInfo* narro VoronoiSimplex simplex; // Get the previous point V (last cached separating axis) - Vector3 v = narrowPhaseInfo->overlappingPair->getCachedSeparatingAxis(); + Vector3 v; + LastFrameCollisionInfo& lastFrameInfo = narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo(); + if (lastFrameInfo.isValid && lastFrameInfo.wasUsingGJK) { + v = lastFrameInfo.gjkSeparatingAxis; + } + else { + v.setAllValues(0, 1, 0); + } // Initialize the upper bound for the square distance decimal distSquare = DECIMAL_LARGEST; @@ -113,7 +120,7 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(const NarrowPhaseInfo* narro if (vDotw > decimal(0.0) && vDotw * vDotw > distSquare * marginSquare) { // Cache the current separating axis for frame coherence - narrowPhaseInfo->overlappingPair->setCachedSeparatingAxis(v); + narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().gjkSeparatingAxis = v; // No intersection, we return return GJKResult::SEPARATED; diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index c82256f3..6e85e303 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -29,6 +29,7 @@ #include "collision/PolyhedronMesh.h" #include "collision/shapes/CapsuleShape.h" #include "collision/shapes/SphereShape.h" +#include "engine/OverlappingPair.h" #include "configuration.h" #include "engine/Profiler.h" #include @@ -329,7 +330,8 @@ bool SATAlgorithm::isMinkowskiFaceCapsuleVsEdge(const Vector3& capsuleSegment, c } // Test collision between two convex polyhedrons -bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { +bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, + ContactManifoldInfo& contactManifoldInfo) const { assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON); assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); @@ -344,94 +346,235 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(const NarrowP uint minFaceIndex = 0; bool isMinPenetrationFaceNormal = false; bool isMinPenetrationFaceNormalPolyhedron1 = false; + uint minSeparatingEdge1Index, minSeparatingEdge2Index; Vector3 separatingEdge1A, separatingEdge1B; Vector3 separatingEdge2A, separatingEdge2B; Vector3 minEdgeVsEdgeSeparatingAxisPolyhedron2Space; - // Test all the face normals of the polyhedron 1 for separating axis - uint faceIndex; - decimal penetrationDepth = testFaceDirectionPolyhedronVsPolyhedron(polyhedron1, polyhedron2, polyhedron1ToPolyhedron2, faceIndex); - if (penetrationDepth <= decimal(0.0)) { + LastFrameCollisionInfo& lastFrameInfo = narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo(); - // We have found a separating axis - return false; - } - if (penetrationDepth < minPenetrationDepth - SAME_SEPARATING_AXIS_BIAS) { - isMinPenetrationFaceNormal = true; - minPenetrationDepth = penetrationDepth; - minFaceIndex = faceIndex; - isMinPenetrationFaceNormalPolyhedron1 = true; - } + // True if the shapes were overlapping in the previous frame and are + // still overlapping on the same axis in this frame + bool isTemporalCoherenceValid = false; - // Test all the face normals of the polyhedron 2 for separating axis - penetrationDepth = testFaceDirectionPolyhedronVsPolyhedron(polyhedron2, polyhedron1, polyhedron2ToPolyhedron1, faceIndex); - if (penetrationDepth <= decimal(0.0)) { + // If the shapes are not triangles (no temporal coherence for triangle collision because we do not store previous + // frame collision data per triangle) + if (polyhedron1->getType() != CollisionShapeType::TRIANGLE && polyhedron2->getType() != CollisionShapeType::TRIANGLE) { - // We have found a separating axis - return false; - } - if (penetrationDepth < minPenetrationDepth - SAME_SEPARATING_AXIS_BIAS) { - isMinPenetrationFaceNormal = true; - minPenetrationDepth = penetrationDepth; - minFaceIndex = faceIndex; - isMinPenetrationFaceNormalPolyhedron1 = false; - } + // If the last frame collision info is valid and was also using SAT algorithm + if (lastFrameInfo.isValid && lastFrameInfo.wasUsingSAT) { - // 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) { + // We perform temporal coherence, we check if there is still an overlapping along the previous minimum separating + // axis. If it is the case, we directly report the collision without executing the whole SAT algorithm again. If + // the shapes are still separated along this axis, we directly exit with no collision. - // Get an edge of polyhedron 1 - HalfEdgeStructure::Edge edge1 = polyhedron1->getHalfEdge(i); - - const Vector3 edge1A = polyhedron1ToPolyhedron2 * polyhedron1->getVertexPosition(edge1.vertexIndex); - 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) { - - // Get an edge of polyhedron 2 - HalfEdgeStructure::Edge edge2 = polyhedron2->getHalfEdge(j); - - const Vector3 edge2A = polyhedron2->getVertexPosition(edge2.vertexIndex); - const Vector3 edge2B = polyhedron2->getVertexPosition(polyhedron2->getHalfEdge(edge2.nextEdgeIndex).vertexIndex); - const Vector3 edge2Direction = edge2B - edge2A; - - // If the two edges build a minkowski face (and the cross product is - // therefore a candidate for separating axis - if (testEdgesBuildMinkowskiFace(polyhedron1, edge1, polyhedron2, edge2, polyhedron1ToPolyhedron2)) { - - Vector3 separatingAxisPolyhedron2Space; - - // Compute the penetration depth - decimal penetrationDepth = computeDistanceBetweenEdges(edge1A, edge2A, polyhedron2->getCentroid(), - edge1Direction, edge2Direction, separatingAxisPolyhedron2Space); + // If the previous separating axis (or axis with minimum penetration depth) + // was a face normal of polyhedron 1 + if (lastFrameInfo.satIsAxisFacePolyhedron1) { + decimal penetrationDepth = testSingleFaceDirectionPolyhedronVsPolyhedron(polyhedron1, polyhedron2, polyhedron1ToPolyhedron2, + lastFrameInfo.satMinAxisFaceIndex); + // If the previous axis is a separating axis if (penetrationDepth <= decimal(0.0)) { - // We have found a separating axis + // Return no collision return false; } - if (penetrationDepth < minPenetrationDepth - SAME_SEPARATING_AXIS_BIAS) { + // The two shapes are overlapping as in the previous frame and on the same axis, therefore + // we will skip the entire SAT algorithm because the minimum separating axis did not change + isTemporalCoherenceValid = lastFrameInfo.wasColliding; + + if (isTemporalCoherenceValid) { minPenetrationDepth = penetrationDepth; - isMinPenetrationFaceNormalPolyhedron1 = false; - isMinPenetrationFaceNormal = false; - separatingEdge1A = edge1A; - separatingEdge1B = edge1B; - separatingEdge2A = edge2A; - separatingEdge2B = edge2B; - minEdgeVsEdgeSeparatingAxisPolyhedron2Space = separatingAxisPolyhedron2Space; + minFaceIndex = lastFrameInfo.satMinAxisFaceIndex; + isMinPenetrationFaceNormal = true; + isMinPenetrationFaceNormalPolyhedron1 = true; + } + } + else if (lastFrameInfo.satIsAxisFacePolyhedron2) { // If the previous separating axis (or axis with minimum penetration depth) + // was a face normal of polyhedron 2 + + decimal penetrationDepth = testSingleFaceDirectionPolyhedronVsPolyhedron(polyhedron2, polyhedron1, polyhedron2ToPolyhedron1, + lastFrameInfo.satMinAxisFaceIndex); + // If the previous axis is a separating axis + if (penetrationDepth <= decimal(0.0)) { + + // Return no collision + return false; } + // The two shapes are overlapping as in the previous frame and on the same axis, therefore + // we will skip the entire SAT algorithm because the minimum separating axis did not change + isTemporalCoherenceValid = lastFrameInfo.wasColliding; + + if (isTemporalCoherenceValid) { + + minPenetrationDepth = penetrationDepth; + minFaceIndex = lastFrameInfo.satMinAxisFaceIndex; + isMinPenetrationFaceNormal = true; + isMinPenetrationFaceNormalPolyhedron1 = false; + } + } + else { // If the previous separating axis (or axis with minimum penetration depth) was the cross product of two edges + + HalfEdgeStructure::Edge edge1 = polyhedron1->getHalfEdge(lastFrameInfo.satMinEdge1Index); + HalfEdgeStructure::Edge edge2 = polyhedron2->getHalfEdge(lastFrameInfo.satMinEdge2Index); + + // If the two edges build a minkowski face (and the cross product is + // therefore a candidate for separating axis + if (testEdgesBuildMinkowskiFace(polyhedron1, edge1, polyhedron2, edge2, polyhedron1ToPolyhedron2)) { + + Vector3 separatingAxisPolyhedron2Space; + + const Vector3 edge1A = polyhedron1ToPolyhedron2 * polyhedron1->getVertexPosition(edge1.vertexIndex); + const Vector3 edge1B = polyhedron1ToPolyhedron2 * polyhedron1->getVertexPosition(polyhedron1->getHalfEdge(edge1.nextEdgeIndex).vertexIndex); + const Vector3 edge1Direction = edge1B - edge1A; + const Vector3 edge2A = polyhedron2->getVertexPosition(edge2.vertexIndex); + const Vector3 edge2B = polyhedron2->getVertexPosition(polyhedron2->getHalfEdge(edge2.nextEdgeIndex).vertexIndex); + const Vector3 edge2Direction = edge2B - edge2A; + + // Compute the penetration depth + decimal penetrationDepth = computeDistanceBetweenEdges(edge1A, edge2A, polyhedron2->getCentroid(), + edge1Direction, edge2Direction, separatingAxisPolyhedron2Space); + + // If the previous axis is a separating axis + if (penetrationDepth <= decimal(0.0)) { + + // Return no collision + return false; + } + + // The two shapes are overlapping as in the previous frame and on the same axis, therefore + // we will skip the entire SAT algorithm because the minimum separating axis did not change + isTemporalCoherenceValid = lastFrameInfo.wasColliding; + + if (isTemporalCoherenceValid) { + + minPenetrationDepth = penetrationDepth; + isMinPenetrationFaceNormal = false; + isMinPenetrationFaceNormalPolyhedron1 = false; + minSeparatingEdge1Index = lastFrameInfo.satMinEdge1Index; + minSeparatingEdge2Index = lastFrameInfo.satMinEdge2Index; + separatingEdge1A = edge1A; + separatingEdge1B = edge1B; + separatingEdge2A = edge2A; + separatingEdge2B = edge2B; + minEdgeVsEdgeSeparatingAxisPolyhedron2Space = separatingAxisPolyhedron2Space; + } + } } } } + // We the shapes are still overlapping in the same axis as in + // the previous frame, we skip the whole SAT algorithm + if (isTemporalCoherenceValid) { + + // Test all the face normals of the polyhedron 1 for separating axis + uint faceIndex; + decimal penetrationDepth = testFacesDirectionPolyhedronVsPolyhedron(polyhedron1, polyhedron2, polyhedron1ToPolyhedron2, faceIndex); + if (penetrationDepth <= decimal(0.0)) { + + lastFrameInfo.satIsAxisFacePolyhedron1 = true; + lastFrameInfo.satIsAxisFacePolyhedron2 = false; + lastFrameInfo.satMinAxisFaceIndex = faceIndex; + + // We have found a separating axis + return false; + } + if (penetrationDepth < minPenetrationDepth - SAME_SEPARATING_AXIS_BIAS) { + isMinPenetrationFaceNormal = true; + minPenetrationDepth = penetrationDepth; + minFaceIndex = faceIndex; + isMinPenetrationFaceNormalPolyhedron1 = true; + } + + // Test all the face normals of the polyhedron 2 for separating axis + penetrationDepth = testFacesDirectionPolyhedronVsPolyhedron(polyhedron2, polyhedron1, polyhedron2ToPolyhedron1, faceIndex); + if (penetrationDepth <= decimal(0.0)) { + + lastFrameInfo.satIsAxisFacePolyhedron1 = false; + lastFrameInfo.satIsAxisFacePolyhedron2 = true; + lastFrameInfo.satMinAxisFaceIndex = faceIndex; + + // We have found a separating axis + return false; + } + if (penetrationDepth < minPenetrationDepth - SAME_SEPARATING_AXIS_BIAS) { + isMinPenetrationFaceNormal = true; + minPenetrationDepth = penetrationDepth; + minFaceIndex = faceIndex; + isMinPenetrationFaceNormalPolyhedron1 = 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) { + + // Get an edge of polyhedron 1 + HalfEdgeStructure::Edge edge1 = polyhedron1->getHalfEdge(i); + + const Vector3 edge1A = polyhedron1ToPolyhedron2 * polyhedron1->getVertexPosition(edge1.vertexIndex); + 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) { + + // Get an edge of polyhedron 2 + HalfEdgeStructure::Edge edge2 = polyhedron2->getHalfEdge(j); + + const Vector3 edge2A = polyhedron2->getVertexPosition(edge2.vertexIndex); + const Vector3 edge2B = polyhedron2->getVertexPosition(polyhedron2->getHalfEdge(edge2.nextEdgeIndex).vertexIndex); + const Vector3 edge2Direction = edge2B - edge2A; + + // If the two edges build a minkowski face (and the cross product is + // therefore a candidate for separating axis + if (testEdgesBuildMinkowskiFace(polyhedron1, edge1, polyhedron2, edge2, polyhedron1ToPolyhedron2)) { + + Vector3 separatingAxisPolyhedron2Space; + + // Compute the penetration depth + decimal penetrationDepth = computeDistanceBetweenEdges(edge1A, edge2A, polyhedron2->getCentroid(), + edge1Direction, edge2Direction, separatingAxisPolyhedron2Space); + + if (penetrationDepth <= decimal(0.0)) { + + lastFrameInfo.satIsAxisFacePolyhedron1 = false; + lastFrameInfo.satIsAxisFacePolyhedron2 = false; + lastFrameInfo.satMinEdge1Index = i; + lastFrameInfo.satMinEdge2Index = j; + + // We have found a separating axis + return false; + } + + if (penetrationDepth < minPenetrationDepth - SAME_SEPARATING_AXIS_BIAS) { + + minPenetrationDepth = penetrationDepth; + isMinPenetrationFaceNormalPolyhedron1 = false; + isMinPenetrationFaceNormal = false; + minSeparatingEdge1Index = i; + minSeparatingEdge2Index = j; + separatingEdge1A = edge1A; + separatingEdge1B = edge1B; + separatingEdge2A = edge2A; + separatingEdge2B = edge2B; + minEdgeVsEdgeSeparatingAxisPolyhedron2Space = separatingAxisPolyhedron2Space; + } + + } + } + } + } + + // Here we know the shapes are overlapping on a given minimum separating axis. + // Now, we will clip the shapes along this axis to find the contact points + assert(minPenetrationDepth > decimal(0.0)); assert((isMinPenetrationFaceNormal && minFaceIndex >= 0) || !isMinPenetrationFaceNormal); - // If the separation axis is a face normal + // If the minimum separating axis is a face normal if (isMinPenetrationFaceNormal) { const ConvexPolyhedronShape* referencePolyhedron = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron1 : polyhedron2; @@ -439,6 +582,8 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(const NarrowP const Transform& referenceToIncidentTransform = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron1ToPolyhedron2 : polyhedron2ToPolyhedron1; const Transform& incidentToReferenceTransform = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron2ToPolyhedron1 : polyhedron1ToPolyhedron2; + assert(minPenetrationDepth > decimal(0.0)); + const Vector3 axisReferenceSpace = referencePolyhedron->getFaceNormal(minFaceIndex); const Vector3 axisIncidentSpace = referenceToIncidentTransform.getOrientation() * axisReferenceSpace; @@ -491,8 +636,12 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(const NarrowP } while (currentEdgeIndex != firstEdgeIndex); + assert(planesNormals.size() > 0); + assert(planesNormals.size() == planesPoints.size()); + // Clip the reference faces with the adjacent planes of the reference face std::vector clipPolygonVertices = clipPolygonWithPlanes(polygonVertices, planesPoints, planesNormals); + assert(clipPolygonVertices.size() > 0); // We only keep the clipped points that are below the reference face const Vector3 referenceFaceVertex = referencePolyhedron->getVertexPosition(firstEdgeIndex); @@ -514,6 +663,10 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(const NarrowP isMinPenetrationFaceNormalPolyhedron1 ? contactPointIncidentPolyhedron : contactPointReferencePolyhedron); } } + + lastFrameInfo.satIsAxisFacePolyhedron1 = isMinPenetrationFaceNormalPolyhedron1; + lastFrameInfo.satIsAxisFacePolyhedron2 = !isMinPenetrationFaceNormalPolyhedron1; + lastFrameInfo.satMinAxisFaceIndex = minFaceIndex; } else { // If we have an edge vs edge contact @@ -531,6 +684,11 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(const NarrowP // Create the contact point contactManifoldInfo.addContactPoint(normalWorld, minPenetrationDepth, closestPointPolyhedron1EdgeLocalSpace, closestPointPolyhedron2Edge); + + lastFrameInfo.satIsAxisFacePolyhedron1 = false; + lastFrameInfo.satIsAxisFacePolyhedron2 = false; + lastFrameInfo.satMinEdge1Index = minSeparatingEdge1Index; + lastFrameInfo.satMinEdge2Index = minSeparatingEdge2Index; } return true; @@ -583,34 +741,47 @@ decimal SATAlgorithm::computeDistanceBetweenEdges(const Vector3& edge1A, const V return -axis.dot(edge2A - edge1A); } +// Return the penetration depth between two polyhedra along a face normal axis of the first polyhedron +decimal SATAlgorithm::testSingleFaceDirectionPolyhedronVsPolyhedron(const ConvexPolyhedronShape* polyhedron1, + const ConvexPolyhedronShape* polyhedron2, + const Transform& polyhedron1ToPolyhedron2, + uint faceIndex) const { + + HalfEdgeStructure::Face face = polyhedron1->getFace(faceIndex); + + // Get the face normal + const Vector3 faceNormal = polyhedron1->getFaceNormal(faceIndex); + + // Convert the face normal into the local-space of polyhedron 2 + const Vector3 faceNormalPolyhedron2Space = polyhedron1ToPolyhedron2.getOrientation() * faceNormal; + + // Get the support point of polyhedron 2 in the inverse direction of face normal + const Vector3 supportPoint = polyhedron2->getLocalSupportPointWithoutMargin(-faceNormalPolyhedron2Space, nullptr); + + // Compute the penetration depth + const Vector3 faceVertex = polyhedron1ToPolyhedron2 * polyhedron1->getVertexPosition(face.faceVertices[0]); + decimal penetrationDepth = (faceVertex - supportPoint).dot(faceNormalPolyhedron2Space); + + return penetrationDepth; +} + // Test all the normals of a polyhedron for separating axis in the polyhedron vs polyhedron case -decimal SATAlgorithm::testFaceDirectionPolyhedronVsPolyhedron(const ConvexPolyhedronShape* polyhedron1, - const ConvexPolyhedronShape* polyhedron2, - const Transform& polyhedron1ToPolyhedron2, - uint& minFaceIndex) const { +decimal SATAlgorithm::testFacesDirectionPolyhedronVsPolyhedron(const ConvexPolyhedronShape* polyhedron1, + const ConvexPolyhedronShape* polyhedron2, + const Transform& polyhedron1ToPolyhedron2, + uint& minFaceIndex) const { decimal minPenetrationDepth = DECIMAL_LARGEST; // For each face of the first polyhedron for (uint f = 0; f < polyhedron1->getNbFaces(); f++) { - HalfEdgeStructure::Face face = polyhedron1->getFace(f); - - // Get the face normal - const Vector3 faceNormal = polyhedron1->getFaceNormal(f); - - // Convert the face normal into the local-space of polyhedron 2 - const Vector3 faceNormalPolyhedron2Space = polyhedron1ToPolyhedron2.getOrientation() * faceNormal; - - // Get the support point of polyhedron 2 in the inverse direction of face normal - const Vector3 supportPoint = polyhedron2->getLocalSupportPointWithoutMargin(-faceNormalPolyhedron2Space, nullptr); - - // Compute the penetration depth - const Vector3 faceVertex = polyhedron1ToPolyhedron2 * polyhedron1->getVertexPosition(face.faceVertices[0]); - decimal penetrationDepth = (faceVertex - supportPoint).dot(faceNormalPolyhedron2Space); + decimal penetrationDepth = testSingleFaceDirectionPolyhedronVsPolyhedron(polyhedron1, polyhedron2, + polyhedron1ToPolyhedron2, f); // If the penetration depth is negative, we have found a separating axis if (penetrationDepth <= decimal(0.0)) { + minFaceIndex = f; return penetrationDepth; } diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.h b/src/collision/narrowphase/SAT/SATAlgorithm.h index a95abe31..3512ef4d 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.h +++ b/src/collision/narrowphase/SAT/SATAlgorithm.h @@ -66,6 +66,17 @@ class SATAlgorithm { const Vector3& edge1Direction, const Vector3& edge2Direction, Vector3& outSeparatingAxis) const; + /// Return the penetration depth between two polyhedra along a face normal axis of the first polyhedron + decimal testSingleFaceDirectionPolyhedronVsPolyhedron(const ConvexPolyhedronShape* polyhedron1, + const ConvexPolyhedronShape* polyhedron2, + const Transform& polyhedron1ToPolyhedron2, + uint faceIndex) const; + + + /// Test all the normals of a polyhedron for separating axis in the polyhedron vs polyhedron case + decimal testFacesDirectionPolyhedronVsPolyhedron(const ConvexPolyhedronShape* polyhedron1, const ConvexPolyhedronShape* polyhedron2, + const Transform& polyhedron1ToPolyhedron2, uint& minFaceIndex) const; + public : // -------------------- Methods -------------------- // @@ -101,10 +112,6 @@ class SATAlgorithm { /// Test collision between two convex meshes bool testCollisionConvexPolyhedronVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; - - /// Test all the normals of a polyhedron for separating axis in the polyhedron vs polyhedron case - decimal testFaceDirectionPolyhedronVsPolyhedron(const ConvexPolyhedronShape* polyhedron1, const ConvexPolyhedronShape* polyhedron2, - const Transform& polyhedron1ToPolyhedron2, uint& minFaceIndex) const; }; } diff --git a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp index 708d9f8d..bb43bd33 100644 --- a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp @@ -31,7 +31,7 @@ // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; -// Compute the narrow-phase collision detection a sphere and a convex polyhedron +// Compute the narrow-phase collision detection between a sphere and a convex polyhedron // This technique is based on the "Robust Contact Creation for Physics Simulations" presentation // by Dirk Gregorius. bool SphereVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, @@ -41,6 +41,9 @@ bool SphereVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* nar GJKAlgorithm gjkAlgorithm; GJKAlgorithm::GJKResult result = gjkAlgorithm.testCollision(narrowPhaseInfo, contactManifoldInfo); + narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = true; + narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = false; + // If we have found a contact point inside the margins (shallow penetration) if (result == GJKAlgorithm::GJKResult::COLLIDE_IN_MARGIN) { @@ -53,7 +56,12 @@ bool SphereVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* nar // Run the SAT algorithm to find the separating axis and compute contact point SATAlgorithm satAlgorithm; - return satAlgorithm.testCollisionSphereVsConvexPolyhedron(narrowPhaseInfo, contactManifoldInfo); + bool isColliding = satAlgorithm.testCollisionSphereVsConvexPolyhedron(narrowPhaseInfo, contactManifoldInfo); + + narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = false; + narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = true; + + return isColliding; } return false; diff --git a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h index c1fd3e55..f2f8d6e5 100644 --- a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h +++ b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h @@ -60,7 +60,7 @@ class SphereVsConvexPolyhedronAlgorithm : public NarrowPhaseAlgorithm { /// Deleted assignment operator SphereVsConvexPolyhedronAlgorithm& operator=(const SphereVsConvexPolyhedronAlgorithm& algorithm) = delete; - /// Compute the narrow-phase collision detection a sphere and a convex polyhedron + /// Compute the narrow-phase collision detection between a sphere and a convex polyhedron virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) override; }; diff --git a/src/engine/OverlappingPair.cpp b/src/engine/OverlappingPair.cpp index 1f5d894e..ce628b7d 100644 --- a/src/engine/OverlappingPair.cpp +++ b/src/engine/OverlappingPair.cpp @@ -32,7 +32,6 @@ using namespace reactphysics3d; // Constructor OverlappingPair::OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, int nbMaxContactManifolds, PoolAllocator& memoryAllocator) - : mContactManifoldSet(shape1, shape2, memoryAllocator, nbMaxContactManifolds), - mCachedSeparatingAxis(0.0, 1.0, 0.0) { + : mContactManifoldSet(shape1, shape2, memoryAllocator, nbMaxContactManifolds) { } diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index c34b91b7..ce028f9c 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -37,6 +37,51 @@ namespace reactphysics3d { // Type for the overlapping pair ID using overlappingpairid = std::pair; +// Structure LastFrameCollisionInfo +/** + * This structure contains collision info about the last frame. + * This is used for temporal coherence between frames. + */ +struct LastFrameCollisionInfo { + + /// True if we have information about the previous frame + bool isValid; + + /// True if the two shapes were colliding in the previous frame + bool wasColliding; + + /// True if we were using GJK algorithm to check for collision in the previous frame + bool wasUsingGJK; + + /// True if we were using SAT algorithm to check for collision in the previous frame + bool wasUsingSAT; + + /// True if there was a narrow-phase collision + /// in the previous frame + bool wasCollidingLastFrame; + + // ----- GJK Algorithm ----- + + /// Previous separating axis + Vector3 gjkSeparatingAxis; + + // SAT Algorithm + bool satIsAxisFacePolyhedron1; + bool satIsAxisFacePolyhedron2; + uint satMinAxisFaceIndex; + uint satMinEdge1Index; + uint satMinEdge2Index; + + /// Constructor + LastFrameCollisionInfo() { + + isValid = false; + wasColliding = false; + wasUsingSAT = false; + wasUsingGJK = false; + } +}; + // Class OverlappingPair /** * This class represents a pair of two proxy collision shapes that are overlapping @@ -54,8 +99,8 @@ class OverlappingPair { /// Set of persistent contact manifolds ContactManifoldSet mContactManifoldSet; - /// Cached previous separating axis - Vector3 mCachedSeparatingAxis; + /// Collision information about the last frame (for temporal coherence) + LastFrameCollisionInfo mLastFrameCollisionInfo; public: @@ -83,11 +128,8 @@ class OverlappingPair { /// Add a contact manifold void addContactManifold(const ContactManifoldInfo& contactManifoldInfo); - /// Return the cached separating axis - Vector3 getCachedSeparatingAxis() const; - - /// Set the cached separating axis - void setCachedSeparatingAxis(const Vector3& axis); + /// Return the last frame collision info + LastFrameCollisionInfo& getLastFrameCollisionInfo(); /// Return the number of contacts in the cache uint getNbContactPoints() const; @@ -124,17 +166,11 @@ inline void OverlappingPair::addContactManifold(const ContactManifoldInfo& conta mContactManifoldSet.addContactManifold(contactManifoldInfo); } -// Return the cached separating axis -inline Vector3 OverlappingPair::getCachedSeparatingAxis() const { - return mCachedSeparatingAxis; +// Return the last frame collision info +inline LastFrameCollisionInfo& OverlappingPair::getLastFrameCollisionInfo() { + return mLastFrameCollisionInfo; } -// Set the cached separating axis -inline void OverlappingPair::setCachedSeparatingAxis(const Vector3& axis) { - mCachedSeparatingAxis = axis; -} - - // Return the number of contact points in the contact manifold inline uint OverlappingPair::getNbContactPoints() const { return mContactManifoldSet.getTotalNbContactPoints(); From 6b0ba1cfbb217fd3c90394e48ba25d5cf3e2dc59 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 29 May 2017 22:30:30 +0200 Subject: [PATCH 072/248] Fix issues in collision detection --- src/collision/CollisionDetection.cpp | 32 +++++++++++++------ src/collision/CollisionDetection.h | 2 +- .../narrowphase/SAT/SATAlgorithm.cpp | 14 ++++---- .../narrowphase/SphereVsCapsuleAlgorithm.cpp | 2 -- 4 files changed, 31 insertions(+), 19 deletions(-) mode change 100644 => 100755 src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 9ce02f9d..dc78d59e 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -407,10 +407,10 @@ void CollisionDetection::clearContactPoints() { } // Compute the middle-phase collision detection between two proxy shapes -NarrowPhaseInfo* CollisionDetection::computeMiddlePhaseForProxyShapes(ProxyShape* shape1, ProxyShape* shape2) { +NarrowPhaseInfo* CollisionDetection::computeMiddlePhaseForProxyShapes(OverlappingPair* pair) { - // Create a temporary overlapping pair - OverlappingPair pair(shape1, shape2, 0, mMemoryAllocator); + ProxyShape* shape1 = pair->getShape1(); + ProxyShape* shape2 = pair->getShape2(); // ------------------------------------------------------- @@ -424,7 +424,7 @@ NarrowPhaseInfo* CollisionDetection::computeMiddlePhaseForProxyShapes(ProxyShape // No middle-phase is necessary, simply create a narrow phase info // for the narrow-phase collision detection - narrowPhaseInfo = new (mMemoryAllocator.allocate(sizeof(NarrowPhaseInfo))) NarrowPhaseInfo(&pair, shape1->getCollisionShape(), + narrowPhaseInfo = new (mMemoryAllocator.allocate(sizeof(NarrowPhaseInfo))) NarrowPhaseInfo(pair, shape1->getCollisionShape(), shape2->getCollisionShape(), shape1->getLocalToWorldTransform(), shape2->getLocalToWorldTransform(), shape1->getCachedCollisionData(), shape2->getCachedCollisionData()); @@ -436,7 +436,7 @@ NarrowPhaseInfo* CollisionDetection::computeMiddlePhaseForProxyShapes(ProxyShape // Run the middle-phase collision detection algorithm to find the triangles of the concave // shape we need to use during the narrow-phase collision detection - computeConvexVsConcaveMiddlePhase(&pair, mMemoryAllocator, &narrowPhaseInfo); + computeConvexVsConcaveMiddlePhase(pair, mMemoryAllocator, &narrowPhaseInfo); } return narrowPhaseInfo; @@ -503,8 +503,11 @@ bool CollisionDetection::testOverlap(CollisionBody* body1, CollisionBody* body2) const CollisionShapeType shape1Type = body1ProxyShape->getCollisionShape()->getType(); const CollisionShapeType shape2Type = body2ProxyShape->getCollisionShape()->getType(); + // Create a temporary overlapping pair + OverlappingPair pair(body1ProxyShape, body2ProxyShape, 0, mMemoryAllocator); + // Compute the middle-phase collision detection between the two shapes - NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(body1ProxyShape, body2ProxyShape); + NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); bool isColliding = false; @@ -591,8 +594,11 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl const CollisionShapeType shape1Type = bodyProxyShape->getCollisionShape()->getType(); const CollisionShapeType shape2Type = proxyShape->getCollisionShape()->getType(); + // Create a temporary overlapping pair + OverlappingPair pair(bodyProxyShape, proxyShape, 0, mMemoryAllocator); + // Compute the middle-phase collision detection between the two shapes - NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(bodyProxyShape, proxyShape); + NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); bool isColliding = false; @@ -666,8 +672,11 @@ void CollisionDetection::testCollision(CollisionBody* body1, CollisionBody* body // Test if the AABBs of the two proxy shapes overlap if (aabb1.testCollision(aabb2)) { + // Create a temporary overlapping pair + OverlappingPair pair(body1ProxyShape, body2ProxyShape, 0, mMemoryAllocator); + // Compute the middle-phase collision detection between the two shapes - NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(body1ProxyShape, body2ProxyShape); + NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); const CollisionShapeType shape1Type = body1ProxyShape->getCollisionShape()->getType(); const CollisionShapeType shape2Type = body2ProxyShape->getCollisionShape()->getType(); @@ -747,8 +756,11 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c const CollisionShapeType shape1Type = bodyProxyShape->getCollisionShape()->getType(); const CollisionShapeType shape2Type = proxyShape->getCollisionShape()->getType(); + // Create a temporary overlapping pair + OverlappingPair pair(bodyProxyShape, proxyShape, 0, mMemoryAllocator); + // Compute the middle-phase collision detection between the two shapes - NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(bodyProxyShape, proxyShape); + NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); // For each narrow-phase info object while (narrowPhaseInfo != nullptr) { @@ -816,7 +828,7 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { mBroadPhaseAlgorithm.testOverlappingShapes(shape1, shape2)) { // Compute the middle-phase collision detection between the two shapes - NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(shape1, shape2); + NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(pair); const CollisionShapeType shape1Type = shape1->getCollisionShape()->getType(); const CollisionShapeType shape2Type = shape2->getCollisionShape()->getType(); diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index 29200ec7..3fe88812 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -136,7 +136,7 @@ class CollisionDetection { NarrowPhaseInfo** firstNarrowPhaseInfo); /// Compute the middle-phase collision detection between two proxy shapes - NarrowPhaseInfo* computeMiddlePhaseForProxyShapes(ProxyShape* shape1, ProxyShape* shape2); + NarrowPhaseInfo* computeMiddlePhaseForProxyShapes(OverlappingPair* pair); public : diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 6e85e303..91db1383 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -48,9 +48,10 @@ bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(const NarrowPhaseInfo* bool isSphereShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE; - assert(isSphereShape1 || narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON); - assert(!isSphereShape1 || narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON); - assert(!isSphereShape1 || narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::SPHERE); + assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON || + narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); + assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE || + narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::SPHERE); // Get the capsule collision shapes const SphereShape* sphere = static_cast(isSphereShape1 ? narrowPhaseInfo->collisionShape1 : narrowPhaseInfo->collisionShape2); @@ -116,9 +117,10 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(const NarrowPhaseInfo* bool isCapsuleShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE; - assert(isCapsuleShape1 || narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON); - assert(!isCapsuleShape1 || narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON); - assert(!isCapsuleShape1 || narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CAPSULE); + assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON || + narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); + assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE || + narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CAPSULE); // Get the collision shapes const CapsuleShape* capsuleShape = static_cast(isCapsuleShape1 ? narrowPhaseInfo->collisionShape1 : narrowPhaseInfo->collisionShape2); diff --git a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp old mode 100644 new mode 100755 index cd437d6e..86255c2b --- a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp @@ -39,8 +39,6 @@ bool SphereVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseI bool isSphereShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE; assert(isSphereShape1 || narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE); - assert(!isSphereShape1 || narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE); - assert(!isSphereShape1 || narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::SPHERE); // Get the collision shapes const SphereShape* sphereShape = static_cast(isSphereShape1 ? narrowPhaseInfo->collisionShape1 : narrowPhaseInfo->collisionShape2); From 3ec8dddd9198c976899041a822125c6f5faafa29 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 29 May 2017 22:31:33 +0200 Subject: [PATCH 073/248] Add box shapes in collision detection scene of testbed application --- .../CollisionDetectionScene.cpp | 46 +++++++++++++++---- .../CollisionDetectionScene.h | 2 + 2 files changed, 40 insertions(+), 8 deletions(-) diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp index 21a0b51a..6351028a 100755 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp @@ -50,10 +50,10 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mCollisionWorld = new rp3d::CollisionWorld(); // ---------- Sphere 1 ---------- // - openglframework::Vector3 position1(0, 0, 0); + openglframework::Vector3 position1(12, 0, 0); // Create a sphere and a corresponding collision body in the dynamics world - mSphere1 = new Sphere(6, position1, mCollisionWorld, mMeshFolderPath); + mSphere1 = new Sphere(4, position1, mCollisionWorld, mMeshFolderPath); mAllShapes.push_back(mSphere1); // Set the color @@ -61,10 +61,10 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mSphere1->setSleepingColor(mRedColorDemo); // ---------- Sphere 2 ---------- // - openglframework::Vector3 position2(4, 0, 0); + openglframework::Vector3 position2(0, 0, 0); // Create a sphere and a corresponding collision body in the dynamics world - mSphere2 = new Sphere(4, position2, mCollisionWorld, mMeshFolderPath); + mSphere2 = new Sphere(2, position2, mCollisionWorld, mMeshFolderPath); mAllShapes.push_back(mSphere2); // Set the color @@ -72,7 +72,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mSphere2->setSleepingColor(mRedColorDemo); // ---------- Capsule 1 ---------- // - openglframework::Vector3 position3(4, 0, 0); + openglframework::Vector3 position3(8, 0, 0); // Create a cylinder and a corresponding collision body in the dynamics world mCapsule1 = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, position3, mCollisionWorld, mMeshFolderPath); @@ -83,7 +83,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mCapsule1->setSleepingColor(mRedColorDemo); // ---------- Capsule 2 ---------- // - openglframework::Vector3 position4(-4, 0, 0); + openglframework::Vector3 position4(-8, 0, 0); // Create a cylinder and a corresponding collision body in the dynamics world mCapsule2 = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, position4, mCollisionWorld, mMeshFolderPath); @@ -93,6 +93,28 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mCapsule2->setColor(mGreyColorDemo); mCapsule2->setSleepingColor(mRedColorDemo); + // ---------- Box 1 ---------- // + openglframework::Vector3 position5(0, -12, 0); + + // Create a cylinder and a corresponding collision body in the dynamics world + mBox1 = new Box(BOX_SIZE, position5, mCollisionWorld, mMeshFolderPath); + mAllShapes.push_back(mBox1); + + // Set the color + mBox1->setColor(mGreyColorDemo); + mBox1->setSleepingColor(mRedColorDemo); + + // ---------- Box 2 ---------- // + openglframework::Vector3 position6(0, 12, 0); + + // Create a cylinder and a corresponding collision body in the dynamics world + mBox2 = new Box(openglframework::Vector3(3, 2, 5), position6, mCollisionWorld, mMeshFolderPath); + mAllShapes.push_back(mBox2); + + // Set the color + mBox2->setColor(mGreyColorDemo); + mBox2->setSleepingColor(mRedColorDemo); + // ---------- Cone ---------- // //openglframework::Vector3 position4(0, 0, 0); @@ -174,6 +196,12 @@ CollisionDetectionScene::~CollisionDetectionScene() { mCollisionWorld->destroyCollisionBody(mCapsule2->getCollisionBody()); delete mCapsule2; + mCollisionWorld->destroyCollisionBody(mBox1->getCollisionBody()); + delete mBox1; + + mCollisionWorld->destroyCollisionBody(mBox2->getCollisionBody()); + delete mBox2; + /* // Destroy the corresponding rigid body from the dynamics world mCollisionWorld->destroyCollisionBody(mCone->getCollisionBody()); @@ -250,6 +278,8 @@ void CollisionDetectionScene::renderSinglePass(openglframework::Shader& shader, if (mSphere2->getCollisionBody()->isActive()) mSphere2->render(shader, worldToCameraMatrix, mIsWireframeEnabled); if (mCapsule1->getCollisionBody()->isActive()) mCapsule1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); if (mCapsule2->getCollisionBody()->isActive()) mCapsule2->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + if (mBox1->getCollisionBody()->isActive()) mBox1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + if (mBox2->getCollisionBody()->isActive()) mBox2->render(shader, worldToCameraMatrix, mIsWireframeEnabled); /* if (mBox->getCollisionBody()->isActive()) mBox->render(shader, worldToCameraMatrix); @@ -286,8 +316,8 @@ bool CollisionDetectionScene::keyboardEvent(int key, int scancode, int action, i return true; } - float stepDist = 0.5f; - float stepAngle = 20 * (3.14f / 180.0f); + float stepDist = 0.2f; + float stepAngle = 15 * (3.14f / 180.0f); if (key == GLFW_KEY_RIGHT && action == GLFW_PRESS) { rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.h b/testbed/scenes/collisiondetection/CollisionDetectionScene.h index 6eeeb25b..51a05412 100755 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.h +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.h @@ -133,6 +133,8 @@ class CollisionDetectionScene : public SceneDemo { Sphere* mSphere2; Capsule* mCapsule1; Capsule* mCapsule2; + Box* mBox1; + Box* mBox2; //Cone* mCone; //Cylinder* mCylinder; //Capsule* mCapsule; From b1597c508fcfae1cd733ece9bfabfb65a1c59694 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 31 May 2017 07:36:39 +0200 Subject: [PATCH 074/248] Working on temporal coherence in SAT algorithm --- .../narrowphase/SAT/SATAlgorithm.cpp | 385 +++++++++++++----- src/collision/narrowphase/SAT/SATAlgorithm.h | 19 + 2 files changed, 305 insertions(+), 99 deletions(-) diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 91db1383..767aff8a 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -71,27 +71,64 @@ bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(const NarrowPhaseInfo* decimal minPenetrationDepth = DECIMAL_LARGEST; uint minFaceIndex = 0; - // For each face of the convex mesh - for (uint f = 0; f < polyhedron->getNbFaces(); f++) { + // True if the shapes were overlapping in the previous frame and are + // still overlapping on the same axis in this frame + bool isTemporalCoherenceValid = false; - // Get the face - HalfEdgeStructure::Face face = polyhedron->getFace(f); + LastFrameCollisionInfo& lastFrameInfo = narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo(); - // Get the face normal - const Vector3 faceNormal = polyhedron->getFaceNormal(f); + // If the last frame collision info is valid and was also using SAT algorithm + if (lastFrameInfo.isValid && lastFrameInfo.wasUsingSAT) { - Vector3 sphereCenterToFacePoint = polyhedron->getVertexPosition(face.faceVertices[0]) - sphereCenter; - decimal penetrationDepth = sphereCenterToFacePoint.dot(faceNormal) + sphere->getRadius(); + // We perform temporal coherence, we check if there is still an overlapping along the previous minimum separating + // axis. If it is the case, we directly report the collision without executing the whole SAT algorithm again. If + // the shapes are still separated along this axis, we directly exit with no collision. - // If the penetration depth is negative, we have found a separating axis + // Compute the penetration depth of the shapes along the face normal direction + decimal penetrationDepth = computePolyhedronFaceVsSpherePenetrationDepth(lastFrameInfo.satMinAxisFaceIndex, polyhedron, + sphere, sphereCenter); + + // If the previous axis is a separating axis if (penetrationDepth <= decimal(0.0)) { + + // Return no collision return false; } - // Check if we have found a new minimum penetration axis - if (penetrationDepth < minPenetrationDepth) { + // The two shapes are overlapping as in the previous frame and on the same axis, therefore + // we will skip the entire SAT algorithm because the minimum separating axis did not change + isTemporalCoherenceValid = lastFrameInfo.wasColliding; + + if (isTemporalCoherenceValid) { + minPenetrationDepth = penetrationDepth; - minFaceIndex = f; + minFaceIndex = lastFrameInfo.satMinAxisFaceIndex; + } + } + + // We the shapes are still overlapping in the same axis as in + // the previous frame, we skip the whole SAT algorithm + if (!isTemporalCoherenceValid) { + + // For each face of the convex mesh + for (uint 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); + + // If the penetration depth is negative, we have found a separating axis + if (penetrationDepth <= decimal(0.0)) { + + lastFrameInfo.satMinAxisFaceIndex = f; + + return false; + } + + // Check if we have found a new minimum penetration axis + if (penetrationDepth < minPenetrationDepth) { + minPenetrationDepth = penetrationDepth; + minFaceIndex = f; + } } } @@ -109,9 +146,27 @@ bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(const NarrowPhaseInfo* isSphereShape1 ? contactPointSphereLocal : contactPointPolyhedronLocal, isSphereShape1 ? contactPointPolyhedronLocal : contactPointSphereLocal); + lastFrameInfo.satMinAxisFaceIndex = minFaceIndex; + return true; } +// 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, + const SphereShape* sphere, const Vector3& sphereCenter) const { + + // Get the face + HalfEdgeStructure::Face face = polyhedron->getFace(faceIndex); + + // Get the face normal + const Vector3 faceNormal = polyhedron->getFaceNormal(faceIndex); + + Vector3 sphereCenterToFacePoint = polyhedron->getVertexPosition(face.faceVertices[0]) - sphereCenter; + decimal penetrationDepth = sphereCenterToFacePoint.dot(faceNormal) + sphere->getRadius(); + + return penetrationDepth; +} + // Test collision between a capsule and a convex mesh bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { @@ -131,6 +186,11 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(const NarrowPhaseInfo* const Transform polyhedronToCapsuleTransform = capsuleToWorld.getInverse() * polyhedronToWorld; + // Compute the end-points of the inner segment of the capsule + const Vector3 capsuleSegA(0, -capsuleShape->getHeight() * decimal(0.5), 0); + const Vector3 capsuleSegB(0, capsuleShape->getHeight() * decimal(0.5), 0); + const Vector3 capsuleSegmentAxis = capsuleSegB - capsuleSegA; + // Minimum penetration depth decimal minPenetrationDepth = DECIMAL_LARGEST; uint minFaceIndex = 0; @@ -140,80 +200,151 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(const NarrowPhaseInfo* Vector3 separatingPolyhedronEdgeVertex1; Vector3 separatingPolyhedronEdgeVertex2; - // For each face of the convex mesh - for (uint f = 0; f < polyhedron->getNbFaces(); f++) { + // True if the shapes were overlapping in the previous frame and are + // still overlapping on the same axis in this frame + bool isTemporalCoherenceValid = false; - // Get the face - HalfEdgeStructure::Face face = polyhedron->getFace(f); + LastFrameCollisionInfo& lastFrameInfo = narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo(); - // Get the face normal - const Vector3 faceNormal = polyhedron->getFaceNormal(f); + // If the last frame collision info is valid and was also using SAT algorithm + if (lastFrameInfo.isValid && lastFrameInfo.wasUsingSAT) { - // Compute the penetration depth (using the capsule support in the direction opposite to the face normal) - const Vector3 faceNormalCapsuleSpace = polyhedronToCapsuleTransform.getOrientation() * faceNormal; - const Vector3 capsuleSupportPoint = capsuleShape->getLocalSupportPointWithMargin(-faceNormalCapsuleSpace, nullptr); - const Vector3 pointOnPolyhedronFace = polyhedronToCapsuleTransform * polyhedron->getVertexPosition(face.faceVertices[0]); - const Vector3 capsuleSupportPointToFacePoint = pointOnPolyhedronFace - capsuleSupportPoint; - const decimal penetrationDepth = capsuleSupportPointToFacePoint.dot(faceNormal); + // We perform temporal coherence, we check if there is still an overlapping along the previous minimum separating + // axis. If it is the case, we directly report the collision without executing the whole SAT algorithm again. If + // the shapes are still separated along this axis, we directly exit with no collision. - // If the penetration depth is negative, we have found a separating axis - if (penetrationDepth <= decimal(0.0)) { - return false; + // If the previous minimum separation axis was a face normal of the polyhedron + if (lastFrameInfo.satIsAxisFacePolyhedron1) { + + Vector3 outFaceNormalCapsuleSpace; + + // Compute the penetration depth along the polyhedron face normal direction + const decimal penetrationDepth = computePolyhedronFaceVsCapsulePenetrationDepth(lastFrameInfo.satMinAxisFaceIndex, polyhedron, + capsuleShape, polyhedronToCapsuleTransform, + outFaceNormalCapsuleSpace); + + // If the previous axis is a separating axis + if (penetrationDepth <= decimal(0.0)) { + + // Return no collision + return false; + } + + // The two shapes are overlapping as in the previous frame and on the same axis, therefore + // we will skip the entire SAT algorithm because the minimum separating axis did not change + isTemporalCoherenceValid = lastFrameInfo.wasColliding; + + if (isTemporalCoherenceValid) { + + minPenetrationDepth = penetrationDepth; + minFaceIndex = lastFrameInfo.satMinAxisFaceIndex; + isMinPenetrationFaceNormal = true; + separatingAxisCapsuleSpace = outFaceNormalCapsuleSpace; + } } + else { // If the previous minimum separation axis the cross product of the capsule inner segment and an edge of the polyhedron - // Check if we have found a new minimum penetration axis - if (penetrationDepth < minPenetrationDepth) { - minPenetrationDepth = penetrationDepth; - minFaceIndex = f; - isMinPenetrationFaceNormal = true; - separatingAxisCapsuleSpace = faceNormalCapsuleSpace; + // Get an edge from the polyhedron (convert it into the capsule local-space) + HalfEdgeStructure::Edge edge = polyhedron->getHalfEdge(lastFrameInfo.satMinEdge1Index); + const Vector3 edgeVertex1 = polyhedron->getVertexPosition(edge.vertexIndex); + const Vector3 edgeVertex2 = polyhedron->getVertexPosition(polyhedron->getHalfEdge(edge.nextEdgeIndex).vertexIndex); + const Vector3 edgeDirectionCapsuleSpace = polyhedronToCapsuleTransform.getOrientation() * (edgeVertex2 - edgeVertex1); + + Vector3 outAxis; + + // Compute the penetration depth along this axis + const decimal penetrationDepth = computeEdgeVsCapsuleInnerSegmentPenetrationDepth(polyhedron, capsuleShape, + capsuleSegmentAxis, edgeVertex1, + edgeDirectionCapsuleSpace, + polyhedronToCapsuleTransform, + outAxis); + + // If the previous axis is a separating axis + if (penetrationDepth <= decimal(0.0)) { + + // Return no collision + return false; + } + + // The two shapes are overlapping as in the previous frame and on the same axis, therefore + // we will skip the entire SAT algorithm because the minimum separating axis did not change + isTemporalCoherenceValid = lastFrameInfo.wasColliding; + + if (isTemporalCoherenceValid) { + + minPenetrationDepth = penetrationDepth; + minEdgeIndex = lastFrameInfo.satMinEdge1Index; + isMinPenetrationFaceNormal = false; + separatingAxisCapsuleSpace = outAxis; + separatingPolyhedronEdgeVertex1 = edgeVertex1; + separatingPolyhedronEdgeVertex2 = edgeVertex2; + } } } - // Compute the end-points of the inner segment of the capsule - const Vector3 capsuleSegA(0, -capsuleShape->getHeight() * decimal(0.5), 0); - const Vector3 capsuleSegB(0, capsuleShape->getHeight() * decimal(0.5), 0); - const Vector3 capsuleSegmentAxis = capsuleSegB - capsuleSegA; + // We the shapes are still overlapping in the same axis as in + // the previous frame, we skip the whole SAT algorithm + if (!isTemporalCoherenceValid) { - // 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 each face of the convex mesh + for (uint f = 0; f < polyhedron->getNbFaces(); f++) { - // Get an edge from the polyhedron (convert it into the capsule local-space) - HalfEdgeStructure::Edge edge = polyhedron->getHalfEdge(e); - const Vector3 edgeVertex1 = polyhedron->getVertexPosition(edge.vertexIndex); - const Vector3 edgeVertex2 = polyhedron->getVertexPosition(polyhedron->getHalfEdge(edge.nextEdgeIndex).vertexIndex); - const Vector3 edgeDirectionCapsuleSpace = polyhedronToCapsuleTransform.getOrientation() * (edgeVertex2 - edgeVertex1); + Vector3 outFaceNormalCapsuleSpace; - HalfEdgeStructure::Edge twinEdge = polyhedron->getHalfEdge(edge.twinEdgeIndex); - const Vector3 adjacentFace1Normal = polyhedronToCapsuleTransform.getOrientation() * polyhedron->getFaceNormal(edge.faceIndex); - const Vector3 adjacentFace2Normal = polyhedronToCapsuleTransform.getOrientation() * polyhedron->getFaceNormal(twinEdge.faceIndex); + // Compute the penetration depth + const decimal penetrationDepth = computePolyhedronFaceVsCapsulePenetrationDepth(f, polyhedron, capsuleShape, + polyhedronToCapsuleTransform, + outFaceNormalCapsuleSpace); - // Check using the Gauss Map if this edge cross product can be as separating axis - if (isMinkowskiFaceCapsuleVsEdge(capsuleSegmentAxis, adjacentFace1Normal, adjacentFace2Normal)) { + // If the penetration depth is negative, we have found a separating axis + if (penetrationDepth <= decimal(0.0)) { - // Compute the axis to test (cross product between capsule inner segment and polyhedron edge) - Vector3 axis = capsuleSegmentAxis.cross(edgeDirectionCapsuleSpace); + lastFrameInfo.satIsAxisFacePolyhedron1 = true; + lastFrameInfo.satMinAxisFaceIndex = f; - // Skip separating axis test if polyhedron edge is parallel to the capsule inner segment - if (axis.lengthSquare() >= decimal(0.00001)) { + return false; + } - const Vector3 polyhedronCentroid = polyhedronToCapsuleTransform * polyhedron->getCentroid(); - const Vector3 pointOnPolyhedronEdge = polyhedronToCapsuleTransform * edgeVertex1; + // Check if we have found a new minimum penetration axis + if (penetrationDepth < minPenetrationDepth) { + minPenetrationDepth = penetrationDepth; + minFaceIndex = f; + isMinPenetrationFaceNormal = true; + separatingAxisCapsuleSpace = outFaceNormalCapsuleSpace; + } + } - // Swap axis direction if necessary such that it points out of the polyhedron - if (axis.dot(pointOnPolyhedronEdge - polyhedronCentroid) < 0) { - axis = -axis; - } + // 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) { - axis.normalize(); + // Get an edge from the polyhedron (convert it into the capsule local-space) + HalfEdgeStructure::Edge edge = polyhedron->getHalfEdge(e); + const Vector3 edgeVertex1 = polyhedron->getVertexPosition(edge.vertexIndex); + const Vector3 edgeVertex2 = polyhedron->getVertexPosition(polyhedron->getHalfEdge(edge.nextEdgeIndex).vertexIndex); + const Vector3 edgeDirectionCapsuleSpace = polyhedronToCapsuleTransform.getOrientation() * (edgeVertex2 - edgeVertex1); + + HalfEdgeStructure::Edge twinEdge = polyhedron->getHalfEdge(edge.twinEdgeIndex); + const Vector3 adjacentFace1Normal = polyhedronToCapsuleTransform.getOrientation() * polyhedron->getFaceNormal(edge.faceIndex); + const Vector3 adjacentFace2Normal = polyhedronToCapsuleTransform.getOrientation() * polyhedron->getFaceNormal(twinEdge.faceIndex); + + // Check using the Gauss Map if this edge cross product can be as separating axis + if (isMinkowskiFaceCapsuleVsEdge(capsuleSegmentAxis, adjacentFace1Normal, adjacentFace2Normal)) { + + Vector3 outAxis; // Compute the penetration depth - const Vector3 capsuleSupportPoint = capsuleShape->getLocalSupportPointWithMargin(-axis, nullptr); - const Vector3 capsuleSupportPointToEdgePoint = pointOnPolyhedronEdge - capsuleSupportPoint; - const decimal penetrationDepth = capsuleSupportPointToEdgePoint.dot(axis); + const decimal penetrationDepth = computeEdgeVsCapsuleInnerSegmentPenetrationDepth(polyhedron, capsuleShape, + capsuleSegmentAxis, edgeVertex1, + edgeDirectionCapsuleSpace, + polyhedronToCapsuleTransform, + outAxis); // If the penetration depth is negative, we have found a separating axis if (penetrationDepth <= decimal(0.0)) { + + lastFrameInfo.satIsAxisFacePolyhedron1 = false; + lastFrameInfo.satMinEdge1Index = e; + return false; } @@ -222,12 +353,13 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(const NarrowPhaseInfo* minPenetrationDepth = penetrationDepth; minEdgeIndex = e; isMinPenetrationFaceNormal = false; - separatingAxisCapsuleSpace = axis; + separatingAxisCapsuleSpace = outAxis; separatingPolyhedronEdgeVertex1 = edgeVertex1; separatingPolyhedronEdgeVertex2 = edgeVertex2; } } } + } // Convert the inner capsule segment points into the polyhedron local-space @@ -246,6 +378,9 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(const NarrowPhaseInfo* polyhedronToCapsuleTransform, normalWorld, separatingAxisCapsuleSpace, capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, contactManifoldInfo, isCapsuleShape1); + + lastFrameInfo.satIsAxisFacePolyhedron1 = true; + lastFrameInfo.satMinAxisFaceIndex = minFaceIndex; } else { // The separating axis is the cross product of a polyhedron edge and the inner capsule segment @@ -264,11 +399,68 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(const NarrowPhaseInfo* contactManifoldInfo.addContactPoint(normalWorld, minPenetrationDepth, isCapsuleShape1 ? contactPointCapsule : closestPointPolyhedronEdge, isCapsuleShape1 ? closestPointPolyhedronEdge : contactPointCapsule); + + lastFrameInfo.satIsAxisFacePolyhedron1 = false; + lastFrameInfo.satMinEdge1Index = minEdgeIndex; } return true; } +// Compute the penetration depth when the separating axis is the cross product of polyhedron edge and capsule inner segment +decimal SATAlgorithm::computeEdgeVsCapsuleInnerSegmentPenetrationDepth(const ConvexPolyhedronShape* polyhedron, const CapsuleShape* capsule, + const Vector3& capsuleSegmentAxis, const Vector3& edgeVertex1, + const Vector3& edgeDirectionCapsuleSpace, + const Transform& polyhedronToCapsuleTransform, Vector3& outAxis) const { + + decimal penetrationDepth = DECIMAL_LARGEST; + + // Compute the axis to test (cross product between capsule inner segment and polyhedron edge) + outAxis = capsuleSegmentAxis.cross(edgeDirectionCapsuleSpace); + + // Skip separating axis test if polyhedron edge is parallel to the capsule inner segment + if (outAxis.lengthSquare() >= decimal(0.00001)) { + + const Vector3 polyhedronCentroid = polyhedronToCapsuleTransform * polyhedron->getCentroid(); + const Vector3 pointOnPolyhedronEdge = polyhedronToCapsuleTransform * edgeVertex1; + + // Swap axis direction if necessary such that it points out of the polyhedron + if (outAxis.dot(pointOnPolyhedronEdge - polyhedronCentroid) < 0) { + outAxis = -outAxis; + } + + outAxis.normalize(); + + // Compute the penetration depth + const Vector3 capsuleSupportPoint = capsule->getLocalSupportPointWithMargin(-outAxis, nullptr); + const Vector3 capsuleSupportPointToEdgePoint = pointOnPolyhedronEdge - capsuleSupportPoint; + penetrationDepth = capsuleSupportPointToEdgePoint.dot(outAxis); + } + + return penetrationDepth; +} + +// 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, + const CapsuleShape* capsule, const Transform& polyhedronToCapsuleTransform, + Vector3& outFaceNormalCapsuleSpace) const { + + // Get the face + HalfEdgeStructure::Face face = polyhedron->getFace(polyhedronFaceIndex); + + // Get the face normal + const Vector3 faceNormal = polyhedron->getFaceNormal(polyhedronFaceIndex); + + // Compute the penetration depth (using the capsule support in the direction opposite to the face normal) + outFaceNormalCapsuleSpace = polyhedronToCapsuleTransform.getOrientation() * faceNormal; + const Vector3 capsuleSupportPoint = capsule->getLocalSupportPointWithMargin(-outFaceNormalCapsuleSpace, nullptr); + const Vector3 pointOnPolyhedronFace = polyhedronToCapsuleTransform * polyhedron->getVertexPosition(face.faceVertices[0]); + const Vector3 capsuleSupportPointToFacePoint = pointOnPolyhedronFace - capsuleSupportPoint; + const decimal penetrationDepth = capsuleSupportPointToFacePoint.dot(faceNormal); + + return penetrationDepth; +} + // Compute the two contact points between a polyhedron and a capsule when the separating // axis is a face normal of the polyhedron void SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceIndex, decimal capsuleRadius, const ConvexPolyhedronShape* polyhedron, @@ -424,47 +616,42 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(const NarrowP HalfEdgeStructure::Edge edge1 = polyhedron1->getHalfEdge(lastFrameInfo.satMinEdge1Index); HalfEdgeStructure::Edge edge2 = polyhedron2->getHalfEdge(lastFrameInfo.satMinEdge2Index); - // If the two edges build a minkowski face (and the cross product is - // therefore a candidate for separating axis - if (testEdgesBuildMinkowskiFace(polyhedron1, edge1, polyhedron2, edge2, polyhedron1ToPolyhedron2)) { + Vector3 separatingAxisPolyhedron2Space; - Vector3 separatingAxisPolyhedron2Space; + const Vector3 edge1A = polyhedron1ToPolyhedron2 * polyhedron1->getVertexPosition(edge1.vertexIndex); + const Vector3 edge1B = polyhedron1ToPolyhedron2 * polyhedron1->getVertexPosition(polyhedron1->getHalfEdge(edge1.nextEdgeIndex).vertexIndex); + const Vector3 edge1Direction = edge1B - edge1A; + const Vector3 edge2A = polyhedron2->getVertexPosition(edge2.vertexIndex); + const Vector3 edge2B = polyhedron2->getVertexPosition(polyhedron2->getHalfEdge(edge2.nextEdgeIndex).vertexIndex); + const Vector3 edge2Direction = edge2B - edge2A; - const Vector3 edge1A = polyhedron1ToPolyhedron2 * polyhedron1->getVertexPosition(edge1.vertexIndex); - const Vector3 edge1B = polyhedron1ToPolyhedron2 * polyhedron1->getVertexPosition(polyhedron1->getHalfEdge(edge1.nextEdgeIndex).vertexIndex); - const Vector3 edge1Direction = edge1B - edge1A; - const Vector3 edge2A = polyhedron2->getVertexPosition(edge2.vertexIndex); - const Vector3 edge2B = polyhedron2->getVertexPosition(polyhedron2->getHalfEdge(edge2.nextEdgeIndex).vertexIndex); - const Vector3 edge2Direction = edge2B - edge2A; + // Compute the penetration depth + decimal penetrationDepth = computeDistanceBetweenEdges(edge1A, edge2A, polyhedron2->getCentroid(), + edge1Direction, edge2Direction, separatingAxisPolyhedron2Space); - // Compute the penetration depth - decimal penetrationDepth = computeDistanceBetweenEdges(edge1A, edge2A, polyhedron2->getCentroid(), - edge1Direction, edge2Direction, separatingAxisPolyhedron2Space); + // If the previous axis is a separating axis + if (penetrationDepth <= decimal(0.0)) { - // If the previous axis is a separating axis - if (penetrationDepth <= decimal(0.0)) { + // Return no collision + return false; + } - // Return no collision - return false; - } + // The two shapes are overlapping as in the previous frame and on the same axis, therefore + // we will skip the entire SAT algorithm because the minimum separating axis did not change + isTemporalCoherenceValid = lastFrameInfo.wasColliding; - // The two shapes are overlapping as in the previous frame and on the same axis, therefore - // we will skip the entire SAT algorithm because the minimum separating axis did not change - isTemporalCoherenceValid = lastFrameInfo.wasColliding; + if (isTemporalCoherenceValid) { - if (isTemporalCoherenceValid) { - - minPenetrationDepth = penetrationDepth; - isMinPenetrationFaceNormal = false; - isMinPenetrationFaceNormalPolyhedron1 = false; - minSeparatingEdge1Index = lastFrameInfo.satMinEdge1Index; - minSeparatingEdge2Index = lastFrameInfo.satMinEdge2Index; - separatingEdge1A = edge1A; - separatingEdge1B = edge1B; - separatingEdge2A = edge2A; - separatingEdge2B = edge2B; - minEdgeVsEdgeSeparatingAxisPolyhedron2Space = separatingAxisPolyhedron2Space; - } + minPenetrationDepth = penetrationDepth; + isMinPenetrationFaceNormal = false; + isMinPenetrationFaceNormalPolyhedron1 = false; + minSeparatingEdge1Index = lastFrameInfo.satMinEdge1Index; + minSeparatingEdge2Index = lastFrameInfo.satMinEdge2Index; + separatingEdge1A = edge1A; + separatingEdge1B = edge1B; + separatingEdge2A = edge2A; + separatingEdge2B = edge2B; + minEdgeVsEdgeSeparatingAxisPolyhedron2Space = separatingAxisPolyhedron2Space; } } } @@ -472,7 +659,7 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(const NarrowP // We the shapes are still overlapping in the same axis as in // the previous frame, we skip the whole SAT algorithm - if (isTemporalCoherenceValid) { + if (!isTemporalCoherenceValid) { // Test all the face normals of the polyhedron 1 for separating axis uint faceIndex; diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.h b/src/collision/narrowphase/SAT/SATAlgorithm.h index 3512ef4d..7a002fce 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.h +++ b/src/collision/narrowphase/SAT/SATAlgorithm.h @@ -31,9 +31,13 @@ #include "collision/NarrowPhaseInfo.h" #include "collision/shapes/ConvexPolyhedronShape.h" + /// ReactPhysics3D namespace namespace reactphysics3d { +class CapsuleShape; +class SphereShape; + // Class SATAlgorithm class SATAlgorithm { @@ -77,6 +81,21 @@ class SATAlgorithm { decimal testFacesDirectionPolyhedronVsPolyhedron(const ConvexPolyhedronShape* polyhedron1, const ConvexPolyhedronShape* polyhedron2, 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, + 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, + const CapsuleShape* capsule, const Transform& polyhedronToCapsuleTransform, + Vector3& outFaceNormalCapsuleSpace) const; + + /// Compute the penetration depth when the separating axis is the cross product of polyhedron edge and capsule inner segment + decimal computeEdgeVsCapsuleInnerSegmentPenetrationDepth(const ConvexPolyhedronShape* polyhedron, const CapsuleShape* capsule, + const Vector3& capsuleSegmentAxis, const Vector3& edgeVertex1, + const Vector3& edgeDirectionCapsuleSpace, + const Transform& polyhedronToCapsuleTransform, Vector3& outAxis) const; + public : // -------------------- Methods -------------------- // From 95db87fd624fd2cde6b6f4f750eda8ba7a4bd205 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 5 Jun 2017 00:05:49 +0200 Subject: [PATCH 075/248] Working on contacts reduction --- CMakeLists.txt | 1 + src/collision/CollisionDetection.cpp | 13 +- src/collision/ContactManifold.h | 3 - src/collision/ContactManifoldInfo.cpp | 278 ++++++++++++++++++++++++++ src/collision/ContactManifoldInfo.h | 72 ++----- 5 files changed, 306 insertions(+), 61 deletions(-) create mode 100644 src/collision/ContactManifoldInfo.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 2e3be144..cba141df 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -62,6 +62,7 @@ SET (REACTPHYSICS3D_SOURCES "src/body/RigidBody.cpp" "src/collision/ContactPointInfo.h" "src/collision/ContactManifoldInfo.h" + "src/collision/ContactManifoldInfo.cpp" "src/collision/broadphase/BroadPhaseAlgorithm.h" "src/collision/broadphase/BroadPhaseAlgorithm.cpp" "src/collision/broadphase/DynamicAABBTree.h" diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index dc78d59e..0e7c8078 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -248,8 +248,8 @@ void CollisionDetection::computeNarrowPhase() { ContactManifoldInfo contactManifoldInfo(mSingleFrameAllocator); if (narrowPhaseAlgorithm->testCollision(currentNarrowPhaseInfo, contactManifoldInfo)) { - // Reduce the number of points in the contact manifold - contactManifoldInfo.reduce(); + // Reduce the number of points in the contact manifold (if necessary) + contactManifoldInfo.reduce(currentNarrowPhaseInfo->shape1ToWorldTransform); // If it is the first contact since the pairs are overlapping if (currentNarrowPhaseInfo->overlappingPair->getNbContactPoints() == 0) { @@ -696,6 +696,9 @@ void CollisionDetection::testCollision(CollisionBody* body1, CollisionBody* body ContactManifoldInfo contactManifoldInfo(mMemoryAllocator); if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactManifoldInfo)) { + // Reduce the number of points in the contact manifold (if necessary) + contactManifoldInfo.reduce(narrowPhaseInfo->shape1ToWorldTransform); + CollisionCallback::CollisionCallbackInfo collisionInfo(contactManifoldInfo, body1, body2, body1ProxyShape, body2ProxyShape); @@ -777,6 +780,9 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c ContactManifoldInfo contactManifoldInfo(mMemoryAllocator); if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactManifoldInfo)) { + // Reduce the number of points in the contact manifold (if necessary) + contactManifoldInfo.reduce(narrowPhaseInfo->shape1ToWorldTransform); + CollisionCallback::CollisionCallbackInfo collisionInfo(contactManifoldInfo, body, proxyShape->getBody(), bodyProxyShape, proxyShape); @@ -848,6 +854,9 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { ContactManifoldInfo contactManifoldInfo(mMemoryAllocator); if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactManifoldInfo)) { + // Reduce the number of points in the contact manifold (if necessary) + contactManifoldInfo.reduce(narrowPhaseInfo->shape1ToWorldTransform); + CollisionCallback::CollisionCallbackInfo collisionInfo(contactManifoldInfo, shape1->getBody(), shape2->getBody(), shape1, shape2); diff --git a/src/collision/ContactManifold.h b/src/collision/ContactManifold.h index da323c0f..893a84a7 100644 --- a/src/collision/ContactManifold.h +++ b/src/collision/ContactManifold.h @@ -37,9 +37,6 @@ /// ReactPhysics3D namespace namespace reactphysics3d { -// Constants -const uint MAX_CONTACT_POINTS_IN_MANIFOLD = 4; // Maximum number of contacts in the manifold - // Class declarations class ContactManifold; diff --git a/src/collision/ContactManifoldInfo.cpp b/src/collision/ContactManifoldInfo.cpp new file mode 100644 index 00000000..c06785ea --- /dev/null +++ b/src/collision/ContactManifoldInfo.cpp @@ -0,0 +1,278 @@ +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "ContactManifoldInfo.h" + +using namespace reactphysics3d; + +// Constructor +ContactManifoldInfo::ContactManifoldInfo(Allocator& allocator) + : mContactPointsList(nullptr), mAllocator(allocator), mNbContactPoints(0) {} + +// Destructor +ContactManifoldInfo::~ContactManifoldInfo() { + + // Remove all the contact points + reset(); +} + +// Add a new contact point into the manifold +void ContactManifoldInfo::addContactPoint(const Vector3& contactNormal, decimal penDepth, + const Vector3& localPt1, const Vector3& localPt2) { + + assert(penDepth > decimal(0.0)); + + // Create the contact point info + ContactPointInfo* contactPointInfo = new (mAllocator.allocate(sizeof(ContactPointInfo))) + ContactPointInfo(contactNormal, penDepth, localPt1, localPt2); + + // Add it into the linked list of contact points + contactPointInfo->next = mContactPointsList; + mContactPointsList = contactPointInfo; + + mNbContactPoints++; +} + +// Remove all the contact points +void ContactManifoldInfo::reset() { + + // Delete all the contact points in the linked list + ContactPointInfo* element = mContactPointsList; + while(element != nullptr) { + ContactPointInfo* elementToDelete = element; + element = element->next; + + // Delete the current element + mAllocator.release(elementToDelete, sizeof(ContactPointInfo)); + } + + mContactPointsList = nullptr; + mNbContactPoints = 0; +} + +// Reduce the number of points in the contact manifold +// This is based on the technique described by Dirk Gregorius in his +// "Contacts Creation" GDC presentation +void ContactManifoldInfo::reduce(const Transform& shape1ToWorldTransform) { + + assert(mContactPointsList != nullptr); + + // TODO : Implement this (do not forget to deallocate removed points) + + // The following algorithm only works to reduce to 4 contact points + assert(MAX_CONTACT_POINTS_IN_MANIFOLD == 4); + + // If there are too many contact points in the manifold + if (mNbContactPoints > MAX_CONTACT_POINTS_IN_MANIFOLD) { + + ContactPointInfo* pointsToKeep[MAX_CONTACT_POINTS_IN_MANIFOLD]; + + // Compute the initial contact point we need to keep. + // The first point we keep is always the point in a given + // constant direction (in order to always have same contact points + // between frames for better stability) + + const Transform worldToShape1Transform = shape1ToWorldTransform.getInverse(); + + // Compute the contact normal of the manifold (we use the first contact point) + // in the local-space of the first collision shape + const Vector3 contactNormalShape1Space = worldToShape1Transform.getOrientation() * mContactPointsList->normal; + + // Compute a search direction + const Vector3 searchDirection(1, 1, 1); + ContactPointInfo* element = mContactPointsList; + pointsToKeep[0] = element; + decimal maxDotProduct = searchDirection.dot(element->localPoint1); + element = element->next; + while(element != nullptr) { + + decimal dotProduct = searchDirection.dot(element->localPoint1); + if (dotProduct > maxDotProduct) { + maxDotProduct = dotProduct; + pointsToKeep[0] = element; + } + element = element->next; + } + + // Compute the second contact point we need to keep. + // The second point we keep is the one farthest away from the first point. + + decimal maxDistance = decimal(0.0); + element = mContactPointsList; + while(element != nullptr) { + + if (element == pointsToKeep[0]) { + element = element->next; + continue; + } + + decimal distance = (pointsToKeep[0]->localPoint1 - element->localPoint1).lengthSquare(); + if (distance >= maxDistance) { + maxDistance = distance; + pointsToKeep[1] = element; + } + element = element->next; + } + assert(pointsToKeep[1] != nullptr); + + // Compute the third contact point we need to keep. + // The second point is the one producing the triangle with the larger area + // with first and second point. + + // We compute the most positive or most negative triangle area (depending on winding) + ContactPointInfo* thirdPointMaxArea = nullptr; + ContactPointInfo* thirdPointMinArea = nullptr; + decimal minArea = decimal(0.0); + decimal maxArea = decimal(0.0); + bool isPreviousAreaPositive = true; + element = mContactPointsList; + while(element != nullptr) { + + if (element == pointsToKeep[0] || element == pointsToKeep[1]) { + element = element->next; + continue; + } + + const Vector3 newToFirst = pointsToKeep[0]->localPoint1 - element->localPoint1; + const Vector3 newToSecond = pointsToKeep[1]->localPoint1 - element->localPoint1; + + // Compute the triangle area + decimal area = newToFirst.cross(newToSecond).dot(contactNormalShape1Space); + + if (area >= maxArea) { + maxArea = area; + thirdPointMaxArea = element; + } + if (area <= minArea) { + minArea = area; + thirdPointMinArea = element; + } + element = element->next; + } + assert(minArea <= decimal(0.0)); + assert(maxArea >= decimal(0.0)); + if (maxArea > (-minArea)) { + isPreviousAreaPositive = true; + pointsToKeep[2] = thirdPointMaxArea; + } + else { + isPreviousAreaPositive = false; + pointsToKeep[2] = thirdPointMinArea; + } + assert(pointsToKeep[2] != nullptr); + + // Compute the 4th point by choosing the triangle that add the most + // triangle area to the previous triangle and has opposite sign area (opposite winding) + + decimal largestArea = decimal(0.0); // Largest area (positive or negative) + element = mContactPointsList; + + // For each remaining point + while(element != nullptr) { + + if (element == pointsToKeep[0] || element == pointsToKeep[1] || element == pointsToKeep[2]) { + element = element->next; + continue; + } + + // For each edge of the triangle made by the first three points + for (uint i=0; i<3; i++) { + + uint edgeVertex1Index = i; + uint edgeVertex2Index = i < 2 ? i + 1 : 0; + + const Vector3 newToFirst = pointsToKeep[edgeVertex1Index]->localPoint1 - element->localPoint1; + const Vector3 newToSecond = pointsToKeep[edgeVertex2Index]->localPoint1 - element->localPoint1; + + // Compute the triangle area + decimal area = newToFirst.cross(newToSecond).dot(contactNormalShape1Space); + + // We are looking at the triangle with maximal area (positive or negative). + // If the previous area is positive, we are looking at negative area now. + // If the previous area is negative, we are looking at the positive area now. + if (isPreviousAreaPositive && area < largestArea) { + largestArea = area; + pointsToKeep[3] = element; + } + else if (!isPreviousAreaPositive && area > largestArea) { + largestArea = area; + pointsToKeep[3] = element; + } + + element = element->next; + } + } + assert(pointsToKeep[3] != nullptr); + + // Delete the contact points we do not want to keep from the linked list + element = mContactPointsList; + ContactPointInfo* previousElement = nullptr; + while(element != nullptr) { + + // Skip the points we want to keep + if (element == pointsToKeep[0] || element == pointsToKeep[1] || + element == pointsToKeep[2] || element == pointsToKeep[3]) { + + previousElement = element; + element = element->next; + continue; + } + + ContactPointInfo* elementToDelete = element; + if (previousElement != nullptr) { + previousElement->next = elementToDelete->next; + } + else { + mContactPointsList = elementToDelete->next; + } + element = element->next; + + // Delete the current element + mAllocator.release(elementToDelete, sizeof(ContactPointInfo)); + } + + mNbContactPoints = 4; + } +} + +/// Return the largest penetration depth among the contact points +decimal ContactManifoldInfo::getLargestPenetrationDepth() const { + + decimal maxDepth = decimal(0.0); + ContactPointInfo* element = mContactPointsList; + while(element != nullptr) { + + if (element->penetrationDepth > maxDepth) { + maxDepth = element->penetrationDepth; + } + + element = element->next; + } + + return maxDepth; +} + + diff --git a/src/collision/ContactManifoldInfo.h b/src/collision/ContactManifoldInfo.h index f631b9fc..a7e84a98 100644 --- a/src/collision/ContactManifoldInfo.h +++ b/src/collision/ContactManifoldInfo.h @@ -33,6 +33,8 @@ /// ReactPhysics3D namespace namespace reactphysics3d { +// Constants +const uint MAX_CONTACT_POINTS_IN_MANIFOLD = 4; // Maximum number of contacts in the manifold // Class ContactManifoldInfo /** @@ -51,22 +53,18 @@ class ContactManifoldInfo { /// Memory allocator used to allocate contact points Allocator& mAllocator; - // -------------------- Methods -------------------- // - + /// Number of contact points in the manifold + uint mNbContactPoints; public: // -------------------- Methods -------------------- // /// Constructor - ContactManifoldInfo(Allocator& allocator) : mContactPointsList(nullptr), mAllocator(allocator) {} + ContactManifoldInfo(Allocator& allocator); /// Destructor - ~ContactManifoldInfo() { - - // Remove all the contact points - reset(); - } + ~ContactManifoldInfo(); /// Deleted copy-constructor ContactManifoldInfo(const ContactManifoldInfo& contactManifold) = delete; @@ -76,64 +74,26 @@ class ContactManifoldInfo { /// Add a new contact point into the manifold void addContactPoint(const Vector3& contactNormal, decimal penDepth, - const Vector3& localPt1, const Vector3& localPt2) { - - assert(penDepth > decimal(0.0)); - - // Create the contact point info - ContactPointInfo* contactPointInfo = new (mAllocator.allocate(sizeof(ContactPointInfo))) - ContactPointInfo(contactNormal, penDepth, localPt1, localPt2); - - // Add it into the linked list of contact points - contactPointInfo->next = mContactPointsList; - mContactPointsList = contactPointInfo; - } + const Vector3& localPt1, const Vector3& localPt2); /// Remove all the contact points - void reset() { - - // Delete all the contact points in the linked list - ContactPointInfo* element = mContactPointsList; - while(element != nullptr) { - ContactPointInfo* elementToDelete = element; - element = element->next; - - // Delete the current element - mAllocator.release(elementToDelete, sizeof(ContactPointInfo)); - } - - mContactPointsList = nullptr; - } + void reset(); /// Get the first contact point info of the linked list of contact points - ContactPointInfo* getFirstContactPointInfo() const { - return mContactPointsList; - } + ContactPointInfo* getFirstContactPointInfo() const; /// Reduce the number of points in the contact manifold - void reduce() { - - // TODO : Implement this (do not forget to deallocate removed points) - } + void reduce(const Transform& shape1ToWorldTransform); /// Return the largest penetration depth among the contact points - decimal getLargestPenetrationDepth() const { - - decimal maxDepth = decimal(0.0); - ContactPointInfo* element = mContactPointsList; - while(element != nullptr) { - - if (element->penetrationDepth > maxDepth) { - maxDepth = element->penetrationDepth; - } - - element = element->next; - } - - return maxDepth; - } + decimal getLargestPenetrationDepth() const; }; +// Get the first contact point info of the linked list of contact points +inline ContactPointInfo* ContactManifoldInfo::getFirstContactPointInfo() const { + return mContactPointsList; +} + } #endif From 2f43e554b54f674f26a22c5e0c5cf4af0453dab8 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 6 Jun 2017 21:12:26 +0200 Subject: [PATCH 076/248] Make TriangleShape inherits from ConvexPolyhedronShape --- src/collision/HalfEdgeStructure.h | 5 +- .../narrowphase/SAT/SATAlgorithm.cpp | 168 ++++++++++-------- src/collision/shapes/ConvexPolyhedronShape.h | 4 - src/collision/shapes/TriangleShape.cpp | 56 +++++- src/collision/shapes/TriangleShape.h | 118 +++++++++--- 5 files changed, 249 insertions(+), 102 deletions(-) diff --git a/src/collision/HalfEdgeStructure.h b/src/collision/HalfEdgeStructure.h index 01e305c5..6b4e3aa1 100644 --- a/src/collision/HalfEdgeStructure.h +++ b/src/collision/HalfEdgeStructure.h @@ -53,6 +53,9 @@ class HalfEdgeStructure { uint edgeIndex; // Index of an half-edge of the face std::vector faceVertices; // Index of the vertices of the face + /// Constructor + Face() {} + /// Constructor Face(std::vector vertices) : faceVertices(vertices) {} }; @@ -155,7 +158,7 @@ inline HalfEdgeStructure::Edge HalfEdgeStructure::getHalfEdge(uint index) const return mEdges[index]; } -// Retunr a given vertex +// Return a given vertex inline HalfEdgeStructure::Vertex HalfEdgeStructure::getVertex(uint index) const { assert(index < mVertices.size()); return mVertices[index]; diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 767aff8a..3bd3e796 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -46,6 +46,8 @@ const decimal SATAlgorithm::SAME_SEPARATING_AXIS_BIAS = decimal(0.001); // Test collision between a sphere and a convex mesh bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { + PROFILE("SATAlgorithm::testCollisionSphereVsConvexPolyhedron()"); + bool isSphereShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE; assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON || @@ -77,32 +79,37 @@ bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(const NarrowPhaseInfo* LastFrameCollisionInfo& lastFrameInfo = narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo(); - // If the last frame collision info is valid and was also using SAT algorithm - if (lastFrameInfo.isValid && lastFrameInfo.wasUsingSAT) { + // If the shapes are not triangles (no temporal coherence for triangle collision because we do not store previous + // frame collision data per triangle) + if (polyhedron->getType() != CollisionShapeType::TRIANGLE) { - // We perform temporal coherence, we check if there is still an overlapping along the previous minimum separating - // axis. If it is the case, we directly report the collision without executing the whole SAT algorithm again. If - // the shapes are still separated along this axis, we directly exit with no collision. + // If the last frame collision info is valid and was also using SAT algorithm + if (lastFrameInfo.isValid && lastFrameInfo.wasUsingSAT) { - // Compute the penetration depth of the shapes along the face normal direction - decimal penetrationDepth = computePolyhedronFaceVsSpherePenetrationDepth(lastFrameInfo.satMinAxisFaceIndex, polyhedron, - sphere, sphereCenter); + // We perform temporal coherence, we check if there is still an overlapping along the previous minimum separating + // axis. If it is the case, we directly report the collision without executing the whole SAT algorithm again. If + // the shapes are still separated along this axis, we directly exit with no collision. - // If the previous axis is a separating axis - if (penetrationDepth <= decimal(0.0)) { + // Compute the penetration depth of the shapes along the face normal direction + decimal penetrationDepth = computePolyhedronFaceVsSpherePenetrationDepth(lastFrameInfo.satMinAxisFaceIndex, polyhedron, + sphere, sphereCenter); - // Return no collision - return false; - } + // If the previous axis is a separating axis + if (penetrationDepth <= decimal(0.0)) { - // The two shapes are overlapping as in the previous frame and on the same axis, therefore - // we will skip the entire SAT algorithm because the minimum separating axis did not change - isTemporalCoherenceValid = lastFrameInfo.wasColliding; + // Return no collision + return false; + } - if (isTemporalCoherenceValid) { + // The two shapes are overlapping as in the previous frame and on the same axis, therefore + // we will skip the entire SAT algorithm because the minimum separating axis did not change + isTemporalCoherenceValid = lastFrameInfo.wasColliding; - minPenetrationDepth = penetrationDepth; - minFaceIndex = lastFrameInfo.satMinAxisFaceIndex; + if (isTemporalCoherenceValid) { + + minPenetrationDepth = penetrationDepth; + minFaceIndex = lastFrameInfo.satMinAxisFaceIndex; + } } } @@ -170,6 +177,8 @@ decimal SATAlgorithm::computePolyhedronFaceVsSpherePenetrationDepth(uint faceInd // Test collision between a capsule and a convex mesh bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { + PROFILE("SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron()"); + bool isCapsuleShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE; assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON || @@ -206,78 +215,83 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(const NarrowPhaseInfo* LastFrameCollisionInfo& lastFrameInfo = narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo(); - // If the last frame collision info is valid and was also using SAT algorithm - if (lastFrameInfo.isValid && lastFrameInfo.wasUsingSAT) { + // If the shapes are not triangles (no temporal coherence for triangle collision because we do not store previous + // frame collision data per triangle) + if (polyhedron->getType() != CollisionShapeType::TRIANGLE) { - // We perform temporal coherence, we check if there is still an overlapping along the previous minimum separating - // axis. If it is the case, we directly report the collision without executing the whole SAT algorithm again. If - // the shapes are still separated along this axis, we directly exit with no collision. + // If the last frame collision info is valid and was also using SAT algorithm + if (lastFrameInfo.isValid && lastFrameInfo.wasUsingSAT) { - // If the previous minimum separation axis was a face normal of the polyhedron - if (lastFrameInfo.satIsAxisFacePolyhedron1) { + // We perform temporal coherence, we check if there is still an overlapping along the previous minimum separating + // axis. If it is the case, we directly report the collision without executing the whole SAT algorithm again. If + // the shapes are still separated along this axis, we directly exit with no collision. - Vector3 outFaceNormalCapsuleSpace; + // If the previous minimum separation axis was a face normal of the polyhedron + if (lastFrameInfo.satIsAxisFacePolyhedron1) { - // Compute the penetration depth along the polyhedron face normal direction - const decimal penetrationDepth = computePolyhedronFaceVsCapsulePenetrationDepth(lastFrameInfo.satMinAxisFaceIndex, polyhedron, - capsuleShape, polyhedronToCapsuleTransform, - outFaceNormalCapsuleSpace); + Vector3 outFaceNormalCapsuleSpace; - // If the previous axis is a separating axis - if (penetrationDepth <= decimal(0.0)) { + // Compute the penetration depth along the polyhedron face normal direction + const decimal penetrationDepth = computePolyhedronFaceVsCapsulePenetrationDepth(lastFrameInfo.satMinAxisFaceIndex, polyhedron, + capsuleShape, polyhedronToCapsuleTransform, + outFaceNormalCapsuleSpace); - // Return no collision - return false; + // If the previous axis is a separating axis + if (penetrationDepth <= decimal(0.0)) { + + // Return no collision + return false; + } + + // The two shapes are overlapping as in the previous frame and on the same axis, therefore + // we will skip the entire SAT algorithm because the minimum separating axis did not change + isTemporalCoherenceValid = lastFrameInfo.wasColliding; + + if (isTemporalCoherenceValid) { + + minPenetrationDepth = penetrationDepth; + minFaceIndex = lastFrameInfo.satMinAxisFaceIndex; + isMinPenetrationFaceNormal = true; + separatingAxisCapsuleSpace = outFaceNormalCapsuleSpace; + } } + else { // If the previous minimum separation axis the cross product of the capsule inner segment and an edge of the polyhedron - // The two shapes are overlapping as in the previous frame and on the same axis, therefore - // we will skip the entire SAT algorithm because the minimum separating axis did not change - isTemporalCoherenceValid = lastFrameInfo.wasColliding; + // Get an edge from the polyhedron (convert it into the capsule local-space) + HalfEdgeStructure::Edge edge = polyhedron->getHalfEdge(lastFrameInfo.satMinEdge1Index); + const Vector3 edgeVertex1 = polyhedron->getVertexPosition(edge.vertexIndex); + const Vector3 edgeVertex2 = polyhedron->getVertexPosition(polyhedron->getHalfEdge(edge.nextEdgeIndex).vertexIndex); + const Vector3 edgeDirectionCapsuleSpace = polyhedronToCapsuleTransform.getOrientation() * (edgeVertex2 - edgeVertex1); - if (isTemporalCoherenceValid) { + Vector3 outAxis; - minPenetrationDepth = penetrationDepth; - minFaceIndex = lastFrameInfo.satMinAxisFaceIndex; - isMinPenetrationFaceNormal = true; - separatingAxisCapsuleSpace = outFaceNormalCapsuleSpace; - } - } - else { // If the previous minimum separation axis the cross product of the capsule inner segment and an edge of the polyhedron + // Compute the penetration depth along this axis + const decimal penetrationDepth = computeEdgeVsCapsuleInnerSegmentPenetrationDepth(polyhedron, capsuleShape, + capsuleSegmentAxis, edgeVertex1, + edgeDirectionCapsuleSpace, + polyhedronToCapsuleTransform, + outAxis); - // Get an edge from the polyhedron (convert it into the capsule local-space) - HalfEdgeStructure::Edge edge = polyhedron->getHalfEdge(lastFrameInfo.satMinEdge1Index); - const Vector3 edgeVertex1 = polyhedron->getVertexPosition(edge.vertexIndex); - const Vector3 edgeVertex2 = polyhedron->getVertexPosition(polyhedron->getHalfEdge(edge.nextEdgeIndex).vertexIndex); - const Vector3 edgeDirectionCapsuleSpace = polyhedronToCapsuleTransform.getOrientation() * (edgeVertex2 - edgeVertex1); + // If the previous axis is a separating axis + if (penetrationDepth <= decimal(0.0)) { - Vector3 outAxis; + // Return no collision + return false; + } - // Compute the penetration depth along this axis - const decimal penetrationDepth = computeEdgeVsCapsuleInnerSegmentPenetrationDepth(polyhedron, capsuleShape, - capsuleSegmentAxis, edgeVertex1, - edgeDirectionCapsuleSpace, - polyhedronToCapsuleTransform, - outAxis); + // The two shapes are overlapping as in the previous frame and on the same axis, therefore + // we will skip the entire SAT algorithm because the minimum separating axis did not change + isTemporalCoherenceValid = lastFrameInfo.wasColliding; - // If the previous axis is a separating axis - if (penetrationDepth <= decimal(0.0)) { + if (isTemporalCoherenceValid) { - // Return no collision - return false; - } - - // The two shapes are overlapping as in the previous frame and on the same axis, therefore - // we will skip the entire SAT algorithm because the minimum separating axis did not change - isTemporalCoherenceValid = lastFrameInfo.wasColliding; - - if (isTemporalCoherenceValid) { - - minPenetrationDepth = penetrationDepth; - minEdgeIndex = lastFrameInfo.satMinEdge1Index; - isMinPenetrationFaceNormal = false; - separatingAxisCapsuleSpace = outAxis; - separatingPolyhedronEdgeVertex1 = edgeVertex1; - separatingPolyhedronEdgeVertex2 = edgeVertex2; + minPenetrationDepth = penetrationDepth; + minEdgeIndex = lastFrameInfo.satMinEdge1Index; + isMinPenetrationFaceNormal = false; + separatingAxisCapsuleSpace = outAxis; + separatingPolyhedronEdgeVertex1 = edgeVertex1; + separatingPolyhedronEdgeVertex2 = edgeVertex2; + } } } } @@ -527,6 +541,8 @@ bool SATAlgorithm::isMinkowskiFaceCapsuleVsEdge(const Vector3& capsuleSegment, c bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { + PROFILE("SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron()"); + assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON); assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); diff --git a/src/collision/shapes/ConvexPolyhedronShape.h b/src/collision/shapes/ConvexPolyhedronShape.h index f6d2a34b..6c1de4d5 100644 --- a/src/collision/shapes/ConvexPolyhedronShape.h +++ b/src/collision/shapes/ConvexPolyhedronShape.h @@ -42,10 +42,6 @@ class ConvexPolyhedronShape : public ConvexShape { protected : - // -------------------- Attributes -------------------- // - - // -------------------- Methods -------------------- // - public : // -------------------- Methods -------------------- // diff --git a/src/collision/shapes/TriangleShape.cpp b/src/collision/shapes/TriangleShape.cpp index 4767435b..9c0deb38 100644 --- a/src/collision/shapes/TriangleShape.cpp +++ b/src/collision/shapes/TriangleShape.cpp @@ -40,10 +40,16 @@ using namespace reactphysics3d; * @param margin The collision margin (in meters) around the collision shape */ TriangleShape::TriangleShape(const Vector3& point1, const Vector3& point2, const Vector3& point3, decimal margin) - : ConvexShape(CollisionShapeType::TRIANGLE, margin) { + : ConvexPolyhedronShape(margin) { + mPoints[0] = point1; mPoints[1] = point2; mPoints[2] = point3; + + // Compute the triangle normal + mNormal = (point3 - point1).cross(point2 - point1); + mNormal.normalize(); + mRaycastTestType = TriangleRaycastSide::FRONT; } @@ -120,3 +126,51 @@ bool TriangleShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape return true; } +// Return a given half-edge of the polyhedron +HalfEdgeStructure::Edge TriangleShape::getHalfEdge(uint edgeIndex) const { + assert(edgeIndex < getNbHalfEdges()); + + HalfEdgeStructure::Edge edge; + + switch(edgeIndex) { + case 0: + edge.vertexIndex = 0; + edge.twinEdgeIndex = 1; + edge.faceIndex = 0; + edge.nextEdgeIndex = 2; + break; + case 1: + edge.vertexIndex = 1; + edge.twinEdgeIndex = 0; + edge.faceIndex = 1; + edge.nextEdgeIndex = 5; + break; + case 2: + edge.vertexIndex = 1; + edge.twinEdgeIndex = 3; + edge.faceIndex = 0; + edge.nextEdgeIndex = 4; + break; + case 3: + edge.vertexIndex = 2; + edge.twinEdgeIndex = 2; + edge.faceIndex = 1; + edge.nextEdgeIndex = 1; + break; + case 4: + edge.vertexIndex = 2; + edge.twinEdgeIndex = 5; + edge.faceIndex = 0; + edge.nextEdgeIndex = 0; + break; + case 5: + edge.vertexIndex = 0; + edge.twinEdgeIndex = 4; + edge.faceIndex = 1; + edge.nextEdgeIndex = 3; + break; + } + + return edge; + +} diff --git a/src/collision/shapes/TriangleShape.h b/src/collision/shapes/TriangleShape.h index 29732f8f..e25086b8 100644 --- a/src/collision/shapes/TriangleShape.h +++ b/src/collision/shapes/TriangleShape.h @@ -28,7 +28,7 @@ // Libraries #include "mathematics/mathematics.h" -#include "ConvexShape.h" +#include "ConvexPolyhedronShape.h" /// ReactPhysics3D namespace namespace reactphysics3d { @@ -51,7 +51,7 @@ enum class TriangleRaycastSide { * This class represents a triangle collision shape that is centered * at the origin and defined three points. */ -class TriangleShape : public ConvexShape { +class TriangleShape : public ConvexPolyhedronShape { protected: @@ -60,6 +60,9 @@ class TriangleShape : public ConvexShape { /// Three points of the triangle Vector3 mPoints[3]; + /// Normal of the triangle + Vector3 mNormal; + /// Raycast test type for the triangle (front, back, front-back) TriangleRaycastSide mRaycastTestType; @@ -113,11 +116,32 @@ class TriangleShape : public ConvexShape { // Set the raycast test type (front, back, front-back) void setRaycastTestType(TriangleRaycastSide testType); - /// Return the coordinates of a given vertex of the triangle - Vector3 getVertex(int index) const; + /// Return the number of faces of the polyhedron + virtual uint getNbFaces() const override; - /// Return true if the collision shape is a polyhedron - virtual bool isPolyhedron() const override; + /// Return a given face of the polyhedron + virtual HalfEdgeStructure::Face getFace(uint faceIndex) const override; + + /// Return the number of vertices of the polyhedron + virtual uint getNbVertices() const override; + + /// Return a given vertex of the polyhedron + virtual HalfEdgeStructure::Vertex getVertex(uint vertexIndex) const override; + + /// Return the position of a given vertex + virtual Vector3 getVertexPosition(uint vertexIndex) const override; + + /// Return the normal vector of a given face of the polyhedron + virtual Vector3 getFaceNormal(uint faceIndex) const override; + + /// Return the number of half-edges of the polyhedron + virtual uint getNbHalfEdges() const override; + + /// Return a given half-edge of the polyhedron + virtual HalfEdgeStructure::Edge getHalfEdge(uint edgeIndex) const override; + + /// Return the centroid of the polyhedron + virtual Vector3 getCentroid() const override; // ---------- Friendship ---------- // @@ -199,6 +223,74 @@ inline bool TriangleShape::testPointInside(const Vector3& localPoint, ProxyShape return false; } +// Return the number of faces of the polyhedron +inline uint TriangleShape::getNbFaces() const { + return 2; +} + +// Return a given face of the polyhedron +inline HalfEdgeStructure::Face TriangleShape::getFace(uint faceIndex) const { + assert(faceIndex < 2); + + HalfEdgeStructure::Face face; + + if (faceIndex == 0) { + face.faceVertices.push_back(0); + face.faceVertices.push_back(1); + face.faceVertices.push_back(2); + face.edgeIndex = 0; + + } + else { + face.faceVertices.push_back(0); + face.faceVertices.push_back(2); + face.faceVertices.push_back(1); + face.edgeIndex = 1; + } + + return face; +} + +// Return the number of vertices of the polyhedron +inline uint TriangleShape::getNbVertices() const { + return 3; +} + +// Return a given vertex of the polyhedron +inline HalfEdgeStructure::Vertex TriangleShape::getVertex(uint vertexIndex) const { + assert(vertexIndex < 3); + + HalfEdgeStructure::Vertex vertex(vertexIndex); + switch (vertexIndex) { + case 0: vertex.edgeIndex = 0; break; + case 1: vertex.edgeIndex = 2; break; + case 2: vertex.edgeIndex = 4; break; + } + return vertex; +} + +// Return the position of a given vertex +inline Vector3 TriangleShape::getVertexPosition(uint vertexIndex) const { + assert(vertexIndex < 3); + return mPoints[vertexIndex]; +} + +// Return the normal vector of a given face of the polyhedron +inline Vector3 TriangleShape::getFaceNormal(uint faceIndex) const { + assert(faceIndex < 2); + return faceIndex == 0 ? mNormal : -mNormal; +} + +// Return the centroid of the box +inline Vector3 TriangleShape::getCentroid() const { + return (mPoints[0] + mPoints[1] + mPoints[2]) / decimal(3.0); +} + +// Return the number of half-edges of the polyhedron +inline uint TriangleShape::getNbHalfEdges() const { + return 6; +} + // Return the raycast test type (front, back, front-back) inline TriangleRaycastSide TriangleShape::getRaycastTestType() const { return mRaycastTestType; @@ -212,20 +304,6 @@ inline void TriangleShape::setRaycastTestType(TriangleRaycastSide testType) { mRaycastTestType = testType; } -// Return the coordinates of a given vertex of the triangle -/** - * @param index Index (0 to 2) of a vertex of the triangle - */ -inline Vector3 TriangleShape::getVertex(int index) const { - assert(index >= 0 && index < 3); - return mPoints[index]; -} - -// Return true if the collision shape is a polyhedron -inline bool TriangleShape::isPolyhedron() const { - return true; -} - } #endif From 6e9a84823a77c5f1aef7e94e44f654ffb3b17021 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 17 Jul 2017 08:05:40 +0200 Subject: [PATCH 077/248] Fix issues in collision detection --- .../CapsuleVsConvexPolyhedronAlgorithm.cpp | 31 +++++++++++++------ .../narrowphase/SAT/SATAlgorithm.cpp | 4 +-- .../SphereVsConvexPolyhedronAlgorithm.cpp | 5 +++ src/collision/shapes/BoxShape.cpp | 12 ++++--- src/mathematics/mathematics_functions.cpp | 5 +++ src/mathematics/mathematics_functions.h | 3 ++ .../CollisionDetectionScene.cpp | 8 ++--- 7 files changed, 48 insertions(+), 20 deletions(-) mode change 100644 => 100755 src/mathematics/mathematics_functions.cpp mode change 100644 => 100755 src/mathematics/mathematics_functions.h diff --git a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp index 142a7fc9..b538dfa7 100644 --- a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp @@ -29,6 +29,7 @@ #include "GJK/GJKAlgorithm.h" #include "collision/shapes/CapsuleShape.h" #include "collision/shapes/ConvexPolyhedronShape.h" +#include // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; @@ -47,40 +48,52 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* na narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = true; narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = false; + assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON || + narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); + assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE || + narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CAPSULE); + // If we have found a contact point inside the margins (shallow penetration) if (result == GJKAlgorithm::GJKResult::COLLIDE_IN_MARGIN) { - // GJK has found a shallow contact. If the contact normal is parallel to a face of the - // polyhedron mesh, we would like to create two contact points instead of a single one - // (as in the deep contact case with SAT algorithm) + // GJK has found a shallow contact. If the face of the polyhedron mesh is orthogonal to the + // capsule inner segment and parallel to the contact point normal, we would like to create + // two contact points instead of a single one (as in the deep contact case with SAT algorithm) // Get the contact point created by GJK ContactPointInfo* contactPoint = contactManifoldInfo.getFirstContactPointInfo(); + assert(contactPoint != nullptr); bool isCapsuleShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE; - assert(isCapsuleShape1 || narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON); - assert(!isCapsuleShape1 || narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON); - assert(!isCapsuleShape1 || narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CAPSULE); // Get the collision shapes const CapsuleShape* capsuleShape = static_cast(isCapsuleShape1 ? narrowPhaseInfo->collisionShape1 : narrowPhaseInfo->collisionShape2); const ConvexPolyhedronShape* polyhedron = static_cast(isCapsuleShape1 ? narrowPhaseInfo->collisionShape2 : narrowPhaseInfo->collisionShape1); // For each face of the polyhedron - // For each face of the convex mesh for (uint f = 0; f < polyhedron->getNbFaces(); f++) { // Get the face HalfEdgeStructure::Face face = polyhedron->getFace(f); const Transform polyhedronToWorld = isCapsuleShape1 ? narrowPhaseInfo->shape2ToWorldTransform : narrowPhaseInfo->shape1ToWorldTransform; + const Transform capsuleToWorld = isCapsuleShape1 ? narrowPhaseInfo->shape1ToWorldTransform : narrowPhaseInfo->shape2ToWorldTransform; // Get the face normal const Vector3 faceNormal = polyhedron->getFaceNormal(f); const Vector3 faceNormalWorld = polyhedronToWorld.getOrientation() * faceNormal; - // If the polyhedron face normal is parallel to the computed GJK contact normal - if (areParallelVectors(faceNormalWorld, contactPoint->normal)) { + const Vector3 capsuleSegA(0, -capsuleShape->getHeight() * decimal(0.5), 0); + const Vector3 capsuleSegB(0, capsuleShape->getHeight() * decimal(0.5), 0); + const Vector3 capsuleInnerSegmentWorld = capsuleToWorld.getOrientation() * (capsuleSegB - capsuleSegA); + + bool isFaceNormalInDirectionOfContactNormal = faceNormalWorld.dot(contactPoint->normal) > decimal(0.0); + bool isFaceNormalInContactDirection = (isCapsuleShape1 && !isFaceNormalInDirectionOfContactNormal) || (!isCapsuleShape1 && isFaceNormalInDirectionOfContactNormal); + + // If the polyhedron face normal is orthogonal to the capsule inner segment and parallel to the contact point normal and the face normal + // is in direction of the contact normal (from the polyhedron point of view). + if (isFaceNormalInContactDirection && areOrthogonalVectors(faceNormalWorld, capsuleInnerSegmentWorld) + && areParallelVectors(faceNormalWorld, contactPoint->normal)) { // Remove the previous contact point computed by GJK contactManifoldInfo.reset(); diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 3bd3e796..d204a88e 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -296,7 +296,7 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(const NarrowPhaseInfo* } } - // We the shapes are still overlapping in the same axis as in + // If the shapes are still overlapping in the same axis as in the previous frame // the previous frame, we skip the whole SAT algorithm if (!isTemporalCoherenceValid) { @@ -470,7 +470,7 @@ decimal SATAlgorithm::computePolyhedronFaceVsCapsulePenetrationDepth(uint polyhe const Vector3 capsuleSupportPoint = capsule->getLocalSupportPointWithMargin(-outFaceNormalCapsuleSpace, nullptr); const Vector3 pointOnPolyhedronFace = polyhedronToCapsuleTransform * polyhedron->getVertexPosition(face.faceVertices[0]); const Vector3 capsuleSupportPointToFacePoint = pointOnPolyhedronFace - capsuleSupportPoint; - const decimal penetrationDepth = capsuleSupportPointToFacePoint.dot(faceNormal); + const decimal penetrationDepth = capsuleSupportPointToFacePoint.dot(outFaceNormalCapsuleSpace); return penetrationDepth; } diff --git a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp index bb43bd33..068a79ff 100644 --- a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp @@ -41,6 +41,11 @@ bool SphereVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* nar GJKAlgorithm gjkAlgorithm; GJKAlgorithm::GJKResult result = gjkAlgorithm.testCollision(narrowPhaseInfo, contactManifoldInfo); + assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON || + narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); + assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE || + narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CAPSULE); + narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = true; narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = false; diff --git a/src/collision/shapes/BoxShape.cpp b/src/collision/shapes/BoxShape.cpp index e1c97844..af6a30b8 100644 --- a/src/collision/shapes/BoxShape.cpp +++ b/src/collision/shapes/BoxShape.cpp @@ -57,15 +57,15 @@ BoxShape::BoxShape(const Vector3& extent, decimal margin) std::vector face0; face0.push_back(0); face0.push_back(1); face0.push_back(2); face0.push_back(3); std::vector face1; - face1.push_back(1); face0.push_back(5); face0.push_back(6); face0.push_back(2); + face1.push_back(1); face1.push_back(5); face1.push_back(6); face1.push_back(2); std::vector face2; - face2.push_back(4); face0.push_back(7); face0.push_back(6); face0.push_back(5); + face2.push_back(4); face2.push_back(7); face2.push_back(6); face2.push_back(5); std::vector face3; - face3.push_back(4); face0.push_back(0); face0.push_back(3); face0.push_back(7); + face3.push_back(4); face3.push_back(0); face3.push_back(3); face3.push_back(7); std::vector face4; - face4.push_back(4); face0.push_back(5); face0.push_back(1); face0.push_back(0); + face4.push_back(4); face4.push_back(5); face4.push_back(1); face4.push_back(0); std::vector face5; - face5.push_back(2); face0.push_back(6); face0.push_back(7); face0.push_back(3); + face5.push_back(2); face5.push_back(6); face5.push_back(7); face5.push_back(3); mHalfEdgeStructure.addFace(face0); mHalfEdgeStructure.addFace(face1); @@ -73,6 +73,8 @@ BoxShape::BoxShape(const Vector3& extent, decimal margin) mHalfEdgeStructure.addFace(face3); mHalfEdgeStructure.addFace(face4); mHalfEdgeStructure.addFace(face5); + + mHalfEdgeStructure.init(); } // Return the local inertia tensor of the collision shape diff --git a/src/mathematics/mathematics_functions.cpp b/src/mathematics/mathematics_functions.cpp old mode 100644 new mode 100755 index e01c749a..24329732 --- a/src/mathematics/mathematics_functions.cpp +++ b/src/mathematics/mathematics_functions.cpp @@ -65,6 +65,11 @@ bool reactphysics3d::areParallelVectors(const Vector3& vector1, const Vector3& v return vector1.cross(vector2).lengthSquare() < decimal(0.00001); } +/// Return true if two vectors are orthogonal +bool reactphysics3d::areOrthogonalVectors(const Vector3& vector1, const Vector3& vector2) { + return std::abs(vector1.dot(vector2)) < decimal(0.00001); +} + /// Compute and return a point on segment from "segPointA" and "segPointB" that is closest to point "pointC" Vector3 reactphysics3d::computeClosestPointOnSegment(const Vector3& segPointA, const Vector3& segPointB, const Vector3& pointC) { diff --git a/src/mathematics/mathematics_functions.h b/src/mathematics/mathematics_functions.h old mode 100644 new mode 100755 index c695f342..5ee03a19 --- a/src/mathematics/mathematics_functions.h +++ b/src/mathematics/mathematics_functions.h @@ -79,6 +79,9 @@ inline bool sameSign(decimal a, decimal b) { /// Return true if two vectors are parallel bool areParallelVectors(const Vector3& vector1, const Vector3& vector2); +/// Return true if two vectors are orthogonal +bool areOrthogonalVectors(const Vector3& vector1, const Vector3& vector2); + /// Clamp a vector such that it is no longer than a given maximum length Vector3 clamp(const Vector3& vector, decimal maxLength); diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp index 6351028a..e8f09670 100755 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp @@ -61,7 +61,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mSphere1->setSleepingColor(mRedColorDemo); // ---------- Sphere 2 ---------- // - openglframework::Vector3 position2(0, 0, 0); + openglframework::Vector3 position2(12, 8, 0); // Create a sphere and a corresponding collision body in the dynamics world mSphere2 = new Sphere(2, position2, mCollisionWorld, mMeshFolderPath); @@ -72,7 +72,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mSphere2->setSleepingColor(mRedColorDemo); // ---------- Capsule 1 ---------- // - openglframework::Vector3 position3(8, 0, 0); + openglframework::Vector3 position3(0, -12, 0); // Create a cylinder and a corresponding collision body in the dynamics world mCapsule1 = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, position3, mCollisionWorld, mMeshFolderPath); @@ -94,7 +94,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mCapsule2->setSleepingColor(mRedColorDemo); // ---------- Box 1 ---------- // - openglframework::Vector3 position5(0, -12, 0); + openglframework::Vector3 position5(0, -0, 0); // Create a cylinder and a corresponding collision body in the dynamics world mBox1 = new Box(BOX_SIZE, position5, mCollisionWorld, mMeshFolderPath); @@ -105,7 +105,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mBox1->setSleepingColor(mRedColorDemo); // ---------- Box 2 ---------- // - openglframework::Vector3 position6(0, 12, 0); + openglframework::Vector3 position6(0, 8, 0); // Create a cylinder and a corresponding collision body in the dynamics world mBox2 = new Box(openglframework::Vector3(3, 2, 5), position6, mCollisionWorld, mMeshFolderPath); From ddd7f500a659b983c59c31984af074845864ab9f Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 17 Jul 2017 18:35:51 +0200 Subject: [PATCH 078/248] Fix issues in SAT algorithm --- .../narrowphase/SAT/SATAlgorithm.cpp | 51 ++++++++++--------- .../SphereVsConvexPolyhedronAlgorithm.cpp | 4 +- 2 files changed, 30 insertions(+), 25 deletions(-) diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index d204a88e..4e15eb15 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -141,15 +141,11 @@ bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(const NarrowPhaseInfo* const Vector3 minFaceNormal = polyhedron->getFaceNormal(minFaceIndex); Vector3 normalWorld = -(polyhedronToWorldTransform.getOrientation() * minFaceNormal); - const Vector3 contactPointSphereLocal = sphereToWorldTransform.getInverse() * normalWorld * sphere->getRadius(); + const Vector3 contactPointSphereLocal = sphereToWorldTransform.getInverse().getOrientation() * normalWorld * sphere->getRadius(); const Vector3 contactPointPolyhedronLocal = sphereCenter + minFaceNormal * (minPenetrationDepth - sphere->getRadius()); - if (!isSphereShape1) { - normalWorld = -normalWorld; - } - // Create the contact info object - contactManifoldInfo.addContactPoint(normalWorld, minPenetrationDepth, + contactManifoldInfo.addContactPoint(isSphereShape1 ? normalWorld : -normalWorld, minPenetrationDepth, isSphereShape1 ? contactPointSphereLocal : contactPointPolyhedronLocal, isSphereShape1 ? contactPointPolyhedronLocal : contactPointSphereLocal); @@ -497,32 +493,41 @@ void SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceI // Construct a clippling plane for each adjacent edge of the separting face of the polyhedron planesPoints.push_back(polyhedron->getVertexPosition(edge.vertexIndex)); - planesNormals.push_back(polyhedron->getFaceNormal(twinEdge.faceIndex)); + planesNormals.push_back(-polyhedron->getFaceNormal(twinEdge.faceIndex)); edgeIndex = edge.nextEdgeIndex; } while(edgeIndex != firstEdgeIndex); // First we clip the inner segment of the capsule with the four planes of the adjacent faces - std::vector clipSegment = clipSegmentWithPlanes(capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, - planesPoints, planesNormals); + std::vector clipSegment = clipSegmentWithPlanes(capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, planesPoints, planesNormals); + assert(clipSegment.size() == 2); - // Project the two clipped points into the polyhedron face - const Vector3 faceNormal = polyhedron->getFaceNormal(referenceFaceIndex); - const Vector3 contactPoint1Polyhedron = clipSegment[0] + faceNormal * (penetrationDepth - capsuleRadius); - const Vector3 contactPoint2Polyhedron = clipSegment[1] + faceNormal * (penetrationDepth - capsuleRadius); + const Vector3 faceNormal = polyhedron->getFaceNormal(referenceFaceIndex); - // Project the two clipped points into the capsule bounds - const Vector3 contactPoint1Capsule = (polyhedronToCapsuleTransform * clipSegment[0]) - separatingAxisCapsuleSpace * capsuleRadius; - const Vector3 contactPoint2Capsule = (polyhedronToCapsuleTransform * clipSegment[1]) - separatingAxisCapsuleSpace * capsuleRadius; + // Project the two clipped points into the polyhedron face + const Vector3 delta = faceNormal * (penetrationDepth - capsuleRadius); - // Create the contact points - contactManifoldInfo.addContactPoint(normalWorld, penetrationDepth, - isCapsuleShape1 ? contactPoint1Capsule : contactPoint1Polyhedron, - isCapsuleShape1 ? contactPoint1Polyhedron : contactPoint1Capsule); - contactManifoldInfo.addContactPoint(normalWorld, penetrationDepth, - isCapsuleShape1 ? contactPoint2Capsule : contactPoint2Polyhedron, - isCapsuleShape1 ? contactPoint2Polyhedron : contactPoint2Capsule); + // For each of the two clipped points + for (int i = 0; i<2; i++) { + + // Compute the penetration depth of the two clipped points (to filter out the points that does not correspond to the penetration depth) + const decimal clipPointPenDepth = (planesPoints[0] - clipSegment[i]).dot(faceNormal); + + // If the clipped point is one that produce this penetration depth, we keep it + if (clipPointPenDepth > penetrationDepth - capsuleRadius - decimal(0.001)) { + + const Vector3 contactPointPolyhedron = clipSegment[i] + delta; + + // Project the clipped point into the capsule bounds + const Vector3 contactPointCapsule = (polyhedronToCapsuleTransform * clipSegment[i]) - separatingAxisCapsuleSpace * capsuleRadius; + + // Create the contact point + contactManifoldInfo.addContactPoint(isCapsuleShape1 ? -normalWorld : normalWorld, penetrationDepth, + isCapsuleShape1 ? contactPointCapsule : contactPointPolyhedron, + isCapsuleShape1 ? contactPointPolyhedron : contactPointCapsule); + } + } } // This method returns true if an edge of a polyhedron and a capsule forms a diff --git a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp index 068a79ff..d90a29b3 100644 --- a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp @@ -43,8 +43,8 @@ bool SphereVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* nar assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON || narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); - assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE || - narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CAPSULE); + assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE || + narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::SPHERE); narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = true; narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = false; From 6eec956eb0afcdf6cf0194da3c520158fd3aa0d4 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Fri, 21 Jul 2017 08:09:43 +0200 Subject: [PATCH 079/248] Fix issues in SAT algorithm between two convex polyhedra --- src/collision/narrowphase/SAT/SATAlgorithm.cpp | 15 ++++++++------- src/mathematics/mathematics_functions.cpp | 5 +++++ src/mathematics/mathematics_functions.h | 3 +++ 3 files changed, 16 insertions(+), 7 deletions(-) diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 4e15eb15..c838d8ab 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -854,18 +854,19 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(const NarrowP assert(clipPolygonVertices.size() > 0); // We only keep the clipped points that are below the reference face - const Vector3 referenceFaceVertex = referencePolyhedron->getVertexPosition(firstEdgeIndex); + const Vector3 referenceFaceVertex = referencePolyhedron->getVertexPosition(referencePolyhedron->getHalfEdge(firstEdgeIndex).vertexIndex); std::vector::const_iterator itPoints; for (itPoints = clipPolygonVertices.begin(); itPoints != clipPolygonVertices.end(); ++itPoints) { // If the clip point is bellow the reference face - if (((*itPoints) - referenceFaceVertex).dot(axisReferenceSpace) < decimal(0.0)) { + if (((*itPoints) - referenceFaceVertex).dot(axisReferenceSpace) < decimal(0.0)) + { // Convert the clip incident polyhedron vertex into the incident polyhedron local-space const Vector3 contactPointIncidentPolyhedron = referenceToIncidentTransform * (*itPoints); // Project the contact point onto the reference face - Vector3 contactPointReferencePolyhedron = (*itPoints) + axisReferenceSpace * minPenetrationDepth; + Vector3 contactPointReferencePolyhedron = projectPointOntoPlane(*itPoints, axisReferenceSpace, referenceFaceVertex); // Create a new contact point contactManifoldInfo.addContactPoint(normalWorld, minPenetrationDepth, @@ -1011,8 +1012,8 @@ bool SATAlgorithm::testEdgesBuildMinkowskiFace(const ConvexPolyhedronShape* poly const ConvexPolyhedronShape* polyhedron2, const HalfEdgeStructure::Edge& edge2, const Transform& polyhedron1ToPolyhedron2) const { - const Vector3 a = polyhedron1ToPolyhedron2 * polyhedron1->getFaceNormal(edge1.faceIndex); - const Vector3 b = polyhedron1ToPolyhedron2 * polyhedron1->getFaceNormal(polyhedron1->getHalfEdge(edge1.twinEdgeIndex).faceIndex); + const Vector3 a = polyhedron1ToPolyhedron2.getOrientation() * polyhedron1->getFaceNormal(edge1.faceIndex); + const Vector3 b = polyhedron1ToPolyhedron2.getOrientation() * polyhedron1->getFaceNormal(polyhedron1->getHalfEdge(edge1.twinEdgeIndex).faceIndex); const Vector3 c = polyhedron2->getFaceNormal(edge2.faceIndex); const Vector3 d = polyhedron2->getFaceNormal(polyhedron2->getHalfEdge(edge2.twinEdgeIndex).faceIndex); @@ -1020,12 +1021,12 @@ bool SATAlgorithm::testEdgesBuildMinkowskiFace(const ConvexPolyhedronShape* poly // Compute b.cross(a) using the edge direction const Vector3 edge1Vertex1 = polyhedron1->getVertexPosition(edge1.vertexIndex); const Vector3 edge1Vertex2 = polyhedron1->getVertexPosition(polyhedron1->getHalfEdge(edge1.twinEdgeIndex).vertexIndex); - const Vector3 bCrossA = polyhedron1ToPolyhedron2.getOrientation() * (edge1Vertex2 - edge1Vertex1); + const Vector3 bCrossA = polyhedron1ToPolyhedron2.getOrientation() * (edge1Vertex1 - edge1Vertex2); // Compute d.cross(c) using the edge direction const Vector3 edge2Vertex1 = polyhedron2->getVertexPosition(edge2.vertexIndex); const Vector3 edge2Vertex2 = polyhedron2->getVertexPosition(polyhedron2->getHalfEdge(edge2.twinEdgeIndex).vertexIndex); - const Vector3 dCrossC = edge2Vertex2 - edge2Vertex1; + const Vector3 dCrossC = edge2Vertex1 - edge2Vertex2; // Test if the two arcs of the Gauss Map intersect (therefore forming a minkowski face) // Note that we negate the normals of the second polyhedron because we are looking at the diff --git a/src/mathematics/mathematics_functions.cpp b/src/mathematics/mathematics_functions.cpp index 24329732..d627ed7b 100755 --- a/src/mathematics/mathematics_functions.cpp +++ b/src/mathematics/mathematics_functions.cpp @@ -354,4 +354,9 @@ std::vector reactphysics3d::clipPolygonWithPlanes(const std::vector clipSegmentWithPlanes(const Vector3& segA, const Vector3& s std::vector clipPolygonWithPlanes(const std::vector& polygonVertices, const std::vector& planesPoints, const std::vector& planesNormals); +/// Project a point onto a plane that is given by a point and its unit length normal +Vector3 projectPointOntoPlane(const Vector3& point, const Vector3& planeNormal, const Vector3& planePoint); + } From 8b82c4ac819998ea2af634a8a5858fd0cada31df Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 30 Jul 2017 22:14:46 +0200 Subject: [PATCH 080/248] Refactor the way to create the contact manifolds and contact points --- CMakeLists.txt | 4 + src/body/CollisionBody.cpp | 6 +- src/collision/CollisionCallback.cpp | 79 ++++ src/collision/CollisionCallback.h | 89 ++++ src/collision/CollisionDetection.cpp | 425 ++++++++++++------ src/collision/CollisionDetection.h | 17 +- src/collision/ContactManifold.cpp | 82 ++-- src/collision/ContactManifold.h | 248 ++++++---- src/collision/ContactManifoldInfo.cpp | 60 +-- src/collision/ContactManifoldInfo.h | 45 +- src/collision/ContactManifoldSet.cpp | 278 +++++++----- src/collision/ContactManifoldSet.h | 84 ++-- src/collision/NarrowPhaseInfo.cpp | 97 ++++ src/collision/NarrowPhaseInfo.h | 22 +- src/collision/OverlapCallback.h | 57 +++ .../narrowphase/CapsuleVsCapsuleAlgorithm.cpp | 8 +- .../narrowphase/CapsuleVsCapsuleAlgorithm.h | 3 +- .../CapsuleVsConvexPolyhedronAlgorithm.cpp | 15 +- .../CapsuleVsConvexPolyhedronAlgorithm.h | 3 +- .../narrowphase/ConcaveVsConvexAlgorithm.cpp | 178 ++++---- .../narrowphase/ConcaveVsConvexAlgorithm.h | 26 +- ...xPolyhedronVsConvexPolyhedronAlgorithm.cpp | 5 +- ...vexPolyhedronVsConvexPolyhedronAlgorithm.h | 3 +- .../narrowphase/GJK/GJKAlgorithm.cpp | 5 +- src/collision/narrowphase/GJK/GJKAlgorithm.h | 5 +- .../narrowphase/NarrowPhaseAlgorithm.h | 4 +- .../narrowphase/SAT/SATAlgorithm.cpp | 22 +- src/collision/narrowphase/SAT/SATAlgorithm.h | 8 +- .../narrowphase/SphereVsCapsuleAlgorithm.cpp | 4 +- .../narrowphase/SphereVsCapsuleAlgorithm.h | 3 +- .../SphereVsConvexPolyhedronAlgorithm.cpp | 7 +- .../SphereVsConvexPolyhedronAlgorithm.h | 3 +- .../narrowphase/SphereVsSphereAlgorithm.cpp | 5 +- .../narrowphase/SphereVsSphereAlgorithm.h | 3 +- src/collision/shapes/BoxShape.h | 2 + src/collision/shapes/CollisionShape.h | 17 - src/constraint/ContactPoint.cpp | 9 +- src/constraint/ContactPoint.h | 70 ++- src/engine/CollisionWorld.h | 58 --- src/engine/ContactSolver.cpp | 8 +- src/engine/DynamicsWorld.cpp | 11 +- src/engine/EventListener.h | 10 +- src/engine/OverlappingPair.cpp | 100 ++++- src/engine/OverlappingPair.h | 69 ++- src/memory/Allocator.h | 3 + src/memory/PoolAllocator.h | 8 + src/memory/SingleFrameAllocator.h | 9 +- src/reactphysics3d.h | 2 + .../CollisionDetectionScene.h | 40 +- testbed/src/SceneDemo.cpp | 6 +- 50 files changed, 1558 insertions(+), 767 deletions(-) create mode 100644 src/collision/CollisionCallback.cpp create mode 100644 src/collision/CollisionCallback.h create mode 100644 src/collision/NarrowPhaseInfo.cpp create mode 100644 src/collision/OverlapCallback.h diff --git a/CMakeLists.txt b/CMakeLists.txt index cba141df..1e1d2fcf 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -132,6 +132,7 @@ SET (REACTPHYSICS3D_SOURCES "src/collision/CollisionDetection.h" "src/collision/CollisionDetection.cpp" "src/collision/NarrowPhaseInfo.h" + "src/collision/NarrowPhaseInfo.cpp" "src/collision/ContactManifold.h" "src/collision/ContactManifold.cpp" "src/collision/ContactManifoldSet.h" @@ -167,6 +168,9 @@ SET (REACTPHYSICS3D_SOURCES "src/engine/Profiler.cpp" "src/engine/Timer.h" "src/engine/Timer.cpp" + "src/collision/CollisionCallback.h" + "src/collision/CollisionCallback.cpp" + "src/collision/OverlapCallback.h" "src/mathematics/mathematics.h" "src/mathematics/mathematics_functions.h" "src/mathematics/mathematics_functions.cpp" diff --git a/src/body/CollisionBody.cpp b/src/body/CollisionBody.cpp index db22f606..39d47de4 100644 --- a/src/body/CollisionBody.cpp +++ b/src/body/CollisionBody.cpp @@ -177,7 +177,7 @@ void CollisionBody::resetContactManifoldsList() { // Delete the linked list of contact manifolds of that body ContactManifoldListElement* currentElement = mContactManifoldsList; while (currentElement != nullptr) { - ContactManifoldListElement* nextElement = currentElement->next; + ContactManifoldListElement* nextElement = currentElement->getNext(); // Delete the current element currentElement->~ContactManifoldListElement(); @@ -272,8 +272,8 @@ int CollisionBody::resetIsAlreadyInIslandAndCountManifolds() { // this body ContactManifoldListElement* currentElement = mContactManifoldsList; while (currentElement != nullptr) { - currentElement->contactManifold->mIsAlreadyInIsland = false; - currentElement = currentElement->next; + currentElement->getContactManifold()->mIsAlreadyInIsland = false; + currentElement = currentElement->getNext(); nbManifolds++; } diff --git a/src/collision/CollisionCallback.cpp b/src/collision/CollisionCallback.cpp new file mode 100644 index 00000000..f470763d --- /dev/null +++ b/src/collision/CollisionCallback.cpp @@ -0,0 +1,79 @@ +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "collision/CollisionCallback.h" +#include "engine/OverlappingPair.h" +#include "memory/Allocator.h" +#include "collision/ContactManifold.h" + +// We want to use the ReactPhysics3D namespace +using namespace reactphysics3d; + +// Constructor +CollisionCallback::CollisionCallbackInfo::CollisionCallbackInfo(OverlappingPair* pair, Allocator& allocator) : + contactManifoldElements(nullptr), body1(pair->getShape1()->getBody()), + body2(pair->getShape2()->getBody()), + proxyShape1(pair->getShape1()), proxyShape2(pair->getShape2()), + mMemoryAllocator(allocator) { + + assert(pair != nullptr); + + const ContactManifoldSet& manifoldSet = pair->getContactManifoldSet(); + + // For each contact manifold in the set of manifolds in the pair + ContactManifold* contactManifold = manifoldSet.getContactManifolds(); + while (contactManifold != nullptr) { + + assert(contactManifold->getNbContactPoints() > 0); + + // Add the contact manifold at the beginning of the linked + // list of contact manifolds of the first body + ContactManifoldListElement* element = new (mMemoryAllocator.allocate(sizeof(ContactManifoldListElement))) + ContactManifoldListElement(contactManifold, + contactManifoldElements); + contactManifoldElements = element; + + contactManifold = contactManifold->getNext(); + } +} + +// Destructor +CollisionCallback::CollisionCallbackInfo::~CollisionCallbackInfo() { + + // Release memory allocator for the contact manifold list elements + ContactManifoldListElement* element = contactManifoldElements; + while (element != nullptr) { + + ContactManifoldListElement* nextElement = element->getNext(); + + // Delete and release memory + element->~ContactManifoldListElement(); + mMemoryAllocator.release(element, sizeof(ContactManifoldListElement)); + + element = nextElement; + } +} + diff --git a/src/collision/CollisionCallback.h b/src/collision/CollisionCallback.h new file mode 100644 index 00000000..f860b42d --- /dev/null +++ b/src/collision/CollisionCallback.h @@ -0,0 +1,89 @@ +/******************************************************************************** +* 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_COLLISION_CALLBACK_H +#define REACTPHYSICS3D_COLLISION_CALLBACK_H + +// Libraries +#include "collision/ContactManifold.h" + +/// ReactPhysics3D namespace +namespace reactphysics3d { + +// Class CollisionCallback +/** + * This class can be used to register a callback for collision test queries. + * You should implement your own class inherited from this one and implement + * the notifyContact() method. This method will called each time a contact + * point is reported. + */ +class CollisionCallback { + + public: + + // Structure CollisionCallbackInfo + /** + * This structure represents the contact information between two collision + * shapes of two bodies + */ + struct CollisionCallbackInfo { + + public: + + /// Pointer to the first element of the linked-list that contains contact manifolds + ContactManifoldListElement* contactManifoldElements; + + /// Pointer to the first body of the contact + CollisionBody* body1; + + /// Pointer to the second body of the contact + CollisionBody* body2; + + /// Pointer to the proxy shape of first body + const ProxyShape* proxyShape1; + + /// Pointer to the proxy shape of second body + const ProxyShape* proxyShape2; + + /// Memory allocator + Allocator& mMemoryAllocator; + + // Constructor + CollisionCallbackInfo(OverlappingPair* pair, Allocator& allocator); + + // Destructor + ~CollisionCallbackInfo(); + }; + + /// Destructor + virtual ~CollisionCallback() = default; + + /// This method will be called for each reported contact point + virtual void notifyContact(const CollisionCallbackInfo& collisionCallbackInfo)=0; +}; + +} + +#endif diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 0e7c8078..57360706 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -26,10 +26,13 @@ // Libraries #include "CollisionDetection.h" #include "engine/CollisionWorld.h" +#include "collision/OverlapCallback.h" #include "body/Body.h" #include "collision/shapes/BoxShape.h" #include "body/RigidBody.h" #include "configuration.h" +#include "collision/CollisionCallback.h" +#include "collision/OverlapCallback.h" #include #include #include @@ -43,7 +46,7 @@ using namespace std; // Constructor CollisionDetection::CollisionDetection(CollisionWorld* world, PoolAllocator& memoryAllocator, SingleFrameAllocator& singleFrameAllocator) - : mMemoryAllocator(memoryAllocator), mSingleFrameAllocator(singleFrameAllocator), + : mPoolAllocator(memoryAllocator), mSingleFrameAllocator(singleFrameAllocator), mWorld(world), mNarrowPhaseInfoList(nullptr), mBroadPhaseAlgorithm(*this), mIsCollisionShapesAdded(false) { @@ -83,7 +86,7 @@ void CollisionDetection::computeBroadPhase() { // Ask the broad-phase to recompute the overlapping pairs of collision // shapes. This call can only add new overlapping pairs in the collision // detection. - mBroadPhaseAlgorithm.computeOverlappingPairs(mMemoryAllocator); + mBroadPhaseAlgorithm.computeOverlappingPairs(mPoolAllocator); } } @@ -101,25 +104,24 @@ void CollisionDetection::computeMiddlePhase() { OverlappingPair* pair = it->second; + // Make all the contact manifolds and contact points of the pair obselete + pair->makeContactsObselete(); + ProxyShape* shape1 = pair->getShape1(); ProxyShape* shape2 = pair->getShape2(); assert(shape1->mBroadPhaseID != shape2->mBroadPhaseID); - // Check if the collision filtering allows collision between the two shapes and - // that the two shapes are still overlapping. Otherwise, we destroy the + // Check if the two shapes are still overlapping. Otherwise, we destroy the // overlapping pair - if (((shape1->getCollideWithMaskBits() & shape2->getCollisionCategoryBits()) == 0 || - (shape1->getCollisionCategoryBits() & shape2->getCollideWithMaskBits()) == 0) || - !mBroadPhaseAlgorithm.testOverlappingShapes(shape1, shape2)) { + if (!mBroadPhaseAlgorithm.testOverlappingShapes(shape1, shape2)) { std::map::iterator itToRemove = it; ++it; - // TODO : Remove all the contact manifold of the overlapping pair from the contact manifolds list of the two bodies involved - // Destroy the overlapping pair itToRemove->second->~OverlappingPair(); + mWorld->mPoolAllocator.release(itToRemove->second, sizeof(OverlappingPair)); mOverlappingPairs.erase(itToRemove); continue; @@ -128,56 +130,61 @@ void CollisionDetection::computeMiddlePhase() { ++it; } - CollisionBody* const body1 = shape1->getBody(); - CollisionBody* const body2 = shape2->getBody(); + // Check if the collision filtering allows collision between the two shapes + if (((shape1->getCollideWithMaskBits() & shape2->getCollisionCategoryBits()) != 0 && + (shape1->getCollisionCategoryBits() & shape2->getCollideWithMaskBits()) != 0)) { - // Check that at least one body is awake and not static - bool isBody1Active = !body1->isSleeping() && body1->getType() != BodyType::STATIC; - bool isBody2Active = !body2->isSleeping() && body2->getType() != BodyType::STATIC; - if (!isBody1Active && !isBody2Active) continue; + CollisionBody* const body1 = shape1->getBody(); + CollisionBody* const body2 = shape2->getBody(); - // Check if the bodies are in the set of bodies that cannot collide between each other - bodyindexpair bodiesIndex = OverlappingPair::computeBodiesIndexPair(body1, body2); - if (mNoCollisionPairs.count(bodiesIndex) > 0) continue; + // Check that at least one body is awake and not static + bool isBody1Active = !body1->isSleeping() && body1->getType() != BodyType::STATIC; + bool isBody2Active = !body2->isSleeping() && body2->getType() != BodyType::STATIC; + if (!isBody1Active && !isBody2Active) continue; - const CollisionShapeType shape1Type = shape1->getCollisionShape()->getType(); - const CollisionShapeType shape2Type = shape2->getCollisionShape()->getType(); + // Check if the bodies are in the set of bodies that cannot collide between each other + bodyindexpair bodiesIndex = OverlappingPair::computeBodiesIndexPair(body1, body2); + if (mNoCollisionPairs.count(bodiesIndex) > 0) continue; - // If both shapes are convex - if ((CollisionShape::isConvex(shape1Type) && CollisionShape::isConvex(shape2Type))) { + const CollisionShapeType shape1Type = shape1->getCollisionShape()->getType(); + const CollisionShapeType shape2Type = shape2->getCollisionShape()->getType(); - // No middle-phase is necessary, simply create a narrow phase info - // for the narrow-phase collision detection - NarrowPhaseInfo* firstNarrowPhaseInfo = mNarrowPhaseInfoList; - mNarrowPhaseInfoList = new (mSingleFrameAllocator.allocate(sizeof(NarrowPhaseInfo))) - NarrowPhaseInfo(pair, shape1->getCollisionShape(), - shape2->getCollisionShape(), shape1->getLocalToWorldTransform(), - shape2->getLocalToWorldTransform(), shape1->getCachedCollisionData(), - shape2->getCachedCollisionData()); - mNarrowPhaseInfoList->next = firstNarrowPhaseInfo; + // If both shapes are convex + if ((CollisionShape::isConvex(shape1Type) && CollisionShape::isConvex(shape2Type))) { - } - // Concave vs Convex algorithm - else if ((!CollisionShape::isConvex(shape1Type) && CollisionShape::isConvex(shape2Type)) || - (!CollisionShape::isConvex(shape2Type) && CollisionShape::isConvex(shape1Type))) { + // No middle-phase is necessary, simply create a narrow phase info + // for the narrow-phase collision detection + NarrowPhaseInfo* firstNarrowPhaseInfo = mNarrowPhaseInfoList; + mNarrowPhaseInfoList = new (mSingleFrameAllocator.allocate(sizeof(NarrowPhaseInfo))) + NarrowPhaseInfo(pair, shape1->getCollisionShape(), + shape2->getCollisionShape(), shape1->getLocalToWorldTransform(), + shape2->getLocalToWorldTransform(), shape1->getCachedCollisionData(), + shape2->getCachedCollisionData()); + mNarrowPhaseInfoList->next = firstNarrowPhaseInfo; - NarrowPhaseInfo* narrowPhaseInfo = nullptr; - computeConvexVsConcaveMiddlePhase(pair, mSingleFrameAllocator, &narrowPhaseInfo); - - // Add all the narrow-phase info object reported by the callback into the - // list of all the narrow-phase info object - while (narrowPhaseInfo != nullptr) { - NarrowPhaseInfo* next = narrowPhaseInfo->next; - narrowPhaseInfo->next = mNarrowPhaseInfoList; - mNarrowPhaseInfoList = narrowPhaseInfo; - - narrowPhaseInfo = next; } - } - // Concave vs Concave shape - else { - // Not handled - continue; + // Concave vs Convex algorithm + else if ((!CollisionShape::isConvex(shape1Type) && CollisionShape::isConvex(shape2Type)) || + (!CollisionShape::isConvex(shape2Type) && CollisionShape::isConvex(shape1Type))) { + + NarrowPhaseInfo* narrowPhaseInfo = nullptr; + computeConvexVsConcaveMiddlePhase(pair, mSingleFrameAllocator, &narrowPhaseInfo); + + // Add all the narrow-phase info object reported by the callback into the + // list of all the narrow-phase info object + while (narrowPhaseInfo != nullptr) { + NarrowPhaseInfo* next = narrowPhaseInfo->next; + narrowPhaseInfo->next = mNarrowPhaseInfoList; + mNarrowPhaseInfoList = narrowPhaseInfo; + + narrowPhaseInfo = next; + } + } + // Concave vs Concave shape + else { + // Not handled + continue; + } } } } @@ -231,7 +238,7 @@ void CollisionDetection::computeNarrowPhase() { PROFILE("CollisionDetection::computeNarrowPhase()"); - const NarrowPhaseInfo* currentNarrowPhaseInfo = mNarrowPhaseInfoList; + NarrowPhaseInfo* currentNarrowPhaseInfo = mNarrowPhaseInfoList; while (currentNarrowPhaseInfo != nullptr) { // Select the narrow phase algorithm to use according to the two collision shapes @@ -245,30 +252,16 @@ void CollisionDetection::computeNarrowPhase() { // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - ContactManifoldInfo contactManifoldInfo(mSingleFrameAllocator); - if (narrowPhaseAlgorithm->testCollision(currentNarrowPhaseInfo, contactManifoldInfo)) { + if (narrowPhaseAlgorithm->testCollision(currentNarrowPhaseInfo, true)) { - // Reduce the number of points in the contact manifold (if necessary) - contactManifoldInfo.reduce(currentNarrowPhaseInfo->shape1ToWorldTransform); - - // If it is the first contact since the pairs are overlapping - if (currentNarrowPhaseInfo->overlappingPair->getNbContactPoints() == 0) { - - // Trigger a callback event - if (mWorld->mEventListener != nullptr) mWorld->mEventListener->beginContact(contactManifoldInfo); - } - - // Add the contact manifold to the corresponding overlapping pair - currentNarrowPhaseInfo->overlappingPair->addContactManifold(contactManifoldInfo); + // Add the contact points as a potential contact manifold into the pair + currentNarrowPhaseInfo->addContactPointsAsPotentialContactManifold(); // Add the overlapping pair into the set of pairs in contact during narrow-phase overlappingpairid pairId = OverlappingPair::computeID(currentNarrowPhaseInfo->overlappingPair->getShape1(), currentNarrowPhaseInfo->overlappingPair->getShape2()); mContactOverlappingPairs[pairId] = currentNarrowPhaseInfo->overlappingPair; - // Trigger a callback event for the new contact - if (mWorld->mEventListener != nullptr) mWorld->mEventListener->newContact(contactManifoldInfo); - currentNarrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasColliding = true; } else { @@ -282,8 +275,14 @@ void CollisionDetection::computeNarrowPhase() { currentNarrowPhaseInfo = currentNarrowPhaseInfo->next; } + // Convert the potential contact into actual contacts + processAllPotentialContacts(); + // Add all the contact manifolds (between colliding bodies) to the bodies addAllContactManifoldsToBodies(); + + // Report contacts to the user + reportAllContacts(); } // Allow the broadphase to notify the collision detection about an overlapping pair. @@ -302,13 +301,9 @@ void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, Pro // Check if the overlapping pair already exists if (mOverlappingPairs.find(pairID) != mOverlappingPairs.end()) return; - // Compute the maximum number of contact manifolds for this pair - int nbMaxManifolds = CollisionShape::computeNbMaxContactManifolds(shape1->getCollisionShape()->getType(), - shape2->getCollisionShape()->getType()); - // Create the overlapping pair and add it into the set of overlapping pairs - OverlappingPair* newPair = new (mWorld->mPoolAllocator.allocate(sizeof(OverlappingPair))) - OverlappingPair(shape1, shape2, nbMaxManifolds, mWorld->mPoolAllocator); + OverlappingPair* newPair = new (mPoolAllocator.allocate(sizeof(OverlappingPair))) + OverlappingPair(shape1, shape2, mPoolAllocator, mSingleFrameAllocator); assert(newPair != nullptr); #ifndef NDEBUG @@ -372,40 +367,173 @@ void CollisionDetection::addContactManifoldToBody(OverlappingPair* pair) { const ContactManifoldSet& manifoldSet = pair->getContactManifoldSet(); // For each contact manifold in the set of manifolds in the pair - for (int i=0; igetNbContactPoints() > 0); // Add the contact manifold at the beginning of the linked // list of contact manifolds of the first body - void* allocatedMemory1 = mWorld->mPoolAllocator.allocate(sizeof(ContactManifoldListElement)); - ContactManifoldListElement* listElement1 = new (allocatedMemory1) + ContactManifoldListElement* listElement1 = new (mPoolAllocator.allocate(sizeof(ContactManifoldListElement))) ContactManifoldListElement(contactManifold, body1->mContactManifoldsList); body1->mContactManifoldsList = listElement1; // Add the contact manifold at the beginning of the linked // list of the contact manifolds of the second body - void* allocatedMemory2 = mWorld->mPoolAllocator.allocate(sizeof(ContactManifoldListElement)); - ContactManifoldListElement* listElement2 = new (allocatedMemory2) + ContactManifoldListElement* listElement2 = new (mPoolAllocator.allocate(sizeof(ContactManifoldListElement))) ContactManifoldListElement(contactManifold, body2->mContactManifoldsList); body2->mContactManifoldsList = listElement2; + + contactManifold = contactManifold->getNext(); } } -// Delete all the contact points in the currently overlapping pairs -void CollisionDetection::clearContactPoints() { +/// Convert the potential contact into actual contacts +void CollisionDetection::processAllPotentialContacts() { - // For each overlapping pair + // For each overlapping pairs in contact during the narrow-phase std::map::iterator it; - for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ++it) { - it->second->clearContactPoints(); + for (it = mContactOverlappingPairs.begin(); it != mContactOverlappingPairs.end(); ++it) { + + // Process the potential contacts of the overlapping pair + processPotentialContacts(it->second); } } +// Process the potential contact manifold of a pair to create actual contact manifold +void CollisionDetection::processPotentialContacts(OverlappingPair* pair) { + + // Reduce the number of contact points of the manifold + pair->reducePotentialContactManifolds(); + + // If there is a concave mesh shape in the pair + if (pair->hasConcaveShape()) { + + processSmoothMeshContacts(pair); + } + else { // If both collision shapes are convex + + // Add all the potential contact manifolds as actual contact manifolds to the pair + ContactManifoldInfo* potentialManifold = pair->getPotentialContactManifolds(); + while (potentialManifold != nullptr) { + + pair->addContactManifold(potentialManifold); + + potentialManifold = potentialManifold->mNext; + } + } + + // Clear the obselete contact manifolds and contact points + pair->clearObseleteManifoldsAndContactPoints(); + + // Reset the potential contacts of the pair + pair->clearPotentialContactManifolds(); +} + +// Report contacts for all the colliding overlapping pairs +void CollisionDetection::reportAllContacts() { + + // For each overlapping pairs in contact during the narrow-phase + std::map::iterator it; + for (it = mContactOverlappingPairs.begin(); it != mContactOverlappingPairs.end(); ++it) { + + // If there is a user callback + if (mWorld->mEventListener != nullptr) { + + CollisionCallback::CollisionCallbackInfo collisionInfo(it->second, mPoolAllocator); + + // Trigger a callback event to report the new contact to the user + mWorld->mEventListener->newContact(collisionInfo); + } + } +} + +// Process the potential contacts where one collion is a concave shape. +// This method processes the concave triangle mesh collision using the smooth mesh collision algorithm described +// by Pierre Terdiman (http://www.codercorner.com/MeshContacts.pdf). This is used to avoid the collision +// issue with some internal edges. +void CollisionDetection::processSmoothMeshContacts(OverlappingPair* pair) { + +// // Set with the triangle vertices already processed to void further contacts with same triangle +// std::unordered_multimap processTriangleVertices; + +// std::vector smoothContactPoints; + +// // If the collision shape 1 is the triangle +// bool isFirstShapeTriangle = pair->getShape1()->getCollisionShape()->getType() == CollisionShapeType::TRIANGLE; +// assert(isFirstShapeTriangle || pair->getShape2()->getCollisionShape()->getType() == CollisionShapeType::TRIANGLE); +// assert(!isFirstShapeTriangle || pair->getShape2()->getCollisionShape()->getType() != CollisionShapeType::TRIANGLE); + +// const TriangleShape* triangleShape = nullptr; +// if (isFirstShapeTriangle) { +// triangleShape = static_cast(pair->getShape1()->getCollisionShape()); +// } +// else { +// triangleShape = static_cast(pair->getShape2()->getCollisionShape()); +// } +// assert(triangleShape != nullptr); + +// // Get the temporary memory allocator +// Allocator& allocator = pair->getTemporaryAllocator(); + +// // For each potential contact manifold of the pair +// ContactManifoldInfo* potentialManifold = pair->getPotentialContactManifolds(); +// while (potentialManifold != nullptr) { + +// // For each contact point of the potential manifold +// ContactPointInfo* contactPointInfo = potentialManifold->getFirstContactPointInfo(); +// while (contactPointInfo != nullptr) { + +// // Compute the barycentric coordinates of the point in the triangle +// decimal u, v, w; +// computeBarycentricCoordinatesInTriangle(triangleShape->getVertexPosition(0), +// triangleShape->getVertexPosition(1), +// triangleShape->getVertexPosition(2), +// isFirstShapeTriangle ? contactPointInfo->localPoint1 : contactPointInfo->localPoint2, +// u, v, w); +// int nbZeros = 0; +// bool isUZero = approxEqual(u, 0, 0.0001); +// bool isVZero = approxEqual(v, 0, 0.0001); +// bool isWZero = approxEqual(w, 0, 0.0001); +// if (isUZero) nbZeros++; +// if (isVZero) nbZeros++; +// if (isWZero) nbZeros++; + +// // If the triangle contact point is on a triangle vertex of a triangle edge +// if (nbZeros == 1 || nbZeros == 2) { + + +// // Create a smooth mesh contact info +// SmoothMeshContactInfo* smoothContactInfo = new (allocator.allocate(sizeof(SmoothMeshContactInfo))) +// SmoothMeshContactInfo(potentialManifold, contactInfo, isFirstShapeTriangle, +// triangleShape->getVertexPosition(0), +// triangleShape->getVertexPosition(1), +// triangleShape->getVertexPosition(2)); + +// smoothContactPoints.push_back(smoothContactInfo); + +// // Remove the contact point info from the manifold. If the contact point will be kept in the future, we +// // will put the contact point back in the manifold. +// ... +// } + +// // Note that we do not remove the contact points that are not on the vertices or edges of the triangle +// // from the contact manifold because we know we will keep to contact points. We only remove the vertices +// // and edges contact points for the moment. If those points will be kept in the future, we will have to +// // put them back again in the contact manifold +// } + +// potentialManifold = potentialManifold->mNext; +// } + +// // Sort the list of narrow-phase contacts according to their penetration depth +// std::sort(smoothContactPoints.begin(), smoothContactPoints.end(), ContactsDepthCompare()); + +// ... +} + // Compute the middle-phase collision detection between two proxy shapes NarrowPhaseInfo* CollisionDetection::computeMiddlePhaseForProxyShapes(OverlappingPair* pair) { @@ -424,7 +552,7 @@ NarrowPhaseInfo* CollisionDetection::computeMiddlePhaseForProxyShapes(Overlappin // No middle-phase is necessary, simply create a narrow phase info // for the narrow-phase collision detection - narrowPhaseInfo = new (mMemoryAllocator.allocate(sizeof(NarrowPhaseInfo))) NarrowPhaseInfo(pair, shape1->getCollisionShape(), + narrowPhaseInfo = new (mPoolAllocator.allocate(sizeof(NarrowPhaseInfo))) NarrowPhaseInfo(pair, shape1->getCollisionShape(), shape2->getCollisionShape(), shape1->getLocalToWorldTransform(), shape2->getLocalToWorldTransform(), shape1->getCachedCollisionData(), shape2->getCachedCollisionData()); @@ -436,7 +564,7 @@ NarrowPhaseInfo* CollisionDetection::computeMiddlePhaseForProxyShapes(Overlappin // Run the middle-phase collision detection algorithm to find the triangles of the concave // shape we need to use during the narrow-phase collision detection - computeConvexVsConcaveMiddlePhase(pair, mMemoryAllocator, &narrowPhaseInfo); + computeConvexVsConcaveMiddlePhase(pair, mPoolAllocator, &narrowPhaseInfo); } return narrowPhaseInfo; @@ -450,7 +578,7 @@ void CollisionDetection::testAABBOverlap(const AABB& aabb, OverlapCallback* over std::unordered_set reportedBodies; // Ask the broad-phase to get all the overlapping shapes - LinkedList overlappingNodes(mMemoryAllocator); + LinkedList overlappingNodes(mPoolAllocator); mBroadPhaseAlgorithm.reportAllShapesOverlappingWithAABB(aabb, overlappingNodes); // For each overlaping proxy shape @@ -504,7 +632,7 @@ bool CollisionDetection::testOverlap(CollisionBody* body1, CollisionBody* body2) const CollisionShapeType shape2Type = body2ProxyShape->getCollisionShape()->getType(); // Create a temporary overlapping pair - OverlappingPair pair(body1ProxyShape, body2ProxyShape, 0, mMemoryAllocator); + OverlappingPair pair(body1ProxyShape, body2ProxyShape, mPoolAllocator, mPoolAllocator); // Compute the middle-phase collision detection between the two shapes NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); @@ -526,16 +654,18 @@ bool CollisionDetection::testOverlap(CollisionBody* body1, CollisionBody* body2) // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - ContactManifoldInfo contactManifoldInfo(mMemoryAllocator); - isColliding |= narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactManifoldInfo); + isColliding |= narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, false); } } NarrowPhaseInfo* currentNarrowPhaseInfo = narrowPhaseInfo; narrowPhaseInfo = narrowPhaseInfo->next; + // Call the destructor + currentNarrowPhaseInfo->~NarrowPhaseInfo(); + // Release the allocated memory - mMemoryAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); + mPoolAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); } // Return if we have found a narrow-phase collision @@ -570,7 +700,7 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl const AABB& shapeAABB = mBroadPhaseAlgorithm.getFatAABB(bodyProxyShape->mBroadPhaseID); // Ask the broad-phase to get all the overlapping shapes - LinkedList overlappingNodes(mMemoryAllocator); + LinkedList overlappingNodes(mPoolAllocator); mBroadPhaseAlgorithm.reportAllShapesOverlappingWithAABB(shapeAABB, overlappingNodes); const bodyindex bodyId = body->getID(); @@ -595,7 +725,7 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl const CollisionShapeType shape2Type = proxyShape->getCollisionShape()->getType(); // Create a temporary overlapping pair - OverlappingPair pair(bodyProxyShape, proxyShape, 0, mMemoryAllocator); + OverlappingPair pair(bodyProxyShape, proxyShape, mPoolAllocator, mPoolAllocator); // Compute the middle-phase collision detection between the two shapes NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); @@ -617,16 +747,18 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - ContactManifoldInfo contactManifoldInfo(mMemoryAllocator); - isColliding |= narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactManifoldInfo); + isColliding |= narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, false); } } NarrowPhaseInfo* currentNarrowPhaseInfo = narrowPhaseInfo; narrowPhaseInfo = narrowPhaseInfo->next; + // Call the destructor + currentNarrowPhaseInfo->~NarrowPhaseInfo(); + // Release the allocated memory - mMemoryAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); + mPoolAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); } // Return if we have found a narrow-phase collision @@ -673,7 +805,7 @@ void CollisionDetection::testCollision(CollisionBody* body1, CollisionBody* body if (aabb1.testCollision(aabb2)) { // Create a temporary overlapping pair - OverlappingPair pair(body1ProxyShape, body2ProxyShape, 0, mMemoryAllocator); + OverlappingPair pair(body1ProxyShape, body2ProxyShape, mPoolAllocator, mPoolAllocator); // Compute the middle-phase collision detection between the two shapes NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); @@ -693,26 +825,29 @@ void CollisionDetection::testCollision(CollisionBody* body1, CollisionBody* body // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - ContactManifoldInfo contactManifoldInfo(mMemoryAllocator); - if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactManifoldInfo)) { + if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, true)) { - // Reduce the number of points in the contact manifold (if necessary) - contactManifoldInfo.reduce(narrowPhaseInfo->shape1ToWorldTransform); - - CollisionCallback::CollisionCallbackInfo collisionInfo(contactManifoldInfo, body1, body2, - body1ProxyShape, body2ProxyShape); - - // Report the contact to the user - collisionCallback->notifyContact(collisionInfo); + // Add the contact points as a potential contact manifold into the pair + narrowPhaseInfo->addContactPointsAsPotentialContactManifold(); } } NarrowPhaseInfo* currentNarrowPhaseInfo = narrowPhaseInfo; narrowPhaseInfo = narrowPhaseInfo->next; + // Call the destructor + currentNarrowPhaseInfo->~NarrowPhaseInfo(); + // Release the allocated memory - mMemoryAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); + mPoolAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); } + + // Process the potential contacts + processPotentialContacts(&pair); + + // Report the contacts to the user + CollisionCallback::CollisionCallbackInfo collisionInfo(&pair, mPoolAllocator); + collisionCallback->notifyContact(collisionInfo); } // Go to the next proxy shape @@ -737,7 +872,7 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c const AABB& shapeAABB = mBroadPhaseAlgorithm.getFatAABB(bodyProxyShape->mBroadPhaseID); // Ask the broad-phase to get all the overlapping shapes - LinkedList overlappingNodes(mMemoryAllocator); + LinkedList overlappingNodes(mPoolAllocator); mBroadPhaseAlgorithm.reportAllShapesOverlappingWithAABB(shapeAABB, overlappingNodes); const bodyindex bodyId = body->getID(); @@ -760,7 +895,7 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c const CollisionShapeType shape2Type = proxyShape->getCollisionShape()->getType(); // Create a temporary overlapping pair - OverlappingPair pair(bodyProxyShape, proxyShape, 0, mMemoryAllocator); + OverlappingPair pair(bodyProxyShape, proxyShape, mPoolAllocator, mPoolAllocator); // Compute the middle-phase collision detection between the two shapes NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); @@ -777,17 +912,13 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - ContactManifoldInfo contactManifoldInfo(mMemoryAllocator); - if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactManifoldInfo)) { + if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, true)) { - // Reduce the number of points in the contact manifold (if necessary) - contactManifoldInfo.reduce(narrowPhaseInfo->shape1ToWorldTransform); + // Add the contact points as a potential contact manifold into the pair + narrowPhaseInfo->addContactPointsAsPotentialContactManifold(); - CollisionCallback::CollisionCallbackInfo collisionInfo(contactManifoldInfo, body, - proxyShape->getBody(), bodyProxyShape, - proxyShape); - - // Report the contact to the user + // Report the contacts to the user + CollisionCallback::CollisionCallbackInfo collisionInfo(&pair, mPoolAllocator); callback->notifyContact(collisionInfo); } } @@ -795,9 +926,15 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c NarrowPhaseInfo* currentNarrowPhaseInfo = narrowPhaseInfo; narrowPhaseInfo = narrowPhaseInfo->next; + // Call the destructor + currentNarrowPhaseInfo->~NarrowPhaseInfo(); + // Release the allocated memory - mMemoryAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); + mPoolAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); } + + // Process the potential contacts + processPotentialContacts(&pair); } } @@ -822,10 +959,14 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { map::iterator it; for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ++it) { - OverlappingPair* pair = it->second; + OverlappingPair* originalPair = it->second; - ProxyShape* shape1 = pair->getShape1(); - ProxyShape* shape2 = pair->getShape2(); + // Create a new overlapping pair so that we do not work on the original one + OverlappingPair pair(originalPair->getShape1(), originalPair->getShape2(), mPoolAllocator, + mPoolAllocator); + + ProxyShape* shape1 = pair.getShape1(); + ProxyShape* shape2 = pair.getShape2(); // Check if the collision filtering allows collision between the two shapes and // that the two shapes are still overlapping. @@ -834,14 +975,14 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { mBroadPhaseAlgorithm.testOverlappingShapes(shape1, shape2)) { // Compute the middle-phase collision detection between the two shapes - NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(pair); - - const CollisionShapeType shape1Type = shape1->getCollisionShape()->getType(); - const CollisionShapeType shape2Type = shape2->getCollisionShape()->getType(); + NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); // For each narrow-phase info object while (narrowPhaseInfo != nullptr) { + const CollisionShapeType shape1Type = shape1->getCollisionShape()->getType(); + const CollisionShapeType shape2Type = shape2->getCollisionShape()->getType(); + // Select the narrow phase algorithm to use according to the two collision shapes NarrowPhaseAlgorithm* narrowPhaseAlgorithm = selectNarrowPhaseAlgorithm(shape1Type, shape2Type); @@ -851,29 +992,29 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - ContactManifoldInfo contactManifoldInfo(mMemoryAllocator); - if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, contactManifoldInfo)) { + if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, true)) { - // Reduce the number of points in the contact manifold (if necessary) - contactManifoldInfo.reduce(narrowPhaseInfo->shape1ToWorldTransform); + // Add the contact points as a potential contact manifold into the pair + narrowPhaseInfo->addContactPointsAsPotentialContactManifold(); - CollisionCallback::CollisionCallbackInfo collisionInfo(contactManifoldInfo, shape1->getBody(), - shape2->getBody(), shape1, shape2); - - // Report the contact to the user + // Report the contacts to the user + CollisionCallback::CollisionCallbackInfo collisionInfo(&pair, mPoolAllocator); callback->notifyContact(collisionInfo); } - - // The previous frame collision info is now valid - narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().isValid = true; } NarrowPhaseInfo* currentNarrowPhaseInfo = narrowPhaseInfo; narrowPhaseInfo = narrowPhaseInfo->next; + // Call the destructor + currentNarrowPhaseInfo->~NarrowPhaseInfo(); + // Release the allocated memory - mMemoryAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); + mPoolAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); } + + // Process the potential contacts + processPotentialContacts(&pair); } } } diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index 3fe88812..49f0d56b 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -72,7 +72,7 @@ class CollisionDetection { NarrowPhaseAlgorithm* mCollisionMatrix[NB_COLLISION_SHAPE_TYPES][NB_COLLISION_SHAPE_TYPES]; /// Reference to the memory allocator - PoolAllocator& mMemoryAllocator; + PoolAllocator& mPoolAllocator; /// Reference to the single frame memory allocator SingleFrameAllocator& mSingleFrameAllocator; @@ -118,9 +118,6 @@ class CollisionDetection { /// involed in the corresponding contact. void addContactManifoldToBody(OverlappingPair* pair); - /// Delete all the contact points in the currently overlapping pairs - void clearContactPoints(); - /// Fill-in the collision detection matrix void fillInCollisionMatrix(); @@ -137,6 +134,18 @@ class CollisionDetection { /// Compute the middle-phase collision detection between two proxy shapes NarrowPhaseInfo* computeMiddlePhaseForProxyShapes(OverlappingPair* pair); + + /// Convert the potential contact into actual contacts + void processAllPotentialContacts(); + + /// Process the potential contact manifold of a pair to create actual contact manifold + void processPotentialContacts(OverlappingPair* pair); + + /// Report contacts for all the colliding overlapping pairs + void reportAllContacts(); + + /// Process the potential contacts where one collion is a concave shape + void processSmoothMeshContacts(OverlappingPair* pair); public : diff --git a/src/collision/ContactManifold.cpp b/src/collision/ContactManifold.cpp index 36103642..846a418a 100644 --- a/src/collision/ContactManifold.cpp +++ b/src/collision/ContactManifold.cpp @@ -30,15 +30,14 @@ using namespace reactphysics3d; // Constructor -ContactManifold::ContactManifold(const ContactManifoldInfo& manifoldInfo, ProxyShape* shape1, ProxyShape* shape2, - PoolAllocator& memoryAllocator, short normalDirectionId) - : mShape1(shape1), mShape2(shape2), mNormalDirectionId(normalDirectionId), +ContactManifold::ContactManifold(const ContactManifoldInfo* manifoldInfo, ProxyShape* shape1, ProxyShape* shape2, Allocator& memoryAllocator) + : mShape1(shape1), mShape2(shape2), mContactPoints(nullptr), mContactNormalId(manifoldInfo->getContactNormalId()), mNbContactPoints(0), mFrictionImpulse1(0.0), mFrictionImpulse2(0.0), mFrictionTwistImpulse(0.0), mIsAlreadyInIsland(false), - mMemoryAllocator(memoryAllocator) { + mMemoryAllocator(memoryAllocator), mNext(nullptr), mPrevious(nullptr), mIsObselete(false) { // For each contact point info in the manifold - const ContactPointInfo* pointInfo = manifoldInfo.getFirstContactPointInfo(); + const ContactPointInfo* pointInfo = manifoldInfo->getFirstContactPointInfo(); while(pointInfo != nullptr) { // Create the new contact point @@ -46,7 +45,8 @@ ContactManifold::ContactManifold(const ContactManifoldInfo& manifoldInfo, ProxyS ContactPoint(pointInfo, mShape1->getLocalToWorldTransform(), mShape2->getLocalToWorldTransform()); // Add the new contact point into the manifold - mContactPoints[mNbContactPoints] = contact; + contact->setNext(mContactPoints); + mContactPoints = contact; mNbContactPoints++; pointInfo = pointInfo->next; @@ -58,49 +58,69 @@ ContactManifold::ContactManifold(const ContactManifoldInfo& manifoldInfo, ProxyS // Destructor ContactManifold::~ContactManifold() { - clear(); -} -// Clear the contact manifold -void ContactManifold::clear() { - for (uint i=0; i~ContactPoint(); - mMemoryAllocator.release(mContactPoints[i], sizeof(ContactPoint)); + // Delete all the contact points + ContactPoint* contactPoint = mContactPoints; + while(contactPoint != nullptr) { + + ContactPoint* nextContactPoint = contactPoint->getNext(); + + // TODO : Delete this + bool test = mMemoryAllocator.isReleaseNeeded(); + + // Delete the contact point + contactPoint->~ContactPoint(); + mMemoryAllocator.release(contactPoint, sizeof(ContactPoint)); + + contactPoint = nextContactPoint; } - mNbContactPoints = 0; } // Add a contact point void ContactManifold::addContactPoint(const ContactPointInfo* contactPointInfo) { - assert(mNbContactPoints < MAX_CONTACT_POINTS_IN_MANIFOLD); - // Create the new contact point ContactPoint* contactPoint = new (mMemoryAllocator.allocate(sizeof(ContactPoint))) ContactPoint(contactPointInfo, mShape1->getLocalToWorldTransform(), mShape2->getLocalToWorldTransform()); // Add the new contact point into the manifold - mContactPoints[mNbContactPoints] = contactPoint; - mNbContactPoints++; + contactPoint->setNext(mContactPoints); + mContactPoints = contactPoint; + mNbContactPoints++; } -// Remove a contact point -void ContactManifold::removeContactPoint(int index) { +// Clear the obselete contact points +void ContactManifold::clearObseleteContactPoints() { - assert(mNbContactPoints > 0); - assert(index >= 0 && index < mNbContactPoints); + ContactPoint* contactPoint = mContactPoints; + ContactPoint* previousContactPoint = nullptr; + while (contactPoint != nullptr) { - // Delete the contact - mContactPoints[index]->~ContactPoint(); - mMemoryAllocator.release(mContactPoints[index], sizeof(ContactPoint)); + ContactPoint* nextContactPoint = contactPoint->getNext(); - for (int i=index; (i+1) < mNbContactPoints; i++) { - mContactPoints[i] = mContactPoints[i+1]; + if (contactPoint->getIsObselete()) { + + // Delete the contact point + contactPoint->~ContactPoint(); + mMemoryAllocator.release(contactPoint, sizeof(ContactPoint)); + + if (previousContactPoint != nullptr) { + previousContactPoint->setNext(nextContactPoint); + } + else { + mContactPoints = nextContactPoint; + } + + mNbContactPoints--; + } + else { + previousContactPoint = contactPoint; + } + + contactPoint = nextContactPoint; } - mNbContactPoints--; + assert(mNbContactPoints >= 0); + assert(mNbContactPoints <= MAX_CONTACT_POINTS_IN_MANIFOLD); } diff --git a/src/collision/ContactManifold.h b/src/collision/ContactManifold.h index 893a84a7..0704beed 100644 --- a/src/collision/ContactManifold.h +++ b/src/collision/ContactManifold.h @@ -46,40 +46,43 @@ class ContactManifold; */ struct ContactManifoldListElement { - public: + private: // -------------------- Attributes -------------------- // - /// Pointer to the actual contact manifold - ContactManifold* contactManifold; + /// Pointer to a contact manifold with contact points + ContactManifold* mContactManifold; /// Next element of the list - ContactManifoldListElement* next; + ContactManifoldListElement* mNext; + + public: // -------------------- Methods -------------------- // /// Constructor - ContactManifoldListElement(ContactManifold* initContactManifold, - ContactManifoldListElement* initNext) - :contactManifold(initContactManifold), next(initNext) { + ContactManifoldListElement(ContactManifold* contactManifold, + ContactManifoldListElement* next) + :mContactManifold(contactManifold), mNext(next) { } + + /// Return the contact manifold + ContactManifold* getContactManifold() { + return mContactManifold; + } + + /// Return the next element in the linked-list + ContactManifoldListElement* getNext() { + return mNext; + } }; // Class ContactManifold /** * This class represents the set of contact points between two bodies. * The contact manifold is implemented in a way to cache the contact - * points among the frames for better stability following the - * "Contact Generation" presentation of Erwin Coumans at GDC 2010 - * conference (bullet.googlecode.com/files/GDC10_Coumans_Erwin_Contact.pdf). - * Some code of this class is based on the implementation of the - * btPersistentManifold class from Bullet physics engine (www.http://bulletphysics.org). - * The contacts between two bodies are added one after the other in the cache. - * When the cache is full, we have to remove one point. The idea is to keep - * the point with the deepest penetration depth and also to keep the - * points producing the larger area (for a more stable contact manifold). - * The new added point is always kept. + * points among the frames for better stability. */ class ContactManifold { @@ -94,10 +97,10 @@ class ContactManifold { ProxyShape* mShape2; /// Contact points in the manifold - ContactPoint* mContactPoints[MAX_CONTACT_POINTS_IN_MANIFOLD]; + ContactPoint* mContactPoints; /// Normal direction Id (Unique Id representing the normal direction) - short int mNormalDirectionId; + short int mContactNormalId; /// Number of contacts in the cache int8 mNbContactPoints; @@ -124,20 +127,86 @@ class ContactManifold { bool mIsAlreadyInIsland; /// Reference to the memory allocator - PoolAllocator& mMemoryAllocator; + Allocator& mMemoryAllocator; + + /// Pointer to the next contact manifold in the linked-list + ContactManifold* mNext; + + /// Pointer to the previous contact manifold in linked-list + ContactManifold* mPrevious; + + /// True if the contact manifold is obselete + bool mIsObselete; // -------------------- Methods -------------------- // /// Return true if the contact manifold has already been added into an island bool isAlreadyInIsland() const; + + /// Set the pointer to the next element in the linked-list + void setNext(ContactManifold* nextManifold); + + /// Return true if the manifold is obselete + bool getIsObselete() const; + + /// Set to true to make the manifold obselete + void setIsObselete(bool isObselete, bool setContactPoints); + + /// Clear the obselete contact points + void clearObseleteContactPoints(); + + /// Return the contact normal direction Id of the manifold + short getContactNormalId() const; + + /// Return the largest depth of all the contact points + decimal getLargestContactDepth() const; + + /// set the first friction vector at the center of the contact manifold + void setFrictionVector1(const Vector3& mFrictionVector1); + + /// set the second friction vector at the center of the contact manifold + void setFrictionVector2(const Vector3& mFrictionVector2); + + /// Set the first friction accumulated impulse + void setFrictionImpulse1(decimal frictionImpulse1); + + /// Set the second friction accumulated impulse + void setFrictionImpulse2(decimal frictionImpulse2); + + /// Add a contact point + void addContactPoint(const ContactPointInfo* contactPointInfo); + + /// Set the friction twist accumulated impulse + void setFrictionTwistImpulse(decimal frictionTwistImpulse); + + /// Set the accumulated rolling resistance impulse + void setRollingResistanceImpulse(const Vector3& rollingResistanceImpulse); + + /// Set the pointer to the previous element in the linked-list + void setPrevious(ContactManifold* previousManifold); + + /// Return the first friction vector at the center of the contact manifold + const Vector3& getFrictionVector1() const; + + /// Return the second friction vector at the center of the contact manifold + const Vector3& getFrictionVector2() const; + + /// Return the first friction accumulated impulse + decimal getFrictionImpulse1() const; + + /// Return the second friction accumulated impulse + decimal getFrictionImpulse2() const; + + /// Return the friction twist accumulated impulse + decimal getFrictionTwistImpulse() const; public: // -------------------- Methods -------------------- // /// Constructor - ContactManifold(const ContactManifoldInfo& manifoldInfo, ProxyShape* shape1, ProxyShape* shape2, - PoolAllocator& memoryAllocator, short int normalDirectionId); + ContactManifold(const ContactManifoldInfo* manifoldInfo, ProxyShape* shape1, ProxyShape* shape2, + Allocator& memoryAllocator); /// Destructor ~ContactManifold(); @@ -160,68 +229,25 @@ class ContactManifold { /// Return a pointer to the second body of the contact manifold CollisionBody* getBody2() const; - /// Return the normal direction Id - short int getNormalDirectionId() const; - - /// Clear the contact manifold - void clear(); - /// Return the number of contact points in the manifold int8 getNbContactPoints() const; - /// Return the first friction vector at the center of the contact manifold - const Vector3& getFrictionVector1() const; + /// Return a pointer to the first contact point of the manifold + ContactPoint* getContactPoints() const; - /// set the first friction vector at the center of the contact manifold - void setFrictionVector1(const Vector3& mFrictionVector1); + /// Return a pointer to the previous element in the linked-list + ContactManifold* getPrevious() const; - /// Return the second friction vector at the center of the contact manifold - const Vector3& getFrictionVector2() const; - - /// set the second friction vector at the center of the contact manifold - void setFrictionVector2(const Vector3& mFrictionVector2); - - /// Return the first friction accumulated impulse - decimal getFrictionImpulse1() const; - - /// Set the first friction accumulated impulse - void setFrictionImpulse1(decimal frictionImpulse1); - - /// Return the second friction accumulated impulse - decimal getFrictionImpulse2() const; - - /// Set the second friction accumulated impulse - void setFrictionImpulse2(decimal frictionImpulse2); - - /// Return the friction twist accumulated impulse - decimal getFrictionTwistImpulse() const; - - /// Set the friction twist accumulated impulse - void setFrictionTwistImpulse(decimal frictionTwistImpulse); - - /// Set the accumulated rolling resistance impulse - void setRollingResistanceImpulse(const Vector3& rollingResistanceImpulse); - - /// Return a contact point of the manifold - ContactPoint* getContactPoint(uint index) const; - - /// Return the normalized averaged normal vector - Vector3 getAverageContactNormal() const; - - /// Return the largest depth of all the contact points - decimal getLargestContactDepth() const; - - /// Add a contact point - void addContactPoint(const ContactPointInfo* contactPointInfo); - - /// Remove a contact point - void removeContactPoint(int index); + /// Return a pointer to the next element in the linked-list + ContactManifold* getNext() const; // -------------------- Friendship -------------------- // friend class DynamicsWorld; friend class Island; friend class CollisionBody; + friend class ContactManifoldSet; + friend class ContactSolver; }; // Return a pointer to the first proxy shape of the contact @@ -244,11 +270,6 @@ inline CollisionBody* ContactManifold::getBody2() const { return mShape2->getBody(); } -// Return the normal direction Id -inline short int ContactManifold::getNormalDirectionId() const { - return mNormalDirectionId; -} - // Return the number of contact points in the manifold inline int8 ContactManifold::getNbContactPoints() const { return mNbContactPoints; @@ -309,10 +330,9 @@ inline void ContactManifold::setRollingResistanceImpulse(const Vector3& rollingR mRollingResistanceImpulse = rollingResistanceImpulse; } -// Return a contact point of the manifold -inline ContactPoint* ContactManifold::getContactPoint(uint index) const { - assert(index < mNbContactPoints); - return mContactPoints[index]; +// Return a pointer to the first contact point of the manifold +inline ContactPoint* ContactManifold::getContactPoints() const { + return mContactPoints; } // Return true if the contact manifold has already been added into an island @@ -320,31 +340,69 @@ inline bool ContactManifold::isAlreadyInIsland() const { return mIsAlreadyInIsland; } -// Return the normalized averaged normal vector -inline Vector3 ContactManifold::getAverageContactNormal() const { - Vector3 averageNormal; - - for (uint i=0; igetNormal(); - } - - return averageNormal.getUnit(); -} - // Return the largest depth of all the contact points inline decimal ContactManifold::getLargestContactDepth() const { decimal largestDepth = 0.0f; - for (uint i=0; igetPenetrationDepth(); + assert(mNbContactPoints > 0); + + ContactPoint* contactPoint = mContactPoints; + while(contactPoint != nullptr){ + decimal depth = contactPoint->getPenetrationDepth(); if (depth > largestDepth) { largestDepth = depth; } + + contactPoint = contactPoint->getNext(); } return largestDepth; } +// Return a pointer to the previous element in the linked-list +inline ContactManifold* ContactManifold::getPrevious() const { + return mPrevious; +} + +// Set the pointer to the previous element in the linked-list +inline void ContactManifold::setPrevious(ContactManifold* previousManifold) { + mPrevious = previousManifold; +} + +// Return a pointer to the next element in the linked-list +inline ContactManifold* ContactManifold::getNext() const { + return mNext; +} + +// Set the pointer to the next element in the linked-list +inline void ContactManifold::setNext(ContactManifold* nextManifold) { + mNext = nextManifold; +} + +// Return true if the manifold is obselete +inline bool ContactManifold::getIsObselete() const { + return mIsObselete; +} + +// Set to true to make the manifold obselete +inline void ContactManifold::setIsObselete(bool isObselete, bool setContactPoints) { + mIsObselete = isObselete; + + if (setContactPoints) { + ContactPoint* contactPoint = mContactPoints; + while (contactPoint != nullptr) { + contactPoint->setIsObselete(isObselete); + + contactPoint = contactPoint->getNext(); + } + } +} + +// Return the contact normal direction Id of the manifold +inline short ContactManifold::getContactNormalId() const { + return mContactNormalId; +} + } #endif diff --git a/src/collision/ContactManifoldInfo.cpp b/src/collision/ContactManifoldInfo.cpp index c06785ea..a6b8c6df 100644 --- a/src/collision/ContactManifoldInfo.cpp +++ b/src/collision/ContactManifoldInfo.cpp @@ -30,7 +30,8 @@ using namespace reactphysics3d; // Constructor ContactManifoldInfo::ContactManifoldInfo(Allocator& allocator) - : mContactPointsList(nullptr), mAllocator(allocator), mNbContactPoints(0) {} + : mContactPointsList(nullptr), mNbContactPoints(0), mNext(nullptr), mAllocator(allocator), + mContactNormalId(-1) {} // Destructor ContactManifoldInfo::~ContactManifoldInfo() { @@ -40,14 +41,13 @@ ContactManifoldInfo::~ContactManifoldInfo() { } // Add a new contact point into the manifold -void ContactManifoldInfo::addContactPoint(const Vector3& contactNormal, decimal penDepth, - const Vector3& localPt1, const Vector3& localPt2) { +void ContactManifoldInfo::addContactPoint(ContactPointInfo* contactPointInfo, short contactNormalId) { - assert(penDepth > decimal(0.0)); + assert(contactPointInfo->penetrationDepth > decimal(0.0)); + assert(contactNormalId >= 0); + assert(mContactNormalId == -1 || contactNormalId == mContactNormalId); - // Create the contact point info - ContactPointInfo* contactPointInfo = new (mAllocator.allocate(sizeof(ContactPointInfo))) - ContactPointInfo(contactNormal, penDepth, localPt1, localPt2); + mContactNormalId = contactNormalId; // Add it into the linked list of contact points contactPointInfo->next = mContactPointsList; @@ -73,15 +73,31 @@ void ContactManifoldInfo::reset() { mNbContactPoints = 0; } -// Reduce the number of points in the contact manifold +// Return the largest penetration depth among its contact points +decimal ContactManifoldInfo::getLargestPenetrationDepth() const { + + ContactPointInfo* contactPoint = mContactPointsList; + assert(contactPoint != nullptr); + decimal maxDepth = decimal(0.0); + while (contactPoint != nullptr) { + + if (contactPoint->penetrationDepth > maxDepth) { + maxDepth = contactPoint->penetrationDepth; + } + + contactPoint = contactPoint->next; + } + + return maxDepth; +} + +// Reduce the number of contact points of the currently computed manifold // This is based on the technique described by Dirk Gregorius in his // "Contacts Creation" GDC presentation void ContactManifoldInfo::reduce(const Transform& shape1ToWorldTransform) { assert(mContactPointsList != nullptr); - // TODO : Implement this (do not forget to deallocate removed points) - // The following algorithm only works to reduce to 4 contact points assert(MAX_CONTACT_POINTS_IN_MANIFOLD == 4); @@ -221,9 +237,9 @@ void ContactManifoldInfo::reduce(const Transform& shape1ToWorldTransform) { largestArea = area; pointsToKeep[3] = element; } - - element = element->next; } + + element = element->next; } assert(pointsToKeep[3] != nullptr); @@ -250,6 +266,9 @@ void ContactManifoldInfo::reduce(const Transform& shape1ToWorldTransform) { } element = element->next; + // Call the destructor + elementToDelete->~ContactPointInfo(); + // Delete the current element mAllocator.release(elementToDelete, sizeof(ContactPointInfo)); } @@ -258,21 +277,4 @@ void ContactManifoldInfo::reduce(const Transform& shape1ToWorldTransform) { } } -/// Return the largest penetration depth among the contact points -decimal ContactManifoldInfo::getLargestPenetrationDepth() const { - - decimal maxDepth = decimal(0.0); - ContactPointInfo* element = mContactPointsList; - while(element != nullptr) { - - if (element->penetrationDepth > maxDepth) { - maxDepth = element->penetrationDepth; - } - - element = element->next; - } - - return maxDepth; -} - diff --git a/src/collision/ContactManifoldInfo.h b/src/collision/ContactManifoldInfo.h index a7e84a98..5851c375 100644 --- a/src/collision/ContactManifoldInfo.h +++ b/src/collision/ContactManifoldInfo.h @@ -34,7 +34,7 @@ namespace reactphysics3d { // Constants -const uint MAX_CONTACT_POINTS_IN_MANIFOLD = 4; // Maximum number of contacts in the manifold +const int8 MAX_CONTACT_POINTS_IN_MANIFOLD = 4; // Maximum number of contacts in the manifold // Class ContactManifoldInfo /** @@ -50,12 +50,18 @@ class ContactManifoldInfo { /// Linked list with all the contact points ContactPointInfo* mContactPointsList; - /// Memory allocator used to allocate contact points - Allocator& mAllocator; - /// Number of contact points in the manifold uint mNbContactPoints; + /// Next element in the linked-list of contact manifold info + ContactManifoldInfo* mNext; + + /// Reference the the memory allocator where the contact point infos have been allocated + Allocator& mAllocator; + + /// Contact normal direction Id (Identify the contact normal direction of points in manifold) + short mContactNormalId; + public: // -------------------- Methods -------------------- // @@ -66,15 +72,14 @@ class ContactManifoldInfo { /// Destructor ~ContactManifoldInfo(); - /// Deleted copy-constructor + /// Deleted Copy-constructor ContactManifoldInfo(const ContactManifoldInfo& contactManifold) = delete; /// Deleted assignment operator ContactManifoldInfo& operator=(const ContactManifoldInfo& contactManifold) = delete; /// Add a new contact point into the manifold - void addContactPoint(const Vector3& contactNormal, decimal penDepth, - const Vector3& localPt1, const Vector3& localPt2); + void addContactPoint(ContactPointInfo* contactPointInfo, short contactNormalId); /// Remove all the contact points void reset(); @@ -82,11 +87,21 @@ class ContactManifoldInfo { /// Get the first contact point info of the linked list of contact points ContactPointInfo* getFirstContactPointInfo() const; - /// Reduce the number of points in the contact manifold + /// Return the largest penetration depth among its contact points + decimal getLargestPenetrationDepth() const; + + /// Return the pointer to the next manifold info in the linked-list + ContactManifoldInfo* getNext(); + + /// Return the contact normal Id + short getContactNormalId() const; + + /// Reduce the number of contact points of the currently computed manifold void reduce(const Transform& shape1ToWorldTransform); - /// Return the largest penetration depth among the contact points - decimal getLargestPenetrationDepth() const; + // Friendship + friend class OverlappingPair; + friend class CollisionDetection; }; // Get the first contact point info of the linked list of contact points @@ -94,6 +109,16 @@ inline ContactPointInfo* ContactManifoldInfo::getFirstContactPointInfo() const { return mContactPointsList; } +// Return the pointer to the next manifold info in the linked-list +inline ContactManifoldInfo* ContactManifoldInfo::getNext() { + return mNext; +} + +// Return the contact normal Id +inline short ContactManifoldInfo::getContactNormalId() const { + return mContactNormalId; +} + } #endif diff --git a/src/collision/ContactManifoldSet.cpp b/src/collision/ContactManifoldSet.cpp index c9b0d5bb..b9b7f3e8 100644 --- a/src/collision/ContactManifoldSet.cpp +++ b/src/collision/ContactManifoldSet.cpp @@ -30,10 +30,12 @@ using namespace reactphysics3d; // Constructor ContactManifoldSet::ContactManifoldSet(ProxyShape* shape1, ProxyShape* shape2, - PoolAllocator& memoryAllocator, int nbMaxManifolds) - : mNbMaxManifolds(nbMaxManifolds), mNbManifolds(0), mShape1(shape1), - mShape2(shape2), mMemoryAllocator(memoryAllocator) { + Allocator& memoryAllocator) + : mNbManifolds(0), mShape1(shape1), + mShape2(shape2), mMemoryAllocator(memoryAllocator), mManifolds(nullptr) { + // Compute the maximum number of manifolds allowed between the two shapes + mNbMaxManifolds = computeNbMaxContactManifolds(shape1->getCollisionShape(), shape2->getCollisionShape()); } // Destructor @@ -43,167 +45,131 @@ ContactManifoldSet::~ContactManifoldSet() { clear(); } -void ContactManifoldSet::addContactManifold(const ContactManifoldInfo& contactManifoldInfo) { +void ContactManifoldSet::addContactManifold(const ContactManifoldInfo* contactManifoldInfo) { - assert(contactManifoldInfo.getFirstContactPointInfo() != nullptr); + assert(contactManifoldInfo->getFirstContactPointInfo() != nullptr); - // If there is no contact manifold yet - if (mNbManifolds == 0) { + // Try to find an existing contact manifold with similar contact normal + ContactManifold* similarManifold = selectManifoldWithSimilarNormal(contactManifoldInfo->getContactNormalId()); - // If the maximum number of manifold is 1 - if (mNbMaxManifolds == 1) { - createManifold(contactManifoldInfo, 0); - } - else { + // If a similar manifold has been found + if (similarManifold != nullptr) { - // Compute an Id corresponding to the normal direction (using a cubemap) - short int normalDirectionId = computeCubemapNormalId(contactManifoldInfo.getFirstContactPointInfo()->normal); - - createManifold(contactManifoldInfo, normalDirectionId); - } + // Update the old manifold with the new one + updateManifoldWithNewOne(similarManifold, contactManifoldInfo); } - else { // If there is already at least one contact manifold in the set + else { - // If the maximum number of manifold is 1 - if (mNbMaxManifolds == 1) { + // If there are too much contact manifolds in the set + if (mNbManifolds >= mNbMaxManifolds) { - // Replace the old manifold with the new one - updateManifoldWithNewOne(0, contactManifoldInfo); - } - else { + // We need to remove a manifold from the set. + // We seach for the one with the smallest maximum penetration depth among its contact points + ContactManifold* minDepthManifold = getManifoldWithSmallestContactPenetrationDepth(contactManifoldInfo->getLargestPenetrationDepth()); - // Compute an Id corresponding to the normal direction (using a cubemap) - short int normalDirectionId = computeCubemapNormalId(contactManifoldInfo.getFirstContactPointInfo()->normal); + // If the manifold with the minimum penetration depth is an existing one + if (minDepthManifold != nullptr) { - // Select the manifold with the most similar normal (if exists) - int similarManifoldIndex = 0; - if (mNbMaxManifolds > 1) { - similarManifoldIndex = selectManifoldWithSimilarNormal(normalDirectionId); - } + // Remove the manifold + removeManifold(minDepthManifold); - // If a similar manifold has been found - if (similarManifoldIndex != -1) { - - // Replace the old manifold with the new one - updateManifoldWithNewOne(similarManifoldIndex, contactManifoldInfo); - } - else { - - // If we have not reach the maximum number of manifolds - if (mNbManifolds < mNbMaxManifolds) { - - // Create the new contact manifold - createManifold(contactManifoldInfo, normalDirectionId); - } - else { - - decimal newManifoldPenDepth = contactManifoldInfo.getLargestPenetrationDepth(); - - // We have reached the maximum number of manifold, we do not - // want to keep the manifold with the smallest penetration detph - int smallestPenDepthManifoldIndex = getManifoldWithSmallestContactPenetrationDepth(newManifoldPenDepth); - - // If the manifold with the smallest penetration depth is not the new one, - // we have to keep the new manifold and remove the one with the smallest depth - if (smallestPenDepthManifoldIndex >= 0) { - removeManifold(smallestPenDepthManifoldIndex); - createManifold(contactManifoldInfo, normalDirectionId); - } - } + // Create a new contact manifold + createManifold(contactManifoldInfo); } } + + // Create a new contact manifold + createManifold(contactManifoldInfo); } } // Update a previous similar manifold with a new one -void ContactManifoldSet::updateManifoldWithNewOne(int oldManifoldIndex, const ContactManifoldInfo& newManifold) { +void ContactManifoldSet::updateManifoldWithNewOne(ContactManifold* oldManifold, const ContactManifoldInfo* newManifold) { - // For each contact point of the previous manifold - for (int i=0; igetNbContactPoints(); ) { + assert(oldManifold != nullptr); + assert(newManifold != nullptr); - ContactPoint* contactPoint = mManifolds[oldManifoldIndex]->getContactPoint(i); + // For each contact point of the new manifold + ContactPointInfo* contactPointInfo = newManifold->getFirstContactPointInfo(); + assert(contactPointInfo != nullptr); + while (contactPointInfo != nullptr) { - // For each contact point in the new manifold - ContactPointInfo* newPoint = newManifold.getFirstContactPointInfo(); - bool needToRemovePoint = true; - while (newPoint != nullptr) { + // For each contact point in the old manifold + bool isSimilarPointFound = false; + ContactPoint* oldContactPoint = oldManifold->getContactPoints(); + while (oldContactPoint != nullptr) { + + assert(oldContactPoint != nullptr); // If the new contact point is similar (very close) to the old contact point - if (!newPoint->isUsed && contactPoint->isSimilarWithContactPoint(newPoint)) { + if (oldContactPoint->isSimilarWithContactPoint(contactPointInfo)) { // Replace (update) the old contact point with the new one - contactPoint->update(newPoint, mManifolds[oldManifoldIndex]->getShape1()->getLocalToWorldTransform(), - mManifolds[oldManifoldIndex]->getShape2()->getLocalToWorldTransform()); - needToRemovePoint = false; - newPoint->isUsed = true; + oldContactPoint->update(contactPointInfo, mShape1->getLocalToWorldTransform(), mShape2->getLocalToWorldTransform()); + isSimilarPointFound = true; break; } - newPoint = newPoint->next; + oldContactPoint = oldContactPoint->getNext(); } - // If no new contact point is similar to the old one - if (needToRemovePoint) { + // If we have not found a similar contact point + if (!isSimilarPointFound) { - // Remove the old contact point - mManifolds[oldManifoldIndex]->removeContactPoint(i); - } - else { - i++; + // Add the contact point to the manifold + oldManifold->addContactPoint(contactPointInfo); } + + contactPointInfo = contactPointInfo->next; } - // For each point of the new manifold that have not been used yet (to update - // an existing point in the previous manifold), add it into the previous manifold - const ContactPointInfo* newPointInfo = newManifold.getFirstContactPointInfo(); - while (newPointInfo != nullptr) { - - if (!newPointInfo->isUsed) { - mManifolds[oldManifoldIndex]->addContactPoint(newPointInfo); - } - - newPointInfo = newPointInfo->next; - } + // The old manifold is no longer obselete + oldManifold->setIsObselete(false, false); } -// Return the manifold with the smallest contact penetration depth -int ContactManifoldSet::getManifoldWithSmallestContactPenetrationDepth(decimal initDepth) const { +// Return the manifold with the smallest contact penetration depth among its points +ContactManifold* ContactManifoldSet::getManifoldWithSmallestContactPenetrationDepth(decimal initDepth) const { - // The contact point will be in a new contact manifold, we now have too much - // manifolds condidates. We need to remove one. We choose to remove the manifold - // with the smallest contact depth among their points - int smallestDepthManifoldIndex = -1; - decimal minDepth = initDepth; assert(mNbManifolds == mNbMaxManifolds); - for (int i=0; igetLargestContactDepth(); + + ContactManifold* minDepthManifold = nullptr; + decimal minDepth = initDepth; + ContactManifold* manifold = mManifolds; + while (manifold != nullptr) { + decimal depth = manifold->getLargestContactDepth(); if (depth < minDepth) { minDepth = depth; - smallestDepthManifoldIndex = i; + minDepthManifold = manifold; } + + manifold = manifold->getNext(); } - return smallestDepthManifoldIndex; + return minDepthManifold; } -// Return the index of the contact manifold with a similar average normal. -// If no manifold has close enough average normal, it returns -1 -int ContactManifoldSet::selectManifoldWithSimilarNormal(short int normalDirectionId) const { +// Return the contact manifold with a similar average normal. +// If no manifold has close enough average normal, it returns nullptr +ContactManifold* ContactManifoldSet::selectManifoldWithSimilarNormal(short int normalDirectionId) const { + + ContactManifold* manifold = mManifolds; // Return the Id of the manifold with the same normal direction id (if exists) - for (int i=0; igetNormalDirectionId()) { - return i; + while (manifold != nullptr) { + if (normalDirectionId == manifold->getContactNormalId()) { + return manifold; } + + manifold = manifold->getNext(); } - return -1; + return nullptr; } // Map the normal vector into a cubemap face bucket (a face contains 4x4 buckets) // Each face of the cube is divided into 4x4 buckets. This method maps the // normal vector into of the of the bucket and returns a unique Id for the bucket -short int ContactManifoldSet::computeCubemapNormalId(const Vector3& normal) const { +short int ContactManifoldSet::computeCubemapNormalId(const Vector3& normal) { assert(normal.lengthSquare() > MACHINE_EPSILON); @@ -240,36 +206,100 @@ short int ContactManifoldSet::computeCubemapNormalId(const Vector3& normal) cons // Clear the contact manifold set void ContactManifoldSet::clear() { - // Destroy all the contact manifolds - for (int i=mNbManifolds-1; i>=0; i--) { - removeManifold(i); + ContactManifold* manifold = mManifolds; + while(manifold != nullptr) { + + ContactManifold* nextManifold = manifold->getNext(); + + // Delete the contact manifold + manifold->~ContactManifold(); + mMemoryAllocator.release(manifold, sizeof(ContactManifold)); + + manifold = nextManifold; + + mNbManifolds--; } assert(mNbManifolds == 0); } // Create a new contact manifold and add it to the set -void ContactManifoldSet::createManifold(const ContactManifoldInfo& manifoldInfo, short int normalDirectionId) { +void ContactManifoldSet::createManifold(const ContactManifoldInfo* manifoldInfo) { assert(mNbManifolds < mNbMaxManifolds); - mManifolds[mNbManifolds] = new (mMemoryAllocator.allocate(sizeof(ContactManifold))) - ContactManifold(manifoldInfo, mShape1, mShape2, mMemoryAllocator, normalDirectionId); + ContactManifold* manifold = new (mMemoryAllocator.allocate(sizeof(ContactManifold))) + ContactManifold(manifoldInfo, mShape1, mShape2, mMemoryAllocator); + manifold->setPrevious(nullptr); + manifold->setNext(mManifolds); + mManifolds = manifold; + mNbManifolds++; } // Remove a contact manifold from the set -void ContactManifoldSet::removeManifold(int index) { +void ContactManifoldSet::removeManifold(ContactManifold* manifold) { assert(mNbManifolds > 0); - assert(index >= 0 && index < mNbManifolds); - // Delete the new contact - mManifolds[index]->~ContactManifold(); - mMemoryAllocator.release(mManifolds[index], sizeof(ContactManifold)); + ContactManifold* previous = manifold->getPrevious(); + ContactManifold* next = manifold->getNext(); - for (int i=index; (i+1) < mNbManifolds; i++) { - mManifolds[i] = mManifolds[i+1]; + if (previous != nullptr) { + previous->setNext(manifold->getNext()); } + if (next != nullptr) { + next->setPrevious(manifold->getPrevious()); + } + + // Delete the contact manifold + manifold->~ContactManifold(); + mMemoryAllocator.release(manifold, sizeof(ContactManifold)); mNbManifolds--; } + +// Make all the contact manifolds and contact points obselete +void ContactManifoldSet::makeContactsObselete() { + + ContactManifold* manifold = mManifolds; + while (manifold != nullptr) { + + manifold->setIsObselete(true, true); + + manifold = manifold->getNext(); + } +} + +// Clear the obselete contact manifolds and contact points +void ContactManifoldSet::clearObseleteManifoldsAndContactPoints() { + + ContactManifold* manifold = mManifolds; + ContactManifold* previousManifold = nullptr; + while (manifold != nullptr) { + ContactManifold* nextManifold = manifold->getNext(); + + if (manifold->getIsObselete()) { + + if (previousManifold != nullptr) { + previousManifold->setNext(nextManifold); + + if (nextManifold != nullptr) { + nextManifold->setPrevious(previousManifold); + } + } + else { + mManifolds = nextManifold; + } + + // Delete the contact manifold + removeManifold(manifold); + + } + else { + manifold->clearObseleteContactPoints(); + previousManifold = manifold; + } + + manifold = nextManifold; + } +} diff --git a/src/collision/ContactManifoldSet.h b/src/collision/ContactManifoldSet.h index 1a2bac97..0990277c 100644 --- a/src/collision/ContactManifoldSet.h +++ b/src/collision/ContactManifoldSet.h @@ -60,33 +60,34 @@ class ContactManifoldSet { /// Pointer to the second proxy shape of the contact ProxyShape* mShape2; - /// Reference to the memory allocator - PoolAllocator& mMemoryAllocator; + /// Reference to the memory allocator for the contact manifolds + Allocator& mMemoryAllocator; /// Contact manifolds of the set - ContactManifold* mManifolds[MAX_MANIFOLDS_IN_CONTACT_MANIFOLD_SET]; + ContactManifold* mManifolds; // -------------------- Methods -------------------- // /// Create a new contact manifold and add it to the set - void createManifold(const ContactManifoldInfo& manifoldInfo, short normalDirectionId); + void createManifold(const ContactManifoldInfo* manifoldInfo); - /// Remove a contact manifold from the set - void removeManifold(int index); - - // Return the index of the contact manifold with a similar average normal. - int selectManifoldWithSimilarNormal(short int normalDirectionId) const; - - // Map the normal vector into a cubemap face bucket (a face contains 4x4 buckets) - // Each face of the cube is divided into 4x4 buckets. This method maps the - // normal vector into of the of the bucket and returns a unique Id for the bucket - short int computeCubemapNormalId(const Vector3& normal) const; + // Return the contact manifold with a similar average normal. + ContactManifold* selectManifoldWithSimilarNormal(short int normalDirectionId) const; /// Return the manifold with the smallest contact penetration depth - int getManifoldWithSmallestContactPenetrationDepth(decimal initDepth) const; + ContactManifold* getManifoldWithSmallestContactPenetrationDepth(decimal initDepth) const; /// Update a previous similar manifold with a new one - void updateManifoldWithNewOne(int oldManifoldIndex, const ContactManifoldInfo& newManifold); + void updateManifoldWithNewOne(ContactManifold* oldManifold, const ContactManifoldInfo* newManifold); + + /// Return the maximum number of contact manifolds allowed between to collision shapes + int computeNbMaxContactManifolds(const CollisionShape* shape1, const CollisionShape* shape2); + + /// Clear the contact manifold set + void clear(); + + /// Delete a contact manifold + void removeManifold(ContactManifold* manifold); public: @@ -94,13 +95,13 @@ class ContactManifoldSet { /// Constructor ContactManifoldSet(ProxyShape* shape1, ProxyShape* shape2, - PoolAllocator& memoryAllocator, int nbMaxManifolds); + Allocator& memoryAllocator); /// Destructor ~ContactManifoldSet(); /// Add a contact manifold in the set - void addContactManifold(const ContactManifoldInfo& contactManifoldInfo); + void addContactManifold(const ContactManifoldInfo* contactManifoldInfo); /// Return the first proxy shape ProxyShape* getShape1() const; @@ -108,17 +109,25 @@ class ContactManifoldSet { /// Return the second proxy shape ProxyShape* getShape2() const; - /// Clear the contact manifold set - void clear(); - /// Return the number of manifolds in the set int getNbContactManifolds() const; - /// Return a given contact manifold - ContactManifold* getContactManifold(int index) const; + /// Return a pointer to the first element of the linked-list of contact manifolds + ContactManifold* getContactManifolds() const; + + /// Make all the contact manifolds and contact points obselete + void makeContactsObselete(); /// Return the total number of contact points in the set of manifolds int getTotalNbContactPoints() const; + + /// Clear the obselete contact manifolds and contact points + void clearObseleteManifoldsAndContactPoints(); + + // Map the normal vector into a cubemap face bucket (a face contains 4x4 buckets) + // Each face of the cube is divided into 4x4 buckets. This method maps the + // normal vector into of the of the bucket and returns a unique Id for the bucket + static short int computeCubemapNormalId(const Vector3& normal); }; // Return the first proxy shape @@ -136,21 +145,38 @@ inline int ContactManifoldSet::getNbContactManifolds() const { return mNbManifolds; } -// Return a given contact manifold -inline ContactManifold* ContactManifoldSet::getContactManifold(int index) const { - assert(index >= 0 && index < mNbManifolds); - return mManifolds[index]; +// Return a pointer to the first element of the linked-list of contact manifolds +inline ContactManifold* ContactManifoldSet::getContactManifolds() const { + return mManifolds; } // Return the total number of contact points in the set of manifolds inline int ContactManifoldSet::getTotalNbContactPoints() const { int nbPoints = 0; - for (int i=0; igetNbContactPoints(); + + ContactManifold* manifold = mManifolds; + while (manifold != nullptr) { + nbPoints += manifold->getNbContactPoints(); + + manifold = manifold->getNext(); } + return nbPoints; } +// Return the maximum number of contact manifolds allowed between to collision shapes +inline int ContactManifoldSet::computeNbMaxContactManifolds(const CollisionShape* shape1, const CollisionShape* shape2) { + + // If both shapes are convex + if (shape1->isConvex() && shape2->isConvex()) { + return NB_MAX_CONTACT_MANIFOLDS_CONVEX_SHAPE; + + } // If there is at least one concave shape + else { + return NB_MAX_CONTACT_MANIFOLDS_CONCAVE_SHAPE; + } +} + } #endif diff --git a/src/collision/NarrowPhaseInfo.cpp b/src/collision/NarrowPhaseInfo.cpp new file mode 100644 index 00000000..22ee6666 --- /dev/null +++ b/src/collision/NarrowPhaseInfo.cpp @@ -0,0 +1,97 @@ +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include +#include "NarrowPhaseInfo.h" +#include "ContactPointInfo.h" +#include "engine/OverlappingPair.h" + +using namespace reactphysics3d; + +// Constructor +NarrowPhaseInfo::NarrowPhaseInfo(OverlappingPair* pair, const CollisionShape* shape1, + const CollisionShape* shape2, const Transform& shape1Transform, + const Transform& shape2Transform, void** cachedData1, void** cachedData2) + : overlappingPair(pair), collisionShape1(shape1), collisionShape2(shape2), + shape1ToWorldTransform(shape1Transform), shape2ToWorldTransform(shape2Transform), + contactPoints(nullptr), cachedCollisionData1(cachedData1), + cachedCollisionData2(cachedData2), next(nullptr) { + +} + +// Destructor +NarrowPhaseInfo::~NarrowPhaseInfo() { + + assert(contactPoints == nullptr); +} + +// Add a new contact point +void NarrowPhaseInfo::addContactPoint(const Vector3& contactNormal, decimal penDepth, + const Vector3& localPt1, const Vector3& localPt2) { + + assert(penDepth > decimal(0.0)); + + // Get the memory allocator + Allocator& allocator = overlappingPair->getTemporaryAllocator(); + + // Create the contact point info + ContactPointInfo* contactPointInfo = new (allocator.allocate(sizeof(ContactPointInfo))) + ContactPointInfo(contactNormal, penDepth, localPt1, localPt2); + + // Add it into the linked list of contact points + contactPointInfo->next = contactPoints; + contactPoints = contactPointInfo; +} + +/// Take all the generated contact points and create a new potential +/// contact manifold into the overlapping pair +void NarrowPhaseInfo::addContactPointsAsPotentialContactManifold() { + overlappingPair->addPotentialContactPoints(this); +} + +// Reset the remaining contact points +void NarrowPhaseInfo::resetContactPoints() { + + // Get the memory allocator + Allocator& allocator = overlappingPair->getTemporaryAllocator(); + + // For each remaining contact point info + ContactPointInfo* element = contactPoints; + while(element != nullptr) { + + ContactPointInfo* elementToDelete = element; + + element = element->next; + + // Call the destructor + elementToDelete->~ContactPointInfo(); + + // Delete the current element + allocator.release(elementToDelete, sizeof(ContactPointInfo)); + } + + contactPoints = nullptr; +} diff --git a/src/collision/NarrowPhaseInfo.h b/src/collision/NarrowPhaseInfo.h index b97a71be..29bc6c9d 100644 --- a/src/collision/NarrowPhaseInfo.h +++ b/src/collision/NarrowPhaseInfo.h @@ -28,6 +28,7 @@ // Libraries #include "shapes/CollisionShape.h" +#include "collision/ContactManifoldInfo.h" /// Namespace ReactPhysics3D namespace reactphysics3d { @@ -58,6 +59,9 @@ struct NarrowPhaseInfo { /// Transform that maps from collision shape 2 local-space to world-space Transform shape2ToWorldTransform; + /// Linked-list of contact points created during the narrow-phase + ContactPointInfo* contactPoints; + /// Cached collision data of the proxy shape // TODO : Check if we can use separating axis in OverlappingPair instead of cachedCollisionData1 and cachedCollisionData2 void** cachedCollisionData1; @@ -72,12 +76,20 @@ struct NarrowPhaseInfo { /// Constructor NarrowPhaseInfo(OverlappingPair* pair, const CollisionShape* shape1, const CollisionShape* shape2, const Transform& shape1Transform, - const Transform& shape2Transform, void** cachedData1, void** cachedData2) - : overlappingPair(pair), collisionShape1(shape1), collisionShape2(shape2), - shape1ToWorldTransform(shape1Transform), shape2ToWorldTransform(shape2Transform), - cachedCollisionData1(cachedData1), cachedCollisionData2(cachedData2), next(nullptr) { + const Transform& shape2Transform, void** cachedData1, void** cachedData2); - } + /// Destructor + ~NarrowPhaseInfo(); + + /// Add a new contact point + void addContactPoint(const Vector3& contactNormal, decimal penDepth, + const Vector3& localPt1, const Vector3& localPt2); + + /// Create a new potential contact manifold into the overlapping pair using current contact points + void addContactPointsAsPotentialContactManifold(); + + /// Reset the remaining contact points + void resetContactPoints(); }; } diff --git a/src/collision/OverlapCallback.h b/src/collision/OverlapCallback.h new file mode 100644 index 00000000..bbba73d1 --- /dev/null +++ b/src/collision/OverlapCallback.h @@ -0,0 +1,57 @@ +/******************************************************************************** +* 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_OVERLAP_CALLBACK_H +#define REACTPHYSICS3D_OVERLAP_CALLBACK_H + +// Libraries +#include "body/CollisionBody.h" + +/// ReactPhysics3D namespace +namespace reactphysics3d { + +// Class OverlapCallback +/** + * This class can be used to register a callback for collision overlap queries. + * You should implement your own class inherited from this one and implement + * the notifyOverlap() method. This method will called each time a contact + * point is reported. + */ +class OverlapCallback { + + public: + + /// Destructor + virtual ~OverlapCallback() { + + } + + /// This method will be called for each reported overlapping bodies + virtual void notifyOverlap(CollisionBody* collisionBody)=0; +}; + +} + +#endif diff --git a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp index 17008622..f98e4d20 100644 --- a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp @@ -33,7 +33,7 @@ using namespace reactphysics3d; // Compute the narrow-phase collision detection between two capsules // This technique is based on the "Robust Contact Creation for Physics Simulations" presentation // by Dirk Gregorius. -bool CapsuleVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) { +bool CapsuleVsCapsuleAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) { assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE); assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CAPSULE); @@ -116,8 +116,8 @@ bool CapsuleVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhase decimal penetrationDepth = sumRadius - segmentsDistance; // Create the contact info object - contactManifoldInfo.addContactPoint(normalWorld, penetrationDepth, contactPointACapsule1Local, contactPointACapsule2Local); - contactManifoldInfo.addContactPoint(normalWorld, penetrationDepth, contactPointBCapsule1Local, contactPointBCapsule2Local); + narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, contactPointACapsule1Local, contactPointACapsule2Local); + narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, contactPointBCapsule1Local, contactPointBCapsule2Local); return true; } @@ -148,7 +148,7 @@ bool CapsuleVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhase decimal penetrationDepth = sumRadius - closestPointsDistance; // Create the contact info object - contactManifoldInfo.addContactPoint(normalWorld, penetrationDepth, contactPointCapsule1Local, contactPointCapsule2Local); + narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, contactPointCapsule1Local, contactPointCapsule2Local); return true; } diff --git a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h index 9d8393c9..0b19338f 100644 --- a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h +++ b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h @@ -61,8 +61,7 @@ class CapsuleVsCapsuleAlgorithm : public NarrowPhaseAlgorithm { CapsuleVsCapsuleAlgorithm& operator=(const CapsuleVsCapsuleAlgorithm& algorithm) = delete; /// Compute the narrow-phase collision detection between two capsules - virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactManifoldInfo& contactManifoldInfo) override; + virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) override; }; } diff --git a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp index b538dfa7..88bd9ace 100644 --- a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp @@ -37,13 +37,12 @@ using namespace reactphysics3d; // Compute the narrow-phase collision detection between a capsule and a polyhedron // This technique is based on the "Robust Contact Creation for Physics Simulations" presentation // by Dirk Gregorius. -bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactManifoldInfo& contactManifoldInfo) { +bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) { // First, we run the GJK algorithm GJKAlgorithm gjkAlgorithm; SATAlgorithm satAlgorithm; - GJKAlgorithm::GJKResult result = gjkAlgorithm.testCollision(narrowPhaseInfo, contactManifoldInfo); + GJKAlgorithm::GJKResult result = gjkAlgorithm.testCollision(narrowPhaseInfo, reportContacts); narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = true; narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = false; @@ -61,8 +60,8 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* na // two contact points instead of a single one (as in the deep contact case with SAT algorithm) // Get the contact point created by GJK - ContactPointInfo* contactPoint = contactManifoldInfo.getFirstContactPointInfo(); - assert(contactPoint != nullptr); + ContactPointInfo* contactPoint = narrowPhaseInfo->contactPoints; + assert(contactPoint != nullptr); bool isCapsuleShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE; @@ -96,7 +95,7 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* na && areParallelVectors(faceNormalWorld, contactPoint->normal)) { // Remove the previous contact point computed by GJK - contactManifoldInfo.reset(); + narrowPhaseInfo->resetContactPoints(); const Transform capsuleToWorld = isCapsuleShape1 ? narrowPhaseInfo->shape1ToWorldTransform : narrowPhaseInfo->shape2ToWorldTransform; const Transform polyhedronToCapsuleTransform = capsuleToWorld.getInverse() * polyhedronToWorld; @@ -116,7 +115,7 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* na satAlgorithm.computeCapsulePolyhedronFaceContactPoints(f, capsuleShape->getRadius(), polyhedron, contactPoint->penetrationDepth, polyhedronToCapsuleTransform, faceNormalWorld, separatingAxisCapsuleSpace, capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, - contactManifoldInfo, isCapsuleShape1); + narrowPhaseInfo, isCapsuleShape1); break; } @@ -133,7 +132,7 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* na if (result == GJKAlgorithm::GJKResult::INTERPENETRATE) { // Run the SAT algorithm to find the separating axis and compute contact point - bool isColliding = satAlgorithm.testCollisionCapsuleVsConvexPolyhedron(narrowPhaseInfo, contactManifoldInfo); + bool isColliding = satAlgorithm.testCollisionCapsuleVsConvexPolyhedron(narrowPhaseInfo, reportContacts); narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = false; narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = true; diff --git a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h index 6b3f504f..c0dd46d5 100644 --- a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h +++ b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h @@ -61,8 +61,7 @@ class CapsuleVsConvexPolyhedronAlgorithm : public NarrowPhaseAlgorithm { CapsuleVsConvexPolyhedronAlgorithm& operator=(const CapsuleVsConvexPolyhedronAlgorithm& algorithm) = delete; /// Compute the narrow-phase collision detection between a capsule and a polyhedron - virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactManifoldInfo& contactManifoldInfo) override; + virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) override; }; } diff --git a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp index c0da7611..7f5f439b 100644 --- a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp +++ b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp @@ -141,114 +141,114 @@ void ConcaveVsConvexAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseI // Process the concave triangle mesh collision using the smooth mesh collision algorithm described // by Pierre Terdiman (http://www.codercorner.com/MeshContacts.pdf). This is used to avoid the collision // issue with some internal edges. -void ConcaveVsConvexAlgorithm::processSmoothMeshCollision(OverlappingPair* overlappingPair, - std::vector contactPoints, - NarrowPhaseCallback* narrowPhaseCallback) { +//void ConcaveVsConvexAlgorithm::processSmoothMeshCollision(OverlappingPair* overlappingPair, +// std::vector contactPoints, +// NarrowPhaseCallback* narrowPhaseCallback) { - // Set with the triangle vertices already processed to void further contacts with same triangle - std::unordered_multimap processTriangleVertices; +// // Set with the triangle vertices already processed to void further contacts with same triangle +// std::unordered_multimap processTriangleVertices; - // Sort the list of narrow-phase contacts according to their penetration depth - std::sort(contactPoints.begin(), contactPoints.end(), ContactsDepthCompare()); +// // Sort the list of narrow-phase contacts according to their penetration depth +// std::sort(contactPoints.begin(), contactPoints.end(), ContactsDepthCompare()); - // For each contact point (from smaller penetration depth to larger) - std::vector::const_iterator it; - for (it = contactPoints.begin(); it != contactPoints.end(); ++it) { +// // For each contact point (from smaller penetration depth to larger) +// std::vector::const_iterator it; +// for (it = contactPoints.begin(); it != contactPoints.end(); ++it) { - const SmoothMeshContactInfo info = *it; - const Vector3& contactPoint = info.isFirstShapeTriangle ? info.contactInfo.localPoint1 : info.contactInfo.localPoint2; +// const SmoothMeshContactInfo info = *it; +// const Vector3& contactPoint = info.isFirstShapeTriangle ? info.contactInfo.localPoint1 : info.contactInfo.localPoint2; - // Compute the barycentric coordinates of the point in the triangle - decimal u, v, w; - computeBarycentricCoordinatesInTriangle(info.triangleVertices[0], - info.triangleVertices[1], - info.triangleVertices[2], - contactPoint, u, v, w); - int nbZeros = 0; - bool isUZero = approxEqual(u, 0, 0.0001); - bool isVZero = approxEqual(v, 0, 0.0001); - bool isWZero = approxEqual(w, 0, 0.0001); - if (isUZero) nbZeros++; - if (isVZero) nbZeros++; - if (isWZero) nbZeros++; +// // Compute the barycentric coordinates of the point in the triangle +// decimal u, v, w; +// computeBarycentricCoordinatesInTriangle(info.triangleVertices[0], +// info.triangleVertices[1], +// info.triangleVertices[2], +// contactPoint, u, v, w); +// int nbZeros = 0; +// bool isUZero = approxEqual(u, 0, 0.0001); +// bool isVZero = approxEqual(v, 0, 0.0001); +// bool isWZero = approxEqual(w, 0, 0.0001); +// if (isUZero) nbZeros++; +// if (isVZero) nbZeros++; +// if (isWZero) nbZeros++; - // If it is a vertex contact - if (nbZeros == 2) { +// // If it is a vertex contact +// if (nbZeros == 2) { - Vector3 contactVertex = !isUZero ? info.triangleVertices[0] : (!isVZero ? info.triangleVertices[1] : info.triangleVertices[2]); +// Vector3 contactVertex = !isUZero ? info.triangleVertices[0] : (!isVZero ? info.triangleVertices[1] : info.triangleVertices[2]); - // Check that this triangle vertex has not been processed yet - if (!hasVertexBeenProcessed(processTriangleVertices, contactVertex)) { +// // Check that this triangle vertex has not been processed yet +// if (!hasVertexBeenProcessed(processTriangleVertices, contactVertex)) { - // Keep the contact as it is and report it - narrowPhaseCallback->notifyContact(overlappingPair, info.contactInfo); - } - } - else if (nbZeros == 1) { // If it is an edge contact +// // Keep the contact as it is and report it +// narrowPhaseCallback->notifyContact(overlappingPair, info.contactInfo); +// } +// } +// else if (nbZeros == 1) { // If it is an edge contact - Vector3 contactVertex1 = isUZero ? info.triangleVertices[1] : (isVZero ? info.triangleVertices[0] : info.triangleVertices[0]); - Vector3 contactVertex2 = isUZero ? info.triangleVertices[2] : (isVZero ? info.triangleVertices[2] : info.triangleVertices[1]); +// Vector3 contactVertex1 = isUZero ? info.triangleVertices[1] : (isVZero ? info.triangleVertices[0] : info.triangleVertices[0]); +// Vector3 contactVertex2 = isUZero ? info.triangleVertices[2] : (isVZero ? info.triangleVertices[2] : info.triangleVertices[1]); - // Check that this triangle edge has not been processed yet - if (!hasVertexBeenProcessed(processTriangleVertices, contactVertex1) && - !hasVertexBeenProcessed(processTriangleVertices, contactVertex2)) { +// // Check that this triangle edge has not been processed yet +// if (!hasVertexBeenProcessed(processTriangleVertices, contactVertex1) && +// !hasVertexBeenProcessed(processTriangleVertices, contactVertex2)) { - // Keep the contact as it is and report it - narrowPhaseCallback->notifyContact(overlappingPair, info.contactInfo); - } +// // Keep the contact as it is and report it +// narrowPhaseCallback->notifyContact(overlappingPair, info.contactInfo); +// } - } - else { // If it is a face contact +// } +// else { // If it is a face contact - ContactPointInfo newContactInfo(info.contactInfo); +// ContactPointInfo newContactInfo(info.contactInfo); - ProxyShape* firstShape; - ProxyShape* secondShape; - if (info.isFirstShapeTriangle) { - firstShape = overlappingPair->getShape1(); - secondShape = overlappingPair->getShape2(); - } - else { - firstShape = overlappingPair->getShape2(); - secondShape = overlappingPair->getShape1(); - } +// ProxyShape* firstShape; +// ProxyShape* secondShape; +// if (info.isFirstShapeTriangle) { +// firstShape = overlappingPair->getShape1(); +// secondShape = overlappingPair->getShape2(); +// } +// else { +// firstShape = overlappingPair->getShape2(); +// secondShape = overlappingPair->getShape1(); +// } - // We use the triangle normal as the contact normal - Vector3 a = info.triangleVertices[1] - info.triangleVertices[0]; - Vector3 b = info.triangleVertices[2] - info.triangleVertices[0]; - Vector3 localNormal = a.cross(b); - newContactInfo.normal = firstShape->getLocalToWorldTransform().getOrientation() * localNormal; - Vector3 firstLocalPoint = info.isFirstShapeTriangle ? info.contactInfo.localPoint1 : info.contactInfo.localPoint2; - Vector3 firstWorldPoint = firstShape->getLocalToWorldTransform() * firstLocalPoint; - newContactInfo.normal.normalize(); - if (newContactInfo.normal.dot(info.contactInfo.normal) < 0) { - newContactInfo.normal = -newContactInfo.normal; - } +// // We use the triangle normal as the contact normal +// Vector3 a = info.triangleVertices[1] - info.triangleVertices[0]; +// Vector3 b = info.triangleVertices[2] - info.triangleVertices[0]; +// Vector3 localNormal = a.cross(b); +// newContactInfo.normal = firstShape->getLocalToWorldTransform().getOrientation() * localNormal; +// Vector3 firstLocalPoint = info.isFirstShapeTriangle ? info.contactInfo.localPoint1 : info.contactInfo.localPoint2; +// Vector3 firstWorldPoint = firstShape->getLocalToWorldTransform() * firstLocalPoint; +// newContactInfo.normal.normalize(); +// if (newContactInfo.normal.dot(info.contactInfo.normal) < 0) { +// newContactInfo.normal = -newContactInfo.normal; +// } - // We recompute the contact point on the second body with the new normal as described in - // the Smooth Mesh Contacts with GJK of the Game Physics Pearls book (from Gino van Den Bergen and - // Dirk Gregorius) to avoid adding torque - Transform worldToLocalSecondPoint = secondShape->getLocalToWorldTransform().getInverse(); - if (info.isFirstShapeTriangle) { - Vector3 newSecondWorldPoint = firstWorldPoint + newContactInfo.normal; - newContactInfo.localPoint2 = worldToLocalSecondPoint * newSecondWorldPoint; - } - else { - Vector3 newSecondWorldPoint = firstWorldPoint - newContactInfo.normal; - newContactInfo.localPoint1 = worldToLocalSecondPoint * newSecondWorldPoint; - } +// // We recompute the contact point on the second body with the new normal as described in +// // the Smooth Mesh Contacts with GJK of the Game Physics Pearls book (from Gino van Den Bergen and +// // Dirk Gregorius) to avoid adding torque +// Transform worldToLocalSecondPoint = secondShape->getLocalToWorldTransform().getInverse(); +// if (info.isFirstShapeTriangle) { +// Vector3 newSecondWorldPoint = firstWorldPoint + newContactInfo.normal; +// newContactInfo.localPoint2 = worldToLocalSecondPoint * newSecondWorldPoint; +// } +// else { +// Vector3 newSecondWorldPoint = firstWorldPoint - newContactInfo.normal; +// newContactInfo.localPoint1 = worldToLocalSecondPoint * newSecondWorldPoint; +// } - // Report the contact - narrowPhaseCallback->notifyContact(overlappingPair, newContactInfo); - } +// // Report the contact +// narrowPhaseCallback->notifyContact(overlappingPair, newContactInfo); +// } - // Add the three vertices of the triangle to the set of processed - // triangle vertices - addProcessedVertex(processTriangleVertices, info.triangleVertices[0]); - addProcessedVertex(processTriangleVertices, info.triangleVertices[1]); - addProcessedVertex(processTriangleVertices, info.triangleVertices[2]); - } -} +// // Add the three vertices of the triangle to the set of processed +// // triangle vertices +// addProcessedVertex(processTriangleVertices, info.triangleVertices[0]); +// addProcessedVertex(processTriangleVertices, info.triangleVertices[1]); +// addProcessedVertex(processTriangleVertices, info.triangleVertices[2]); +// } +//} // Return true if the vertex is in the set of already processed vertices bool ConcaveVsConvexAlgorithm::hasVertexBeenProcessed(const std::unordered_multimap& processTriangleVertices, const Vector3& vertex) const { diff --git a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h index 531615da..4619e480 100644 --- a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h +++ b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h @@ -83,25 +83,35 @@ class MiddlePhaseTriangleCallback : public TriangleCallback { // Class SmoothMeshContactInfo /** - * This class is used to store data about a contact with a triangle for the smooth - * mesh algorithm. + * Contains data for of potential smooth contact during the smooth mesh + * contacts computation. */ -class SmoothMeshContactInfo { +struct SmoothMeshContactInfo { public: - ContactPointInfo contactInfo; + ContactManifoldInfo* contactManifoldInfo; + ContactPointInfo* contactInfo; bool isFirstShapeTriangle; Vector3 triangleVertices[3]; + bool isUVWZero[3]; /// Constructor - SmoothMeshContactInfo(const ContactPointInfo& contact, bool firstShapeTriangle, const Vector3& trianglePoint1, - const Vector3& trianglePoint2, const Vector3& trianglePoint3) - : contactInfo(contact) { + SmoothMeshContactInfo(ContactManifoldInfo* manifoldInfo, ContactPointInfo* contactPointInfo, + bool firstShapeTriangle, + const Vector3& trianglePoint1, const Vector3& trianglePoint2, + const Vector3& trianglePoint3, bool isUZero, bool isVZero, bool isWZero) + : contactManifoldInfo(manifoldInfo), contactInfo(contactPointInfo) { + isFirstShapeTriangle = firstShapeTriangle; + triangleVertices[0] = trianglePoint1; triangleVertices[1] = trianglePoint2; triangleVertices[2] = trianglePoint3; + + isUVWZero[0] = isUZero; + isUVWZero[1] = isVZero; + isUVWZero[2] = isWZero; } }; @@ -109,7 +119,7 @@ class SmoothMeshContactInfo { struct ContactsDepthCompare { bool operator()(const SmoothMeshContactInfo& contact1, const SmoothMeshContactInfo& contact2) { - return contact1.contactInfo.penetrationDepth < contact2.contactInfo.penetrationDepth; + return contact1.contactInfo->penetrationDepth < contact2.contactInfo->penetrationDepth; } }; diff --git a/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp index 16b9edf5..c6297fb2 100644 --- a/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp @@ -34,12 +34,11 @@ using namespace reactphysics3d; // Compute the narrow-phase collision detection between two convex polyhedra // This technique is based on the "Robust Contact Creation for Physics Simulations" presentation // by Dirk Gregorius. -bool ConvexPolyhedronVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactManifoldInfo& contactManifoldInfo) { +bool ConvexPolyhedronVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) { // Run the SAT algorithm to find the separating axis and compute contact point SATAlgorithm satAlgorithm; - bool isColliding = satAlgorithm.testCollisionConvexPolyhedronVsConvexPolyhedron(narrowPhaseInfo, contactManifoldInfo); + bool isColliding = satAlgorithm.testCollisionConvexPolyhedronVsConvexPolyhedron(narrowPhaseInfo, reportContacts); narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = true; narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = false; diff --git a/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.h b/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.h index ed76d6fc..1e0c9748 100644 --- a/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.h +++ b/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.h @@ -61,8 +61,7 @@ class ConvexPolyhedronVsConvexPolyhedronAlgorithm : public NarrowPhaseAlgorithm ConvexPolyhedronVsConvexPolyhedronAlgorithm& operator=(const ConvexPolyhedronVsConvexPolyhedronAlgorithm& algorithm) = delete; /// Compute the narrow-phase collision detection between two convex polyhedra - virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactManifoldInfo& contactManifoldInfo) override; + virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) override; }; } diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp index 4f7e1177..ff81782f 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp @@ -46,8 +46,7 @@ using namespace reactphysics3d; /// algorithm on the enlarged object to obtain a simplex polytope that contains the /// origin, they we give that simplex polytope to the EPA algorithm which will compute /// the correct penetration depth and contact points between the enlarged objects. -GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactManifoldInfo& contactManifoldInfo) { +GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) { PROFILE("GJKAlgorithm::testCollision()"); @@ -209,7 +208,7 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(const NarrowPhaseInfo* narro } // Add a new contact point - contactManifoldInfo.addContactPoint(normal, penetrationDepth, pA, pB); + narrowPhaseInfo->addContactPoint(normal, penetrationDepth, pA, pB); return GJKResult::COLLIDE_IN_MARGIN; } diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.h b/src/collision/narrowphase/GJK/GJKAlgorithm.h index f40592c4..b8c7319c 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.h +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.h @@ -87,16 +87,13 @@ class GJKAlgorithm { GJKAlgorithm& operator=(const GJKAlgorithm& algorithm) = delete; /// Compute a contact info if the two bounding volumes collide. - GJKResult testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactManifoldInfo& contactManifoldInfo); + GJKResult testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts); /// Use the GJK Algorithm to find if a point is inside a convex collision shape bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape); /// Ray casting algorithm agains a convex collision shape using the GJK Algorithm bool raycast(const Ray& ray, ProxyShape* proxyShape, RaycastInfo& raycastInfo); - - }; } diff --git a/src/collision/narrowphase/NarrowPhaseAlgorithm.h b/src/collision/narrowphase/NarrowPhaseAlgorithm.h index f665181b..035bd8e5 100644 --- a/src/collision/narrowphase/NarrowPhaseAlgorithm.h +++ b/src/collision/narrowphase/NarrowPhaseAlgorithm.h @@ -83,8 +83,10 @@ class NarrowPhaseAlgorithm { /// Deleted assignment operator NarrowPhaseAlgorithm& operator=(const NarrowPhaseAlgorithm& algorithm) = delete; + // TODO : Use the following reportContacts variable in all narrow-phase algorithms + /// Compute a contact info if the two bounding volume collide - virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo)=0; + virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts)=0; }; } diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index c838d8ab..4974d367 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -44,7 +44,7 @@ using namespace reactphysics3d; const decimal SATAlgorithm::SAME_SEPARATING_AXIS_BIAS = decimal(0.001); // Test collision between a sphere and a convex mesh -bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { +bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) const { PROFILE("SATAlgorithm::testCollisionSphereVsConvexPolyhedron()"); @@ -145,7 +145,7 @@ bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(const NarrowPhaseInfo* const Vector3 contactPointPolyhedronLocal = sphereCenter + minFaceNormal * (minPenetrationDepth - sphere->getRadius()); // Create the contact info object - contactManifoldInfo.addContactPoint(isSphereShape1 ? normalWorld : -normalWorld, minPenetrationDepth, + narrowPhaseInfo->addContactPoint(normalWorld, minPenetrationDepth, isSphereShape1 ? contactPointSphereLocal : contactPointPolyhedronLocal, isSphereShape1 ? contactPointPolyhedronLocal : contactPointSphereLocal); @@ -171,7 +171,7 @@ decimal SATAlgorithm::computePolyhedronFaceVsSpherePenetrationDepth(uint faceInd } // Test collision between a capsule and a convex mesh -bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const { +bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) const { PROFILE("SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron()"); @@ -387,7 +387,7 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(const NarrowPhaseInfo* computeCapsulePolyhedronFaceContactPoints(minFaceIndex, capsuleRadius, polyhedron, minPenetrationDepth, polyhedronToCapsuleTransform, normalWorld, separatingAxisCapsuleSpace, capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, - contactManifoldInfo, isCapsuleShape1); + narrowPhaseInfo, isCapsuleShape1); lastFrameInfo.satIsAxisFacePolyhedron1 = true; lastFrameInfo.satMinAxisFaceIndex = minFaceIndex; @@ -406,7 +406,7 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(const NarrowPhaseInfo* const Vector3 contactPointCapsule = (polyhedronToCapsuleTransform * closestPointCapsuleInnerSegment) - separatingAxisCapsuleSpace * capsuleRadius; // Create the contact point - contactManifoldInfo.addContactPoint(normalWorld, minPenetrationDepth, + narrowPhaseInfo->addContactPoint(normalWorld, minPenetrationDepth, isCapsuleShape1 ? contactPointCapsule : closestPointPolyhedronEdge, isCapsuleShape1 ? closestPointPolyhedronEdge : contactPointCapsule); @@ -477,7 +477,7 @@ void SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceI decimal penetrationDepth, const Transform& polyhedronToCapsuleTransform, const Vector3& normalWorld, const Vector3& separatingAxisCapsuleSpace, const Vector3& capsuleSegAPolyhedronSpace, const Vector3& capsuleSegBPolyhedronSpace, - ContactManifoldInfo& contactManifoldInfo, bool isCapsuleShape1) const { + NarrowPhaseInfo* narrowPhaseInfo, bool isCapsuleShape1) const { HalfEdgeStructure::Face face = polyhedron->getFace(referenceFaceIndex); uint firstEdgeIndex = face.edgeIndex; @@ -523,7 +523,7 @@ void SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceI const Vector3 contactPointCapsule = (polyhedronToCapsuleTransform * clipSegment[i]) - separatingAxisCapsuleSpace * capsuleRadius; // Create the contact point - contactManifoldInfo.addContactPoint(isCapsuleShape1 ? -normalWorld : normalWorld, penetrationDepth, + narrowPhaseInfo->addContactPoint(isCapsuleShape1 ? -normalWorld : normalWorld, penetrationDepth, isCapsuleShape1 ? contactPointCapsule : contactPointPolyhedron, isCapsuleShape1 ? contactPointPolyhedron : contactPointCapsule); } @@ -543,8 +543,8 @@ bool SATAlgorithm::isMinkowskiFaceCapsuleVsEdge(const Vector3& capsuleSegment, c } // Test collision between two convex polyhedrons -bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, - ContactManifoldInfo& contactManifoldInfo) const { +bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, + bool reportContacts) const { PROFILE("SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron()"); @@ -869,7 +869,7 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(const NarrowP Vector3 contactPointReferencePolyhedron = projectPointOntoPlane(*itPoints, axisReferenceSpace, referenceFaceVertex); // Create a new contact point - contactManifoldInfo.addContactPoint(normalWorld, minPenetrationDepth, + narrowPhaseInfo->addContactPoint(normalWorld, minPenetrationDepth, isMinPenetrationFaceNormalPolyhedron1 ? contactPointReferencePolyhedron : contactPointIncidentPolyhedron, isMinPenetrationFaceNormalPolyhedron1 ? contactPointIncidentPolyhedron : contactPointReferencePolyhedron); } @@ -893,7 +893,7 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(const NarrowP const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * minEdgeVsEdgeSeparatingAxisPolyhedron2Space; // Create the contact point - contactManifoldInfo.addContactPoint(normalWorld, minPenetrationDepth, + narrowPhaseInfo->addContactPoint(normalWorld, minPenetrationDepth, closestPointPolyhedron1EdgeLocalSpace, closestPointPolyhedron2Edge); lastFrameInfo.satIsAxisFacePolyhedron1 = false; diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.h b/src/collision/narrowphase/SAT/SATAlgorithm.h index 7a002fce..49cd2626 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.h +++ b/src/collision/narrowphase/SAT/SATAlgorithm.h @@ -113,24 +113,24 @@ class SATAlgorithm { SATAlgorithm& operator=(const SATAlgorithm& algorithm) = delete; /// Test collision between a sphere and a convex mesh - bool testCollisionSphereVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; + bool testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) const; /// Test collision between a capsule and a convex mesh - bool testCollisionCapsuleVsConvexPolyhedron(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; + bool testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) const; /// Compute the two contact points between a polyhedron and a capsule when the separating axis is a face normal of the polyhedron void computeCapsulePolyhedronFaceContactPoints(uint referenceFaceIndex, decimal capsuleRadius, const ConvexPolyhedronShape* polyhedron, decimal penetrationDepth, const Transform& polyhedronToCapsuleTransform, const Vector3& normalWorld, const Vector3& separatingAxisCapsuleSpace, const Vector3& capsuleSegAPolyhedronSpace, const Vector3& capsuleSegBPolyhedronSpace, - ContactManifoldInfo& contactManifoldInfo, bool isCapsuleShape1) const; + NarrowPhaseInfo* narrowPhaseInfo, 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(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) const; + bool testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) const; }; } diff --git a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp index 86255c2b..e291fd83 100755 --- a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp @@ -34,7 +34,7 @@ using namespace reactphysics3d; // Compute the narrow-phase collision detection between a sphere and a capsule // This technique is based on the "Robust Contact Creation for Physics Simulations" presentation // by Dirk Gregorius. -bool SphereVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, ContactManifoldInfo& contactManifoldInfo) { +bool SphereVsCapsuleAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) { bool isSphereShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE; @@ -86,7 +86,7 @@ bool SphereVsCapsuleAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseI } // Create the contact info object - contactManifoldInfo.addContactPoint(normalWorld, penetrationDepth, + narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, isSphereShape1 ? contactPointSphereLocal : contactPointCapsuleLocal, isSphereShape1 ? contactPointCapsuleLocal : contactPointSphereLocal); diff --git a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h index 154f6e4c..bb9e9866 100644 --- a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h +++ b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h @@ -61,8 +61,7 @@ class SphereVsCapsuleAlgorithm : public NarrowPhaseAlgorithm { SphereVsCapsuleAlgorithm& operator=(const SphereVsCapsuleAlgorithm& algorithm) = delete; /// Compute the narrow-phase collision detection between a sphere and a capsule - virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactManifoldInfo& contactManifoldInfo) override; + virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) override; }; } diff --git a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp index d90a29b3..049ce449 100644 --- a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp @@ -34,12 +34,11 @@ using namespace reactphysics3d; // Compute the narrow-phase collision detection between a sphere and a convex polyhedron // This technique is based on the "Robust Contact Creation for Physics Simulations" presentation // by Dirk Gregorius. -bool SphereVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactManifoldInfo& contactManifoldInfo) { +bool SphereVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) { // First, we run the GJK algorithm GJKAlgorithm gjkAlgorithm; - GJKAlgorithm::GJKResult result = gjkAlgorithm.testCollision(narrowPhaseInfo, contactManifoldInfo); + GJKAlgorithm::GJKResult result = gjkAlgorithm.testCollision(narrowPhaseInfo, reportContacts); assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON || narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); @@ -61,7 +60,7 @@ bool SphereVsConvexPolyhedronAlgorithm::testCollision(const NarrowPhaseInfo* nar // Run the SAT algorithm to find the separating axis and compute contact point SATAlgorithm satAlgorithm; - bool isColliding = satAlgorithm.testCollisionSphereVsConvexPolyhedron(narrowPhaseInfo, contactManifoldInfo); + bool isColliding = satAlgorithm.testCollisionSphereVsConvexPolyhedron(narrowPhaseInfo, reportContacts); narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = false; narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = true; diff --git a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h index f2f8d6e5..2d9fa801 100644 --- a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h +++ b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h @@ -61,8 +61,7 @@ class SphereVsConvexPolyhedronAlgorithm : public NarrowPhaseAlgorithm { SphereVsConvexPolyhedronAlgorithm& operator=(const SphereVsConvexPolyhedronAlgorithm& algorithm) = delete; /// Compute the narrow-phase collision detection between a sphere and a convex polyhedron - virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactManifoldInfo& contactManifoldInfo) override; + virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) override; }; } diff --git a/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp b/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp index 54e51e52..94211ac0 100644 --- a/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp @@ -30,8 +30,7 @@ // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; -bool SphereVsSphereAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactManifoldInfo& contactManifoldInfo) { +bool SphereVsSphereAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) { assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE); assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::SPHERE); @@ -62,7 +61,7 @@ bool SphereVsSphereAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseIn decimal penetrationDepth = sumRadius - std::sqrt(squaredDistanceBetweenCenters); // Create the contact info object - contactManifoldInfo.addContactPoint(vectorBetweenCenters.getUnit(), penetrationDepth, + narrowPhaseInfo->addContactPoint(vectorBetweenCenters.getUnit(), penetrationDepth, intersectionOnBody1, intersectionOnBody2); return true; diff --git a/src/collision/narrowphase/SphereVsSphereAlgorithm.h b/src/collision/narrowphase/SphereVsSphereAlgorithm.h index b70befd2..1fd885a5 100644 --- a/src/collision/narrowphase/SphereVsSphereAlgorithm.h +++ b/src/collision/narrowphase/SphereVsSphereAlgorithm.h @@ -61,8 +61,7 @@ class SphereVsSphereAlgorithm : public NarrowPhaseAlgorithm { SphereVsSphereAlgorithm& operator=(const SphereVsSphereAlgorithm& algorithm) = delete; /// Compute a contact info if the two bounding volume collide - virtual bool testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - ContactManifoldInfo& contactManifoldInfo) override; + virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) override; }; } diff --git a/src/collision/shapes/BoxShape.h b/src/collision/shapes/BoxShape.h index d2b92dcc..5a07b0cb 100644 --- a/src/collision/shapes/BoxShape.h +++ b/src/collision/shapes/BoxShape.h @@ -237,6 +237,8 @@ inline Vector3 BoxShape::getFaceNormal(uint faceIndex) const { case 4: return Vector3(0, -1, 0); case 5: return Vector3(0, 1, 0); } + + assert(false); } // Return the centroid of the box diff --git a/src/collision/shapes/CollisionShape.h b/src/collision/shapes/CollisionShape.h index 2b1fa576..78b82ae0 100644 --- a/src/collision/shapes/CollisionShape.h +++ b/src/collision/shapes/CollisionShape.h @@ -118,10 +118,6 @@ class CollisionShape { /// Return true if the collision shape type is a convex shape static bool isConvex(CollisionShapeType shapeType); - /// Return the maximum number of contact manifolds in an overlapping pair given two shape types - static int computeNbMaxContactManifolds(CollisionShapeType shapeType1, - CollisionShapeType shapeType2); - // -------------------- Friendship -------------------- // friend class ProxyShape; @@ -151,19 +147,6 @@ inline void CollisionShape::setLocalScaling(const Vector3& scaling) { mScaling = scaling; } -// Return the maximum number of contact manifolds allowed in an overlapping -// pair wit the given two collision shape types -inline int CollisionShape::computeNbMaxContactManifolds(CollisionShapeType shapeType1, - CollisionShapeType shapeType2) { - // If both shapes are convex - if (isConvex(shapeType1) && isConvex(shapeType2)) { - return NB_MAX_CONTACT_MANIFOLDS_CONVEX_SHAPE; - } // If there is at least one concave shape - else { - return NB_MAX_CONTACT_MANIFOLDS_CONCAVE_SHAPE; - } -} - } #endif diff --git a/src/constraint/ContactPoint.cpp b/src/constraint/ContactPoint.cpp index f420bbff..fa6838ec 100644 --- a/src/constraint/ContactPoint.cpp +++ b/src/constraint/ContactPoint.cpp @@ -37,19 +37,20 @@ ContactPoint::ContactPoint(const ContactPointInfo* contactInfo, const Transform& mPenetrationDepth(contactInfo->penetrationDepth), mLocalPointOnBody1(contactInfo->localPoint1), mLocalPointOnBody2(contactInfo->localPoint2), - mIsRestingContact(false) { + mIsRestingContact(false), mIsObselete(false), mNext(nullptr) { assert(mPenetrationDepth > decimal(0.0)); // Compute the world position of the contact points mWorldPointOnBody1 = body1Transform * mLocalPointOnBody1; mWorldPointOnBody2 = body2Transform * mLocalPointOnBody2; + + mIsObselete = false; } // Update the contact point with a new one that is similar (very close) /// The idea is to keep the cache impulse (for warm starting the contact solver) -void ContactPoint::update(const ContactPointInfo* contactInfo, const Transform& body1Transform, - const Transform& body2Transform) { +void ContactPoint::update(const ContactPointInfo* contactInfo, const Transform& body1Transform, const Transform& body2Transform) { assert(isSimilarWithContactPoint(contactInfo)); assert(contactInfo->penetrationDepth > decimal(0.0)); @@ -62,4 +63,6 @@ void ContactPoint::update(const ContactPointInfo* contactInfo, const Transform& // Compute the world position of the contact points mWorldPointOnBody1 = body1Transform * mLocalPointOnBody1; mWorldPointOnBody2 = body2Transform * mLocalPointOnBody2; + + mIsObselete = false; } diff --git a/src/constraint/ContactPoint.h b/src/constraint/ContactPoint.h index ec4c6556..41cc35e4 100644 --- a/src/constraint/ContactPoint.h +++ b/src/constraint/ContactPoint.h @@ -71,6 +71,37 @@ class ContactPoint { /// Cached penetration impulse decimal mPenetrationImpulse; + /// True if the contact point is obselete + bool mIsObselete; + + /// Pointer to the next contact point in the linked-list + ContactPoint* mNext; + + // -------------------- Methods -------------------- // + + /// Update the contact point with a new one that is similar (very close) + void update(const ContactPointInfo* contactInfo, const Transform& body1Transform, + const Transform& body2Transform); + + /// Return true if the contact point is similar (close enougth) to another given contact point + bool isSimilarWithContactPoint(const ContactPointInfo* contactPoint) const; + + /// Set the cached penetration impulse + void setPenetrationImpulse(decimal impulse); + + + /// Set the mIsRestingContact variable + void setIsRestingContact(bool isRestingContact); + + /// Set to true to make the contact point obselete + void setIsObselete(bool isObselete); + + /// Set the next contact point in the linked list + void setNext(ContactPoint* next); + + /// Return true if the contact point is obselete + bool getIsObselete() const; + public : // -------------------- Methods -------------------- // @@ -88,10 +119,6 @@ class ContactPoint { /// Deleted assignment operator ContactPoint& operator=(const ContactPoint& contact) = delete; - /// Update the contact point with a new one that is similar (very close) - void update(const ContactPointInfo* contactInfo, const Transform& body1Transform, - const Transform& body2Transform); - /// Return the normal vector of the contact Vector3 getNormal() const; @@ -110,23 +137,22 @@ class ContactPoint { /// Return the cached penetration impulse decimal getPenetrationImpulse() const; - /// Return true if the contact point is similar (close enougth) to another given contact point - bool isSimilarWithContactPoint(const ContactPointInfo* contactPoint) const; - - /// Set the cached penetration impulse - void setPenetrationImpulse(decimal impulse); - /// Return true if the contact is a resting contact bool getIsRestingContact() const; - /// Set the mIsRestingContact variable - void setIsRestingContact(bool isRestingContact); + /// Return the next contact point in the linked list + ContactPoint* getNext() const; /// Return the penetration depth decimal getPenetrationDepth() const; /// Return the number of bytes used by the contact point size_t getSizeInBytes() const; + + // Friendship + friend class ContactManifold; + friend class ContactManifoldSet; + friend class ContactSolver; }; // Return the normal vector of the contact @@ -180,6 +206,26 @@ inline void ContactPoint::setIsRestingContact(bool isRestingContact) { mIsRestingContact = isRestingContact; } +// Return true if the contact point is obselete +inline bool ContactPoint::getIsObselete() const { + return mIsObselete; +} + +// Set to true to make the contact point obselete +inline void ContactPoint::setIsObselete(bool isObselete) { + mIsObselete = isObselete; +} + +// Return the next contact point in the linked list +inline ContactPoint* ContactPoint::getNext() const { + return mNext; +} + +// Set the next contact point in the linked list +inline void ContactPoint::setNext(ContactPoint* next) { + mNext = next; +} + // Return the penetration depth of the contact inline decimal ContactPoint::getPenetrationDepth() const { return mPenetrationDepth; diff --git a/src/engine/CollisionWorld.h b/src/engine/CollisionWorld.h index 0e24f0c8..82d2601f 100644 --- a/src/engine/CollisionWorld.h +++ b/src/engine/CollisionWorld.h @@ -233,64 +233,6 @@ inline void CollisionWorld::testOverlap(CollisionBody* body, OverlapCallback* ov mCollisionDetection.testOverlap(body, overlapCallback, categoryMaskBits); } -// Class CollisionCallback -/** - * This class can be used to register a callback for collision test queries. - * You should implement your own class inherited from this one and implement - * the notifyContact() method. This method will called each time a contact - * point is reported. - */ -class CollisionCallback { - - public: - - struct CollisionCallbackInfo { - - public: - const ContactManifoldInfo& contactManifold; - CollisionBody* body1; - CollisionBody* body2; - const ProxyShape* proxyShape1; - const ProxyShape* proxyShape2; - - // Constructor - CollisionCallbackInfo(const ContactManifoldInfo& manifold, CollisionBody* b1, CollisionBody* b2, - const ProxyShape* proxShape1, const ProxyShape* proxShape2) : - contactManifold(manifold), body1(b1), body2(b2), - proxyShape1(proxShape1), proxyShape2(proxShape2) { - - } - }; - - /// Destructor - virtual ~CollisionCallback() { - - } - - /// This method will be called for each reported contact point - virtual void notifyContact(const CollisionCallbackInfo& collisionCallbackInfo)=0; -}; - -// Class OverlapCallback -/** - * This class can be used to register a callback for collision overlap queries. - * You should implement your own class inherited from this one and implement - * the notifyOverlap() method. This method will called each time a contact - * point is reported. - */ -class OverlapCallback { - - public: - - /// Destructor - virtual ~OverlapCallback() { - - } - - /// This method will be called for each reported overlapping bodies - virtual void notifyOverlap(CollisionBody* collisionBody)=0; -}; - } #endif diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index d5825d5c..94a82b14 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -148,10 +148,8 @@ void ContactSolver::initializeForIsland(Island* island) { const Vector3& w2 = mAngularVelocities[mContactConstraints[mNbContactManifolds].indexBody2]; // For each contact point of the contact manifold - for (uint c=0; cgetNbContactPoints(); c++) { - - // Get a contact point - ContactPoint* externalContact = externalManifold->getContactPoint(c); + ContactPoint* externalContact = externalManifold->getContactPoints(); + while (externalContact != nullptr) { // Get the contact point on the two bodies Vector3 p1 = externalContact->getWorldPointOnBody1(); @@ -200,6 +198,8 @@ void ContactSolver::initializeForIsland(Island* island) { mContactConstraints[mNbContactManifolds].normal += mContactPoints[mNbContactPoints].normal; mNbContactPoints++; + + externalContact = externalContact->getNext(); } mContactConstraints[mNbContactManifolds].frictionPointBody1 /=static_cast(mContactConstraints[mNbContactManifolds].nbContacts); diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index 4f7bd15a..136d34f6 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -683,9 +683,9 @@ void DynamicsWorld::computeIslands() { // For each contact manifold in which the current body is involded ContactManifoldListElement* contactElement; for (contactElement = bodyToVisit->mContactManifoldsList; contactElement != nullptr; - contactElement = contactElement->next) { + contactElement = contactElement->getNext()) { - ContactManifold* contactManifold = contactElement->contactManifold; + ContactManifold* contactManifold = contactElement->getContactManifold(); assert(contactManifold->getNbContactPoints() > 0); @@ -842,12 +842,13 @@ std::vector DynamicsWorld::getContactsList() const { // For each contact manifold of the pair const ContactManifoldSet& manifoldSet = pair->getContactManifoldSet(); - for (int i=0; igetNext(); } } diff --git a/src/engine/EventListener.h b/src/engine/EventListener.h index e8594255..061724a0 100644 --- a/src/engine/EventListener.h +++ b/src/engine/EventListener.h @@ -27,7 +27,7 @@ #define REACTPHYSICS3D_EVENT_LISTENER_H // Libraries -#include "collision/ContactManifoldInfo.h" +#include "collision/CollisionCallback.h" namespace reactphysics3d { @@ -49,17 +49,11 @@ class EventListener { /// Destructor virtual ~EventListener() = default; - /// Called when a new contact point is found between two bodies that were separated before - /** - * @param contact Information about the contact - */ - virtual void beginContact(const ContactManifoldInfo& contactManifold) {} - /// Called when a new contact point is found between two bodies /** * @param contact Information about the contact */ - virtual void newContact(const ContactManifoldInfo& contactManifold) {} + virtual void newContact(const CollisionCallback::CollisionCallbackInfo& collisionInfo) {} /// Called at the beginning of an internal tick of the simulation step. /// Each time the DynamicsWorld::update() method is called, the physics diff --git a/src/engine/OverlappingPair.cpp b/src/engine/OverlappingPair.cpp index ce628b7d..a23857e3 100644 --- a/src/engine/OverlappingPair.cpp +++ b/src/engine/OverlappingPair.cpp @@ -26,12 +26,108 @@ // Libraries #include #include "OverlappingPair.h" +#include "collision/ContactManifoldInfo.h" using namespace reactphysics3d; // Constructor OverlappingPair::OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, - int nbMaxContactManifolds, PoolAllocator& memoryAllocator) - : mContactManifoldSet(shape1, shape2, memoryAllocator, nbMaxContactManifolds) { + Allocator& manifoldsAllocator, Allocator& temporaryMemoryAllocator) + : mContactManifoldSet(shape1, shape2, manifoldsAllocator), mPotentialContactManifolds(nullptr), + mTempMemoryAllocator(temporaryMemoryAllocator) { } + +// Create a new potential contact manifold using contact-points from narrow-phase +void OverlappingPair::addPotentialContactPoints(NarrowPhaseInfo* narrowPhaseInfo) { + + assert(narrowPhaseInfo->contactPoints != nullptr); + + // For each potential contact point to add + ContactPointInfo* contactPoint = narrowPhaseInfo->contactPoints; + while (contactPoint != nullptr) { + + ContactPointInfo* nextContactPoint = contactPoint->next; + + // Compute the contact normal id + short contactNormalId = ContactManifoldSet::computeCubemapNormalId(contactPoint->normal); + + // Look if the contact point correspond to an existing potential manifold + // (if the contact point normal is similar to the normal of an existing manifold) + ContactManifoldInfo* manifold = mPotentialContactManifolds; + bool similarManifoldFound = false; + while(manifold != nullptr) { + + // If we have found a corresponding manifold for the new contact point + // (a manifold with a similar contact normal direction) + if (manifold->getContactNormalId() == contactNormalId) { + + // Add the contact point to the manifold + manifold->addContactPoint(contactPoint, contactNormalId); + + similarManifoldFound = true; + + break; + } + + manifold = manifold->getNext(); + } + + // If we have not found an existing manifold with a similar contact normal + if (!similarManifoldFound) { + + // Create a new potential contact manifold + ContactManifoldInfo* manifoldInfo = new (mTempMemoryAllocator.allocate(sizeof(ContactManifoldInfo))) + ContactManifoldInfo(mTempMemoryAllocator); + + // Add the manifold into the linked-list of potential contact manifolds + manifoldInfo->mNext = mPotentialContactManifolds; + mPotentialContactManifolds = manifoldInfo; + + // Add the contact point to the manifold + manifoldInfo->addContactPoint(contactPoint, contactNormalId); + } + + contactPoint = nextContactPoint; + } + + // All the contact point info of the narrow-phase info have been moved + // into the potential contacts of the overlapping pair + narrowPhaseInfo->contactPoints = nullptr; +} + +// Clear all the potential contact manifolds +void OverlappingPair::clearPotentialContactManifolds() { + + // Do we need to release memory + if (mTempMemoryAllocator.isReleaseNeeded()) { + + ContactManifoldInfo* element = mPotentialContactManifolds; + while(element != nullptr) { + + // Remove the proxy collision shape + ContactManifoldInfo* elementToRemove = element; + element = element->getNext(); + + // Delete the element + elementToRemove->~ContactManifoldInfo(); + mTempMemoryAllocator.release(elementToRemove, sizeof(ContactManifoldInfo)); + } + } + + mPotentialContactManifolds = nullptr; +} + +// Reduce the number of contact points of all the potential contact manifolds +void OverlappingPair::reducePotentialContactManifolds() { + + // For each potential contact manifold + ContactManifoldInfo* manifold = mPotentialContactManifolds; + while (manifold != nullptr) { + + // Reduce the number of contact points of the manifold + manifold->reduce(mContactManifoldSet.getShape1()->getLocalToWorldTransform()); + + manifold = manifold->getNext(); + } +} diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index ce028f9c..a55df081 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -102,13 +102,19 @@ class OverlappingPair { /// Collision information about the last frame (for temporal coherence) LastFrameCollisionInfo mLastFrameCollisionInfo; + /// Linked-list of potential contact manifold + ContactManifoldInfo* mPotentialContactManifolds; + + /// Memory allocator used to allocated memory for the ContactManifoldInfo and ContactPointInfo + Allocator& mTempMemoryAllocator; + public: // -------------------- Methods -------------------- // /// Constructor OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, - int nbMaxContactManifolds, PoolAllocator& memoryAllocator); + Allocator& memoryAllocator, Allocator& temporaryMemoryAllocator); /// Destructor ~OverlappingPair() = default; @@ -125,9 +131,6 @@ class OverlappingPair { /// Return the pointer to second body ProxyShape* getShape2() const; - /// Add a contact manifold - void addContactManifold(const ContactManifoldInfo& contactManifoldInfo); - /// Return the last frame collision info LastFrameCollisionInfo& getLastFrameCollisionInfo(); @@ -137,8 +140,32 @@ class OverlappingPair { /// Return the a reference to the contact manifold set const ContactManifoldSet& getContactManifoldSet(); - /// Clear the contact points of the contact manifold - void clearContactPoints(); + /// Clear all the potential contact manifolds + void clearPotentialContactManifolds(); + + /// Add potential contact-points from narrow-phase into potential contact manifolds + void addPotentialContactPoints(NarrowPhaseInfo* narrowPhaseInfo); + + /// Add a contact to the contact manifold + void addContactManifold(const ContactManifoldInfo* contactManifoldInfo); + + /// Return a reference to the temporary memory allocator + Allocator& getTemporaryAllocator(); + + /// Return true if one of the shapes of the pair is a concave shape + bool hasConcaveShape() const; + + /// Return a pointer to the first potential contact manifold in the linked-list + ContactManifoldInfo* getPotentialContactManifolds(); + + /// Reduce the number of contact points of all the potential contact manifolds + void reducePotentialContactManifolds(); + + /// Make the contact manifolds and contact points obselete + void makeContactsObselete(); + + /// Clear the obselete contact manifold and contact points + void clearObseleteManifoldsAndContactPoints(); /// Return the pair of bodies index static overlappingpairid computeID(ProxyShape* shape1, ProxyShape* shape2); @@ -162,7 +189,7 @@ inline ProxyShape* OverlappingPair::getShape2() const { } // Add a contact to the contact manifold -inline void OverlappingPair::addContactManifold(const ContactManifoldInfo& contactManifoldInfo) { +inline void OverlappingPair::addContactManifold(const ContactManifoldInfo* contactManifoldInfo) { mContactManifoldSet.addContactManifold(contactManifoldInfo); } @@ -181,6 +208,12 @@ inline const ContactManifoldSet& OverlappingPair::getContactManifoldSet() { return mContactManifoldSet; } +// Make the contact manifolds and contact points obselete +inline void OverlappingPair::makeContactsObselete() { + + mContactManifoldSet.makeContactsObselete(); +} + // Return the pair of bodies index inline overlappingpairid OverlappingPair::computeID(ProxyShape* shape1, ProxyShape* shape2) { assert(shape1->mBroadPhaseID >= 0 && shape2->mBroadPhaseID >= 0); @@ -205,9 +238,25 @@ inline bodyindexpair OverlappingPair::computeBodiesIndexPair(CollisionBody* body return indexPair; } -// Clear the contact points of the contact manifold -inline void OverlappingPair::clearContactPoints() { - mContactManifoldSet.clear(); +// Return a reference to the temporary memory allocator +inline Allocator& OverlappingPair::getTemporaryAllocator() { + return mTempMemoryAllocator; +} + +// Return true if one of the shapes of the pair is a concave shape +inline bool OverlappingPair::hasConcaveShape() const { + return !getShape1()->getCollisionShape()->isConvex() || + !getShape2()->getCollisionShape()->isConvex(); +} + +// Return a pointer to the first potential contact manifold in the linked-list +inline ContactManifoldInfo* OverlappingPair::getPotentialContactManifolds() { + return mPotentialContactManifolds; +} + +// Clear the obselete contact manifold and contact points +inline void OverlappingPair::clearObseleteManifoldsAndContactPoints() { + mContactManifoldSet.clearObseleteManifoldsAndContactPoints(); } } diff --git a/src/memory/Allocator.h b/src/memory/Allocator.h index f7b9ac73..0440a5c9 100644 --- a/src/memory/Allocator.h +++ b/src/memory/Allocator.h @@ -49,6 +49,9 @@ class Allocator { /// Release previously allocated memory. virtual void release(void* pointer, size_t size)=0; + + /// Return true if memory needs to be release with this allocator + virtual bool isReleaseNeeded() const=0; }; } diff --git a/src/memory/PoolAllocator.h b/src/memory/PoolAllocator.h index 71e11714..0664e559 100644 --- a/src/memory/PoolAllocator.h +++ b/src/memory/PoolAllocator.h @@ -138,8 +138,16 @@ class PoolAllocator : public Allocator { /// Release previously allocated memory. virtual void release(void* pointer, size_t size) override; + /// Return true if memory needs to be release with this allocator + virtual bool isReleaseNeeded() const override; + }; +// Return true if memory needs to be release with this allocator +inline bool PoolAllocator::isReleaseNeeded() const { + return true; +} + } #endif diff --git a/src/memory/SingleFrameAllocator.h b/src/memory/SingleFrameAllocator.h index cc030daa..426c2a2d 100644 --- a/src/memory/SingleFrameAllocator.h +++ b/src/memory/SingleFrameAllocator.h @@ -72,10 +72,15 @@ class SingleFrameAllocator : public Allocator { /// Reset the marker of the current allocated memory virtual void reset(); - - + /// Return true if memory needs to be release with this allocator + virtual bool isReleaseNeeded() const override; }; +// Return true if memory needs to be release with this allocator +inline bool SingleFrameAllocator::isReleaseNeeded() const { + return false; +} + } #endif diff --git a/src/reactphysics3d.h b/src/reactphysics3d.h index f6b8b8bf..dd2a6265 100644 --- a/src/reactphysics3d.h +++ b/src/reactphysics3d.h @@ -58,6 +58,8 @@ #include "collision/PolyhedronMesh.h" #include "collision/TriangleVertexArray.h" #include "collision/PolygonVertexArray.h" +#include "collision/CollisionCallback.h" +#include "collision/OverlapCallback.h" #include "constraint/BallAndSocketJoint.h" #include "constraint/SliderJoint.h" #include "constraint/HingeJoint.h" diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.h b/testbed/scenes/collisiondetection/CollisionDetectionScene.h index 51a05412..14ceab1f 100755 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.h +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.h @@ -79,26 +79,34 @@ class ContactManager : public rp3d::CollisionCallback { /// This method will be called for each reported contact point virtual void notifyContact(const CollisionCallbackInfo& collisionCallbackInfo) override { - // For each contact point - rp3d::ContactPointInfo* contactPointInfo = collisionCallbackInfo.contactManifold.getFirstContactPointInfo(); - while (contactPointInfo != nullptr) { + // For each contact manifold + rp3d::ContactManifoldListElement* manifoldElement = collisionCallbackInfo.contactManifoldElements; + while (manifoldElement != nullptr) { - // Contact normal - rp3d::Vector3 normal = contactPointInfo->normal; - openglframework::Vector3 contactNormal(normal.x, normal.y, normal.z); + // Get the contact manifold + rp3d::ContactManifold* contactManifold = manifoldElement->getContactManifold(); - rp3d::Vector3 point1 = contactPointInfo->localPoint1; - point1 = collisionCallbackInfo.proxyShape1->getLocalToWorldTransform() * point1; - - openglframework::Vector3 position1(point1.x, point1.y, point1.z); - mContactPoints.push_back(ContactPoint(position1, contactNormal, openglframework::Color::red())); + // For each contact point + rp3d::ContactPoint* contactPoint = contactManifold->getContactPoints(); + while (contactPoint != nullptr) { - rp3d::Vector3 point2 = contactPointInfo->localPoint2; - point2 = collisionCallbackInfo.proxyShape2->getLocalToWorldTransform() * point2; - openglframework::Vector3 position2(point2.x, point2.y, point2.z); - mContactPoints.push_back(ContactPoint(position2, contactNormal, openglframework::Color::blue())); + // Contact normal + rp3d::Vector3 normal = contactPoint->getNormal(); + openglframework::Vector3 contactNormal(normal.x, normal.y, normal.z); - contactPointInfo = contactPointInfo->next; + rp3d::Vector3 point1 = contactPoint->getLocalPointOnBody1(); + point1 = collisionCallbackInfo.proxyShape1->getLocalToWorldTransform() * point1; + + openglframework::Vector3 position1(point1.x, point1.y, point1.z); + mContactPoints.push_back(ContactPoint(position1, contactNormal, openglframework::Color::red())); + + rp3d::Vector3 point2 = contactPoint->getLocalPointOnBody2(); + point2 = collisionCallbackInfo.proxyShape2->getLocalToWorldTransform() * point2; + openglframework::Vector3 position2(point2.x, point2.y, point2.z); + mContactPoints.push_back(ContactPoint(position2, contactNormal, openglframework::Color::blue())); + + contactPoint = contactPoint->getNext(); + } } } diff --git a/testbed/src/SceneDemo.cpp b/testbed/src/SceneDemo.cpp index 2cb3e440..85e8a66f 100644 --- a/testbed/src/SceneDemo.cpp +++ b/testbed/src/SceneDemo.cpp @@ -342,14 +342,16 @@ std::vector SceneDemo::computeContactPointsOfWorld(const rp3d::Dyn const rp3d::ContactManifold* manifold = *it; // For each contact point of the manifold - for (uint i=0; igetNbContactPoints(); i++) { + rp3d::ContactPoint* contactPoint = manifold->getContactPoints(); + while (contactPoint != nullptr) { - rp3d::ContactPoint* contactPoint = manifold->getContactPoint(i); rp3d::Vector3 point = contactPoint->getWorldPointOnBody1(); rp3d::Vector3 normalWorld = contactPoint->getNormal(); openglframework::Vector3 normal = openglframework::Vector3(normalWorld.x, normalWorld.y, normalWorld.z); ContactPoint contact(openglframework::Vector3(point.x, point.y, point.z), normal, openglframework::Color::red()); contactPoints.push_back(contact); + + contactPoint = contactPoint->getNext(); } } From b6ad69b2786111c965a8560516fc5d12c1abb815 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 30 Jul 2017 23:56:20 +0200 Subject: [PATCH 081/248] Do not compute contacts if not necessary --- .../narrowphase/CapsuleVsCapsuleAlgorithm.cpp | 66 +++--- .../CapsuleVsConvexPolyhedronAlgorithm.cpp | 100 ++++---- .../narrowphase/NarrowPhaseAlgorithm.h | 2 - .../narrowphase/SAT/SATAlgorithm.cpp | 214 +++++++++--------- .../narrowphase/SphereVsCapsuleAlgorithm.cpp | 33 +-- .../narrowphase/SphereVsSphereAlgorithm.cpp | 26 ++- 6 files changed, 235 insertions(+), 206 deletions(-) diff --git a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp index f98e4d20..c98329bf 100644 --- a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp @@ -91,33 +91,37 @@ bool CapsuleVsCapsuleAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, // If the segments were overlapping (the clip segment is valid) if (t1 > decimal(0.0) && t2 > decimal(0.0)) { - // Clip the inner segment of capsule 2 - if (t1 > decimal(1.0)) t1 = decimal(1.0); - const Vector3 clipPointA = capsule2SegB - t1 * seg2; - if (t2 > decimal(1.0)) t2 = decimal(1.0); - const Vector3 clipPointB = capsule2SegA + t2 * seg2; + if (reportContacts) { - // Project point capsule2SegA onto line of innner segment of capsule 1 - const Vector3 seg1Normalized = seg1.getUnit(); - Vector3 pointOnInnerSegCapsule1 = capsule1SegA + seg1Normalized.dot(capsule2SegA - capsule1SegA) * seg1Normalized; + // Clip the inner segment of capsule 2 + if (t1 > decimal(1.0)) t1 = decimal(1.0); + const Vector3 clipPointA = capsule2SegB - t1 * seg2; + if (t2 > decimal(1.0)) t2 = decimal(1.0); + const Vector3 clipPointB = capsule2SegA + t2 * seg2; - // Compute a perpendicular vector from segment 1 to segment 2 - Vector3 segment1ToSegment2 = (capsule2SegA - pointOnInnerSegCapsule1); - Vector3 segment1ToSegment2Normalized = segment1ToSegment2.getUnit(); + // Project point capsule2SegA onto line of innner segment of capsule 1 + const Vector3 seg1Normalized = seg1.getUnit(); + Vector3 pointOnInnerSegCapsule1 = capsule1SegA + seg1Normalized.dot(capsule2SegA - capsule1SegA) * seg1Normalized; - Transform capsule2ToCapsule1SpaceTransform = capsule1ToCapsule2SpaceTransform.getInverse(); - const Vector3 contactPointACapsule1Local = capsule2ToCapsule1SpaceTransform * (clipPointA - segment1ToSegment2 + segment1ToSegment2Normalized * capsuleShape1->getRadius()); - const Vector3 contactPointBCapsule1Local = capsule2ToCapsule1SpaceTransform * (clipPointB - segment1ToSegment2 + segment1ToSegment2Normalized * capsuleShape1->getRadius()); - const Vector3 contactPointACapsule2Local = clipPointA - segment1ToSegment2Normalized * capsuleShape2->getRadius(); - const Vector3 contactPointBCapsule2Local = clipPointB - segment1ToSegment2Normalized * capsuleShape2->getRadius(); + // Compute a perpendicular vector from segment 1 to segment 2 + Vector3 segment1ToSegment2 = (capsule2SegA - pointOnInnerSegCapsule1); + Vector3 segment1ToSegment2Normalized = segment1ToSegment2.getUnit(); - const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * segment1ToSegment2Normalized; + Transform capsule2ToCapsule1SpaceTransform = capsule1ToCapsule2SpaceTransform.getInverse(); + const Vector3 contactPointACapsule1Local = capsule2ToCapsule1SpaceTransform * (clipPointA - segment1ToSegment2 + segment1ToSegment2Normalized * capsuleShape1->getRadius()); + const Vector3 contactPointBCapsule1Local = capsule2ToCapsule1SpaceTransform * (clipPointB - segment1ToSegment2 + segment1ToSegment2Normalized * capsuleShape1->getRadius()); + const Vector3 contactPointACapsule2Local = clipPointA - segment1ToSegment2Normalized * capsuleShape2->getRadius(); + const Vector3 contactPointBCapsule2Local = clipPointB - segment1ToSegment2Normalized * capsuleShape2->getRadius(); - decimal penetrationDepth = sumRadius - segmentsDistance; + const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * segment1ToSegment2Normalized; - // Create the contact info object - narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, contactPointACapsule1Local, contactPointACapsule2Local); - narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, contactPointBCapsule1Local, contactPointBCapsule2Local); + decimal penetrationDepth = sumRadius - segmentsDistance; + + // Create the contact info object + narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, contactPointACapsule1Local, contactPointACapsule2Local); + narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, contactPointBCapsule1Local, contactPointBCapsule2Local); + + } return true; } @@ -137,18 +141,22 @@ bool CapsuleVsCapsuleAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, // If the collision shapes overlap if (closestPointsDistanceSquare < sumRadius * sumRadius && closestPointsDistanceSquare > MACHINE_EPSILON) { - decimal closestPointsDistance = std::sqrt(closestPointsDistanceSquare); - closestPointsSeg1ToSeg2 /= closestPointsDistance; + if (reportContacts) { - const Vector3 contactPointCapsule1Local = capsule1ToCapsule2SpaceTransform.getInverse() * (closestPointCapsule1Seg + closestPointsSeg1ToSeg2 * capsuleShape1->getRadius()); - const Vector3 contactPointCapsule2Local = closestPointCapsule2Seg - closestPointsSeg1ToSeg2 * capsuleShape2->getRadius(); + decimal closestPointsDistance = std::sqrt(closestPointsDistanceSquare); + closestPointsSeg1ToSeg2 /= closestPointsDistance; - const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * closestPointsSeg1ToSeg2; + const Vector3 contactPointCapsule1Local = capsule1ToCapsule2SpaceTransform.getInverse() * (closestPointCapsule1Seg + closestPointsSeg1ToSeg2 * capsuleShape1->getRadius()); + const Vector3 contactPointCapsule2Local = closestPointCapsule2Seg - closestPointsSeg1ToSeg2 * capsuleShape2->getRadius(); - decimal penetrationDepth = sumRadius - closestPointsDistance; + const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * closestPointsSeg1ToSeg2; - // Create the contact info object - narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, contactPointCapsule1Local, contactPointCapsule2Local); + decimal penetrationDepth = sumRadius - closestPointsDistance; + + // Create the contact info object + narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, contactPointCapsule1Local, contactPointCapsule2Local); + + } return true; } diff --git a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp index 88bd9ace..be9cc05f 100644 --- a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp @@ -55,70 +55,74 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPh // If we have found a contact point inside the margins (shallow penetration) if (result == GJKAlgorithm::GJKResult::COLLIDE_IN_MARGIN) { - // GJK has found a shallow contact. If the face of the polyhedron mesh is orthogonal to the - // capsule inner segment and parallel to the contact point normal, we would like to create - // two contact points instead of a single one (as in the deep contact case with SAT algorithm) + if (reportContacts) { - // Get the contact point created by GJK - ContactPointInfo* contactPoint = narrowPhaseInfo->contactPoints; - assert(contactPoint != nullptr); + // GJK has found a shallow contact. If the face of the polyhedron mesh is orthogonal to the + // capsule inner segment and parallel to the contact point normal, we would like to create + // two contact points instead of a single one (as in the deep contact case with SAT algorithm) - bool isCapsuleShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE; + // Get the contact point created by GJK + ContactPointInfo* contactPoint = narrowPhaseInfo->contactPoints; + assert(contactPoint != nullptr); - // Get the collision shapes - const CapsuleShape* capsuleShape = static_cast(isCapsuleShape1 ? narrowPhaseInfo->collisionShape1 : narrowPhaseInfo->collisionShape2); - const ConvexPolyhedronShape* polyhedron = static_cast(isCapsuleShape1 ? narrowPhaseInfo->collisionShape2 : narrowPhaseInfo->collisionShape1); + bool isCapsuleShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE; - // For each face of the polyhedron - for (uint f = 0; f < polyhedron->getNbFaces(); f++) { + // Get the collision shapes + const CapsuleShape* capsuleShape = static_cast(isCapsuleShape1 ? narrowPhaseInfo->collisionShape1 : narrowPhaseInfo->collisionShape2); + const ConvexPolyhedronShape* polyhedron = static_cast(isCapsuleShape1 ? narrowPhaseInfo->collisionShape2 : narrowPhaseInfo->collisionShape1); - // Get the face - HalfEdgeStructure::Face face = polyhedron->getFace(f); + // For each face of the polyhedron + for (uint f = 0; f < polyhedron->getNbFaces(); f++) { - const Transform polyhedronToWorld = isCapsuleShape1 ? narrowPhaseInfo->shape2ToWorldTransform : narrowPhaseInfo->shape1ToWorldTransform; - const Transform capsuleToWorld = isCapsuleShape1 ? narrowPhaseInfo->shape1ToWorldTransform : narrowPhaseInfo->shape2ToWorldTransform; - - // Get the face normal - const Vector3 faceNormal = polyhedron->getFaceNormal(f); - const Vector3 faceNormalWorld = polyhedronToWorld.getOrientation() * faceNormal; - - const Vector3 capsuleSegA(0, -capsuleShape->getHeight() * decimal(0.5), 0); - const Vector3 capsuleSegB(0, capsuleShape->getHeight() * decimal(0.5), 0); - const Vector3 capsuleInnerSegmentWorld = capsuleToWorld.getOrientation() * (capsuleSegB - capsuleSegA); - - bool isFaceNormalInDirectionOfContactNormal = faceNormalWorld.dot(contactPoint->normal) > decimal(0.0); - bool isFaceNormalInContactDirection = (isCapsuleShape1 && !isFaceNormalInDirectionOfContactNormal) || (!isCapsuleShape1 && isFaceNormalInDirectionOfContactNormal); - - // If the polyhedron face normal is orthogonal to the capsule inner segment and parallel to the contact point normal and the face normal - // is in direction of the contact normal (from the polyhedron point of view). - if (isFaceNormalInContactDirection && areOrthogonalVectors(faceNormalWorld, capsuleInnerSegmentWorld) - && areParallelVectors(faceNormalWorld, contactPoint->normal)) { - - // Remove the previous contact point computed by GJK - narrowPhaseInfo->resetContactPoints(); + // Get the face + HalfEdgeStructure::Face face = polyhedron->getFace(f); + const Transform polyhedronToWorld = isCapsuleShape1 ? narrowPhaseInfo->shape2ToWorldTransform : narrowPhaseInfo->shape1ToWorldTransform; const Transform capsuleToWorld = isCapsuleShape1 ? narrowPhaseInfo->shape1ToWorldTransform : narrowPhaseInfo->shape2ToWorldTransform; - const Transform polyhedronToCapsuleTransform = capsuleToWorld.getInverse() * polyhedronToWorld; - // Compute the end-points of the inner segment of the capsule + // Get the face normal + const Vector3 faceNormal = polyhedron->getFaceNormal(f); + const Vector3 faceNormalWorld = polyhedronToWorld.getOrientation() * faceNormal; + const Vector3 capsuleSegA(0, -capsuleShape->getHeight() * decimal(0.5), 0); const Vector3 capsuleSegB(0, capsuleShape->getHeight() * decimal(0.5), 0); + const Vector3 capsuleInnerSegmentWorld = capsuleToWorld.getOrientation() * (capsuleSegB - capsuleSegA); - // Convert the inner capsule segment points into the polyhedron local-space - const Transform capsuleToPolyhedronTransform = polyhedronToCapsuleTransform.getInverse(); - const Vector3 capsuleSegAPolyhedronSpace = capsuleToPolyhedronTransform * capsuleSegA; - const Vector3 capsuleSegBPolyhedronSpace = capsuleToPolyhedronTransform * capsuleSegB; + bool isFaceNormalInDirectionOfContactNormal = faceNormalWorld.dot(contactPoint->normal) > decimal(0.0); + bool isFaceNormalInContactDirection = (isCapsuleShape1 && !isFaceNormalInDirectionOfContactNormal) || (!isCapsuleShape1 && isFaceNormalInDirectionOfContactNormal); - const Vector3 separatingAxisCapsuleSpace = polyhedronToCapsuleTransform.getOrientation() * faceNormal; + // If the polyhedron face normal is orthogonal to the capsule inner segment and parallel to the contact point normal and the face normal + // is in direction of the contact normal (from the polyhedron point of view). + if (isFaceNormalInContactDirection && areOrthogonalVectors(faceNormalWorld, capsuleInnerSegmentWorld) + && areParallelVectors(faceNormalWorld, contactPoint->normal)) { - // Compute and create two contact points - satAlgorithm.computeCapsulePolyhedronFaceContactPoints(f, capsuleShape->getRadius(), polyhedron, contactPoint->penetrationDepth, - polyhedronToCapsuleTransform, faceNormalWorld, separatingAxisCapsuleSpace, - capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, - narrowPhaseInfo, isCapsuleShape1); + // Remove the previous contact point computed by GJK + narrowPhaseInfo->resetContactPoints(); - break; + const Transform capsuleToWorld = isCapsuleShape1 ? narrowPhaseInfo->shape1ToWorldTransform : narrowPhaseInfo->shape2ToWorldTransform; + const Transform polyhedronToCapsuleTransform = capsuleToWorld.getInverse() * polyhedronToWorld; + + // Compute the end-points of the inner segment of the capsule + const Vector3 capsuleSegA(0, -capsuleShape->getHeight() * decimal(0.5), 0); + const Vector3 capsuleSegB(0, capsuleShape->getHeight() * decimal(0.5), 0); + + // Convert the inner capsule segment points into the polyhedron local-space + const Transform capsuleToPolyhedronTransform = polyhedronToCapsuleTransform.getInverse(); + const Vector3 capsuleSegAPolyhedronSpace = capsuleToPolyhedronTransform * capsuleSegA; + const Vector3 capsuleSegBPolyhedronSpace = capsuleToPolyhedronTransform * capsuleSegB; + + const Vector3 separatingAxisCapsuleSpace = polyhedronToCapsuleTransform.getOrientation() * faceNormal; + + // Compute and create two contact points + satAlgorithm.computeCapsulePolyhedronFaceContactPoints(f, capsuleShape->getRadius(), polyhedron, contactPoint->penetrationDepth, + polyhedronToCapsuleTransform, faceNormalWorld, separatingAxisCapsuleSpace, + capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, + narrowPhaseInfo, isCapsuleShape1); + + break; + } } + } narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = false; diff --git a/src/collision/narrowphase/NarrowPhaseAlgorithm.h b/src/collision/narrowphase/NarrowPhaseAlgorithm.h index 035bd8e5..6a8746c6 100644 --- a/src/collision/narrowphase/NarrowPhaseAlgorithm.h +++ b/src/collision/narrowphase/NarrowPhaseAlgorithm.h @@ -83,8 +83,6 @@ class NarrowPhaseAlgorithm { /// Deleted assignment operator NarrowPhaseAlgorithm& operator=(const NarrowPhaseAlgorithm& algorithm) = delete; - // TODO : Use the following reportContacts variable in all narrow-phase algorithms - /// Compute a contact info if the two bounding volume collide virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts)=0; }; diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 4974d367..98686311 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -139,15 +139,18 @@ bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfo* narrow } } - const Vector3 minFaceNormal = polyhedron->getFaceNormal(minFaceIndex); - Vector3 normalWorld = -(polyhedronToWorldTransform.getOrientation() * minFaceNormal); - const Vector3 contactPointSphereLocal = sphereToWorldTransform.getInverse().getOrientation() * normalWorld * sphere->getRadius(); - const Vector3 contactPointPolyhedronLocal = sphereCenter + minFaceNormal * (minPenetrationDepth - sphere->getRadius()); + if (reportContacts) { - // Create the contact info object - narrowPhaseInfo->addContactPoint(normalWorld, minPenetrationDepth, - isSphereShape1 ? contactPointSphereLocal : contactPointPolyhedronLocal, - isSphereShape1 ? contactPointPolyhedronLocal : contactPointSphereLocal); + const Vector3 minFaceNormal = polyhedron->getFaceNormal(minFaceIndex); + Vector3 normalWorld = -(polyhedronToWorldTransform.getOrientation() * minFaceNormal); + const Vector3 contactPointSphereLocal = sphereToWorldTransform.getInverse().getOrientation() * normalWorld * sphere->getRadius(); + const Vector3 contactPointPolyhedronLocal = sphereCenter + minFaceNormal * (minPenetrationDepth - sphere->getRadius()); + + // Create the contact info object + narrowPhaseInfo->addContactPoint(normalWorld, minPenetrationDepth, + isSphereShape1 ? contactPointSphereLocal : contactPointPolyhedronLocal, + isSphereShape1 ? contactPointPolyhedronLocal : contactPointSphereLocal); + } lastFrameInfo.satMinAxisFaceIndex = minFaceIndex; @@ -384,34 +387,39 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfo* narro // We need to clip the inner capsule segment with the adjacent faces of the separating face if (isMinPenetrationFaceNormal) { - computeCapsulePolyhedronFaceContactPoints(minFaceIndex, capsuleRadius, polyhedron, minPenetrationDepth, - polyhedronToCapsuleTransform, normalWorld, separatingAxisCapsuleSpace, - capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, - narrowPhaseInfo, isCapsuleShape1); + if (reportContacts) { + + computeCapsulePolyhedronFaceContactPoints(minFaceIndex, capsuleRadius, polyhedron, minPenetrationDepth, + polyhedronToCapsuleTransform, normalWorld, separatingAxisCapsuleSpace, + capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, + narrowPhaseInfo, isCapsuleShape1); + } lastFrameInfo.satIsAxisFacePolyhedron1 = true; lastFrameInfo.satMinAxisFaceIndex = minFaceIndex; } else { // The separating axis is the cross product of a polyhedron edge and the inner capsule segment - // Compute the closest points between the inner capsule segment and the - // edge of the polyhedron in polyhedron local-space - Vector3 closestPointPolyhedronEdge, closestPointCapsuleInnerSegment; - computeClosestPointBetweenTwoSegments(capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, - separatingPolyhedronEdgeVertex1, separatingPolyhedronEdgeVertex2, - closestPointCapsuleInnerSegment, closestPointPolyhedronEdge); + if (reportContacts) { + // Compute the closest points between the inner capsule segment and the + // edge of the polyhedron in polyhedron local-space + Vector3 closestPointPolyhedronEdge, closestPointCapsuleInnerSegment; + computeClosestPointBetweenTwoSegments(capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, + separatingPolyhedronEdgeVertex1, separatingPolyhedronEdgeVertex2, + closestPointCapsuleInnerSegment, closestPointPolyhedronEdge); - // Project closest capsule inner segment point into the capsule bounds - const Vector3 contactPointCapsule = (polyhedronToCapsuleTransform * closestPointCapsuleInnerSegment) - separatingAxisCapsuleSpace * capsuleRadius; + // Project closest capsule inner segment point into the capsule bounds + const Vector3 contactPointCapsule = (polyhedronToCapsuleTransform * closestPointCapsuleInnerSegment) - separatingAxisCapsuleSpace * capsuleRadius; - // Create the contact point - narrowPhaseInfo->addContactPoint(normalWorld, minPenetrationDepth, - isCapsuleShape1 ? contactPointCapsule : closestPointPolyhedronEdge, - isCapsuleShape1 ? closestPointPolyhedronEdge : contactPointCapsule); + // Create the contact point + narrowPhaseInfo->addContactPoint(normalWorld, minPenetrationDepth, + isCapsuleShape1 ? contactPointCapsule : closestPointPolyhedronEdge, + isCapsuleShape1 ? closestPointPolyhedronEdge : contactPointCapsule); + } - lastFrameInfo.satIsAxisFacePolyhedron1 = false; - lastFrameInfo.satMinEdge1Index = minEdgeIndex; + lastFrameInfo.satIsAxisFacePolyhedron1 = false; + lastFrameInfo.satMinEdge1Index = minEdgeIndex; } return true; @@ -543,8 +551,7 @@ bool SATAlgorithm::isMinkowskiFaceCapsuleVsEdge(const Vector3& capsuleSegment, c } // Test collision between two convex polyhedrons -bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, - bool reportContacts) const { +bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) const { PROFILE("SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron()"); @@ -787,91 +794,93 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn // If the minimum separating axis is a face normal if (isMinPenetrationFaceNormal) { - const ConvexPolyhedronShape* referencePolyhedron = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron1 : polyhedron2; - const ConvexPolyhedronShape* incidentPolyhedron = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron2 : polyhedron1; - const Transform& referenceToIncidentTransform = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron1ToPolyhedron2 : polyhedron2ToPolyhedron1; - const Transform& incidentToReferenceTransform = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron2ToPolyhedron1 : polyhedron1ToPolyhedron2; + if (reportContacts) { - assert(minPenetrationDepth > decimal(0.0)); + const ConvexPolyhedronShape* referencePolyhedron = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron1 : polyhedron2; + const ConvexPolyhedronShape* incidentPolyhedron = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron2 : polyhedron1; + const Transform& referenceToIncidentTransform = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron1ToPolyhedron2 : polyhedron2ToPolyhedron1; + const Transform& incidentToReferenceTransform = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron2ToPolyhedron1 : polyhedron1ToPolyhedron2; - const Vector3 axisReferenceSpace = referencePolyhedron->getFaceNormal(minFaceIndex); - const Vector3 axisIncidentSpace = referenceToIncidentTransform.getOrientation() * axisReferenceSpace; + assert(minPenetrationDepth > decimal(0.0)); - // Compute the world normal - const Vector3 normalWorld = isMinPenetrationFaceNormalPolyhedron1 ? narrowPhaseInfo->shape1ToWorldTransform.getOrientation() * axisReferenceSpace : - -(narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * axisReferenceSpace); + const Vector3 axisReferenceSpace = referencePolyhedron->getFaceNormal(minFaceIndex); + const Vector3 axisIncidentSpace = referenceToIncidentTransform.getOrientation() * axisReferenceSpace; - // Get the reference face - HalfEdgeStructure::Face referenceFace = referencePolyhedron->getFace(minFaceIndex); + // Compute the world normal + const Vector3 normalWorld = isMinPenetrationFaceNormalPolyhedron1 ? narrowPhaseInfo->shape1ToWorldTransform.getOrientation() * axisReferenceSpace : + -(narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * axisReferenceSpace); - // Find the incident face on the other polyhedron (most anti-parallel face) - uint incidentFaceIndex = findMostAntiParallelFaceOnPolyhedron(incidentPolyhedron, axisIncidentSpace); + // Get the reference face + HalfEdgeStructure::Face referenceFace = referencePolyhedron->getFace(minFaceIndex); - // Get the incident face - HalfEdgeStructure::Face incidentFace = incidentPolyhedron->getFace(incidentFaceIndex); + // Find the incident face on the other polyhedron (most anti-parallel face) + uint incidentFaceIndex = findMostAntiParallelFaceOnPolyhedron(incidentPolyhedron, axisIncidentSpace); - std::vector polygonVertices; // Vertices to clip of the incident face - std::vector planesNormals; // Normals of the clipping planes - std::vector planesPoints; // Points on the clipping planes + // Get the incident face + HalfEdgeStructure::Face incidentFace = incidentPolyhedron->getFace(incidentFaceIndex); - // Get all the vertices of the incident face (in the reference local-space) - std::vector::const_iterator it; - for (it = incidentFace.faceVertices.begin(); it != incidentFace.faceVertices.end(); ++it) { - const Vector3 faceVertexIncidentSpace = incidentPolyhedron->getVertexPosition(*it); - polygonVertices.push_back(incidentToReferenceTransform * faceVertexIncidentSpace); - } + std::vector polygonVertices; // Vertices to clip of the incident face + std::vector planesNormals; // Normals of the clipping planes + std::vector planesPoints; // Points on the clipping planes - // Get the reference face clipping planes - uint currentEdgeIndex = referenceFace.edgeIndex; - uint firstEdgeIndex = currentEdgeIndex; - do { + // Get all the vertices of the incident face (in the reference local-space) + std::vector::const_iterator it; + for (it = incidentFace.faceVertices.begin(); it != incidentFace.faceVertices.end(); ++it) { + const Vector3 faceVertexIncidentSpace = incidentPolyhedron->getVertexPosition(*it); + polygonVertices.push_back(incidentToReferenceTransform * faceVertexIncidentSpace); + } - // Get the adjacent edge - HalfEdgeStructure::Edge edge = referencePolyhedron->getHalfEdge(currentEdgeIndex); + // Get the reference face clipping planes + uint currentEdgeIndex = referenceFace.edgeIndex; + uint firstEdgeIndex = currentEdgeIndex; + do { - // Get the twin edge - HalfEdgeStructure::Edge twinEdge = referencePolyhedron->getHalfEdge(edge.twinEdgeIndex); + // Get the adjacent edge + HalfEdgeStructure::Edge edge = referencePolyhedron->getHalfEdge(currentEdgeIndex); - // Get the adjacent face normal (and negate it to have a clipping plane) - Vector3 faceNormal = -referencePolyhedron->getFaceNormal(twinEdge.faceIndex); + // Get the twin edge + HalfEdgeStructure::Edge twinEdge = referencePolyhedron->getHalfEdge(edge.twinEdgeIndex); - // Get a vertex of the clipping plane (vertex of the adjacent edge) - Vector3 faceVertex = referencePolyhedron->getVertexPosition(edge.vertexIndex); + // Get the adjacent face normal (and negate it to have a clipping plane) + Vector3 faceNormal = -referencePolyhedron->getFaceNormal(twinEdge.faceIndex); - planesNormals.push_back(faceNormal); - planesPoints.push_back(faceVertex); + // Get a vertex of the clipping plane (vertex of the adjacent edge) + Vector3 faceVertex = referencePolyhedron->getVertexPosition(edge.vertexIndex); - // Go to the next adjacent edge of the reference face - currentEdgeIndex = edge.nextEdgeIndex; + planesNormals.push_back(faceNormal); + planesPoints.push_back(faceVertex); - } while (currentEdgeIndex != firstEdgeIndex); + // Go to the next adjacent edge of the reference face + currentEdgeIndex = edge.nextEdgeIndex; - assert(planesNormals.size() > 0); - assert(planesNormals.size() == planesPoints.size()); + } while (currentEdgeIndex != firstEdgeIndex); - // Clip the reference faces with the adjacent planes of the reference face - std::vector clipPolygonVertices = clipPolygonWithPlanes(polygonVertices, planesPoints, planesNormals); - assert(clipPolygonVertices.size() > 0); + assert(planesNormals.size() > 0); + assert(planesNormals.size() == planesPoints.size()); - // We only keep the clipped points that are below the reference face - const Vector3 referenceFaceVertex = referencePolyhedron->getVertexPosition(referencePolyhedron->getHalfEdge(firstEdgeIndex).vertexIndex); - std::vector::const_iterator itPoints; - for (itPoints = clipPolygonVertices.begin(); itPoints != clipPolygonVertices.end(); ++itPoints) { + // Clip the reference faces with the adjacent planes of the reference face + std::vector clipPolygonVertices = clipPolygonWithPlanes(polygonVertices, planesPoints, planesNormals); + assert(clipPolygonVertices.size() > 0); - // If the clip point is bellow the reference face - if (((*itPoints) - referenceFaceVertex).dot(axisReferenceSpace) < decimal(0.0)) - { + // We only keep the clipped points that are below the reference face + const Vector3 referenceFaceVertex = referencePolyhedron->getVertexPosition(referencePolyhedron->getHalfEdge(firstEdgeIndex).vertexIndex); + std::vector::const_iterator itPoints; + for (itPoints = clipPolygonVertices.begin(); itPoints != clipPolygonVertices.end(); ++itPoints) { - // Convert the clip incident polyhedron vertex into the incident polyhedron local-space - const Vector3 contactPointIncidentPolyhedron = referenceToIncidentTransform * (*itPoints); + // If the clip point is bellow the reference face + if (((*itPoints) - referenceFaceVertex).dot(axisReferenceSpace) < decimal(0.0)) { - // Project the contact point onto the reference face - Vector3 contactPointReferencePolyhedron = projectPointOntoPlane(*itPoints, axisReferenceSpace, referenceFaceVertex); + // Convert the clip incident polyhedron vertex into the incident polyhedron local-space + const Vector3 contactPointIncidentPolyhedron = referenceToIncidentTransform * (*itPoints); - // Create a new contact point - narrowPhaseInfo->addContactPoint(normalWorld, minPenetrationDepth, - isMinPenetrationFaceNormalPolyhedron1 ? contactPointReferencePolyhedron : contactPointIncidentPolyhedron, - isMinPenetrationFaceNormalPolyhedron1 ? contactPointIncidentPolyhedron : contactPointReferencePolyhedron); + // Project the contact point onto the reference face + Vector3 contactPointReferencePolyhedron = projectPointOntoPlane(*itPoints, axisReferenceSpace, referenceFaceVertex); + + // Create a new contact point + narrowPhaseInfo->addContactPoint(normalWorld, minPenetrationDepth, + isMinPenetrationFaceNormalPolyhedron1 ? contactPointReferencePolyhedron : contactPointIncidentPolyhedron, + isMinPenetrationFaceNormalPolyhedron1 ? contactPointIncidentPolyhedron : contactPointReferencePolyhedron); + } } } @@ -881,20 +890,23 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn } else { // If we have an edge vs edge contact - // Compute the closest points between the two edges (in the local-space of poylhedron 2) - Vector3 closestPointPolyhedron1Edge, closestPointPolyhedron2Edge; - computeClosestPointBetweenTwoSegments(separatingEdge1A, separatingEdge1B, separatingEdge2A, separatingEdge2B, - closestPointPolyhedron1Edge, closestPointPolyhedron2Edge); + if (reportContacts) { - // Compute the contact point on polyhedron 1 edge in the local-space of polyhedron 1 - const Vector3 closestPointPolyhedron1EdgeLocalSpace = polyhedron2ToPolyhedron1 * closestPointPolyhedron1Edge; + // Compute the closest points between the two edges (in the local-space of poylhedron 2) + Vector3 closestPointPolyhedron1Edge, closestPointPolyhedron2Edge; + computeClosestPointBetweenTwoSegments(separatingEdge1A, separatingEdge1B, separatingEdge2A, separatingEdge2B, + closestPointPolyhedron1Edge, closestPointPolyhedron2Edge); - // Compute the world normal - const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * minEdgeVsEdgeSeparatingAxisPolyhedron2Space; + // Compute the contact point on polyhedron 1 edge in the local-space of polyhedron 1 + const Vector3 closestPointPolyhedron1EdgeLocalSpace = polyhedron2ToPolyhedron1 * closestPointPolyhedron1Edge; - // Create the contact point - narrowPhaseInfo->addContactPoint(normalWorld, minPenetrationDepth, - closestPointPolyhedron1EdgeLocalSpace, closestPointPolyhedron2Edge); + // Compute the world normal + const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * minEdgeVsEdgeSeparatingAxisPolyhedron2Space; + + // Create the contact point + narrowPhaseInfo->addContactPoint(normalWorld, minPenetrationDepth, + closestPointPolyhedron1EdgeLocalSpace, closestPointPolyhedron2Edge); + } lastFrameInfo.satIsAxisFacePolyhedron1 = false; lastFrameInfo.satIsAxisFacePolyhedron2 = false; diff --git a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp index e291fd83..52016f2f 100755 --- a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp @@ -71,24 +71,27 @@ bool SphereVsCapsuleAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, b // If the collision shapes overlap if (sphereSegmentDistanceSquare < sumRadius * sumRadius && sphereSegmentDistanceSquare > MACHINE_EPSILON) { - decimal sphereSegmentDistance = std::sqrt(sphereSegmentDistanceSquare); - sphereCenterToSegment /= sphereSegmentDistance; + if (reportContacts) { - const Vector3 contactPointSphereLocal = sphereToCapsuleSpaceTransform.getInverse() * (sphereCenter + sphereCenterToSegment * sphereShape->getRadius()); - const Vector3 contactPointCapsuleLocal = closestPointOnSegment - sphereCenterToSegment * capsuleShape->getRadius(); - - Vector3 normalWorld = capsuleToWorldTransform.getOrientation() * sphereCenterToSegment; - - decimal penetrationDepth = sumRadius - sphereSegmentDistance; + decimal sphereSegmentDistance = std::sqrt(sphereSegmentDistanceSquare); + sphereCenterToSegment /= sphereSegmentDistance; - if (!isSphereShape1) { - normalWorld = -normalWorld; + const Vector3 contactPointSphereLocal = sphereToCapsuleSpaceTransform.getInverse() * (sphereCenter + sphereCenterToSegment * sphereShape->getRadius()); + const Vector3 contactPointCapsuleLocal = closestPointOnSegment - sphereCenterToSegment * capsuleShape->getRadius(); + + Vector3 normalWorld = capsuleToWorldTransform.getOrientation() * sphereCenterToSegment; + + decimal penetrationDepth = sumRadius - sphereSegmentDistance; + + if (!isSphereShape1) { + normalWorld = -normalWorld; + } + + // Create the contact info object + narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, + isSphereShape1 ? contactPointSphereLocal : contactPointCapsuleLocal, + isSphereShape1 ? contactPointCapsuleLocal : contactPointSphereLocal); } - - // Create the contact info object - narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, - isSphereShape1 ? contactPointSphereLocal : contactPointCapsuleLocal, - isSphereShape1 ? contactPointCapsuleLocal : contactPointSphereLocal); return true; } diff --git a/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp b/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp index 94211ac0..1335c911 100644 --- a/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp @@ -52,17 +52,21 @@ bool SphereVsSphereAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bo // If the sphere collision shapes intersect if (squaredDistanceBetweenCenters < sumRadius * sumRadius) { - Vector3 centerSphere2InBody1LocalSpace = transform1.getInverse() * transform2.getPosition(); - Vector3 centerSphere1InBody2LocalSpace = transform2.getInverse() * transform1.getPosition(); - Vector3 intersectionOnBody1 = sphereShape1->getRadius() * - centerSphere2InBody1LocalSpace.getUnit(); - Vector3 intersectionOnBody2 = sphereShape2->getRadius() * - centerSphere1InBody2LocalSpace.getUnit(); - decimal penetrationDepth = sumRadius - std::sqrt(squaredDistanceBetweenCenters); - - // Create the contact info object - narrowPhaseInfo->addContactPoint(vectorBetweenCenters.getUnit(), penetrationDepth, - intersectionOnBody1, intersectionOnBody2); + + if (reportContacts) { + + Vector3 centerSphere2InBody1LocalSpace = transform1.getInverse() * transform2.getPosition(); + Vector3 centerSphere1InBody2LocalSpace = transform2.getInverse() * transform1.getPosition(); + Vector3 intersectionOnBody1 = sphereShape1->getRadius() * + centerSphere2InBody1LocalSpace.getUnit(); + Vector3 intersectionOnBody2 = sphereShape2->getRadius() * + centerSphere1InBody2LocalSpace.getUnit(); + decimal penetrationDepth = sumRadius - std::sqrt(squaredDistanceBetweenCenters); + + // Create the contact info object + narrowPhaseInfo->addContactPoint(vectorBetweenCenters.getUnit(), penetrationDepth, + intersectionOnBody1, intersectionOnBody2); + } return true; } From dfb4b811f9af79d1b53db448dcbfc57411abb52a Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 1 Aug 2017 12:39:20 +0200 Subject: [PATCH 082/248] Edit user manual documentation --- .../UserManual/ReactPhysics3D-UserManual.tex | 42 +++++++++++++------ 1 file changed, 30 insertions(+), 12 deletions(-) diff --git a/documentation/UserManual/ReactPhysics3D-UserManual.tex b/documentation/UserManual/ReactPhysics3D-UserManual.tex index c7e66ccb..e1c20e5d 100644 --- a/documentation/UserManual/ReactPhysics3D-UserManual.tex +++ b/documentation/UserManual/ReactPhysics3D-UserManual.tex @@ -373,6 +373,7 @@ world.enableSleeping(false); \end{sloppypar} \subsection{Updating the Dynamics World} + \label{sec:updating_dynamics_world} The \texttt{DynamicsWorld} is used to simulate physics through time. It has to be updated each time you want to simulate a step forward in time. Most of the time, you want to update the world right before rendering a new frame in a real-time application. \\ @@ -611,19 +612,36 @@ rigidBody->applyTorque(torque); \subsection{Updating a Rigid Body} When you call the \texttt{DynamicsWorld::update()} method, the collisions between the bodies are computed and the joints are evaluated. Then, the bodies position - and orientation - are updated accordingly. After calling this method, you can get the updated position and orientation of each body to render it. To do that, you simply need to use the - \texttt{RigidBody::getInterpolatedTransform()} method to get the interpolated transform. This transform represents the current local-to-world-space transformation - of the body. \\ + and orientation are updated accordingly. \\ - Here is how to get the interpolated transform of a rigid body: \\ + Remember that in section \ref{sec:updating_dynamics_world} we were using a time accumulator in order to always have fixed physics time steps. + Now imagine a situation where the rendering frame rate is higher than the the physics frame rate. It means that at the end of most rendering + frames there will be some time left in the accumulator for the physics time that has not been simulated yet by the physics engine. + It means that we are rendering the state of the physics simulation at a time different from the rendering time which can cause a visual stuttering effect. \\ + + To solve this, the idea is to interpolate between the previous and current physics state of the simulation based on how much time is left in the + accumulator. First we compute the interpolation factor as follows: \\ \begin{lstlisting} -// Here, body is a RigidBody* pointer previously created -// Get the interpolated transform of the rigid body -rp3d::Transform transform = body->getInterpolatedTransform(); - \end{lstlisting} + // Compute the interpolation factor ("accumulator" is the time left in the accumulator and + // "dt" is the physics time step) + const float interpolationFactor = accumulator / dt; + \end{lstlisting} + + \vspace{0.6cm} + + Then we get the current transform of the rigid body and use it with the previous transform (transform at the previous frame) to + compute the interpolated transform as in the following code: \\ + + \begin{lstlisting} + + // Get the current transform of the rigid body + rp3d::Transform currentTransform = body->getTransform(); + + // Interpolate the transform between the previous one and the new one + rp3d::Transform interpolatedTransform = rp3d::Transform::interpolateTransforms(previousTransform, currentTransform, interpolationFactor); + \end{lstlisting} \vspace{0.6cm} @@ -631,9 +649,9 @@ rp3d::Transform transform = body->getInterpolatedTransform(); following code: \\ \begin{lstlisting} -// Get the OpenGL matrix array of the transform -float matrix[16]; -transform.getOpenGLMatrix(matrix); + // Get the OpenGL matrix array of the transform + float matrix[16]; + transform.getOpenGLMatrix(matrix); \end{lstlisting} \subsection{Destroying a Rigid Body} From 2f601909423be819bf1d67e4535fe31cf8edb009 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 1 Aug 2017 15:57:46 +0200 Subject: [PATCH 083/248] Do not generate contact in GJK algorithm if not needed --- .../narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp | 1 - src/collision/narrowphase/GJK/GJKAlgorithm.cpp | 7 +++++-- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp index be9cc05f..73a1dd13 100644 --- a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp @@ -122,7 +122,6 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPh break; } } - } narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = false; diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp index ff81782f..10d344f1 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp @@ -207,8 +207,11 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhase return GJKResult::INTERPENETRATE; } - // Add a new contact point - narrowPhaseInfo->addContactPoint(normal, penetrationDepth, pA, pB); + if (reportContacts) { + + // Add a new contact point + narrowPhaseInfo->addContactPoint(normal, penetrationDepth, pA, pB); + } return GJKResult::COLLIDE_IN_MARGIN; } From 319cc72cde3052239b62cbb0f51a1f8bf8db252c Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Fri, 18 Aug 2017 17:50:27 +0200 Subject: [PATCH 084/248] Fix issues in collision detection --- src/collision/CollisionCallback.cpp | 1 + src/collision/CollisionDetection.cpp | 33 ++-- src/collision/ContactManifoldSet.cpp | 4 + .../narrowphase/CapsuleVsCapsuleAlgorithm.cpp | 167 ++++++++++++------ .../narrowphase/SAT/SATAlgorithm.cpp | 19 +- .../narrowphase/SphereVsCapsuleAlgorithm.cpp | 57 ++++-- .../narrowphase/SphereVsSphereAlgorithm.cpp | 28 ++- src/collision/shapes/ConvexMeshShape.h | 4 +- src/engine/OverlappingPair.h | 8 + 9 files changed, 227 insertions(+), 94 deletions(-) mode change 100644 => 100755 src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp mode change 100644 => 100755 src/collision/narrowphase/SphereVsSphereAlgorithm.cpp diff --git a/src/collision/CollisionCallback.cpp b/src/collision/CollisionCallback.cpp index f470763d..db820db4 100644 --- a/src/collision/CollisionCallback.cpp +++ b/src/collision/CollisionCallback.cpp @@ -45,6 +45,7 @@ CollisionCallback::CollisionCallbackInfo::CollisionCallbackInfo(OverlappingPair* // For each contact manifold in the set of manifolds in the pair ContactManifold* contactManifold = manifoldSet.getContactManifolds(); + assert(contactManifold != nullptr); while (contactManifold != nullptr) { assert(contactManifold->getNbContactPoints() > 0); diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 57360706..0abd82a3 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -440,7 +440,7 @@ void CollisionDetection::reportAllContacts() { for (it = mContactOverlappingPairs.begin(); it != mContactOverlappingPairs.end(); ++it) { // If there is a user callback - if (mWorld->mEventListener != nullptr) { + if (mWorld->mEventListener != nullptr && it->second->hasContacts()) { CollisionCallback::CollisionCallbackInfo collisionInfo(it->second, mPoolAllocator); @@ -845,9 +845,12 @@ void CollisionDetection::testCollision(CollisionBody* body1, CollisionBody* body // Process the potential contacts processPotentialContacts(&pair); - // Report the contacts to the user - CollisionCallback::CollisionCallbackInfo collisionInfo(&pair, mPoolAllocator); - collisionCallback->notifyContact(collisionInfo); + if (pair.hasContacts()) { + + // Report the contacts to the user + CollisionCallback::CollisionCallbackInfo collisionInfo(&pair, mPoolAllocator); + collisionCallback->notifyContact(collisionInfo); + } } // Go to the next proxy shape @@ -916,10 +919,6 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c // Add the contact points as a potential contact manifold into the pair narrowPhaseInfo->addContactPointsAsPotentialContactManifold(); - - // Report the contacts to the user - CollisionCallback::CollisionCallbackInfo collisionInfo(&pair, mPoolAllocator); - callback->notifyContact(collisionInfo); } } @@ -935,6 +934,13 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c // Process the potential contacts processPotentialContacts(&pair); + + if (pair.hasContacts()) { + + // Report the contacts to the user + CollisionCallback::CollisionCallbackInfo collisionInfo(&pair, mPoolAllocator); + callback->notifyContact(collisionInfo); + } } } @@ -996,10 +1002,6 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { // Add the contact points as a potential contact manifold into the pair narrowPhaseInfo->addContactPointsAsPotentialContactManifold(); - - // Report the contacts to the user - CollisionCallback::CollisionCallbackInfo collisionInfo(&pair, mPoolAllocator); - callback->notifyContact(collisionInfo); } } @@ -1015,6 +1017,13 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { // Process the potential contacts processPotentialContacts(&pair); + + if (pair.hasContacts()) { + + // Report the contacts to the user + CollisionCallback::CollisionCallbackInfo collisionInfo(&pair, mPoolAllocator); + callback->notifyContact(collisionInfo); + } } } } diff --git a/src/collision/ContactManifoldSet.cpp b/src/collision/ContactManifoldSet.cpp index b9b7f3e8..23602dda 100644 --- a/src/collision/ContactManifoldSet.cpp +++ b/src/collision/ContactManifoldSet.cpp @@ -247,6 +247,10 @@ void ContactManifoldSet::removeManifold(ContactManifold* manifold) { if (previous != nullptr) { previous->setNext(manifold->getNext()); } + else { + mManifolds = next; + } + if (next != nullptr) { next->setPrevious(manifold->getPrevious()); } diff --git a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp old mode 100644 new mode 100755 index c98329bf..b15cb186 --- a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp @@ -63,68 +63,88 @@ bool CapsuleVsCapsuleAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, decimal sumRadius = capsuleShape2->getRadius() + capsuleShape1->getRadius(); // If the two capsules are parallel (we create two contact points) - if (areParallelVectors(seg1, seg2)) { + bool areCapsuleInnerSegmentsParralel = areParallelVectors(seg1, seg2); + if (areCapsuleInnerSegmentsParralel) { // If the distance between the two segments is larger than the sum of the capsules radius (we do not have overlapping) - const decimal segmentsDistance = computePointToLineDistance(capsule1SegA, capsule1SegB, capsule2SegA); - if (segmentsDistance >= sumRadius) { + const decimal segmentsPerpendicularDistance = computePointToLineDistance(capsule1SegA, capsule1SegB, capsule2SegA); + if (segmentsPerpendicularDistance >= sumRadius) { // The capsule are parallel but their inner segment distance is larger than the sum of the capsules radius. // Therefore, we do not have overlap. If the inner segments overlap, we do not report any collision. return false; } - // If the distance between the two segments is larger than zero (inner segments of capsules are not overlapping) - // If the inner segments are overlapping, we cannot compute a contact normal (unknown direction). In this case, - // we skip the parallel contact points calculation (there might still be contact in the spherical caps of the capsules) - if (segmentsDistance > MACHINE_EPSILON) { + // Compute the planes that goes through the extreme points of the inner segment of capsule 1 + decimal d1 = seg1.dot(capsule1SegA); + decimal d2 = -seg1.dot(capsule1SegB); - // Compute the planes that goes through the extreme points of the inner segment of capsule 1 - decimal d1 = seg1.dot(capsule1SegA); - decimal d2 = -seg1.dot(capsule1SegB); + // Clip the inner segment of capsule 2 with the two planes that go through extreme points of inner + // segment of capsule 1 + decimal t1 = computePlaneSegmentIntersection(capsule2SegB, capsule2SegA, d1, seg1); + decimal t2 = computePlaneSegmentIntersection(capsule2SegA, capsule2SegB, d2, -seg1); - // Clip the inner segment of capsule 2 with the two planes that go through extreme points of inner - // segment of capsule 1 - decimal t1 = computePlaneSegmentIntersection(capsule2SegB, capsule2SegA, d1, seg1); - decimal t2 = computePlaneSegmentIntersection(capsule2SegA, capsule2SegB, d2, -seg1); + // If the segments were overlapping (the clip segment is valid) + if (t1 > decimal(0.0) && t2 > decimal(0.0)) { - // If the segments were overlapping (the clip segment is valid) - if (t1 > decimal(0.0) && t2 > decimal(0.0)) { + if (reportContacts) { - if (reportContacts) { + // Clip the inner segment of capsule 2 + if (t1 > decimal(1.0)) t1 = decimal(1.0); + const Vector3 clipPointA = capsule2SegB - t1 * seg2; + if (t2 > decimal(1.0)) t2 = decimal(1.0); + const Vector3 clipPointB = capsule2SegA + t2 * seg2; - // Clip the inner segment of capsule 2 - if (t1 > decimal(1.0)) t1 = decimal(1.0); - const Vector3 clipPointA = capsule2SegB - t1 * seg2; - if (t2 > decimal(1.0)) t2 = decimal(1.0); - const Vector3 clipPointB = capsule2SegA + t2 * seg2; + // Project point capsule2SegA onto line of innner segment of capsule 1 + const Vector3 seg1Normalized = seg1.getUnit(); + Vector3 pointOnInnerSegCapsule1 = capsule1SegA + seg1Normalized.dot(capsule2SegA - capsule1SegA) * seg1Normalized; - // Project point capsule2SegA onto line of innner segment of capsule 1 - const Vector3 seg1Normalized = seg1.getUnit(); - Vector3 pointOnInnerSegCapsule1 = capsule1SegA + seg1Normalized.dot(capsule2SegA - capsule1SegA) * seg1Normalized; + Vector3 normalCapsule2SpaceNormalized; + Vector3 segment1ToSegment2; - // Compute a perpendicular vector from segment 1 to segment 2 - Vector3 segment1ToSegment2 = (capsule2SegA - pointOnInnerSegCapsule1); - Vector3 segment1ToSegment2Normalized = segment1ToSegment2.getUnit(); + // If the inner capsule segments perpendicular distance is not zero (the inner segments are not overlapping) + if (segmentsPerpendicularDistance > MACHINE_EPSILON) { - Transform capsule2ToCapsule1SpaceTransform = capsule1ToCapsule2SpaceTransform.getInverse(); - const Vector3 contactPointACapsule1Local = capsule2ToCapsule1SpaceTransform * (clipPointA - segment1ToSegment2 + segment1ToSegment2Normalized * capsuleShape1->getRadius()); - const Vector3 contactPointBCapsule1Local = capsule2ToCapsule1SpaceTransform * (clipPointB - segment1ToSegment2 + segment1ToSegment2Normalized * capsuleShape1->getRadius()); - const Vector3 contactPointACapsule2Local = clipPointA - segment1ToSegment2Normalized * capsuleShape2->getRadius(); - const Vector3 contactPointBCapsule2Local = clipPointB - segment1ToSegment2Normalized * capsuleShape2->getRadius(); + // Compute a perpendicular vector from segment 1 to segment 2 + segment1ToSegment2 = (capsule2SegA - pointOnInnerSegCapsule1); + normalCapsule2SpaceNormalized = segment1ToSegment2.getUnit(); + } + else { // If the capsule inner segments are overlapping (degenerate case) - const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * segment1ToSegment2Normalized; + // We cannot use the vector between segments as a contact normal. To generate a contact normal, we take + // any vector that is orthogonal to the inner capsule segments. - decimal penetrationDepth = sumRadius - segmentsDistance; + Vector3 vec1(1, 0, 0); + Vector3 vec2(0, 1, 0); - // Create the contact info object - narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, contactPointACapsule1Local, contactPointACapsule2Local); - narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, contactPointBCapsule1Local, contactPointBCapsule2Local); + Vector3 seg2Normalized = seg2.getUnit(); - } + // Get the vectors (among vec1 and vec2) that is the most orthogonal to the capsule 2 inner segment (smallest absolute dot product) + decimal cosA1 = std::abs(seg2Normalized.x); // abs(vec1.dot(seg2)) + decimal cosA2 = std::abs(seg2Normalized.y); // abs(vec2.dot(seg2)) - return true; - } + segment1ToSegment2.setToZero(); + + // We choose as a contact normal, any direction that is perpendicular to the inner capsules segments + normalCapsule2SpaceNormalized = cosA1 < cosA2 ? seg2Normalized.cross(vec1) : seg2Normalized.cross(vec2); + } + + Transform capsule2ToCapsule1SpaceTransform = capsule1ToCapsule2SpaceTransform.getInverse(); + const Vector3 contactPointACapsule1Local = capsule2ToCapsule1SpaceTransform * (clipPointA - segment1ToSegment2 + normalCapsule2SpaceNormalized * capsuleShape1->getRadius()); + const Vector3 contactPointBCapsule1Local = capsule2ToCapsule1SpaceTransform * (clipPointB - segment1ToSegment2 + normalCapsule2SpaceNormalized * capsuleShape1->getRadius()); + const Vector3 contactPointACapsule2Local = clipPointA - normalCapsule2SpaceNormalized * capsuleShape2->getRadius(); + const Vector3 contactPointBCapsule2Local = clipPointB - normalCapsule2SpaceNormalized * capsuleShape2->getRadius(); + + decimal penetrationDepth = sumRadius - segmentsPerpendicularDistance; + + const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * normalCapsule2SpaceNormalized; + + // Create the contact info object + narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, contactPointACapsule1Local, contactPointACapsule2Local); + narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, contactPointBCapsule1Local, contactPointBCapsule2Local); + } + + return true; } } @@ -132,31 +152,72 @@ bool CapsuleVsCapsuleAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, Vector3 closestPointCapsule1Seg; Vector3 closestPointCapsule2Seg; computeClosestPointBetweenTwoSegments(capsule1SegA, capsule1SegB, capsule2SegA, capsule2SegB, - closestPointCapsule1Seg, closestPointCapsule2Seg); + closestPointCapsule1Seg, closestPointCapsule2Seg); // Compute the distance between the sphere center and the closest point on the segment Vector3 closestPointsSeg1ToSeg2 = (closestPointCapsule2Seg - closestPointCapsule1Seg); const decimal closestPointsDistanceSquare = closestPointsSeg1ToSeg2.lengthSquare(); // If the collision shapes overlap - if (closestPointsDistanceSquare < sumRadius * sumRadius && closestPointsDistanceSquare > MACHINE_EPSILON) { + if (closestPointsDistanceSquare < sumRadius * sumRadius) { + + if (reportContacts) { - if (reportContacts) { + // If the distance between the inner segments is not zero + if (closestPointsDistanceSquare > MACHINE_EPSILON) { - decimal closestPointsDistance = std::sqrt(closestPointsDistanceSquare); - closestPointsSeg1ToSeg2 /= closestPointsDistance; + decimal closestPointsDistance = std::sqrt(closestPointsDistanceSquare); + closestPointsSeg1ToSeg2 /= closestPointsDistance; - const Vector3 contactPointCapsule1Local = capsule1ToCapsule2SpaceTransform.getInverse() * (closestPointCapsule1Seg + closestPointsSeg1ToSeg2 * capsuleShape1->getRadius()); - const Vector3 contactPointCapsule2Local = closestPointCapsule2Seg - closestPointsSeg1ToSeg2 * capsuleShape2->getRadius(); + const Vector3 contactPointCapsule1Local = capsule1ToCapsule2SpaceTransform.getInverse() * (closestPointCapsule1Seg + closestPointsSeg1ToSeg2 * capsuleShape1->getRadius()); + const Vector3 contactPointCapsule2Local = closestPointCapsule2Seg - closestPointsSeg1ToSeg2 * capsuleShape2->getRadius(); - const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * closestPointsSeg1ToSeg2; + const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * closestPointsSeg1ToSeg2; - decimal penetrationDepth = sumRadius - closestPointsDistance; + decimal penetrationDepth = sumRadius - closestPointsDistance; - // Create the contact info object - narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, contactPointCapsule1Local, contactPointCapsule2Local); + // Create the contact info object + narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, contactPointCapsule1Local, contactPointCapsule2Local); + } + else { // The segment are overlapping (degenerate case) - } + // If the capsule segments are parralel + if (areCapsuleInnerSegmentsParralel) { + + // The segment are parallel, not overlapping and their distance is zero. + // Therefore, the capsules are just touching at the top of their inner segments + decimal squareDistCapsule2PointToCapsuleSegA = (capsule1SegA - closestPointCapsule2Seg).lengthSquare(); + + Vector3 capsule1SegmentMostExtremePoint = squareDistCapsule2PointToCapsuleSegA > MACHINE_EPSILON ? capsule1SegA : capsule1SegB; + Vector3 normalCapsuleSpace2 = (closestPointCapsule2Seg - capsule1SegmentMostExtremePoint); + normalCapsuleSpace2.normalize(); + + const Vector3 contactPointCapsule1Local = capsule1ToCapsule2SpaceTransform.getInverse() * (closestPointCapsule1Seg + normalCapsuleSpace2 * capsuleShape1->getRadius()); + const Vector3 contactPointCapsule2Local = closestPointCapsule2Seg - normalCapsuleSpace2 * capsuleShape2->getRadius(); + + const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * normalCapsuleSpace2; + + // Create the contact info object + narrowPhaseInfo->addContactPoint(normalWorld, sumRadius, contactPointCapsule1Local, contactPointCapsule2Local); + } + else { // If the capsules inner segments are not parallel + + // We cannot use a vector between the segments as contact normal. We need to compute a new contact normal with the cross + // product between the two segments. + Vector3 normalCapsuleSpace2 = seg1.cross(seg2); + normalCapsuleSpace2.normalize(); + + // Compute the contact points on both shapes + const Vector3 contactPointCapsule1Local = capsule1ToCapsule2SpaceTransform.getInverse() * (closestPointCapsule1Seg + normalCapsuleSpace2 * capsuleShape1->getRadius()); + const Vector3 contactPointCapsule2Local = closestPointCapsule2Seg - normalCapsuleSpace2 * capsuleShape2->getRadius(); + + const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * normalCapsuleSpace2; + + // Create the contact info object + narrowPhaseInfo->addContactPoint(normalWorld, sumRadius, contactPointCapsule1Local, contactPointCapsule2Local); + } + } + } return true; } diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 98686311..cebec9a6 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -838,17 +838,20 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn // Get the adjacent edge HalfEdgeStructure::Edge edge = referencePolyhedron->getHalfEdge(currentEdgeIndex); - // Get the twin edge - HalfEdgeStructure::Edge twinEdge = referencePolyhedron->getHalfEdge(edge.twinEdgeIndex); + // Get the twin edge + HalfEdgeStructure::Edge twinEdge = referencePolyhedron->getHalfEdge(edge.twinEdgeIndex); - // Get the adjacent face normal (and negate it to have a clipping plane) - Vector3 faceNormal = -referencePolyhedron->getFaceNormal(twinEdge.faceIndex); + // Compute the edge vertices and edge direction + Vector3 edgeV1 = referencePolyhedron->getVertexPosition(edge.vertexIndex); + Vector3 edgeV2 = referencePolyhedron->getVertexPosition(twinEdge.vertexIndex); + Vector3 edgeDirection = edgeV2 - edgeV1; - // Get a vertex of the clipping plane (vertex of the adjacent edge) - Vector3 faceVertex = referencePolyhedron->getVertexPosition(edge.vertexIndex); + // Compute the normal of the clipping plane for this edge + // The clipping plane is perpendicular to the edge direction and the reference face normal + Vector3 clipPlaneNormal = axisReferenceSpace.cross(edgeDirection); - planesNormals.push_back(faceNormal); - planesPoints.push_back(faceVertex); + planesNormals.push_back(clipPlaneNormal); + planesPoints.push_back(edgeV1); // Go to the next adjacent edge of the reference face currentEdgeIndex = edge.nextEdgeIndex; diff --git a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp index 52016f2f..a5d7a6ac 100755 --- a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp @@ -69,28 +69,61 @@ bool SphereVsCapsuleAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, b decimal sumRadius = sphereShape->getRadius() + capsuleShape->getRadius(); // If the collision shapes overlap - if (sphereSegmentDistanceSquare < sumRadius * sumRadius && sphereSegmentDistanceSquare > MACHINE_EPSILON) { + if (sphereSegmentDistanceSquare < sumRadius * sumRadius) { + + decimal penetrationDepth; + Vector3 normalWorld; + Vector3 contactPointSphereLocal; + Vector3 contactPointCapsuleLocal; if (reportContacts) { - decimal sphereSegmentDistance = std::sqrt(sphereSegmentDistanceSquare); - sphereCenterToSegment /= sphereSegmentDistance; + // If the sphere center is not on the capsule inner segment + if (sphereSegmentDistanceSquare > MACHINE_EPSILON) { - const Vector3 contactPointSphereLocal = sphereToCapsuleSpaceTransform.getInverse() * (sphereCenter + sphereCenterToSegment * sphereShape->getRadius()); - const Vector3 contactPointCapsuleLocal = closestPointOnSegment - sphereCenterToSegment * capsuleShape->getRadius(); + decimal sphereSegmentDistance = std::sqrt(sphereSegmentDistanceSquare); + sphereCenterToSegment /= sphereSegmentDistance; - Vector3 normalWorld = capsuleToWorldTransform.getOrientation() * sphereCenterToSegment; + contactPointSphereLocal = sphereToCapsuleSpaceTransform.getInverse() * (sphereCenter + sphereCenterToSegment * sphereShape->getRadius()); + contactPointCapsuleLocal = closestPointOnSegment - sphereCenterToSegment * capsuleShape->getRadius(); - decimal penetrationDepth = sumRadius - sphereSegmentDistance; + normalWorld = capsuleToWorldTransform.getOrientation() * sphereCenterToSegment; - if (!isSphereShape1) { - normalWorld = -normalWorld; - } + penetrationDepth = sumRadius - sphereSegmentDistance; + + if (!isSphereShape1) { + normalWorld = -normalWorld; + } + } + else { // If the sphere center is on the capsule inner segment (degenerate case) + + // We take any direction that is orthogonal to the inner capsule segment as a contact normal + + // Capsule inner segment + Vector3 capsuleSegment = (capsuleSegB - capsuleSegA).getUnit(); + + Vector3 vec1(1, 0, 0); + Vector3 vec2(0, 1, 0); + + // Get the vectors (among vec1 and vec2) that is the most orthogonal to the capsule inner segment (smallest absolute dot product) + decimal cosA1 = std::abs(capsuleSegment.x); // abs(vec1.dot(seg2)) + decimal cosA2 = std::abs(capsuleSegment.y); // abs(vec2.dot(seg2)) + + penetrationDepth = sumRadius; + + // We choose as a contact normal, any direction that is perpendicular to the inner capsule segment + Vector3 normalCapsuleSpace = cosA1 < cosA2 ? capsuleSegment.cross(vec1) : capsuleSegment.cross(vec2); + normalWorld = capsuleToWorldTransform.getOrientation() * normalCapsuleSpace; + + // Compute the two local contact points + contactPointSphereLocal = sphereToCapsuleSpaceTransform.getInverse() * (sphereCenter + normalCapsuleSpace * sphereShape->getRadius()); + contactPointCapsuleLocal = sphereCenter - normalCapsuleSpace * capsuleShape->getRadius(); + } // Create the contact info object narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, - isSphereShape1 ? contactPointSphereLocal : contactPointCapsuleLocal, - isSphereShape1 ? contactPointCapsuleLocal : contactPointSphereLocal); + isSphereShape1 ? contactPointSphereLocal : contactPointCapsuleLocal, + isSphereShape1 ? contactPointCapsuleLocal : contactPointSphereLocal); } return true; diff --git a/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp b/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp old mode 100644 new mode 100755 index 1335c911..0b520213 --- a/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp @@ -57,15 +57,29 @@ bool SphereVsSphereAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bo Vector3 centerSphere2InBody1LocalSpace = transform1.getInverse() * transform2.getPosition(); Vector3 centerSphere1InBody2LocalSpace = transform2.getInverse() * transform1.getPosition(); - Vector3 intersectionOnBody1 = sphereShape1->getRadius() * - centerSphere2InBody1LocalSpace.getUnit(); - Vector3 intersectionOnBody2 = sphereShape2->getRadius() * - centerSphere1InBody2LocalSpace.getUnit(); decimal penetrationDepth = sumRadius - std::sqrt(squaredDistanceBetweenCenters); + Vector3 intersectionOnBody1; + Vector3 intersectionOnBody2; + Vector3 normal; - // Create the contact info object - narrowPhaseInfo->addContactPoint(vectorBetweenCenters.getUnit(), penetrationDepth, - intersectionOnBody1, intersectionOnBody2); + // If the two sphere centers are not at the same position + if (squaredDistanceBetweenCenters > MACHINE_EPSILON) { + + intersectionOnBody1 = sphereShape1->getRadius() * centerSphere2InBody1LocalSpace.getUnit(); + intersectionOnBody2 = sphereShape2->getRadius() * centerSphere1InBody2LocalSpace.getUnit(); + normal = vectorBetweenCenters.getUnit(); + } + else { // If the sphere centers are at the same position (degenerate case) + + // Take any contact normal direction + normal.setAllValues(0, 1, 0); + + intersectionOnBody1 = sphereShape1->getRadius() * (transform1.getInverse().getOrientation() * normal); + intersectionOnBody2 = sphereShape2->getRadius() * (transform2.getInverse().getOrientation() * normal); + } + + // Create the contact info object + narrowPhaseInfo->addContactPoint(normal, penetrationDepth, intersectionOnBody1, intersectionOnBody2); } return true; diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index 28ba9c86..dd2b7021 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -233,7 +233,7 @@ inline HalfEdgeStructure::Edge ConvexMeshShape::getHalfEdge(uint edgeIndex) cons // Return the position of a given vertex inline Vector3 ConvexMeshShape::getVertexPosition(uint vertexIndex) const { assert(vertexIndex < getNbVertices()); - return mPolyhedronMesh->getVertex(vertexIndex); + return mPolyhedronMesh->getVertex(vertexIndex) * mScaling; } // Return the normal vector of a given face of the polyhedron @@ -244,7 +244,7 @@ inline Vector3 ConvexMeshShape::getFaceNormal(uint faceIndex) const { // Return the centroid of the polyhedron inline Vector3 ConvexMeshShape::getCentroid() const { - return mPolyhedronMesh->getCentroid(); + return mPolyhedronMesh->getCentroid() * mScaling; } } diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index a55df081..906cddb7 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -155,6 +155,9 @@ class OverlappingPair { /// Return true if one of the shapes of the pair is a concave shape bool hasConcaveShape() const; + /// Return true if the overlapping pair has contact manifolds with contacts + bool hasContacts() const; + /// Return a pointer to the first potential contact manifold in the linked-list ContactManifoldInfo* getPotentialContactManifolds(); @@ -249,6 +252,11 @@ inline bool OverlappingPair::hasConcaveShape() const { !getShape2()->getCollisionShape()->isConvex(); } +// Return true if the overlapping pair has contact manifolds with contacts +inline bool OverlappingPair::hasContacts() const { + return mContactManifoldSet.getContactManifolds() != nullptr; +} + // Return a pointer to the first potential contact manifold in the linked-list inline ContactManifoldInfo* OverlappingPair::getPotentialContactManifolds() { return mPotentialContactManifolds; From 11589dbb2cc5e8048260f90c548ed464e833fd5e Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Fri, 18 Aug 2017 17:51:10 +0200 Subject: [PATCH 085/248] Edit collision detection scene --- .../CollisionDetectionScene.cpp | 49 +++++-------------- .../CollisionDetectionScene.h | 7 ++- 2 files changed, 15 insertions(+), 41 deletions(-) diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp index e8f09670..a99d494d 100755 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp @@ -72,7 +72,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mSphere2->setSleepingColor(mRedColorDemo); // ---------- Capsule 1 ---------- // - openglframework::Vector3 position3(0, -12, 0); + openglframework::Vector3 position3(-6, 7, 0); // Create a cylinder and a corresponding collision body in the dynamics world mCapsule1 = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, position3, mCollisionWorld, mMeshFolderPath); @@ -83,7 +83,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mCapsule1->setSleepingColor(mRedColorDemo); // ---------- Capsule 2 ---------- // - openglframework::Vector3 position4(-8, 0, 0); + openglframework::Vector3 position4(11, -8, 0); // Create a cylinder and a corresponding collision body in the dynamics world mCapsule2 = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, position4, mCollisionWorld, mMeshFolderPath); @@ -115,38 +115,16 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mBox2->setColor(mGreyColorDemo); mBox2->setSleepingColor(mRedColorDemo); - // ---------- Cone ---------- // - //openglframework::Vector3 position4(0, 0, 0); - - // Create a cone and a corresponding collision body in the dynamics world - //mCone = new Cone(CONE_RADIUS, CONE_HEIGHT, position4, mCollisionWorld, - // mMeshFolderPath); - - // Set the color - //mCone->setColor(mGreyColorDemo); - //mCone->setSleepingColor(mRedColorDemo); - - // ---------- Cylinder ---------- // - //openglframework::Vector3 position5(0, 0, 0); - - // Create a cylinder and a corresponding collision body in the dynamics world - //mCylinder = new Cylinder(CYLINDER_RADIUS, CYLINDER_HEIGHT, position5, - // mCollisionWorld, mMeshFolderPath); - - // Set the color - //mCylinder->setColor(mGreyColorDemo); - //mCylinder->setSleepingColor(mRedColorDemo); - - // ---------- Convex Mesh ---------- // - //openglframework::Vector3 position7(0, 0, 0); + openglframework::Vector3 position7(-5, 0, 0); // Create a convex mesh and a corresponding collision body in the dynamics world - //mConvexMesh = new ConvexMesh(position7, mCollisionWorld, mMeshFolderPath + "convexmesh.obj"); + mConvexMesh = new ConvexMesh(position7, mCollisionWorld, mMeshFolderPath + "convexmesh.obj"); + mAllShapes.push_back(mConvexMesh); // Set the color - //mConvexMesh->setColor(mGreyColorDemo); - //mConvexMesh->setSleepingColor(mRedColorDemo); + mConvexMesh->setColor(mGreyColorDemo); + mConvexMesh->setSleepingColor(mRedColorDemo); // ---------- Concave Mesh ---------- // //openglframework::Vector3 position8(0, 0, 0); @@ -202,6 +180,9 @@ CollisionDetectionScene::~CollisionDetectionScene() { mCollisionWorld->destroyCollisionBody(mBox2->getCollisionBody()); delete mBox2; + mCollisionWorld->destroyCollisionBody(mConvexMesh->getCollisionBody()); + delete mConvexMesh; + /* // Destroy the corresponding rigid body from the dynamics world mCollisionWorld->destroyCollisionBody(mCone->getCollisionBody()); @@ -217,13 +198,7 @@ CollisionDetectionScene::~CollisionDetectionScene() { mCollisionWorld->destroyCollisionBody(mCapsule->getCollisionBody()); // Destroy the sphere - delete mCapsule; - - // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mConvexMesh->getCollisionBody()); - - // Destroy the convex mesh - delete mConvexMesh; + delete mCapsule; // Destroy the corresponding rigid body from the dynamics world mCollisionWorld->destroyCollisionBody(mDumbbell->getCollisionBody()); @@ -280,13 +255,13 @@ void CollisionDetectionScene::renderSinglePass(openglframework::Shader& shader, if (mCapsule2->getCollisionBody()->isActive()) mCapsule2->render(shader, worldToCameraMatrix, mIsWireframeEnabled); if (mBox1->getCollisionBody()->isActive()) mBox1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); if (mBox2->getCollisionBody()->isActive()) mBox2->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + if (mConvexMesh->getCollisionBody()->isActive()) mConvexMesh->render(shader, worldToCameraMatrix, mIsWireframeEnabled); /* if (mBox->getCollisionBody()->isActive()) mBox->render(shader, worldToCameraMatrix); if (mCone->getCollisionBody()->isActive()) mCone->render(shader, worldToCameraMatrix); if (mCylinder->getCollisionBody()->isActive()) mCylinder->render(shader, worldToCameraMatrix); if (mCapsule->getCollisionBody()->isActive()) mCapsule->render(shader, worldToCameraMatrix); - if (mConvexMesh->getCollisionBody()->isActive()) mConvexMesh->render(shader, worldToCameraMatrix); if (mDumbbell->getCollisionBody()->isActive()) mDumbbell->render(shader, worldToCameraMatrix); if (mConcaveMesh->getCollisionBody()->isActive()) mConcaveMesh->render(shader, worldToCameraMatrix); if (mHeightField->getCollisionBody()->isActive()) mHeightField->render(shader, worldToCameraMatrix); diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.h b/testbed/scenes/collisiondetection/CollisionDetectionScene.h index 14ceab1f..d0f1b569 100755 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.h +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.h @@ -107,6 +107,8 @@ class ContactManager : public rp3d::CollisionCallback { contactPoint = contactPoint->getNext(); } + + manifoldElement = manifoldElement->getNext(); } } @@ -143,10 +145,7 @@ class CollisionDetectionScene : public SceneDemo { Capsule* mCapsule2; Box* mBox1; Box* mBox2; - //Cone* mCone; - //Cylinder* mCylinder; - //Capsule* mCapsule; - //ConvexMesh* mConvexMesh; + ConvexMesh* mConvexMesh; //Dumbbell* mDumbbell; //ConcaveMesh* mConcaveMesh; //HeightField* mHeightField; From 624e01b595e8723295caa13f6c6a13c84033c2e8 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 21 Aug 2017 07:35:08 +0200 Subject: [PATCH 086/248] Working on ConcaveMeshShape and HeightFieldShape collision detection --- CMakeLists.txt | 2 + src/collision/CollisionDetection.cpp | 2 + src/collision/ContactManifold.h | 9 +- src/collision/MiddlePhaseTriangleCallback.cpp | 49 ++++ src/collision/MiddlePhaseTriangleCallback.h | 84 +++++++ src/collision/PolyhedronMesh.cpp | 4 + src/collision/TriangleVertexArray.cpp | 238 +++++++++++++++++- src/collision/TriangleVertexArray.h | 71 +++++- .../CapsuleVsConvexPolyhedronAlgorithm.cpp | 2 +- .../narrowphase/ConcaveVsConvexAlgorithm.cpp | 9 +- .../narrowphase/ConcaveVsConvexAlgorithm.h | 26 +- .../narrowphase/GJK/GJKAlgorithm.cpp | 9 +- .../narrowphase/SAT/SATAlgorithm.cpp | 75 ++++-- src/collision/narrowphase/SAT/SATAlgorithm.h | 2 +- .../SphereVsConvexPolyhedronAlgorithm.cpp | 10 +- src/collision/shapes/ConcaveMeshShape.cpp | 112 ++------- src/collision/shapes/ConcaveMeshShape.h | 22 +- src/collision/shapes/ConcaveShape.h | 3 +- src/collision/shapes/ConvexShape.h | 2 + src/collision/shapes/HeightFieldShape.cpp | 42 +++- src/collision/shapes/HeightFieldShape.h | 3 +- src/collision/shapes/TriangleShape.cpp | 104 +++++++- src/collision/shapes/TriangleShape.h | 52 +++- 23 files changed, 770 insertions(+), 162 deletions(-) create mode 100644 src/collision/MiddlePhaseTriangleCallback.cpp create mode 100644 src/collision/MiddlePhaseTriangleCallback.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 1e1d2fcf..dcc2e4bf 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -137,6 +137,8 @@ SET (REACTPHYSICS3D_SOURCES "src/collision/ContactManifold.cpp" "src/collision/ContactManifoldSet.h" "src/collision/ContactManifoldSet.cpp" + "src/collision/MiddlePhaseTriangleCallback.h" + "src/collision/MiddlePhaseTriangleCallback.cpp" "src/constraint/BallAndSocketJoint.h" "src/constraint/BallAndSocketJoint.cpp" "src/constraint/ContactPoint.h" diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 0abd82a3..0c21240a 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -29,9 +29,11 @@ #include "collision/OverlapCallback.h" #include "body/Body.h" #include "collision/shapes/BoxShape.h" +#include "collision/shapes/ConcaveShape.h" #include "body/RigidBody.h" #include "configuration.h" #include "collision/CollisionCallback.h" +#include "collision/MiddlePhaseTriangleCallback.h" #include "collision/OverlapCallback.h" #include #include diff --git a/src/collision/ContactManifold.h b/src/collision/ContactManifold.h index 0704beed..ada20003 100644 --- a/src/collision/ContactManifold.h +++ b/src/collision/ContactManifold.h @@ -80,9 +80,14 @@ struct ContactManifoldListElement { // Class ContactManifold /** - * This class represents the set of contact points between two bodies. + * This class represents a set of contact points between two bodies that + * all have a similar contact normal direction. Usually, there is a single + * contact manifold when two convex shapes are in contact. However, when + * a convex shape collides with a concave shape, there can be several + * contact manifolds with different normal directions. * The contact manifold is implemented in a way to cache the contact - * points among the frames for better stability. + * points among the frames for better stability (warm starting of the + * contact solver) */ class ContactManifold { diff --git a/src/collision/MiddlePhaseTriangleCallback.cpp b/src/collision/MiddlePhaseTriangleCallback.cpp new file mode 100644 index 00000000..e99da461 --- /dev/null +++ b/src/collision/MiddlePhaseTriangleCallback.cpp @@ -0,0 +1,49 @@ +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "collision/MiddlePhaseTriangleCallback.h" + +using namespace reactphysics3d; + +// Report collision between a triangle of a concave shape and the convex mesh shape (for middle-phase) +void MiddlePhaseTriangleCallback::testTriangle(uint meshSubPart, uint triangleIndex, const Vector3* trianglePoints, + const Vector3* verticesNormals) { + + // Create a triangle collision shape + decimal margin = mConcaveShape->getTriangleMargin(); + TriangleShape* triangleShape = new (mAllocator.allocate(sizeof(TriangleShape))) + TriangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], + verticesNormals, meshSubPart, triangleIndex, margin); + + // Create a narrow phase info for the narrow-phase collision detection + NarrowPhaseInfo* firstNarrowPhaseInfo = narrowPhaseInfoList; + narrowPhaseInfoList = new (mAllocator.allocate(sizeof(NarrowPhaseInfo))) + NarrowPhaseInfo(mOverlappingPair, mConvexProxyShape->getCollisionShape(), + triangleShape, mConvexProxyShape->getLocalToWorldTransform(), + mConcaveProxyShape->getLocalToWorldTransform(), mConvexProxyShape->getCachedCollisionData(), + mConcaveProxyShape->getCachedCollisionData()); + narrowPhaseInfoList->next = firstNarrowPhaseInfo; +} diff --git a/src/collision/MiddlePhaseTriangleCallback.h b/src/collision/MiddlePhaseTriangleCallback.h new file mode 100644 index 00000000..36bfac24 --- /dev/null +++ b/src/collision/MiddlePhaseTriangleCallback.h @@ -0,0 +1,84 @@ +/******************************************************************************** +* 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_MIDDLE_PHASE_TRIANGLE_CALLBACK_H +#define REACTPHYSICS3D_MIDDLE_PHASE_TRIANGLE_CALLBACK_H + +// Libraries +#include "collision/shapes/ConcaveShape.h" +#include "collision/narrowphase/NarrowPhaseAlgorithm.h" + +/// Namespace ReactPhysics3D +namespace reactphysics3d { + +// Class ConvexVsTriangleCallback +/** + * This class is used to report a collision between the triangle + * of a concave mesh shape and a convex shape during the + * middle-phase algorithm. + */ +class MiddlePhaseTriangleCallback : public TriangleCallback { + + protected: + + /// Broadphase overlapping pair + OverlappingPair* mOverlappingPair; + + /// Pointer to the concave proxy shape + ProxyShape* mConcaveProxyShape; + + /// Pointer to the convex proxy shape + ProxyShape* mConvexProxyShape; + + /// Pointer to the concave collision shape + const ConcaveShape* mConcaveShape; + + /// Reference to the single-frame memory allocator + Allocator& mAllocator; + + public: + + /// Pointer to the first element of the linked-list of narrow-phase info + NarrowPhaseInfo* narrowPhaseInfoList; + + /// Constructor + MiddlePhaseTriangleCallback(OverlappingPair* overlappingPair, + ProxyShape* concaveProxyShape, + ProxyShape* convexProxyShape, const ConcaveShape* concaveShape, + Allocator& allocator) + :mOverlappingPair(overlappingPair), mConcaveProxyShape(concaveProxyShape), + mConvexProxyShape(convexProxyShape), mConcaveShape(concaveShape), + mAllocator(allocator), narrowPhaseInfoList(nullptr) { + + } + + /// Test collision between a triangle and the convex mesh shape + virtual void testTriangle(uint meshSubpart, uint triangleIndex, const Vector3* trianglePoints, + const Vector3* verticesNormals) override; +}; + +} + +#endif diff --git a/src/collision/PolyhedronMesh.cpp b/src/collision/PolyhedronMesh.cpp index 61b1e3c8..b4f82fad 100644 --- a/src/collision/PolyhedronMesh.cpp +++ b/src/collision/PolyhedronMesh.cpp @@ -30,6 +30,10 @@ using namespace reactphysics3d; // Constructor +/* + * Create a polyhedron mesh given an array of polygons. + * @param polygonVertexArray Pointer to the array of polygons and their vertices + */ PolyhedronMesh::PolyhedronMesh(PolygonVertexArray* polygonVertexArray) { mPolygonVertexArray = polygonVertexArray; diff --git a/src/collision/TriangleVertexArray.cpp b/src/collision/TriangleVertexArray.cpp index 883b0ab7..ad59d37a 100644 --- a/src/collision/TriangleVertexArray.cpp +++ b/src/collision/TriangleVertexArray.cpp @@ -25,13 +25,19 @@ // Libraries #include "TriangleVertexArray.h" +#include "mathematics/Vector3.h" +#include using namespace reactphysics3d; -// Constructor +// Constructor without vertices normals /// Note that your data will not be copied into the TriangleVertexArray and /// therefore, you need to make sure that those data are always valid during -/// the lifetime of the TriangleVertexArray. +/// the lifetime of the TriangleVertexArray. With this constructor, you do not +/// need to provide vertices normals for smooth mesh collision. Therefore, the +/// vertices normals will be computed automatically. The vertices normals are +/// computed with weighted average of the associated triangle face normal. The +/// weights are the angle between the associated edges of neighbor triangle face. /** * @param nbVertices Number of vertices in the array * @param verticesStart Pointer to the first vertices of the array @@ -48,9 +54,237 @@ TriangleVertexArray::TriangleVertexArray(uint nbVertices, void* verticesStart, i mNbVertices = nbVertices; mVerticesStart = reinterpret_cast(verticesStart); mVerticesStride = verticesStride; + mVerticesNormalsStart = nullptr; + mVerticesNormalsStride = 0; mNbTriangles = nbTriangles; mIndicesStart = reinterpret_cast(indexesStart); mIndicesStride = indexesStride; mVertexDataType = vertexDataType; + mVertexNormaldDataType = NormalDataType::NORMAL_FLOAT_TYPE; mIndexDataType = indexDataType; + mAreVerticesNormalsProvidedByUser = false; + + // Compute the vertices normals because they are not provided by the user + computeVerticesNormals(); +} + +// Constructor with vertices normals +/// Note that your data will not be copied into the TriangleVertexArray and +/// therefore, you need to make sure that those data are always valid during +/// the lifetime of the TriangleVertexArray. With this constructor, you need +/// to provide the vertices normals that will be used for smooth mesh collision. +/** + * @param nbVertices Number of vertices in the array + * @param verticesStart Pointer to the first vertices of the array + * @param verticesStride Number of bytes between the beginning of two consecutive vertices + * @param verticesNormalsStart Pointer to the first vertex normal of the array + * @param verticesNormalsStride Number of bytes between the beginning of two consecutive vertex normals + * @param nbTriangles Number of triangles in the array + * @param indexesStart Pointer to the first triangle index + * @param indexesStride Number of bytes between the beginning of two consecutive triangle indices + * @param vertexDataType Type of data for the vertices (float, double) + * @param indexDataType Type of data for the indices (short, int) + */ +TriangleVertexArray::TriangleVertexArray(uint nbVertices, void* verticesStart, int verticesStride, + void* verticesNormalsStart, int verticesNormalsStride, + uint nbTriangles, void* indexesStart, int indexesStride, + VertexDataType vertexDataType, NormalDataType normalDataType, + IndexDataType indexDataType) { + + mNbVertices = nbVertices; + mVerticesStart = reinterpret_cast(verticesStart); + mVerticesStride = verticesStride; + mVerticesNormalsStart = reinterpret_cast(verticesNormalsStart); + mVerticesNormalsStride = verticesNormalsStride; + mNbTriangles = nbTriangles; + mIndicesStart = reinterpret_cast(indexesStart); + mIndicesStride = indexesStride; + mVertexDataType = vertexDataType; + mVertexNormaldDataType = normalDataType; + mIndexDataType = indexDataType; + mAreVerticesNormalsProvidedByUser = true; + + assert(mVerticesNormalsStart != nullptr); +} + +// Destructor +TriangleVertexArray::~TriangleVertexArray() { + + // If the vertices normals have not been provided by the user + if (!mAreVerticesNormalsProvidedByUser) { + + // Release the allocated memory + float* verticesNormals = reinterpret_cast(mVerticesNormalsStart); + delete[] verticesNormals; + } +} + +// Compute the vertices normals when they are not provided by the user +/// The vertices normals are computed with weighted average of the associated +/// triangle face normal. The weights are the angle between the associated edges +/// of neighbor triangle face. +void TriangleVertexArray::computeVerticesNormals() { + + // Allocate memory for the vertices normals + float* verticesNormals = new float[mNbVertices * 3]; + + // Init vertices normals to zero + for (uint i=0; i(verticesNormals); +} + +// Return the indices of the three vertices of a given triangle in the array +void TriangleVertexArray::getTriangleVerticesIndices(uint triangleIndex, uint* outVerticesIndices) const { + + assert(triangleIndex >= 0 && triangleIndex < mNbTriangles); + + void* vertexIndexPointer = (mIndicesStart + triangleIndex * 3 * mIndicesStride); + + // For each vertex of the triangle + for (int i=0; i < 3; i++) { + + // Get the index of the current vertex in the triangle + if (mIndexDataType == TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE) { + outVerticesIndices[i] = ((uint*)vertexIndexPointer)[i]; + } + else if (mIndexDataType == TriangleVertexArray::IndexDataType::INDEX_SHORT_TYPE) { + outVerticesIndices[i] = ((unsigned short*)vertexIndexPointer)[i]; + } + else { + assert(false); + } + } +} + +// Return the vertices coordinates of a triangle +void TriangleVertexArray::getTriangleVertices(uint triangleIndex, Vector3* outTriangleVertices) const { + + assert(triangleIndex >= 0 && triangleIndex < mNbTriangles); + + void* vertexIndexPointer = (mIndicesStart + triangleIndex * 3 * mIndicesStride); + + // For each vertex of the triangle + for (int k=0; k < 3; k++) { + + // Get the index of the current vertex in the triangle + int vertexIndex = 0; + if (mIndexDataType == TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE) { + vertexIndex = ((uint*)vertexIndexPointer)[k]; + } + else if (mIndexDataType == TriangleVertexArray::IndexDataType::INDEX_SHORT_TYPE) { + vertexIndex = ((unsigned short*)vertexIndexPointer)[k]; + } + else { + assert(false); + } + + // Get the vertices components of the triangle + if (mVertexDataType == TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE) { + const float* vertices = (float*)(mVerticesStart + vertexIndex * mVerticesStride); + outTriangleVertices[k][0] = decimal(vertices[0]); + outTriangleVertices[k][1] = decimal(vertices[1]); + outTriangleVertices[k][2] = decimal(vertices[2]); + } + else if (mVertexDataType == TriangleVertexArray::VertexDataType::VERTEX_DOUBLE_TYPE) { + const double* vertices = (double*)(mVerticesStart + vertexIndex * mVerticesStride); + outTriangleVertices[k][0] = decimal(vertices[0]); + outTriangleVertices[k][1] = decimal(vertices[1]); + outTriangleVertices[k][2] = decimal(vertices[2]); + } + else { + assert(false); + } + } +} + +// Return the three vertices normals of a triangle +void TriangleVertexArray::getTriangleVerticesNormals(uint triangleIndex, Vector3* outTriangleVerticesNormals) const { + + assert(triangleIndex >= 0 && triangleIndex < mNbTriangles); + + void* vertexIndexPointer = (mIndicesStart + triangleIndex * 3 * mIndicesStride); + + // For each vertex of the triangle + for (int k=0; k < 3; k++) { + + // Get the index of the current vertex in the triangle + int vertexIndex = 0; + if (mIndexDataType == TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE) { + vertexIndex = ((uint*)vertexIndexPointer)[k]; + } + else if (mIndexDataType == TriangleVertexArray::IndexDataType::INDEX_SHORT_TYPE) { + vertexIndex = ((unsigned short*)vertexIndexPointer)[k]; + } + else { + assert(false); + } + + // Get the normals from the array + if (mVertexNormaldDataType == TriangleVertexArray::NormalDataType::NORMAL_FLOAT_TYPE) { + const float* normal = (float*)(mVerticesNormalsStart + vertexIndex * mVerticesNormalsStride); + outTriangleVerticesNormals[k][0] = decimal(normal[0]); + outTriangleVerticesNormals[k][1] = decimal(normal[1]); + outTriangleVerticesNormals[k][2] = decimal(normal[2]); + } + else if (mVertexNormaldDataType == TriangleVertexArray::NormalDataType::NORMAL_DOUBLE_TYPE) { + const double* normal = (double*)(mVerticesNormalsStart + vertexIndex * mVerticesNormalsStride); + outTriangleVerticesNormals[k][0] = decimal(normal[0]); + outTriangleVerticesNormals[k][1] = decimal(normal[1]); + outTriangleVerticesNormals[k][2] = decimal(normal[2]); + } + else { + assert(false); + } + } } diff --git a/src/collision/TriangleVertexArray.h b/src/collision/TriangleVertexArray.h index 8e434919..20ae9387 100644 --- a/src/collision/TriangleVertexArray.h +++ b/src/collision/TriangleVertexArray.h @@ -31,6 +31,8 @@ namespace reactphysics3d { +struct Vector3; + // Class TriangleVertexArray /** * This class is used to describe the vertices and faces of a triangular mesh. @@ -48,11 +50,16 @@ class TriangleVertexArray { /// Data type for the vertices in the array enum class VertexDataType {VERTEX_FLOAT_TYPE, VERTEX_DOUBLE_TYPE}; + /// Data type for the vertex normals in the array + enum class NormalDataType {NORMAL_FLOAT_TYPE, NORMAL_DOUBLE_TYPE}; + /// Data type for the indices in the array enum class IndexDataType {INDEX_INTEGER_TYPE, INDEX_SHORT_TYPE}; protected: + // -------------------- Attributes -------------------- // + /// Number of vertices in the array uint mNbVertices; @@ -63,6 +70,13 @@ class TriangleVertexArray { /// values in the array int mVerticesStride; + /// Pointer to the first vertex normal value in the array + unsigned char* mVerticesNormalsStart; + + /// Stride (number of bytes) between the beginning of two vertex normals + /// values in the array + int mVerticesNormalsStride; + /// Number of triangles in the array uint mNbTriangles; @@ -76,22 +90,45 @@ class TriangleVertexArray { /// Data type of the vertices in the array VertexDataType mVertexDataType; + /// Data type of the vertex normals in the array + NormalDataType mVertexNormaldDataType; + /// Data type of the indices in the array IndexDataType mIndexDataType; + /// True if the vertices normals are provided by the user + bool mAreVerticesNormalsProvidedByUser; + + // -------------------- Methods -------------------- // + + /// Compute the vertices normals when they are not provided by the user + void computeVerticesNormals(); + public: - /// Constructor + // -------------------- Methods -------------------- // + + /// Constructor without vertices normals TriangleVertexArray(uint nbVertices, void* verticesStart, int verticesStride, uint nbTriangles, void* indexesStart, int indexesStride, VertexDataType vertexDataType, IndexDataType indexDataType); + /// Constructor with vertices normals + TriangleVertexArray(uint nbVertices, void* verticesStart, int verticesStride, + void* verticesNormalsStart, int verticesNormalsStride, + uint nbTriangles, void* indexesStart, int indexesStride, + VertexDataType vertexDataType, NormalDataType normalDataType, + IndexDataType indexDataType); + /// Destructor - ~TriangleVertexArray() = default; + ~TriangleVertexArray(); /// Return the vertex data type VertexDataType getVertexDataType() const; + /// Return the vertex normal data type + NormalDataType getVertexNormalDataType() const; + /// Return the index data type IndexDataType getIndexDataType() const; @@ -104,14 +141,29 @@ class TriangleVertexArray { /// Return the vertices stride (number of bytes) int getVerticesStride() const; + /// Return the vertex normals stride (number of bytes) + int getVerticesNormlasStride() const; + /// Return the indices stride (number of bytes) int getIndicesStride() const; /// Return the pointer to the start of the vertices array unsigned char* getVerticesStart() const; + /// Return the pointer to the start of the vertex normals array + unsigned char* getVerticesNormalsStart() const; + /// Return the pointer to the start of the indices array unsigned char* getIndicesStart() const; + + /// Return the vertices coordinates of a triangle + void getTriangleVertices(uint triangleIndex, Vector3* outTriangleVertices) const; + + /// Return the three vertices normals of a triangle + void getTriangleVerticesNormals(uint triangleIndex, Vector3* outTriangleVerticesNormals) const; + + /// Return the indices of the three vertices of a given triangle in the array + void getTriangleVerticesIndices(uint triangleIndex, uint* outVerticesIndices) const; }; // Return the vertex data type @@ -119,6 +171,11 @@ inline TriangleVertexArray::VertexDataType TriangleVertexArray::getVertexDataTyp return mVertexDataType; } +// Return the vertex normal data type +inline TriangleVertexArray::NormalDataType TriangleVertexArray::getVertexNormalDataType() const { + return mVertexNormaldDataType; +} + // Return the index data type inline TriangleVertexArray::IndexDataType TriangleVertexArray::getIndexDataType() const { return mIndexDataType; @@ -139,6 +196,11 @@ inline int TriangleVertexArray::getVerticesStride() const { return mVerticesStride; } +// Return the vertex normals stride (number of bytes) +inline int TriangleVertexArray::getVerticesNormlasStride() const { + return mVerticesNormalsStride; +} + // Return the indices stride (number of bytes) inline int TriangleVertexArray::getIndicesStride() const { return mIndicesStride; @@ -149,6 +211,11 @@ inline unsigned char* TriangleVertexArray::getVerticesStart() const { return mVerticesStart; } +// Return the pointer to the start of the vertex normals array +inline unsigned char* TriangleVertexArray::getVerticesNormalsStart() const { + return mVerticesNormalsStart; +} + // Return the pointer to the start of the indices array inline unsigned char* TriangleVertexArray::getIndicesStart() const { return mIndicesStart; diff --git a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp index 73a1dd13..72ba2e06 100644 --- a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp @@ -82,7 +82,7 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPh // Get the face normal const Vector3 faceNormal = polyhedron->getFaceNormal(f); - const Vector3 faceNormalWorld = polyhedronToWorld.getOrientation() * faceNormal; + Vector3 faceNormalWorld = polyhedronToWorld.getOrientation() * faceNormal; const Vector3 capsuleSegA(0, -capsuleShape->getHeight() * decimal(0.5), 0); const Vector3 capsuleSegB(0, capsuleShape->getHeight() * decimal(0.5), 0); diff --git a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp index 7f5f439b..8a2475a2 100644 --- a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp +++ b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp @@ -22,7 +22,7 @@ * 3. This notice may not be removed or altered from any source distribution. * * * ********************************************************************************/ - +/* // Libraries #include "collision/shapes/ConcaveShape.h" #include "collision/shapes/TriangleShape.h" @@ -34,12 +34,14 @@ using namespace reactphysics3d; // Report collision between a triangle of a concave shape and the convex mesh shape (for middle-phase) -void MiddlePhaseTriangleCallback::testTriangle(const Vector3* trianglePoints) { +void MiddlePhaseTriangleCallback::testTriangle(uint meshSubPart, uint triangleIndex, const Vector3* trianglePoints, + const Vector3* verticesNormals) { // Create a triangle collision shape decimal margin = mConcaveShape->getTriangleMargin(); TriangleShape* triangleShape = new (mAllocator.allocate(sizeof(TriangleShape))) - TriangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], margin); + TriangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], + verticesNormals, meshSubPart, triangleIndex, margin); // Create a narrow phase info for the narrow-phase collision detection NarrowPhaseInfo* firstNarrowPhaseInfo = narrowPhaseInfoList; @@ -297,3 +299,4 @@ bool ConcaveVsConvexAlgorithm::hasVertexBeenProcessed(const std::unordered_multi // // smooth mesh collision // mContactPoints.push_back(smoothContactInfo); //} +*/ diff --git a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h index 4619e480..70cd3dbc 100644 --- a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h +++ b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h @@ -22,7 +22,7 @@ * 3. This notice may not be removed or altered from any source distribution. * * * ********************************************************************************/ - +/* #ifndef REACTPHYSICS3D_CONCAVE_VS_CONVEX_ALGORITHM_H #define REACTPHYSICS3D_CONCAVE_VS_CONVEX_ALGORITHM_H @@ -37,11 +37,6 @@ namespace reactphysics3d { // Class ConvexVsTriangleCallback -/** - * This class is used to report a collision between the triangle - * of a concave mesh shape and a convex shape during the - * middle-phase algorithm - */ class MiddlePhaseTriangleCallback : public TriangleCallback { protected: @@ -78,14 +73,11 @@ class MiddlePhaseTriangleCallback : public TriangleCallback { } /// Test collision between a triangle and the convex mesh shape - virtual void testTriangle(const Vector3* trianglePoints) override; + virtual void testTriangle(uint meshSubpart, uint triangleIndex, const Vector3* trianglePoints, + const Vector3* verticesNormals) override; }; // Class SmoothMeshContactInfo -/** - * Contains data for of potential smooth contact during the smooth mesh - * contacts computation. - */ struct SmoothMeshContactInfo { public: @@ -131,11 +123,6 @@ struct ContactsDepthCompare { // TODO : Delete this // Class SmoothCollisionNarrowPhaseCallback -/** - * This class is used as a narrow-phase callback to get narrow-phase contacts - * of the concave triangle mesh to temporary store them in order to be used in - * the smooth mesh collision algorithm if this one is enabled. - */ class SmoothCollisionNarrowPhaseCallback { private: @@ -155,12 +142,6 @@ class SmoothCollisionNarrowPhaseCallback { // TODO : Delete this // Class ConcaveVsConvexAlgorithm -/** - * This class is used to compute the narrow-phase collision detection - * between a concave collision shape and a convex collision shape. The idea is - * to use the GJK collision detection algorithm to compute the collision between - * the convex shape and each of the triangles in the concave shape. - */ class ConcaveVsConvexAlgorithm { protected : @@ -212,3 +193,4 @@ inline void ConcaveVsConvexAlgorithm::addProcessedVertex(std::unordered_multimap #endif +*/ diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp index 10d344f1..609c415a 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp @@ -27,6 +27,7 @@ #include "GJKAlgorithm.h" #include "constraint/ContactPoint.h" #include "engine/OverlappingPair.h" +#include "collision/shapes/TriangleShape.h" #include "configuration.h" #include "engine/Profiler.h" #include @@ -76,7 +77,8 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhase // Transform a point from local space of body 2 to local // space of body 1 (the GJK algorithm is done in local space of body 1) - Transform body2Tobody1 = transform1.getInverse() * transform2; + Transform transform1Inverse = transform1.getInverse(); + Transform body2Tobody1 = transform1Inverse * transform2; // Matrix that transform a direction from local // space of body 1 into local space of body 2 @@ -209,6 +211,10 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhase if (reportContacts) { + // Compute smooth triangle mesh contact if one of the two collision shapes is a triangle + TriangleShape::computeSmoothTriangleMeshContact(shape1, shape2, pA, pB, transform1, transform2, + penetrationDepth, normal); + // Add a new contact point narrowPhaseInfo->addContactPoint(normal, penetrationDepth, pA, pB); } @@ -219,6 +225,7 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhase return GJKResult::SEPARATED; } + // Use the GJK Algorithm to find if a point is inside a convex collision shape bool GJKAlgorithm::testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) { diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index cebec9a6..23ce86e0 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -30,6 +30,7 @@ #include "collision/shapes/CapsuleShape.h" #include "collision/shapes/SphereShape.h" #include "engine/OverlappingPair.h" +#include "collision/shapes/TriangleShape.h" #include "configuration.h" #include "engine/Profiler.h" #include @@ -143,13 +144,21 @@ bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfo* narrow const Vector3 minFaceNormal = polyhedron->getFaceNormal(minFaceIndex); Vector3 normalWorld = -(polyhedronToWorldTransform.getOrientation() * minFaceNormal); - const Vector3 contactPointSphereLocal = sphereToWorldTransform.getInverse().getOrientation() * normalWorld * sphere->getRadius(); - const Vector3 contactPointPolyhedronLocal = sphereCenter + minFaceNormal * (minPenetrationDepth - sphere->getRadius()); + Vector3 contactPointSphereLocal = sphereToWorldTransform.getInverse().getOrientation() * normalWorld * sphere->getRadius(); + Vector3 contactPointPolyhedronLocal = sphereCenter + minFaceNormal * (minPenetrationDepth - sphere->getRadius()); + + // Compute smooth triangle mesh contact if one of the two collision shapes is a triangle + TriangleShape::computeSmoothTriangleMeshContact(narrowPhaseInfo->collisionShape1, narrowPhaseInfo->collisionShape2, + isSphereShape1 ? contactPointSphereLocal : contactPointPolyhedronLocal, + isSphereShape1 ? contactPointPolyhedronLocal : contactPointSphereLocal, + narrowPhaseInfo->shape1ToWorldTransform, narrowPhaseInfo->shape2ToWorldTransform, + minPenetrationDepth, normalWorld); + // Create the contact info object narrowPhaseInfo->addContactPoint(normalWorld, minPenetrationDepth, - isSphereShape1 ? contactPointSphereLocal : contactPointPolyhedronLocal, - isSphereShape1 ? contactPointPolyhedronLocal : contactPointSphereLocal); + isSphereShape1 ? contactPointSphereLocal : contactPointPolyhedronLocal, + isSphereShape1 ? contactPointPolyhedronLocal : contactPointSphereLocal); } lastFrameInfo.satMinAxisFaceIndex = minFaceIndex; @@ -380,7 +389,7 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfo* narro const Vector3 capsuleSegAPolyhedronSpace = capsuleToPolyhedronTransform * capsuleSegA; const Vector3 capsuleSegBPolyhedronSpace = capsuleToPolyhedronTransform * capsuleSegB; - const Vector3 normalWorld = capsuleToWorld.getOrientation() * separatingAxisCapsuleSpace; + Vector3 normalWorld = capsuleToWorld.getOrientation() * separatingAxisCapsuleSpace; const decimal capsuleRadius = capsuleShape->getRadius(); // If the separating axis is a face normal @@ -410,7 +419,14 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfo* narro closestPointCapsuleInnerSegment, closestPointPolyhedronEdge); // Project closest capsule inner segment point into the capsule bounds - const Vector3 contactPointCapsule = (polyhedronToCapsuleTransform * closestPointCapsuleInnerSegment) - separatingAxisCapsuleSpace * capsuleRadius; + Vector3 contactPointCapsule = (polyhedronToCapsuleTransform * closestPointCapsuleInnerSegment) - separatingAxisCapsuleSpace * capsuleRadius; + + // Compute smooth triangle mesh contact if one of the two collision shapes is a triangle + TriangleShape::computeSmoothTriangleMeshContact(narrowPhaseInfo->collisionShape1, narrowPhaseInfo->collisionShape2, + isCapsuleShape1 ? contactPointCapsule : closestPointPolyhedronEdge, + isCapsuleShape1 ? closestPointPolyhedronEdge : contactPointCapsule, + narrowPhaseInfo->shape1ToWorldTransform, narrowPhaseInfo->shape2ToWorldTransform, + minPenetrationDepth, normalWorld); // Create the contact point narrowPhaseInfo->addContactPoint(normalWorld, minPenetrationDepth, @@ -483,7 +499,7 @@ decimal SATAlgorithm::computePolyhedronFaceVsCapsulePenetrationDepth(uint polyhe // axis is a face normal of the polyhedron void SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceIndex, decimal capsuleRadius, const ConvexPolyhedronShape* polyhedron, decimal penetrationDepth, const Transform& polyhedronToCapsuleTransform, - const Vector3& normalWorld, const Vector3& separatingAxisCapsuleSpace, + Vector3& normalWorld, const Vector3& separatingAxisCapsuleSpace, const Vector3& capsuleSegAPolyhedronSpace, const Vector3& capsuleSegBPolyhedronSpace, NarrowPhaseInfo* narrowPhaseInfo, bool isCapsuleShape1) const { @@ -525,15 +541,27 @@ void SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceI // If the clipped point is one that produce this penetration depth, we keep it if (clipPointPenDepth > penetrationDepth - capsuleRadius - decimal(0.001)) { - const Vector3 contactPointPolyhedron = clipSegment[i] + delta; + Vector3 contactPointPolyhedron = clipSegment[i] + delta; // Project the clipped point into the capsule bounds - const Vector3 contactPointCapsule = (polyhedronToCapsuleTransform * clipSegment[i]) - separatingAxisCapsuleSpace * capsuleRadius; + Vector3 contactPointCapsule = (polyhedronToCapsuleTransform * clipSegment[i]) - separatingAxisCapsuleSpace * capsuleRadius; + + if (isCapsuleShape1) { + normalWorld = -normalWorld; + } + + // Compute smooth triangle mesh contact if one of the two collision shapes is a triangle + TriangleShape::computeSmoothTriangleMeshContact(narrowPhaseInfo->collisionShape1, narrowPhaseInfo->collisionShape2, + isCapsuleShape1 ? contactPointCapsule : contactPointPolyhedron, + isCapsuleShape1 ? contactPointPolyhedron : contactPointCapsule, + narrowPhaseInfo->shape1ToWorldTransform, narrowPhaseInfo->shape2ToWorldTransform, + penetrationDepth, normalWorld); + // Create the contact point - narrowPhaseInfo->addContactPoint(isCapsuleShape1 ? -normalWorld : normalWorld, penetrationDepth, - isCapsuleShape1 ? contactPointCapsule : contactPointPolyhedron, - isCapsuleShape1 ? contactPointPolyhedron : contactPointCapsule); + narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, + isCapsuleShape1 ? contactPointCapsule : contactPointPolyhedron, + isCapsuleShape1 ? contactPointPolyhedron : contactPointCapsule); } } } @@ -807,7 +835,7 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn const Vector3 axisIncidentSpace = referenceToIncidentTransform.getOrientation() * axisReferenceSpace; // Compute the world normal - const Vector3 normalWorld = isMinPenetrationFaceNormalPolyhedron1 ? narrowPhaseInfo->shape1ToWorldTransform.getOrientation() * axisReferenceSpace : + Vector3 normalWorld = isMinPenetrationFaceNormalPolyhedron1 ? narrowPhaseInfo->shape1ToWorldTransform.getOrientation() * axisReferenceSpace : -(narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * axisReferenceSpace); // Get the reference face @@ -874,11 +902,18 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn if (((*itPoints) - referenceFaceVertex).dot(axisReferenceSpace) < decimal(0.0)) { // Convert the clip incident polyhedron vertex into the incident polyhedron local-space - const Vector3 contactPointIncidentPolyhedron = referenceToIncidentTransform * (*itPoints); + Vector3 contactPointIncidentPolyhedron = referenceToIncidentTransform * (*itPoints); // Project the contact point onto the reference face Vector3 contactPointReferencePolyhedron = projectPointOntoPlane(*itPoints, axisReferenceSpace, referenceFaceVertex); + // Compute smooth triangle mesh contact if one of the two collision shapes is a triangle + TriangleShape::computeSmoothTriangleMeshContact(narrowPhaseInfo->collisionShape1, narrowPhaseInfo->collisionShape2, + isMinPenetrationFaceNormalPolyhedron1 ? contactPointReferencePolyhedron : contactPointIncidentPolyhedron, + isMinPenetrationFaceNormalPolyhedron1 ? contactPointIncidentPolyhedron : contactPointReferencePolyhedron, + narrowPhaseInfo->shape1ToWorldTransform, narrowPhaseInfo->shape2ToWorldTransform, + minPenetrationDepth, normalWorld); + // Create a new contact point narrowPhaseInfo->addContactPoint(normalWorld, minPenetrationDepth, isMinPenetrationFaceNormalPolyhedron1 ? contactPointReferencePolyhedron : contactPointIncidentPolyhedron, @@ -901,14 +936,20 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn closestPointPolyhedron1Edge, closestPointPolyhedron2Edge); // Compute the contact point on polyhedron 1 edge in the local-space of polyhedron 1 - const Vector3 closestPointPolyhedron1EdgeLocalSpace = polyhedron2ToPolyhedron1 * closestPointPolyhedron1Edge; + Vector3 closestPointPolyhedron1EdgeLocalSpace = polyhedron2ToPolyhedron1 * closestPointPolyhedron1Edge; // Compute the world normal - const Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * minEdgeVsEdgeSeparatingAxisPolyhedron2Space; + Vector3 normalWorld = narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * minEdgeVsEdgeSeparatingAxisPolyhedron2Space; + + // Compute smooth triangle mesh contact if one of the two collision shapes is a triangle + TriangleShape::computeSmoothTriangleMeshContact(narrowPhaseInfo->collisionShape1, narrowPhaseInfo->collisionShape2, + closestPointPolyhedron1EdgeLocalSpace, closestPointPolyhedron2Edge, + narrowPhaseInfo->shape1ToWorldTransform, narrowPhaseInfo->shape2ToWorldTransform, + minPenetrationDepth, normalWorld); // Create the contact point narrowPhaseInfo->addContactPoint(normalWorld, minPenetrationDepth, - closestPointPolyhedron1EdgeLocalSpace, closestPointPolyhedron2Edge); + closestPointPolyhedron1EdgeLocalSpace, closestPointPolyhedron2Edge); } lastFrameInfo.satIsAxisFacePolyhedron1 = false; diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.h b/src/collision/narrowphase/SAT/SATAlgorithm.h index 49cd2626..73838d95 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.h +++ b/src/collision/narrowphase/SAT/SATAlgorithm.h @@ -121,7 +121,7 @@ class SATAlgorithm { /// Compute the two contact points between a polyhedron and a capsule when the separating axis is a face normal of the polyhedron void computeCapsulePolyhedronFaceContactPoints(uint referenceFaceIndex, decimal capsuleRadius, const ConvexPolyhedronShape* polyhedron, decimal penetrationDepth, const Transform& polyhedronToCapsuleTransform, - const Vector3& normalWorld, const Vector3& separatingAxisCapsuleSpace, + Vector3& normalWorld, const Vector3& separatingAxisCapsuleSpace, const Vector3& capsuleSegAPolyhedronSpace, const Vector3& capsuleSegBPolyhedronSpace, NarrowPhaseInfo* narrowPhaseInfo, bool isCapsuleShape1) const; diff --git a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp index 049ce449..7ecda325 100644 --- a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp @@ -36,15 +36,15 @@ using namespace reactphysics3d; // by Dirk Gregorius. bool SphereVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) { + assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON || + narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); + assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE || + narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::SPHERE); + // First, we run the GJK algorithm GJKAlgorithm gjkAlgorithm; GJKAlgorithm::GJKResult result = gjkAlgorithm.testCollision(narrowPhaseInfo, reportContacts); - assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON || - narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); - assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE || - narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::SPHERE); - narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = true; narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = false; diff --git a/src/collision/shapes/ConcaveMeshShape.cpp b/src/collision/shapes/ConcaveMeshShape.cpp index a0bd1094..8cb5235a 100644 --- a/src/collision/shapes/ConcaveMeshShape.cpp +++ b/src/collision/shapes/ConcaveMeshShape.cpp @@ -49,51 +49,13 @@ void ConcaveMeshShape::initBVHTree() { // Get the triangle vertex array of the current sub-part TriangleVertexArray* triangleVertexArray = mTriangleMesh->getSubpart(subPart); - TriangleVertexArray::VertexDataType vertexType = triangleVertexArray->getVertexDataType(); - TriangleVertexArray::IndexDataType indexType = triangleVertexArray->getIndexDataType(); - unsigned char* verticesStart = triangleVertexArray->getVerticesStart(); - unsigned char* indicesStart = triangleVertexArray->getIndicesStart(); - int vertexStride = triangleVertexArray->getVerticesStride(); - int indexStride = triangleVertexArray->getIndicesStride(); - // For each triangle of the concave mesh for (uint triangleIndex=0; triangleIndexgetNbTriangles(); triangleIndex++) { - void* vertexIndexPointer = (indicesStart + triangleIndex * 3 * indexStride); Vector3 trianglePoints[3]; - // For each vertex of the triangle - for (int k=0; k < 3; k++) { - - // Get the index of the current vertex in the triangle - int vertexIndex = 0; - if (indexType == TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE) { - vertexIndex = ((uint*)vertexIndexPointer)[k]; - } - else if (indexType == TriangleVertexArray::IndexDataType::INDEX_SHORT_TYPE) { - vertexIndex = ((unsigned short*)vertexIndexPointer)[k]; - } - else { - assert(false); - } - - // Get the vertices components of the triangle - if (vertexType == TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE) { - const float* vertices = (float*)(verticesStart + vertexIndex * vertexStride); - trianglePoints[k][0] = decimal(vertices[0]) * mScaling.x; - trianglePoints[k][1] = decimal(vertices[1]) * mScaling.y; - trianglePoints[k][2] = decimal(vertices[2]) * mScaling.z; - } - else if (vertexType == TriangleVertexArray::VertexDataType::VERTEX_DOUBLE_TYPE) { - const double* vertices = (double*)(verticesStart + vertexIndex * vertexStride); - trianglePoints[k][0] = decimal(vertices[0]) * mScaling.x; - trianglePoints[k][1] = decimal(vertices[1]) * mScaling.y; - trianglePoints[k][2] = decimal(vertices[2]) * mScaling.z; - } - else { - assert(false); - } - } + // Get the triangle vertices + triangleVertexArray->getTriangleVertices(triangleIndex, trianglePoints); // Create the AABB for the triangle AABB aabb = AABB::createAABBForTriangle(trianglePoints); @@ -106,56 +68,32 @@ void ConcaveMeshShape::initBVHTree() { } // Return the three vertices coordinates (in the array outTriangleVertices) of a triangle -// given the start vertex index pointer of the triangle -void ConcaveMeshShape::getTriangleVerticesWithIndexPointer(int32 subPart, int32 triangleIndex, - Vector3* outTriangleVertices) const { +void ConcaveMeshShape::getTriangleVertices(uint subPart, uint triangleIndex, + Vector3* outTriangleVertices) const { // Get the triangle vertex array of the current sub-part TriangleVertexArray* triangleVertexArray = mTriangleMesh->getSubpart(subPart); - TriangleVertexArray::VertexDataType vertexType = triangleVertexArray->getVertexDataType(); - TriangleVertexArray::IndexDataType indexType = triangleVertexArray->getIndexDataType(); - unsigned char* verticesStart = triangleVertexArray->getVerticesStart(); - unsigned char* indicesStart = triangleVertexArray->getIndicesStart(); - int vertexStride = triangleVertexArray->getVerticesStride(); - int indexStride = triangleVertexArray->getIndicesStride(); + // Get the vertices coordinates of the triangle + triangleVertexArray->getTriangleVertices(triangleIndex, outTriangleVertices); - void* vertexIndexPointer = (indicesStart + triangleIndex * 3 * indexStride); - - // For each vertex of the triangle - for (int k=0; k < 3; k++) { - - // Get the index of the current vertex in the triangle - int vertexIndex = 0; - if (indexType == TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE) { - vertexIndex = ((uint*)vertexIndexPointer)[k]; - } - else if (indexType == TriangleVertexArray::IndexDataType::INDEX_SHORT_TYPE) { - vertexIndex = ((unsigned short*)vertexIndexPointer)[k]; - } - else { - assert(false); - } - - // Get the vertices components of the triangle - if (vertexType == TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE) { - const float* vertices = (float*)(verticesStart + vertexIndex * vertexStride); - outTriangleVertices[k][0] = decimal(vertices[0]) * mScaling.x; - outTriangleVertices[k][1] = decimal(vertices[1]) * mScaling.y; - outTriangleVertices[k][2] = decimal(vertices[2]) * mScaling.z; - } - else if (vertexType == TriangleVertexArray::VertexDataType::VERTEX_DOUBLE_TYPE) { - const double* vertices = (double*)(verticesStart + vertexIndex * vertexStride); - outTriangleVertices[k][0] = decimal(vertices[0]) * mScaling.x; - outTriangleVertices[k][1] = decimal(vertices[1]) * mScaling.y; - outTriangleVertices[k][2] = decimal(vertices[2]) * mScaling.z; - } - else { - assert(false); - } - } + // Apply the scaling factor to the vertices + outTriangleVertices[0] *= mScaling.x; + outTriangleVertices[1] *= mScaling.x; + outTriangleVertices[2] *= mScaling.x; } +// Return the three vertex normals (in the array outVerticesNormals) of a triangle +void ConcaveMeshShape::getTriangleVerticesNormals(uint subPart, uint triangleIndex, Vector3* outVerticesNormals) const { + + // Get the triangle vertex array of the current sub-part + TriangleVertexArray* triangleVertexArray = mTriangleMesh->getSubpart(subPart); + + // Get the vertices normals of the triangle + triangleVertexArray->getTriangleVerticesNormals(triangleIndex, outVerticesNormals); +} + + // Use a callback method on all triangles of the concave shape inside a given AABB void ConcaveMeshShape::testAllTriangles(TriangleCallback& callback, const AABB& localAABB) const { @@ -208,11 +146,15 @@ void ConcaveMeshRaycastCallback::raycastTriangles() { // Get the triangle vertices for this node from the concave mesh shape Vector3 trianglePoints[3]; - mConcaveMeshShape.getTriangleVerticesWithIndexPointer(data[0], data[1], trianglePoints); + mConcaveMeshShape.getTriangleVertices(data[0], data[1], trianglePoints); + // Get the vertices normals of the triangle + Vector3 verticesNormals[3]; + mConcaveMeshShape.getTriangleVerticesNormals(data[0], data[1], verticesNormals); // Create a triangle collision shape decimal margin = mConcaveMeshShape.getTriangleMargin(); - TriangleShape triangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], margin); + TriangleShape triangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], + verticesNormals, data[0], data[1], margin); triangleShape.setRaycastTestType(mConcaveMeshShape.getRaycastTestType()); // Ray casting test against the collision shape diff --git a/src/collision/shapes/ConcaveMeshShape.h b/src/collision/shapes/ConcaveMeshShape.h index 83e5103a..309ec27c 100644 --- a/src/collision/shapes/ConcaveMeshShape.h +++ b/src/collision/shapes/ConcaveMeshShape.h @@ -118,6 +118,10 @@ class ConcaveMeshShape : public ConcaveShape { /// Dynamic AABB tree to accelerate collision with the triangles DynamicAABBTree mDynamicAABBTree; + /// Array with computed vertices normals for each TriangleVertexArray of the triangle mesh (only + /// if the user did not provide its own vertices normals) + Vector3** mComputedVerticesNormals; + // -------------------- Methods -------------------- // /// Raycast method with feedback information @@ -130,9 +134,13 @@ class ConcaveMeshShape : public ConcaveShape { void initBVHTree(); /// Return the three vertices coordinates (in the array outTriangleVertices) of a triangle - /// given the start vertex index pointer of the triangle. - void getTriangleVerticesWithIndexPointer(int32 subPart, int32 triangleIndex, - Vector3* outTriangleVertices) const; + void getTriangleVertices(uint subPart, uint 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; + + /// Get a smooth contact normal for collision for a triangle of the mesh + Vector3 computeSmoothLocalContactNormalForTriangle(TriangleShape* triangleShape, const Vector3& localContactPoint) const; public: @@ -224,10 +232,14 @@ inline void ConvexTriangleAABBOverlapCallback::notifyOverlappingNode(int nodeId) // Get the triangle vertices for this node from the concave mesh shape Vector3 trianglePoints[3]; - mConcaveMeshShape.getTriangleVerticesWithIndexPointer(data[0], data[1], trianglePoints); + mConcaveMeshShape.getTriangleVertices(data[0], data[1], trianglePoints); + + // Get the vertices normals of the triangle + Vector3 verticesNormals[3]; + mConcaveMeshShape.getTriangleVerticesNormals(data[0], data[1], verticesNormals); // Call the callback to test narrow-phase collision with this triangle - mTriangleTestCallback.testTriangle(trianglePoints); + mTriangleTestCallback.testTriangle(data[0], data[1], trianglePoints, verticesNormals); } } diff --git a/src/collision/shapes/ConcaveShape.h b/src/collision/shapes/ConcaveShape.h index c5657b2b..6e07187f 100644 --- a/src/collision/shapes/ConcaveShape.h +++ b/src/collision/shapes/ConcaveShape.h @@ -46,7 +46,8 @@ class TriangleCallback { virtual ~TriangleCallback() = default; /// Report a triangle - virtual void testTriangle(const Vector3* trianglePoints)=0; + virtual void testTriangle(uint meshSubPart, uint triangleIndex, + const Vector3* trianglePoints, const Vector3* verticesNormals)=0; }; diff --git a/src/collision/shapes/ConvexShape.h b/src/collision/shapes/ConvexShape.h index 4b98c9fa..94acc7f9 100644 --- a/src/collision/shapes/ConvexShape.h +++ b/src/collision/shapes/ConvexShape.h @@ -49,10 +49,12 @@ class ConvexShape : public CollisionShape { // -------------------- Methods -------------------- // // Return a local support point in a given direction with the object margin + // TODO : Try to remove cachedCollisionData parameter Vector3 getLocalSupportPointWithMargin(const Vector3& direction, void** cachedCollisionData) const; /// Return a local support point in a given direction without the object margin + // TODO : Try to remove cachedCollisionData parameter virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, void** cachedCollisionData) const=0; diff --git a/src/collision/shapes/HeightFieldShape.cpp b/src/collision/shapes/HeightFieldShape.cpp index 02ef852f..c8fc97f2 100644 --- a/src/collision/shapes/HeightFieldShape.cpp +++ b/src/collision/shapes/HeightFieldShape.cpp @@ -133,24 +133,48 @@ void HeightFieldShape::testAllTriangles(TriangleCallback& callback, const AABB& for (int j = jMin; j < jMax; j++) { // Compute the four point of the current quad - Vector3 p1 = getVertexAt(i, j); - Vector3 p2 = getVertexAt(i, j + 1); - Vector3 p3 = getVertexAt(i + 1, j); - Vector3 p4 = getVertexAt(i + 1, j + 1); + const Vector3 p1 = getVertexAt(i, j); + const Vector3 p2 = getVertexAt(i, j + 1); + const Vector3 p3 = getVertexAt(i + 1, j); + const Vector3 p4 = getVertexAt(i + 1, j + 1); // Generate the first triangle for the current grid rectangle Vector3 trianglePoints[3] = {p1, p2, p3}; + // Compute the triangle normal + Vector3 triangle1Normal = (p2 - p1).cross(p3 - p1).getUnit(); + + // Use the triangle face normal as vertices normals (this is an aproximation. The correct + // solution would be to compute all the normals of the neighbor triangles and use their + // weighted average (with incident angle as weight) at the vertices. However, this solution + // seems too expensive (it requires to compute the normal of all neighbor triangles instead + // and compute the angle of incident edges with asin(). Maybe we could also precompute the + // vertices normal at the HeightFieldShape constructor but it will require extra memory to + // store them. + Vector3 verticesNormals1[3] = {triangle1Normal, triangle1Normal, triangle1Normal}; + // Test collision against the first triangle - callback.testTriangle(trianglePoints); + callback.testTriangle(0, 0, trianglePoints, verticesNormals1); // Generate the second triangle for the current grid rectangle trianglePoints[0] = p3; trianglePoints[1] = p2; trianglePoints[2] = p4; + // Compute the triangle normal + Vector3 triangle2Normal = (p2 - p3).cross(p4 - p3).getUnit(); + + // Use the triangle face normal as vertices normals (this is an aproximation. The correct + // solution would be to compute all the normals of the neighbor triangles and use their + // weighted average (with incident angle as weight) at the vertices. However, this solution + // seems too expensive (it requires to compute the normal of all neighbor triangles instead + // and compute the angle of incident edges with asin(). Maybe we could also precompute the + // vertices normal at the HeightFieldShape constructor but it will require extra memory to + // store them. + Vector3 verticesNormals2[3] = {triangle2Normal, triangle2Normal, triangle2Normal}; + // Test collision against the second triangle - callback.testTriangle(trianglePoints); + callback.testTriangle(0, 0, trianglePoints, verticesNormals2); } } } @@ -232,11 +256,13 @@ Vector3 HeightFieldShape::getVertexAt(int x, int y) const { } // Raycast test between a ray and a triangle of the heightfield -void TriangleOverlapCallback::testTriangle(const Vector3* trianglePoints) { +void TriangleOverlapCallback::testTriangle(uint meshSubPart, uint triangleIndex, const Vector3* trianglePoints, + const Vector3* verticesNormals) { // Create a triangle collision shape decimal margin = mHeightFieldShape.getTriangleMargin(); - TriangleShape triangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], margin); + TriangleShape triangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], + verticesNormals, meshSubPart, triangleIndex, margin); triangleShape.setRaycastTestType(mHeightFieldShape.getRaycastTestType()); // Ray casting test against the collision shape diff --git a/src/collision/shapes/HeightFieldShape.h b/src/collision/shapes/HeightFieldShape.h index 6f2b8459..aa0cd787 100644 --- a/src/collision/shapes/HeightFieldShape.h +++ b/src/collision/shapes/HeightFieldShape.h @@ -64,7 +64,8 @@ class TriangleOverlapCallback : public TriangleCallback { bool getIsHit() const {return mIsHit;} /// Raycast test between a ray and a triangle of the heightfield - virtual void testTriangle(const Vector3* trianglePoints) override; + virtual void testTriangle(uint meshSubPart, uint triangleIndex, + const Vector3* trianglePoints, const Vector3* verticesNormals) override; }; diff --git a/src/collision/shapes/TriangleShape.cpp b/src/collision/shapes/TriangleShape.cpp index 9c0deb38..72eb93d3 100644 --- a/src/collision/shapes/TriangleShape.cpp +++ b/src/collision/shapes/TriangleShape.cpp @@ -26,6 +26,7 @@ // Libraries #include "TriangleShape.h" #include "collision/ProxyShape.h" +#include "mathematics/mathematics_functions.h" #include "engine/Profiler.h" #include "configuration.h" #include @@ -34,13 +35,17 @@ using namespace reactphysics3d; // Constructor /** + * Do not use this constructor. It is supposed to be used internally only. + * Use a ConcaveMeshShape instead. * @param point1 First point of the triangle * @param point2 Second point of the triangle * @param point3 Third point of the triangle + * @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& point1, const Vector3& point2, const Vector3& point3, decimal margin) - : ConvexPolyhedronShape(margin) { +TriangleShape::TriangleShape(const Vector3& point1, const Vector3& point2, const Vector3& point3, + const Vector3* verticesNormals, uint meshSubPart, uint triangleIndex, decimal margin) + : ConvexPolyhedronShape(margin), mMeshSubPart(meshSubPart), mTriangleIndex(triangleIndex) { mPoints[0] = point1; mPoints[1] = point2; @@ -50,9 +55,104 @@ TriangleShape::TriangleShape(const Vector3& point1, const Vector3& point2, const mNormal = (point3 - point1).cross(point2 - point1); mNormal.normalize(); + mVerticesNormals[0] = verticesNormals[0]; + mVerticesNormals[1] = verticesNormals[1]; + mVerticesNormals[2] = verticesNormals[2]; + mRaycastTestType = TriangleRaycastSide::FRONT; } +// This method compute the smooth mesh contact with a triangle in case one of the two collision +// shapes is a triangle. The idea in this case is to use a smooth vertex normal of the triangle mesh +// at the contact point instead of the triangle normal to avoid the internal edge collision issue. +// This method will return the new smooth world contact +// normal of the triangle and the the local contact point on the other shape. +void TriangleShape::computeSmoothTriangleMeshContact(const CollisionShape* shape1, const CollisionShape* shape2, + Vector3& localContactPointShape1, Vector3 localContactPointShape2, + const Transform& shape1ToWorld, const Transform& shape2ToWorld, + decimal penetrationDepth, Vector3& outSmoothVertexNormal) { + + assert(shape1->getType() != CollisionShapeType::TRIANGLE || shape2->getType() != CollisionShapeType::TRIANGLE); + + // If one the shape is a triangle + bool isShape1Triangle = shape1->getType() == CollisionShapeType::TRIANGLE; + if (isShape1Triangle || shape2->getType() == CollisionShapeType::TRIANGLE) { + + const TriangleShape* triangleShape = isShape1Triangle ? static_cast(shape1): + static_cast(shape2); + + // Compute the smooth triangle mesh contact normal and recompute the local contact point on the other shape + triangleShape->computeSmoothMeshContact(isShape1Triangle ? localContactPointShape1 : localContactPointShape2, + isShape1Triangle ? shape1ToWorld : shape2ToWorld, + isShape1Triangle ? shape2ToWorld.getInverse() : shape1ToWorld.getInverse(), + penetrationDepth, + isShape1Triangle ? localContactPointShape2 : localContactPointShape1, + outSmoothVertexNormal); + + // Make sure the direction of the contact normal is from shape1 to shape2 + if (!isShape1Triangle) { + outSmoothVertexNormal = -outSmoothVertexNormal; + } + } +} + + +// This method implements the technique described in Game Physics Pearl book +// by Gino van der Bergen and Dirk Gregorius to get smooth triangle mesh collision. The idea is +// to replace the contact normal of the triangle shape with the precomputed normal of the triangle +// mesh at this point. Then, we need to recompute the contact point on the other shape in order to +// stay aligned with the new contact normal. This method will return the new smooth world contact +// normal of the triangle and the the local contact point on the other shape. +void TriangleShape::computeSmoothMeshContact(Vector3 localContactPointTriangle, const Transform& triangleShapeToWorldTransform, + const Transform& worldToOtherShapeTransform, decimal penetrationDepth, + Vector3& outNewLocalContactPointOtherShape, Vector3& outSmoothWorldContactTriangleNormal) const { + + // Get the smooth contact normal of the mesh at the contact point on the triangle + Vector3 localNormal = computeSmoothLocalContactNormalForTriangle(localContactPointTriangle); + + // Convert the local contact normal into world-space + outSmoothWorldContactTriangleNormal = triangleShapeToWorldTransform.getOrientation() * localNormal; + + // Convert the contact normal into the local-space of the other shape + Vector3 normalOtherShape = worldToOtherShapeTransform.getOrientation() * outSmoothWorldContactTriangleNormal; + + // Convert the local contact point of the triangle into the local-space of the other shape + Vector3 trianglePointOtherShape = worldToOtherShapeTransform * triangleShapeToWorldTransform * + localContactPointTriangle; + + // Re-align the local contact point on the other shape such that it is aligned along + // the new contact normal + Vector3 otherShapePoint = trianglePointOtherShape - normalOtherShape * penetrationDepth; + outNewLocalContactPointOtherShape.setAllValues(otherShapePoint.x, otherShapePoint.y, otherShapePoint.z); +} + +// Get a smooth contact normal for collision for a triangle of the mesh +/// This is used to avoid the internal edges issue that occurs when a shape is colliding with +/// several triangles of a concave mesh. If the shape collide with an edge of the triangle for instance, +/// the computed contact normal from this triangle edge is not necessarily in the direction of the surface +/// normal of the mesh at this point. The idea to solve this problem is to use the real (smooth) surface +/// normal of the mesh at this point as the contact normal. This technique is described in the chapter 5 +/// of the Game Physics Pearl book by Gino van der Bergen and Dirk Gregorius. The vertices normals of the +/// mesh are either provided by the user or precomputed if the user did not provide them. +Vector3 TriangleShape::computeSmoothLocalContactNormalForTriangle(const Vector3& localContactPoint) const { + + // Compute the barycentric coordinates of the point in the triangle + decimal u, v, w; + computeBarycentricCoordinatesInTriangle(mPoints[0], mPoints[1], mPoints[2], localContactPoint, u, v, w); + + int nbZeros = 0; + bool isUZero = approxEqual(u, decimal(0), decimal(0.0001)); + bool isVZero = approxEqual(v, decimal(0), decimal(0.0001)); + bool isWZero = approxEqual(w, decimal(0), decimal(0.0001)); + if (isUZero) nbZeros++; + if (isVZero) nbZeros++; + if (isWZero) nbZeros++; + + // We compute the contact normal as the barycentric interpolation of the three vertices normals + return (u * mVerticesNormals[0] + v * mVerticesNormals[1] + w * mVerticesNormals[2]).getUnit(); +} + + // Raycast method with feedback information /// This method use the line vs triangle raycasting technique described in /// Real-time Collision Detection by Christer Ericson. diff --git a/src/collision/shapes/TriangleShape.h b/src/collision/shapes/TriangleShape.h index e25086b8..900b71db 100644 --- a/src/collision/shapes/TriangleShape.h +++ b/src/collision/shapes/TriangleShape.h @@ -49,7 +49,10 @@ enum class TriangleRaycastSide { // Class TriangleShape /** * This class represents a triangle collision shape that is centered - * at the origin and defined three points. + * at the origin and defined three points. A user cannot instanciate + * an object of this class. This class is for internal use only. Instances + * of this class are created when the user creates an HeightFieldShape and + * a ConcaveMeshShape */ class TriangleShape : public ConvexPolyhedronShape { @@ -63,15 +66,27 @@ class TriangleShape : public ConvexPolyhedronShape { /// Normal of the triangle Vector3 mNormal; + /// Three vertices normals for smooth collision with triangle mesh + Vector3 mVerticesNormals[3]; + /// Raycast test type for the triangle (front, back, front-back) TriangleRaycastSide mRaycastTestType; + /// Index of the mesh sub part in the original mesh + uint mMeshSubPart; + + /// Triangle index of the triangle in the sub mesh + uint mTriangleIndex; + // -------------------- Methods -------------------- // /// Return a local support point in a given direction without the object margin virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, void** cachedCollisionData) const override; + /// Get a smooth contact normal for collision for a triangle of the mesh + Vector3 computeSmoothLocalContactNormalForTriangle(const Vector3& localContactPoint) const; + /// Return true if a point is inside the collision shape virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const override; @@ -81,13 +96,20 @@ class TriangleShape : public ConvexPolyhedronShape { /// Return the number of bytes used by the collision shape virtual size_t getSizeInBytes() const override; + // -------------------- Methods -------------------- // + + /// This method implements the technique described in Game Physics Pearl book + void computeSmoothMeshContact(Vector3 localContactPointTriangle, const Transform& triangleShapeToWorldTransform, + const Transform& worldToOtherShapeTransform, decimal penetrationDepth, + Vector3& outNewLocalContactPointOtherShape, Vector3& outSmoothWorldContactTriangleNormal) const; + public: // -------------------- Methods -------------------- // /// Constructor TriangleShape(const Vector3& point1, const Vector3& point2, const Vector3& point3, - decimal margin = OBJECT_MARGIN); + const Vector3* verticesNormals, uint meshSubPart, uint triangleIndex, decimal margin = OBJECT_MARGIN); /// Destructor virtual ~TriangleShape() override = default; @@ -143,10 +165,23 @@ class TriangleShape : public ConvexPolyhedronShape { /// Return the centroid of the polyhedron virtual Vector3 getCentroid() const override; + /// Return the index of the sub part mesh of the original mesh + uint getMeshSubPart() const; + + /// Return the triangle index in the original mesh + uint getTriangleIndex() const; + + /// This method compute the smooth mesh contact with a triangle in case one of the two collision shapes is a triangle. The idea in this case is to use a smooth vertex normal of the triangle mesh + static void computeSmoothTriangleMeshContact(const CollisionShape* shape1, const CollisionShape* shape2, + Vector3& localContactPointShape1, Vector3 localContactPointShape2, + const Transform& shape1ToWorld, const Transform& shape2ToWorld, + decimal penetrationDepth, Vector3& outSmoothVertexNormal); + // ---------- Friendship ---------- // friend class ConcaveMeshRaycastCallback; friend class TriangleOverlapCallback; + friend class MiddlePhaseTriangleCallback; }; // Return the number of bytes used by the collision shape @@ -155,8 +190,7 @@ inline size_t TriangleShape::getSizeInBytes() const { } // Return a local support point in a given direction without the object margin -inline Vector3 TriangleShape::getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const { +inline Vector3 TriangleShape::getLocalSupportPointWithoutMargin(const Vector3& direction, void** cachedCollisionData) const { Vector3 dotProducts(direction.dot(mPoints[0]), direction.dot(mPoints[1]), direction.dot(mPoints[2])); return mPoints[dotProducts.getMaxAxis()]; } @@ -286,6 +320,16 @@ inline Vector3 TriangleShape::getCentroid() const { return (mPoints[0] + mPoints[1] + mPoints[2]) / decimal(3.0); } +// Return the index of the sub part mesh of the original mesh +inline uint TriangleShape::getMeshSubPart() const { + return mMeshSubPart; +} + +// Return the triangle index in the original mesh +inline uint TriangleShape::getTriangleIndex() const { + return mTriangleIndex; +} + // Return the number of half-edges of the polyhedron inline uint TriangleShape::getNbHalfEdges() const { return 6; From e725af80b6bc9da177f01ca1892a65007db1ffa4 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 22 Aug 2017 07:38:22 +0200 Subject: [PATCH 087/248] Update raycasting test code for convex mesh and remove commented code --- test/tests/collision/TestRaycast.h | 147 +++++++++-------------------- testbed/common/ConvexMesh.cpp | 7 -- 2 files changed, 46 insertions(+), 108 deletions(-) diff --git a/test/tests/collision/TestRaycast.h b/test/tests/collision/TestRaycast.h index 0f25ab94..93860a1c 100644 --- a/test/tests/collision/TestRaycast.h +++ b/test/tests/collision/TestRaycast.h @@ -110,7 +110,6 @@ class TestRaycast : public Test { CollisionBody* mSphereBody; CollisionBody* mCapsuleBody; CollisionBody* mConvexMeshBody; - CollisionBody* mConvexMeshBodyEdgesInfo; CollisionBody* mCylinderBody; CollisionBody* mCompoundBody; CollisionBody* mTriangleBody; @@ -128,7 +127,6 @@ class TestRaycast : public Test { SphereShape* mSphereShape; CapsuleShape* mCapsuleShape; ConvexMeshShape* mConvexMeshShape; - ConvexMeshShape* mConvexMeshShapeEdgesInfo; TriangleShape* mTriangleShape; ConcaveShape* mConcaveMeshShape; HeightFieldShape* mHeightFieldShape; @@ -138,7 +136,6 @@ class TestRaycast : public Test { ProxyShape* mSphereProxyShape; ProxyShape* mCapsuleProxyShape; ProxyShape* mConvexMeshProxyShape; - ProxyShape* mConvexMeshProxyShapeEdgesInfo; ProxyShape* mCompoundSphereProxyShape; ProxyShape* mCompoundCapsuleProxyShape; ProxyShape* mTriangleProxyShape; @@ -152,6 +149,11 @@ class TestRaycast : public Test { std::vector mConcaveMeshIndices; TriangleVertexArray* mConcaveMeshVertexArray; float mHeightFieldData[100]; + PolygonVertexArray::PolygonFace mPolygonFaces[6]; + PolygonVertexArray* mPolygonVertexArray; + PolyhedronMesh* mPolyhedronMesh; + Vector3 mPolyhedronVertices[8]; + int mPolyhedronIndices[4 * 6]; public : @@ -175,7 +177,6 @@ class TestRaycast : public Test { mSphereBody = mWorld->createCollisionBody(mBodyTransform); mCapsuleBody = mWorld->createCollisionBody(mBodyTransform); mConvexMeshBody = mWorld->createCollisionBody(mBodyTransform); - mConvexMeshBodyEdgesInfo = mWorld->createCollisionBody(mBodyTransform); mCylinderBody = mWorld->createCollisionBody(mBodyTransform); mCompoundBody = mWorld->createCollisionBody(mBodyTransform); mTriangleBody = mWorld->createCollisionBody(mBodyTransform); @@ -200,51 +201,47 @@ class TestRaycast : public Test { const Vector3 triangleVertex1(100, 100, 0); const Vector3 triangleVertex2(105, 100, 0); const Vector3 triangleVertex3(100, 103, 0); - mTriangleShape = new TriangleShape(triangleVertex1, triangleVertex2, triangleVertex3); + Vector3 triangleVerticesNormals[3] = {Vector3(0, 0, 1), Vector3(0, 0, 1), Vector3(0, 0, 1)}; + mTriangleShape = new TriangleShape(triangleVertex1, triangleVertex2, triangleVertex3, triangleVerticesNormals, 0, 0); mTriangleProxyShape = mTriangleBody->addCollisionShape(mTriangleShape, mShapeTransform); mCapsuleShape = new CapsuleShape(2, 5); mCapsuleProxyShape = mCapsuleBody->addCollisionShape(mCapsuleShape, mShapeTransform); // TODO : Create convex mesh shape with new way (polyhedron mesh) to add test again - // Box of dimension (2, 3, 4) - /*mConvexMeshShape = new ConvexMeshShape(0.0); - mConvexMeshShape->addVertex(Vector3(-2, -3, -4)); - mConvexMeshShape->addVertex(Vector3(2, -3, -4)); - mConvexMeshShape->addVertex(Vector3(2, -3, 4)); - mConvexMeshShape->addVertex(Vector3(-2, -3, 4)); - mConvexMeshShape->addVertex(Vector3(-2, 3, -4)); - mConvexMeshShape->addVertex(Vector3(2, 3, -4)); - mConvexMeshShape->addVertex(Vector3(2, 3, 4)); - mConvexMeshShape->addVertex(Vector3(-2, 3, 4)); - mConvexMeshProxyShape = mConvexMeshBody->addCollisionShape(mConvexMeshShape, mShapeTransform); + // Box of extents (2, 3, 4) + mPolyhedronVertices[0] = Vector3(-2, -3, -4); + mPolyhedronVertices[1] = Vector3(2, -3, -4); + mPolyhedronVertices[2] = Vector3(2, -3, 4); + mPolyhedronVertices[3] = Vector3(-2, -3, 4); + mPolyhedronVertices[4] = Vector3(-2, 3, -4); + mPolyhedronVertices[5] = Vector3(2, 3, -4); + mPolyhedronVertices[6] = Vector3(2, 3, 4); + mPolyhedronVertices[7] = Vector3(-2, 3, 4); - mConvexMeshShapeEdgesInfo = new ConvexMeshShape(0.0); - mConvexMeshShapeEdgesInfo->addVertex(Vector3(-2, -3, -4)); - mConvexMeshShapeEdgesInfo->addVertex(Vector3(2, -3, -4)); - mConvexMeshShapeEdgesInfo->addVertex(Vector3(2, -3, 4)); - mConvexMeshShapeEdgesInfo->addVertex(Vector3(-2, -3, 4)); - mConvexMeshShapeEdgesInfo->addVertex(Vector3(-2, 3, -4)); - mConvexMeshShapeEdgesInfo->addVertex(Vector3(2, 3, -4)); - mConvexMeshShapeEdgesInfo->addVertex(Vector3(2, 3, 4)); - mConvexMeshShapeEdgesInfo->addVertex(Vector3(-2, 3, 4)); - mConvexMeshShapeEdgesInfo->addEdge(0, 1); - mConvexMeshShapeEdgesInfo->addEdge(1, 2); - mConvexMeshShapeEdgesInfo->addEdge(2, 3); - mConvexMeshShapeEdgesInfo->addEdge(0, 3); - mConvexMeshShapeEdgesInfo->addEdge(4, 5); - mConvexMeshShapeEdgesInfo->addEdge(5, 6); - mConvexMeshShapeEdgesInfo->addEdge(6, 7); - mConvexMeshShapeEdgesInfo->addEdge(4, 7); - mConvexMeshShapeEdgesInfo->addEdge(0, 4); - mConvexMeshShapeEdgesInfo->addEdge(1, 5); - mConvexMeshShapeEdgesInfo->addEdge(2, 6); - mConvexMeshShapeEdgesInfo->addEdge(3, 7); - mConvexMeshShapeEdgesInfo->setIsEdgesInformationUsed(true); - mConvexMeshProxyShapeEdgesInfo = mConvexMeshBodyEdgesInfo->addCollisionShape( - mConvexMeshShapeEdgesInfo, - mShapeTransform); - */ + mPolyhedronIndices[0] = 0; mPolyhedronIndices[1] = 1; mPolyhedronIndices[2] = 2; mPolyhedronIndices[3] = 3; + mPolyhedronIndices[4] = 1; mPolyhedronIndices[5] = 5; mPolyhedronIndices[6] = 6; mPolyhedronIndices[7] = 2; + mPolyhedronIndices[8] = 0; mPolyhedronIndices[9] = 4; mPolyhedronIndices[10] = 5; mPolyhedronIndices[11] = 1; + mPolyhedronIndices[12] = 0; mPolyhedronIndices[13] = 3; mPolyhedronIndices[14] = 7; mPolyhedronIndices[15] = 4; + mPolyhedronIndices[16] = 3; mPolyhedronIndices[17] = 2; mPolyhedronIndices[18] = 6; mPolyhedronIndices[19] = 7; + mPolyhedronIndices[20] = 2; mPolyhedronIndices[21] = 5; mPolyhedronIndices[22] = 4; mPolyhedronIndices[23] = 7; + + // Polygon faces descriptions for the polyhedron + for (int f=0; f < 8; f++) { + PolygonVertexArray::PolygonFace& face = mPolygonFaces[f]; + face.indexBase = f * 4; + face.nbVertices = 4; + } + + // Create the polygon vertex array + mPolygonVertexArray = new PolygonVertexArray(8, mPolyhedronVertices, sizeof(Vector3), + mPolyhedronIndices, sizeof(int), 6, mPolygonFaces, + PolygonVertexArray::VertexDataType::VERTEX_FLOAT_TYPE, + PolygonVertexArray::IndexDataType::INDEX_INTEGER_TYPE); + + mPolyhedronMesh = new PolyhedronMesh(mPolygonVertexArray); + mConvexMeshShape = new ConvexMeshShape(mPolyhedronMesh); + mConvexMeshProxyShape = mConvexMeshBody->addCollisionShape(mConvexMeshShape, mShapeTransform); // Compound shape is a cylinder and a sphere Vector3 positionShape2(Vector3(4, 2, -3)); @@ -300,8 +297,7 @@ class TestRaycast : public Test { mBoxProxyShape->setCollisionCategoryBits(CATEGORY1); mSphereProxyShape->setCollisionCategoryBits(CATEGORY1); mCapsuleProxyShape->setCollisionCategoryBits(CATEGORY1); - //mConvexMeshProxyShape->setCollisionCategoryBits(CATEGORY2); - //mConvexMeshProxyShapeEdgesInfo->setCollisionCategoryBits(CATEGORY2); + mConvexMeshProxyShape->setCollisionCategoryBits(CATEGORY2); mCompoundSphereProxyShape->setCollisionCategoryBits(CATEGORY2); mCompoundCapsuleProxyShape->setCollisionCategoryBits(CATEGORY2); mTriangleProxyShape->setCollisionCategoryBits(CATEGORY1); @@ -314,13 +310,15 @@ class TestRaycast : public Test { delete mBoxShape; delete mSphereShape; delete mCapsuleShape; - //delete mConvexMeshShape; - //delete mConvexMeshShapeEdgesInfo; + delete mConvexMeshShape; delete mTriangleShape; delete mConcaveMeshShape; delete mHeightFieldShape; delete mConcaveMeshVertexArray; + + delete mPolygonVertexArray; + delete mPolyhedronMesh; } /// Run the tests @@ -1299,7 +1297,6 @@ class TestRaycast : public Test { /// CollisionWorld::raycast() methods. void testConvexMesh() { - /* // ----- Test feedback data ----- // Vector3 point1 = mLocalShapeToWorld * Vector3(1 , 2, 6); Vector3 point2 = mLocalShapeToWorld * Vector3(1, 2, -4); @@ -1339,16 +1336,6 @@ class TestRaycast : public Test { test(approxEqual(raycastInfo2.worldPoint.y, hitPoint.y, epsilon)); test(approxEqual(raycastInfo2.worldPoint.z, hitPoint.z, epsilon)); - // ProxyCollisionShape::raycast() - RaycastInfo raycastInfo3; - test(mConvexMeshBodyEdgesInfo->raycast(ray, raycastInfo3)); - test(raycastInfo3.body == mConvexMeshBodyEdgesInfo); - test(raycastInfo3.proxyShape == mConvexMeshProxyShapeEdgesInfo); - test(approxEqual(raycastInfo3.hitFraction, decimal(0.2), epsilon)); - test(approxEqual(raycastInfo3.worldPoint.x, hitPoint.x, epsilon)); - test(approxEqual(raycastInfo3.worldPoint.y, hitPoint.y, epsilon)); - test(approxEqual(raycastInfo3.worldPoint.z, hitPoint.z, epsilon)); - // ProxyCollisionShape::raycast() RaycastInfo raycastInfo4; test(mConvexMeshProxyShape->raycast(ray, raycastInfo4)); @@ -1359,16 +1346,6 @@ class TestRaycast : public Test { test(approxEqual(raycastInfo4.worldPoint.y, hitPoint.y, epsilon)); test(approxEqual(raycastInfo4.worldPoint.z, hitPoint.z, epsilon)); - // ProxyCollisionShape::raycast() - RaycastInfo raycastInfo5; - test(mConvexMeshProxyShapeEdgesInfo->raycast(ray, raycastInfo5)); - test(raycastInfo5.body == mConvexMeshBodyEdgesInfo); - test(raycastInfo5.proxyShape == mConvexMeshProxyShapeEdgesInfo); - test(approxEqual(raycastInfo5.hitFraction, decimal(0.2), epsilon)); - test(approxEqual(raycastInfo5.worldPoint.x, hitPoint.x, epsilon)); - test(approxEqual(raycastInfo5.worldPoint.y, hitPoint.y, epsilon)); - test(approxEqual(raycastInfo5.worldPoint.z, hitPoint.z, epsilon)); - Ray ray1(mLocalShapeToWorld * Vector3(0, 0, 0), mLocalShapeToWorld * Vector3(5, 7, -1)); Ray ray2(mLocalShapeToWorld * Vector3(5, 11, 7), mLocalShapeToWorld * Vector3(17, 29, 28)); Ray ray3(mLocalShapeToWorld * Vector3(1, 2, 3), mLocalShapeToWorld * Vector3(-11, 2, 24)); @@ -1387,10 +1364,9 @@ class TestRaycast : public Test { Ray ray16(mLocalShapeToWorld * Vector3(-1, 2, -7), mLocalShapeToWorld * Vector3(-1, 2, 30)); // ----- Test raycast miss ----- // + RaycastInfo raycastInfo3; test(!mConvexMeshBody->raycast(ray1, raycastInfo3)); - test(!mConvexMeshBodyEdgesInfo->raycast(ray1, raycastInfo3)); test(!mConvexMeshProxyShape->raycast(ray1, raycastInfo3)); - test(!mConvexMeshProxyShapeEdgesInfo->raycast(ray1, raycastInfo3)); mCallback.reset(); mWorld->raycast(ray1, &mCallback); test(!mCallback.isHit); @@ -1402,73 +1378,55 @@ class TestRaycast : public Test { test(!mCallback.isHit); test(!mConvexMeshBody->raycast(ray2, raycastInfo3)); - test(!mConvexMeshBodyEdgesInfo->raycast(ray2, raycastInfo3)); test(!mConvexMeshProxyShape->raycast(ray2, raycastInfo3)); - test(!mConvexMeshProxyShapeEdgesInfo->raycast(ray2, raycastInfo3)); mCallback.reset(); mWorld->raycast(ray2, &mCallback); test(!mCallback.isHit); test(!mConvexMeshBody->raycast(ray3, raycastInfo3)); - test(!mConvexMeshBodyEdgesInfo->raycast(ray3, raycastInfo3)); test(!mConvexMeshProxyShape->raycast(ray3, raycastInfo3)); - test(!mConvexMeshProxyShapeEdgesInfo->raycast(ray3, raycastInfo3)); mCallback.reset(); mWorld->raycast(ray3, &mCallback); test(!mCallback.isHit); test(!mConvexMeshBody->raycast(ray4, raycastInfo3)); - test(!mConvexMeshBodyEdgesInfo->raycast(ray4, raycastInfo3)); test(!mConvexMeshProxyShape->raycast(ray4, raycastInfo3)); - test(!mConvexMeshProxyShapeEdgesInfo->raycast(ray4, raycastInfo3)); mCallback.reset(); mWorld->raycast(ray4, &mCallback); test(!mCallback.isHit); test(!mConvexMeshBody->raycast(ray5, raycastInfo3)); - test(!mConvexMeshBodyEdgesInfo->raycast(ray5, raycastInfo3)); test(!mConvexMeshProxyShape->raycast(ray5, raycastInfo3)); - test(!mConvexMeshProxyShapeEdgesInfo->raycast(ray5, raycastInfo3)); mCallback.reset(); mWorld->raycast(ray5, &mCallback); test(!mCallback.isHit); test(!mConvexMeshBody->raycast(ray6, raycastInfo3)); - test(!mConvexMeshBodyEdgesInfo->raycast(ray6, raycastInfo3)); test(!mConvexMeshProxyShape->raycast(ray6, raycastInfo3)); - test(!mConvexMeshProxyShapeEdgesInfo->raycast(ray6, raycastInfo3)); mCallback.reset(); mWorld->raycast(ray6, &mCallback); test(!mCallback.isHit); test(!mConvexMeshBody->raycast(ray7, raycastInfo3)); - test(!mConvexMeshBodyEdgesInfo->raycast(ray7, raycastInfo3)); test(!mConvexMeshProxyShape->raycast(ray7, raycastInfo3)); - test(!mConvexMeshProxyShapeEdgesInfo->raycast(ray7, raycastInfo3)); mCallback.reset(); mWorld->raycast(ray7, &mCallback); test(!mCallback.isHit); test(!mConvexMeshBody->raycast(ray8, raycastInfo3)); - test(!mConvexMeshBodyEdgesInfo->raycast(ray8, raycastInfo3)); test(!mConvexMeshProxyShape->raycast(ray8, raycastInfo3)); - test(!mConvexMeshProxyShapeEdgesInfo->raycast(ray8, raycastInfo3)); mCallback.reset(); mWorld->raycast(ray8, &mCallback); test(!mCallback.isHit); test(!mConvexMeshBody->raycast(ray9, raycastInfo3)); - test(!mConvexMeshBodyEdgesInfo->raycast(ray9, raycastInfo3)); test(!mConvexMeshProxyShape->raycast(ray9, raycastInfo3)); - test(!mConvexMeshProxyShapeEdgesInfo->raycast(ray9, raycastInfo3)); mCallback.reset(); mWorld->raycast(ray9, &mCallback); test(!mCallback.isHit); test(!mConvexMeshBody->raycast(ray10, raycastInfo3)); - test(!mConvexMeshBodyEdgesInfo->raycast(ray10, raycastInfo3)); test(!mConvexMeshProxyShape->raycast(ray10, raycastInfo3)); - test(!mConvexMeshProxyShapeEdgesInfo->raycast(ray10, raycastInfo3)); mCallback.reset(); mWorld->raycast(ray10, &mCallback); test(!mCallback.isHit); @@ -1494,10 +1452,8 @@ class TestRaycast : public Test { // ----- Test raycast hits ----- // test(mConvexMeshBody->raycast(ray11, raycastInfo3)); - test(mConvexMeshBodyEdgesInfo->raycast(ray11, raycastInfo3)); test(mConvexMeshProxyShape->raycast(ray11, raycastInfo3)); - test(mConvexMeshProxyShapeEdgesInfo->raycast(ray11, raycastInfo3)); - mCallback.reset(); + mCallback.reset(); mWorld->raycast(ray11, &mCallback); test(mCallback.isHit); mCallback.reset(); @@ -1505,9 +1461,7 @@ class TestRaycast : public Test { test(mCallback.isHit); test(mConvexMeshBody->raycast(ray12, raycastInfo3)); - test(mConvexMeshBodyEdgesInfo->raycast(ray12, raycastInfo3)); test(mConvexMeshProxyShape->raycast(ray12, raycastInfo3)); - test(mConvexMeshProxyShapeEdgesInfo->raycast(ray12, raycastInfo3)); mCallback.reset(); mWorld->raycast(ray12, &mCallback); test(mCallback.isHit); @@ -1516,9 +1470,7 @@ class TestRaycast : public Test { test(mCallback.isHit); test(mConvexMeshBody->raycast(ray13, raycastInfo3)); - test(mConvexMeshBodyEdgesInfo->raycast(ray13, raycastInfo3)); test(mConvexMeshProxyShape->raycast(ray13, raycastInfo3)); - test(mConvexMeshProxyShapeEdgesInfo->raycast(ray13, raycastInfo3)); mCallback.reset(); mWorld->raycast(ray13, &mCallback); test(mCallback.isHit); @@ -1527,9 +1479,7 @@ class TestRaycast : public Test { test(mCallback.isHit); test(mConvexMeshBody->raycast(ray14, raycastInfo3)); - test(mConvexMeshBodyEdgesInfo->raycast(ray14, raycastInfo3)); test(mConvexMeshProxyShape->raycast(ray14, raycastInfo3)); - test(mConvexMeshProxyShapeEdgesInfo->raycast(ray14, raycastInfo3)); mCallback.reset(); mWorld->raycast(ray14, &mCallback); test(mCallback.isHit); @@ -1538,9 +1488,7 @@ class TestRaycast : public Test { test(mCallback.isHit); test(mConvexMeshBody->raycast(ray15, raycastInfo3)); - test(mConvexMeshBodyEdgesInfo->raycast(ray15, raycastInfo3)); test(mConvexMeshProxyShape->raycast(ray15, raycastInfo3)); - test(mConvexMeshProxyShapeEdgesInfo->raycast(ray15, raycastInfo3)); mCallback.reset(); mWorld->raycast(ray15, &mCallback); test(mCallback.isHit); @@ -1549,16 +1497,13 @@ class TestRaycast : public Test { test(mCallback.isHit); test(mConvexMeshBody->raycast(ray16, raycastInfo3)); - test(mConvexMeshBodyEdgesInfo->raycast(ray16, raycastInfo3)); test(mConvexMeshProxyShape->raycast(ray16, raycastInfo3)); - test(mConvexMeshProxyShapeEdgesInfo->raycast(ray16, raycastInfo3)); mCallback.reset(); mWorld->raycast(ray16, &mCallback); test(mCallback.isHit); mCallback.reset(); mWorld->raycast(Ray(ray16.point1, ray16.point2, decimal(0.8)), &mCallback); test(mCallback.isHit); - */ } /// Test the CollisionBody::raycast() and diff --git a/testbed/common/ConvexMesh.cpp b/testbed/common/ConvexMesh.cpp index 11be5732..b3cb3b95 100644 --- a/testbed/common/ConvexMesh.cpp +++ b/testbed/common/ConvexMesh.cpp @@ -40,13 +40,6 @@ ConvexMesh::ConvexMesh(const openglframework::Vector3 &position, // Compute the scaling matrix mScalingMatrix = openglframework::Matrix4::identity(); - // Vertex and Indices array for the triangle mesh (data in shared and not copied) - /*mPolygonVertexArray = - new rp3d::TriangleVertexArray(getNbVertices(), &(mVertices[0]), sizeof(openglframework::Vector3), - getNbFaces(0), &(mIndices[0][0]), sizeof(int), - rp3d::TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE, - rp3d::TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE);*/ - // Polygon faces descriptions for the polyhedron mPolygonFaces = new rp3d::PolygonVertexArray::PolygonFace[getNbFaces(0)]; rp3d::PolygonVertexArray::PolygonFace* face = mPolygonFaces; From a655ffb4623a84f386be4427f60215fe3a7758c0 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 31 Aug 2017 22:42:19 +0200 Subject: [PATCH 088/248] Fix issue in ContactManifoldSet.cpp --- src/collision/ContactManifoldSet.cpp | 16 ++++++++++++---- 1 file changed, 12 insertions(+), 4 deletions(-) diff --git a/src/collision/ContactManifoldSet.cpp b/src/collision/ContactManifoldSet.cpp index 23602dda..fb3beda2 100644 --- a/src/collision/ContactManifoldSet.cpp +++ b/src/collision/ContactManifoldSet.cpp @@ -60,6 +60,8 @@ void ContactManifoldSet::addContactManifold(const ContactManifoldInfo* contactMa } else { + bool addNewManifold = true; + // If there are too much contact manifolds in the set if (mNbManifolds >= mNbMaxManifolds) { @@ -72,14 +74,20 @@ void ContactManifoldSet::addContactManifold(const ContactManifoldInfo* contactMa // Remove the manifold removeManifold(minDepthManifold); + } + else { - // Create a new contact manifold - createManifold(contactManifoldInfo); + // The manifold we do not want to get is the new one. Therefore, we do not add it to the set + addNewManifold = false; } } - // Create a new contact manifold - createManifold(contactManifoldInfo); + // If we need to add the new contact manifold + if (addNewManifold) { + + // Create a new contact manifold + createManifold(contactManifoldInfo); + } } } From 9b89f66667806fbca2f3390cf909b9ea8d4c5b68 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 31 Aug 2017 23:11:00 +0200 Subject: [PATCH 089/248] Fix issues and refactor collision shape type and collision shape name --- src/collision/CollisionDetection.cpp | 70 ++++++++----------- src/collision/MiddlePhaseTriangleCallback.cpp | 5 +- src/collision/NarrowPhaseInfo.cpp | 18 +++-- src/collision/NarrowPhaseInfo.h | 13 ++-- src/collision/ProxyShape.h | 15 ++++ .../narrowphase/DefaultCollisionDispatch.cpp | 1 - .../narrowphase/SAT/SATAlgorithm.cpp | 6 +- src/collision/shapes/BoxShape.cpp | 2 +- src/collision/shapes/CapsuleShape.cpp | 2 +- src/collision/shapes/CollisionShape.cpp | 2 +- src/collision/shapes/CollisionShape.h | 37 ++++++---- src/collision/shapes/ConcaveMeshShape.cpp | 6 +- src/collision/shapes/ConcaveMeshShape.h | 3 - src/collision/shapes/ConcaveShape.cpp | 5 +- src/collision/shapes/ConcaveShape.h | 24 +------ src/collision/shapes/ConvexMeshShape.cpp | 2 +- .../shapes/ConvexPolyhedronShape.cpp | 4 +- src/collision/shapes/ConvexPolyhedronShape.h | 2 +- src/collision/shapes/ConvexShape.cpp | 4 +- src/collision/shapes/ConvexShape.h | 2 +- src/collision/shapes/HeightFieldShape.cpp | 2 +- src/collision/shapes/SphereShape.cpp | 2 +- src/collision/shapes/TriangleShape.cpp | 18 ++--- src/collision/shapes/TriangleShape.h | 2 +- src/engine/OverlappingPair.cpp | 7 +- src/engine/OverlappingPair.h | 2 +- testbed/common/ConcaveMesh.cpp | 2 - .../CollisionDetectionScene.cpp | 22 +++--- .../CollisionDetectionScene.h | 2 +- 29 files changed, 138 insertions(+), 144 deletions(-) diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 0c21240a..3c4b771b 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -148,11 +148,11 @@ void CollisionDetection::computeMiddlePhase() { bodyindexpair bodiesIndex = OverlappingPair::computeBodiesIndexPair(body1, body2); if (mNoCollisionPairs.count(bodiesIndex) > 0) continue; - const CollisionShapeType shape1Type = shape1->getCollisionShape()->getType(); - const CollisionShapeType shape2Type = shape2->getCollisionShape()->getType(); + bool isShape1Convex = shape1->getCollisionShape()->isConvex(); + bool isShape2Convex = shape2->getCollisionShape()->isConvex(); // If both shapes are convex - if ((CollisionShape::isConvex(shape1Type) && CollisionShape::isConvex(shape2Type))) { + if (isShape1Convex && isShape2Convex) { // No middle-phase is necessary, simply create a narrow phase info // for the narrow-phase collision detection @@ -161,13 +161,12 @@ void CollisionDetection::computeMiddlePhase() { NarrowPhaseInfo(pair, shape1->getCollisionShape(), shape2->getCollisionShape(), shape1->getLocalToWorldTransform(), shape2->getLocalToWorldTransform(), shape1->getCachedCollisionData(), - shape2->getCachedCollisionData()); + shape2->getCachedCollisionData(), mSingleFrameAllocator); mNarrowPhaseInfoList->next = firstNarrowPhaseInfo; } // Concave vs Convex algorithm - else if ((!CollisionShape::isConvex(shape1Type) && CollisionShape::isConvex(shape2Type)) || - (!CollisionShape::isConvex(shape2Type) && CollisionShape::isConvex(shape1Type))) { + else if ((!isShape1Convex && isShape2Convex) || (!isShape2Convex && isShape1Convex)) { NarrowPhaseInfo* narrowPhaseInfo = nullptr; computeConvexVsConcaveMiddlePhase(pair, mSingleFrameAllocator, &narrowPhaseInfo); @@ -410,22 +409,14 @@ void CollisionDetection::processPotentialContacts(OverlappingPair* pair) { // Reduce the number of contact points of the manifold pair->reducePotentialContactManifolds(); - // If there is a concave mesh shape in the pair - if (pair->hasConcaveShape()) { + // Add all the potential contact manifolds as actual contact manifolds to the pair + ContactManifoldInfo* potentialManifold = pair->getPotentialContactManifolds(); + while (potentialManifold != nullptr) { - processSmoothMeshContacts(pair); - } - else { // If both collision shapes are convex + pair->addContactManifold(potentialManifold); - // Add all the potential contact manifolds as actual contact manifolds to the pair - ContactManifoldInfo* potentialManifold = pair->getPotentialContactManifolds(); - while (potentialManifold != nullptr) { - - pair->addContactManifold(potentialManifold); - - potentialManifold = potentialManifold->mNext; - } - } + potentialManifold = potentialManifold->mNext; + } // Clear the obselete contact manifolds and contact points pair->clearObseleteManifoldsAndContactPoints(); @@ -544,25 +535,24 @@ NarrowPhaseInfo* CollisionDetection::computeMiddlePhaseForProxyShapes(Overlappin // ------------------------------------------------------- - const CollisionShapeType shape1Type = shape1->getCollisionShape()->getType(); - const CollisionShapeType shape2Type = shape2->getCollisionShape()->getType(); + const bool isShape1Convex = shape1->getCollisionShape()->isConvex(); + const bool isShape2Convex = shape2->getCollisionShape()->isConvex(); NarrowPhaseInfo* narrowPhaseInfo = nullptr; // If both shapes are convex - if ((CollisionShape::isConvex(shape1Type) && CollisionShape::isConvex(shape2Type))) { + if ((isShape1Convex && isShape2Convex)) { // No middle-phase is necessary, simply create a narrow phase info // for the narrow-phase collision detection narrowPhaseInfo = new (mPoolAllocator.allocate(sizeof(NarrowPhaseInfo))) NarrowPhaseInfo(pair, shape1->getCollisionShape(), shape2->getCollisionShape(), shape1->getLocalToWorldTransform(), shape2->getLocalToWorldTransform(), shape1->getCachedCollisionData(), - shape2->getCachedCollisionData()); + shape2->getCachedCollisionData(), mPoolAllocator); } // Concave vs Convex algorithm - else if ((!CollisionShape::isConvex(shape1Type) && CollisionShape::isConvex(shape2Type)) || - (!CollisionShape::isConvex(shape2Type) && CollisionShape::isConvex(shape1Type))) { + else if ((!isShape1Convex && isShape2Convex) || (!isShape2Convex && isShape1Convex)) { // Run the middle-phase collision detection algorithm to find the triangles of the concave // shape we need to use during the narrow-phase collision detection @@ -630,9 +620,6 @@ bool CollisionDetection::testOverlap(CollisionBody* body1, CollisionBody* body2) // Test if the AABBs of the two proxy shapes overlap if (aabb1.testCollision(aabb2)) { - const CollisionShapeType shape1Type = body1ProxyShape->getCollisionShape()->getType(); - const CollisionShapeType shape2Type = body2ProxyShape->getCollisionShape()->getType(); - // Create a temporary overlapping pair OverlappingPair pair(body1ProxyShape, body2ProxyShape, mPoolAllocator, mPoolAllocator); @@ -647,6 +634,9 @@ bool CollisionDetection::testOverlap(CollisionBody* body1, CollisionBody* body2) // If we have not found a collision yet if (!isColliding) { + const CollisionShapeType shape1Type = narrowPhaseInfo->collisionShape1->getType(); + const CollisionShapeType shape2Type = narrowPhaseInfo->collisionShape2->getType(); + // Select the narrow phase algorithm to use according to the two collision shapes NarrowPhaseAlgorithm* narrowPhaseAlgorithm = selectNarrowPhaseAlgorithm(shape1Type, shape2Type); @@ -723,9 +713,6 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl // Check if the collision filtering allows collision between the two shapes if ((proxyShape->getCollisionCategoryBits() & categoryMaskBits) != 0) { - const CollisionShapeType shape1Type = bodyProxyShape->getCollisionShape()->getType(); - const CollisionShapeType shape2Type = proxyShape->getCollisionShape()->getType(); - // Create a temporary overlapping pair OverlappingPair pair(bodyProxyShape, proxyShape, mPoolAllocator, mPoolAllocator); @@ -740,6 +727,9 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl // If we have not found a collision yet if (!isColliding) { + const CollisionShapeType shape1Type = narrowPhaseInfo->collisionShape1->getType(); + const CollisionShapeType shape2Type = narrowPhaseInfo->collisionShape2->getType(); + // Select the narrow phase algorithm to use according to the two collision shapes NarrowPhaseAlgorithm* narrowPhaseAlgorithm = selectNarrowPhaseAlgorithm(shape1Type, shape2Type); @@ -812,12 +802,12 @@ void CollisionDetection::testCollision(CollisionBody* body1, CollisionBody* body // Compute the middle-phase collision detection between the two shapes NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); - const CollisionShapeType shape1Type = body1ProxyShape->getCollisionShape()->getType(); - const CollisionShapeType shape2Type = body2ProxyShape->getCollisionShape()->getType(); - // For each narrow-phase info object while (narrowPhaseInfo != nullptr) { + const CollisionShapeType shape1Type = narrowPhaseInfo->collisionShape1->getType(); + const CollisionShapeType shape2Type = narrowPhaseInfo->collisionShape2->getType(); + // Select the narrow phase algorithm to use according to the two collision shapes NarrowPhaseAlgorithm* narrowPhaseAlgorithm = selectNarrowPhaseAlgorithm(shape1Type, shape2Type); @@ -896,9 +886,6 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c // Check if the collision filtering allows collision between the two shapes if ((proxyShape->getCollisionCategoryBits() & categoryMaskBits) != 0) { - const CollisionShapeType shape1Type = bodyProxyShape->getCollisionShape()->getType(); - const CollisionShapeType shape2Type = proxyShape->getCollisionShape()->getType(); - // Create a temporary overlapping pair OverlappingPair pair(bodyProxyShape, proxyShape, mPoolAllocator, mPoolAllocator); @@ -908,6 +895,9 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c // For each narrow-phase info object while (narrowPhaseInfo != nullptr) { + const CollisionShapeType shape1Type = narrowPhaseInfo->collisionShape1->getType(); + const CollisionShapeType shape2Type = narrowPhaseInfo->collisionShape2->getType(); + // Select the narrow phase algorithm to use according to the two collision shapes NarrowPhaseAlgorithm* narrowPhaseAlgorithm = selectNarrowPhaseAlgorithm(shape1Type, shape2Type); @@ -988,8 +978,8 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { // For each narrow-phase info object while (narrowPhaseInfo != nullptr) { - const CollisionShapeType shape1Type = shape1->getCollisionShape()->getType(); - const CollisionShapeType shape2Type = shape2->getCollisionShape()->getType(); + const CollisionShapeType shape1Type = narrowPhaseInfo->collisionShape1->getType(); + const CollisionShapeType shape2Type = narrowPhaseInfo->collisionShape2->getType(); // Select the narrow phase algorithm to use according to the two collision shapes NarrowPhaseAlgorithm* narrowPhaseAlgorithm = selectNarrowPhaseAlgorithm(shape1Type, shape2Type); diff --git a/src/collision/MiddlePhaseTriangleCallback.cpp b/src/collision/MiddlePhaseTriangleCallback.cpp index e99da461..a1a183ac 100644 --- a/src/collision/MiddlePhaseTriangleCallback.cpp +++ b/src/collision/MiddlePhaseTriangleCallback.cpp @@ -32,7 +32,8 @@ using namespace reactphysics3d; void MiddlePhaseTriangleCallback::testTriangle(uint meshSubPart, uint triangleIndex, const Vector3* trianglePoints, const Vector3* verticesNormals) { - // Create a triangle collision shape + // Create a triangle collision shape (the allocated memory for the TriangleShape will be released in the + // destructor of the corresponding NarrowPhaseInfo. decimal margin = mConcaveShape->getTriangleMargin(); TriangleShape* triangleShape = new (mAllocator.allocate(sizeof(TriangleShape))) TriangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], @@ -44,6 +45,6 @@ void MiddlePhaseTriangleCallback::testTriangle(uint meshSubPart, uint triangleIn NarrowPhaseInfo(mOverlappingPair, mConvexProxyShape->getCollisionShape(), triangleShape, mConvexProxyShape->getLocalToWorldTransform(), mConcaveProxyShape->getLocalToWorldTransform(), mConvexProxyShape->getCachedCollisionData(), - mConcaveProxyShape->getCachedCollisionData()); + mConcaveProxyShape->getCachedCollisionData(), mAllocator); narrowPhaseInfoList->next = firstNarrowPhaseInfo; } diff --git a/src/collision/NarrowPhaseInfo.cpp b/src/collision/NarrowPhaseInfo.cpp index 22ee6666..b4a92a38 100644 --- a/src/collision/NarrowPhaseInfo.cpp +++ b/src/collision/NarrowPhaseInfo.cpp @@ -27,18 +27,19 @@ #include #include "NarrowPhaseInfo.h" #include "ContactPointInfo.h" +#include "collision/shapes/TriangleShape.h" #include "engine/OverlappingPair.h" using namespace reactphysics3d; // Constructor -NarrowPhaseInfo::NarrowPhaseInfo(OverlappingPair* pair, const CollisionShape* shape1, - const CollisionShape* shape2, const Transform& shape1Transform, - const Transform& shape2Transform, void** cachedData1, void** cachedData2) +NarrowPhaseInfo::NarrowPhaseInfo(OverlappingPair* pair, CollisionShape* shape1, + CollisionShape* shape2, const Transform& shape1Transform, + const Transform& shape2Transform, void** cachedData1, void** cachedData2, Allocator& shapeAllocator) : overlappingPair(pair), collisionShape1(shape1), collisionShape2(shape2), shape1ToWorldTransform(shape1Transform), shape2ToWorldTransform(shape2Transform), contactPoints(nullptr), cachedCollisionData1(cachedData1), - cachedCollisionData2(cachedData2), next(nullptr) { + cachedCollisionData2(cachedData2), collisionShapeAllocator(shapeAllocator), next(nullptr) { } @@ -46,6 +47,15 @@ NarrowPhaseInfo::NarrowPhaseInfo(OverlappingPair* pair, const CollisionShape* sh NarrowPhaseInfo::~NarrowPhaseInfo() { assert(contactPoints == nullptr); + + // Release the memory of the TriangleShape (this memory was allocated in the + // MiddlePhaseTriangleCallback::testTriangle() method) + if (collisionShape1->getName() == CollisionShapeName::TRIANGLE) { + collisionShapeAllocator.release(collisionShape1, sizeof(TriangleShape)); + } + if (collisionShape2->getName() == CollisionShapeName::TRIANGLE) { + collisionShapeAllocator.release(collisionShape2, sizeof(TriangleShape)); + } } // Add a new contact point diff --git a/src/collision/NarrowPhaseInfo.h b/src/collision/NarrowPhaseInfo.h index 29bc6c9d..c9b18094 100644 --- a/src/collision/NarrowPhaseInfo.h +++ b/src/collision/NarrowPhaseInfo.h @@ -48,10 +48,10 @@ struct NarrowPhaseInfo { OverlappingPair* overlappingPair; /// Pointer to the first collision shape to test collision with - const CollisionShape* collisionShape1; + CollisionShape* collisionShape1; /// Pointer to the second collision shape to test collision with - const CollisionShape* collisionShape2; + CollisionShape* collisionShape2; /// Transform that maps from collision shape 1 local-space to world-space Transform shape1ToWorldTransform; @@ -70,13 +70,16 @@ struct NarrowPhaseInfo { // TODO : Check if we can use separating axis in OverlappingPair instead of cachedCollisionData1 and cachedCollisionData2 void** cachedCollisionData2; + /// Memory allocator for the collision shape (Used to release TriangleShape memory in destructor) + Allocator& collisionShapeAllocator; + /// Pointer to the next element in the linked list NarrowPhaseInfo* next; /// Constructor - NarrowPhaseInfo(OverlappingPair* pair, const CollisionShape* shape1, - const CollisionShape* shape2, const Transform& shape1Transform, - const Transform& shape2Transform, void** cachedData1, void** cachedData2); + NarrowPhaseInfo(OverlappingPair* pair, CollisionShape* shape1, + CollisionShape* shape2, const Transform& shape1Transform, + const Transform& shape2Transform, void** cachedData1, void** cachedData2, Allocator& shapeAllocator); /// Destructor ~NarrowPhaseInfo(); diff --git a/src/collision/ProxyShape.h b/src/collision/ProxyShape.h index d9575b3d..36bec740 100644 --- a/src/collision/ProxyShape.h +++ b/src/collision/ProxyShape.h @@ -85,6 +85,11 @@ class ProxyShape { /// proxy shape will collide with every collision categories by default. unsigned short mCollideWithMaskBits; + // -------------------- Methods -------------------- // + + /// Return the collision shape + CollisionShape* getCollisionShape(); + public: // -------------------- Methods -------------------- // @@ -177,6 +182,8 @@ class ProxyShape { friend class DynamicsWorld; friend class GJKAlgorithm; friend class ConvexMeshShape; + friend class ContactManifoldSet; + friend class MiddlePhaseTriangleCallback; }; @@ -193,6 +200,14 @@ inline const CollisionShape* ProxyShape::getCollisionShape() const { return mCollisionShape; } +// Return the collision shape +/** +* @return Pointer to the internal collision shape +*/ +inline CollisionShape* ProxyShape::getCollisionShape() { + return mCollisionShape; +} + // Return the parent body /** * @return Pointer to the parent body diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.cpp b/src/collision/narrowphase/DefaultCollisionDispatch.cpp index df1828ad..05616b27 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.cpp +++ b/src/collision/narrowphase/DefaultCollisionDispatch.cpp @@ -36,7 +36,6 @@ NarrowPhaseAlgorithm* DefaultCollisionDispatch::selectAlgorithm(int type1, int t CollisionShapeType shape1Type = static_cast(type1); CollisionShapeType shape2Type = static_cast(type2); - // Convex vs Convex algorithm (GJK algorithm) if (type1 > type2) { return nullptr; } diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 23ce86e0..c5210c64 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -82,7 +82,7 @@ bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfo* narrow // If the shapes are not triangles (no temporal coherence for triangle collision because we do not store previous // frame collision data per triangle) - if (polyhedron->getType() != CollisionShapeType::TRIANGLE) { + if (polyhedron->getName() != CollisionShapeName::TRIANGLE) { // If the last frame collision info is valid and was also using SAT algorithm if (lastFrameInfo.isValid && lastFrameInfo.wasUsingSAT) { @@ -225,7 +225,7 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfo* narro // If the shapes are not triangles (no temporal coherence for triangle collision because we do not store previous // frame collision data per triangle) - if (polyhedron->getType() != CollisionShapeType::TRIANGLE) { + if (polyhedron->getName() != CollisionShapeName::TRIANGLE) { // If the last frame collision info is valid and was also using SAT algorithm if (lastFrameInfo.isValid && lastFrameInfo.wasUsingSAT) { @@ -609,7 +609,7 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn // If the shapes are not triangles (no temporal coherence for triangle collision because we do not store previous // frame collision data per triangle) - if (polyhedron1->getType() != CollisionShapeType::TRIANGLE && polyhedron2->getType() != CollisionShapeType::TRIANGLE) { + if (polyhedron1->getName() != CollisionShapeName::TRIANGLE && polyhedron2->getName() != CollisionShapeName::TRIANGLE) { // If the last frame collision info is valid and was also using SAT algorithm if (lastFrameInfo.isValid && lastFrameInfo.wasUsingSAT) { diff --git a/src/collision/shapes/BoxShape.cpp b/src/collision/shapes/BoxShape.cpp index af6a30b8..54666136 100644 --- a/src/collision/shapes/BoxShape.cpp +++ b/src/collision/shapes/BoxShape.cpp @@ -38,7 +38,7 @@ using namespace reactphysics3d; * @param margin The collision margin (in meters) around the collision shape */ BoxShape::BoxShape(const Vector3& extent, decimal margin) - : ConvexPolyhedronShape(margin), mExtent(extent - Vector3(margin, margin, margin)) { + : ConvexPolyhedronShape(CollisionShapeName::BOX, margin), mExtent(extent - Vector3(margin, margin, margin)) { assert(extent.x > decimal(0.0) && extent.x > margin); assert(extent.y > decimal(0.0) && extent.y > margin); assert(extent.z > decimal(0.0) && extent.z > margin); diff --git a/src/collision/shapes/CapsuleShape.cpp b/src/collision/shapes/CapsuleShape.cpp index f9f442ce..32ea146c 100644 --- a/src/collision/shapes/CapsuleShape.cpp +++ b/src/collision/shapes/CapsuleShape.cpp @@ -37,7 +37,7 @@ using namespace reactphysics3d; * @param height The height of the capsule (in meters) */ CapsuleShape::CapsuleShape(decimal radius, decimal height) - : ConvexShape(CollisionShapeType::CAPSULE, radius), mHalfHeight(height * decimal(0.5)) { + : ConvexShape(CollisionShapeName::CAPSULE, CollisionShapeType::CAPSULE, radius), mHalfHeight(height * decimal(0.5)) { assert(radius > decimal(0.0)); assert(height > decimal(0.0)); } diff --git a/src/collision/shapes/CollisionShape.cpp b/src/collision/shapes/CollisionShape.cpp index 301c97d2..d03b4a1c 100644 --- a/src/collision/shapes/CollisionShape.cpp +++ b/src/collision/shapes/CollisionShape.cpp @@ -32,7 +32,7 @@ using namespace reactphysics3d; // Constructor -CollisionShape::CollisionShape(CollisionShapeType type) : mType(type), mScaling(1.0, 1.0, 1.0) { +CollisionShape::CollisionShape(CollisionShapeName name, CollisionShapeType type) : mName(name), mType(type), mScaling(1.0, 1.0, 1.0) { } diff --git a/src/collision/shapes/CollisionShape.h b/src/collision/shapes/CollisionShape.h index 78b82ae0..77f96dfb 100644 --- a/src/collision/shapes/CollisionShape.h +++ b/src/collision/shapes/CollisionShape.h @@ -39,9 +39,12 @@ /// ReactPhysics3D namespace namespace reactphysics3d { -/// Type of the collision shape -enum class CollisionShapeType {TRIANGLE, SPHERE, CAPSULE, CONVEX_POLYHEDRON, CONCAVE_MESH, HEIGHTFIELD}; -const int NB_COLLISION_SHAPE_TYPES = 6; +/// Type of collision shapes +enum class CollisionShapeType {SPHERE, CAPSULE, CONVEX_POLYHEDRON, CONCAVE_SHAPE}; +const int NB_COLLISION_SHAPE_TYPES = 4; + +/// Names of collision shapes +enum class CollisionShapeName { TRIANGLE, SPHERE, CAPSULE, BOX, CONVEX_MESH, TRIANGLE_MESH, HEIGHTFIELD }; // Declarations class ProxyShape; @@ -61,6 +64,9 @@ class CollisionShape { /// Type of the collision shape CollisionShapeType mType; + /// Name of the colision shape + CollisionShapeName mName; + /// Scaling vector of the collision shape Vector3 mScaling; @@ -80,7 +86,7 @@ class CollisionShape { // -------------------- Methods -------------------- // /// Constructor - CollisionShape(CollisionShapeType type); + CollisionShape(CollisionShapeName name, CollisionShapeType type); /// Destructor virtual ~CollisionShape() = default; @@ -91,7 +97,10 @@ class CollisionShape { /// Deleted assignment operator CollisionShape& operator=(const CollisionShape& shape) = delete; - /// Return the type of the collision shapes + /// Return the name of the collision shape + CollisionShapeName getName() const; + + /// Return the type of the collision shape CollisionShapeType getType() const; /// Return true if the collision shape is convex, false if it is concave @@ -115,28 +124,28 @@ class CollisionShape { /// Compute the world-space AABB of the collision shape given a transform virtual void computeAABB(AABB& aabb, const Transform& transform) const; - /// Return true if the collision shape type is a convex shape - static bool isConvex(CollisionShapeType shapeType); - // -------------------- Friendship -------------------- // friend class ProxyShape; friend class CollisionWorld; }; +// Return the name of the collision shape +/** +* @return The name of the collision shape (box, sphere, triangle, ...) +*/ +inline CollisionShapeName CollisionShape::getName() const { + return mName; +} + // Return the type of the collision shape /** - * @return The type of the collision shape (box, sphere, cylinder, ...) + * @return The type of the collision shape (sphere, capsule, convex polyhedron, concave mesh) */ inline CollisionShapeType CollisionShape::getType() const { return mType; } -// Return true if the collision shape type is a convex shape -inline bool CollisionShape::isConvex(CollisionShapeType shapeType) { - return shapeType != CollisionShapeType::CONCAVE_MESH && shapeType != CollisionShapeType::HEIGHTFIELD; -} - // Return the scaling vector of the collision shape inline Vector3 CollisionShape::getScaling() const { return mScaling; diff --git a/src/collision/shapes/ConcaveMeshShape.cpp b/src/collision/shapes/ConcaveMeshShape.cpp index 8cb5235a..0a9e1fd6 100644 --- a/src/collision/shapes/ConcaveMeshShape.cpp +++ b/src/collision/shapes/ConcaveMeshShape.cpp @@ -30,7 +30,7 @@ using namespace reactphysics3d; // Constructor ConcaveMeshShape::ConcaveMeshShape(TriangleMesh* triangleMesh) - : ConcaveShape(CollisionShapeType::CONCAVE_MESH) { + : ConcaveShape(CollisionShapeName::TRIANGLE_MESH) { mTriangleMesh = triangleMesh; mRaycastTestType = TriangleRaycastSide::FRONT; @@ -79,8 +79,8 @@ void ConcaveMeshShape::getTriangleVertices(uint subPart, uint triangleIndex, // Apply the scaling factor to the vertices outTriangleVertices[0] *= mScaling.x; - outTriangleVertices[1] *= mScaling.x; - outTriangleVertices[2] *= mScaling.x; + outTriangleVertices[1] *= mScaling.y; + outTriangleVertices[2] *= mScaling.z; } // Return the three vertex normals (in the array outVerticesNormals) of a triangle diff --git a/src/collision/shapes/ConcaveMeshShape.h b/src/collision/shapes/ConcaveMeshShape.h index 309ec27c..b99f2b4a 100644 --- a/src/collision/shapes/ConcaveMeshShape.h +++ b/src/collision/shapes/ConcaveMeshShape.h @@ -139,9 +139,6 @@ class ConcaveMeshShape : public ConcaveShape { /// Return the three vertex normals (in the array outVerticesNormals) of a triangle void getTriangleVerticesNormals(uint subPart, uint triangleIndex, Vector3* outVerticesNormals) const; - /// Get a smooth contact normal for collision for a triangle of the mesh - Vector3 computeSmoothLocalContactNormalForTriangle(TriangleShape* triangleShape, const Vector3& localContactPoint) const; - public: /// Constructor diff --git a/src/collision/shapes/ConcaveShape.cpp b/src/collision/shapes/ConcaveShape.cpp index 3f691468..e8c032d2 100644 --- a/src/collision/shapes/ConcaveShape.cpp +++ b/src/collision/shapes/ConcaveShape.cpp @@ -31,8 +31,7 @@ using namespace reactphysics3d; // Constructor -ConcaveShape::ConcaveShape(CollisionShapeType type) - : CollisionShape(type), mIsSmoothMeshCollisionEnabled(false), - mTriangleMargin(0), mRaycastTestType(TriangleRaycastSide::FRONT) { +ConcaveShape::ConcaveShape(CollisionShapeName name) + : CollisionShape(name, CollisionShapeType::CONCAVE_SHAPE), mTriangleMargin(0), mRaycastTestType(TriangleRaycastSide::FRONT) { } diff --git a/src/collision/shapes/ConcaveShape.h b/src/collision/shapes/ConcaveShape.h index 6e07187f..34e347e0 100644 --- a/src/collision/shapes/ConcaveShape.h +++ b/src/collision/shapes/ConcaveShape.h @@ -63,9 +63,6 @@ class ConcaveShape : public CollisionShape { // -------------------- Attributes -------------------- // - /// True if the smooth mesh collision algorithm is enabled - bool mIsSmoothMeshCollisionEnabled; - // Margin use for collision detection for each triangle decimal mTriangleMargin; @@ -82,7 +79,7 @@ class ConcaveShape : public CollisionShape { // -------------------- Methods -------------------- // /// Constructor - ConcaveShape(CollisionShapeType type); + ConcaveShape(CollisionShapeName name); /// Destructor virtual ~ConcaveShape() override = default; @@ -110,12 +107,6 @@ class ConcaveShape : public CollisionShape { /// Use a callback method on all triangles of the concave shape inside a given AABB virtual void testAllTriangles(TriangleCallback& callback, const AABB& localAABB) const=0; - - /// Return true if the smooth mesh collision is enabled - bool getIsSmoothMeshCollisionEnabled() const; - - /// Enable/disable the smooth mesh collision algorithm - void setIsSmoothMeshCollisionEnabled(bool isEnabled); }; // Return the triangle margin @@ -138,19 +129,6 @@ inline bool ConcaveShape::testPointInside(const Vector3& localPoint, ProxyShape* return false; } -// Return true if the smooth mesh collision is enabled -inline bool ConcaveShape::getIsSmoothMeshCollisionEnabled() const { - return mIsSmoothMeshCollisionEnabled; -} - -// Enable/disable the smooth mesh collision algorithm -/// Smooth mesh collision is used to avoid collisions against some internal edges -/// of the triangle mesh. If it is enabled, collsions with the mesh will be smoother -/// but collisions computation is a bit more expensive. -inline void ConcaveShape::setIsSmoothMeshCollisionEnabled(bool isEnabled) { - mIsSmoothMeshCollisionEnabled = isEnabled; -} - // Return the raycast test type (front, back, front-back) inline TriangleRaycastSide ConcaveShape::getRaycastTestType() const { return mRaycastTestType; diff --git a/src/collision/shapes/ConvexMeshShape.cpp b/src/collision/shapes/ConvexMeshShape.cpp index 263bb736..c8f03fa3 100644 --- a/src/collision/shapes/ConvexMeshShape.cpp +++ b/src/collision/shapes/ConvexMeshShape.cpp @@ -42,7 +42,7 @@ using namespace reactphysics3d; * @param margin Collision margin (in meters) around the collision shape */ ConvexMeshShape::ConvexMeshShape(PolyhedronMesh* polyhedronMesh, decimal margin) - : ConvexPolyhedronShape(margin), mPolyhedronMesh(polyhedronMesh), mMinBounds(0, 0, 0), mMaxBounds(0, 0, 0) { + : ConvexPolyhedronShape(CollisionShapeName::CONVEX_MESH, margin), mPolyhedronMesh(polyhedronMesh), mMinBounds(0, 0, 0), mMaxBounds(0, 0, 0) { // Recalculate the bounds of the mesh recalculateBounds(); diff --git a/src/collision/shapes/ConvexPolyhedronShape.cpp b/src/collision/shapes/ConvexPolyhedronShape.cpp index e73a7cd7..0db54a85 100644 --- a/src/collision/shapes/ConvexPolyhedronShape.cpp +++ b/src/collision/shapes/ConvexPolyhedronShape.cpp @@ -31,7 +31,7 @@ using namespace reactphysics3d; // Constructor -ConvexPolyhedronShape::ConvexPolyhedronShape(decimal margin) - : ConvexShape(CollisionShapeType::CONVEX_POLYHEDRON, margin) { +ConvexPolyhedronShape::ConvexPolyhedronShape(CollisionShapeName name, decimal margin) + : ConvexShape(name, CollisionShapeType::CONVEX_POLYHEDRON, margin) { } diff --git a/src/collision/shapes/ConvexPolyhedronShape.h b/src/collision/shapes/ConvexPolyhedronShape.h index 6c1de4d5..fe1f07a9 100644 --- a/src/collision/shapes/ConvexPolyhedronShape.h +++ b/src/collision/shapes/ConvexPolyhedronShape.h @@ -47,7 +47,7 @@ class ConvexPolyhedronShape : public ConvexShape { // -------------------- Methods -------------------- // /// Constructor - ConvexPolyhedronShape(decimal margin); + ConvexPolyhedronShape(CollisionShapeName name, decimal margin); /// Destructor virtual ~ConvexPolyhedronShape() override = default; diff --git a/src/collision/shapes/ConvexShape.cpp b/src/collision/shapes/ConvexShape.cpp index f077cdcb..649e50f5 100644 --- a/src/collision/shapes/ConvexShape.cpp +++ b/src/collision/shapes/ConvexShape.cpp @@ -31,8 +31,8 @@ using namespace reactphysics3d; // Constructor -ConvexShape::ConvexShape(CollisionShapeType type, decimal margin) - : CollisionShape(type), mMargin(margin) { +ConvexShape::ConvexShape(CollisionShapeName name, CollisionShapeType type, decimal margin) + : CollisionShape(name, type), mMargin(margin) { } diff --git a/src/collision/shapes/ConvexShape.h b/src/collision/shapes/ConvexShape.h index 94acc7f9..4bf4b718 100644 --- a/src/collision/shapes/ConvexShape.h +++ b/src/collision/shapes/ConvexShape.h @@ -63,7 +63,7 @@ class ConvexShape : public CollisionShape { // -------------------- Methods -------------------- // /// Constructor - ConvexShape(CollisionShapeType type, decimal margin); + ConvexShape(CollisionShapeName name, CollisionShapeType type, decimal margin); /// Destructor virtual ~ConvexShape() override = default; diff --git a/src/collision/shapes/HeightFieldShape.cpp b/src/collision/shapes/HeightFieldShape.cpp index c8fc97f2..b13cf69b 100644 --- a/src/collision/shapes/HeightFieldShape.cpp +++ b/src/collision/shapes/HeightFieldShape.cpp @@ -42,7 +42,7 @@ using namespace reactphysics3d; HeightFieldShape::HeightFieldShape(int nbGridColumns, int nbGridRows, decimal minHeight, decimal maxHeight, const void* heightFieldData, HeightDataType dataType, int upAxis, decimal integerHeightScale) - : ConcaveShape(CollisionShapeType::HEIGHTFIELD), mNbColumns(nbGridColumns), mNbRows(nbGridRows), + : ConcaveShape(CollisionShapeName::HEIGHTFIELD), mNbColumns(nbGridColumns), mNbRows(nbGridRows), mWidth(nbGridColumns - 1), mLength(nbGridRows - 1), mMinHeight(minHeight), mMaxHeight(maxHeight), mUpAxis(upAxis), mIntegerHeightScale(integerHeightScale), mHeightDataType(dataType) { diff --git a/src/collision/shapes/SphereShape.cpp b/src/collision/shapes/SphereShape.cpp index 73fe49aa..8583e80d 100644 --- a/src/collision/shapes/SphereShape.cpp +++ b/src/collision/shapes/SphereShape.cpp @@ -35,7 +35,7 @@ using namespace reactphysics3d; /** * @param radius Radius of the sphere (in meters) */ -SphereShape::SphereShape(decimal radius) : ConvexShape(CollisionShapeType::SPHERE, radius) { +SphereShape::SphereShape(decimal radius) : ConvexShape(CollisionShapeName::SPHERE, CollisionShapeType::SPHERE, radius) { assert(radius > decimal(0.0)); } diff --git a/src/collision/shapes/TriangleShape.cpp b/src/collision/shapes/TriangleShape.cpp index 72eb93d3..c72dd133 100644 --- a/src/collision/shapes/TriangleShape.cpp +++ b/src/collision/shapes/TriangleShape.cpp @@ -45,7 +45,7 @@ using namespace reactphysics3d; */ TriangleShape::TriangleShape(const Vector3& point1, const Vector3& point2, const Vector3& point3, const Vector3* verticesNormals, uint meshSubPart, uint triangleIndex, decimal margin) - : ConvexPolyhedronShape(margin), mMeshSubPart(meshSubPart), mTriangleIndex(triangleIndex) { + : ConvexPolyhedronShape(CollisionShapeName::TRIANGLE, margin), mMeshSubPart(meshSubPart), mTriangleIndex(triangleIndex) { mPoints[0] = point1; mPoints[1] = point2; @@ -68,15 +68,15 @@ TriangleShape::TriangleShape(const Vector3& point1, const Vector3& point2, const // This method will return the new smooth world contact // normal of the triangle and the the local contact point on the other shape. void TriangleShape::computeSmoothTriangleMeshContact(const CollisionShape* shape1, const CollisionShape* shape2, - Vector3& localContactPointShape1, Vector3 localContactPointShape2, + Vector3& localContactPointShape1, Vector3& localContactPointShape2, const Transform& shape1ToWorld, const Transform& shape2ToWorld, decimal penetrationDepth, Vector3& outSmoothVertexNormal) { - assert(shape1->getType() != CollisionShapeType::TRIANGLE || shape2->getType() != CollisionShapeType::TRIANGLE); + assert(shape1->getName() != CollisionShapeName::TRIANGLE || shape2->getName() != CollisionShapeName::TRIANGLE); // If one the shape is a triangle - bool isShape1Triangle = shape1->getType() == CollisionShapeType::TRIANGLE; - if (isShape1Triangle || shape2->getType() == CollisionShapeType::TRIANGLE) { + bool isShape1Triangle = shape1->getName() == CollisionShapeName::TRIANGLE; + if (isShape1Triangle || shape2->getName() == CollisionShapeName::TRIANGLE) { const TriangleShape* triangleShape = isShape1Triangle ? static_cast(shape1): static_cast(shape2); @@ -140,14 +140,6 @@ Vector3 TriangleShape::computeSmoothLocalContactNormalForTriangle(const Vector3& decimal u, v, w; computeBarycentricCoordinatesInTriangle(mPoints[0], mPoints[1], mPoints[2], localContactPoint, u, v, w); - int nbZeros = 0; - bool isUZero = approxEqual(u, decimal(0), decimal(0.0001)); - bool isVZero = approxEqual(v, decimal(0), decimal(0.0001)); - bool isWZero = approxEqual(w, decimal(0), decimal(0.0001)); - if (isUZero) nbZeros++; - if (isVZero) nbZeros++; - if (isWZero) nbZeros++; - // We compute the contact normal as the barycentric interpolation of the three vertices normals return (u * mVerticesNormals[0] + v * mVerticesNormals[1] + w * mVerticesNormals[2]).getUnit(); } diff --git a/src/collision/shapes/TriangleShape.h b/src/collision/shapes/TriangleShape.h index 900b71db..609d5892 100644 --- a/src/collision/shapes/TriangleShape.h +++ b/src/collision/shapes/TriangleShape.h @@ -173,7 +173,7 @@ class TriangleShape : public ConvexPolyhedronShape { /// This method compute the smooth mesh contact with a triangle in case one of the two collision shapes is a triangle. The idea in this case is to use a smooth vertex normal of the triangle mesh static void computeSmoothTriangleMeshContact(const CollisionShape* shape1, const CollisionShape* shape2, - Vector3& localContactPointShape1, Vector3 localContactPointShape2, + Vector3& localContactPointShape1, Vector3& localContactPointShape2, const Transform& shape1ToWorld, const Transform& shape2ToWorld, decimal penetrationDepth, Vector3& outSmoothVertexNormal); diff --git a/src/engine/OverlappingPair.cpp b/src/engine/OverlappingPair.cpp index a23857e3..f3f85fa1 100644 --- a/src/engine/OverlappingPair.cpp +++ b/src/engine/OverlappingPair.cpp @@ -36,7 +36,12 @@ OverlappingPair::OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, : mContactManifoldSet(shape1, shape2, manifoldsAllocator), mPotentialContactManifolds(nullptr), mTempMemoryAllocator(temporaryMemoryAllocator) { -} +} + +// Destructor +OverlappingPair::~OverlappingPair() { + assert(mPotentialContactManifolds == nullptr); +} // Create a new potential contact manifold using contact-points from narrow-phase void OverlappingPair::addPotentialContactPoints(NarrowPhaseInfo* narrowPhaseInfo) { diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index 906cddb7..e8c89dda 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -117,7 +117,7 @@ class OverlappingPair { Allocator& memoryAllocator, Allocator& temporaryMemoryAllocator); /// Destructor - ~OverlappingPair() = default; + ~OverlappingPair(); /// Deleted copy-constructor OverlappingPair(const OverlappingPair& pair) = delete; diff --git a/testbed/common/ConcaveMesh.cpp b/testbed/common/ConcaveMesh.cpp index 608e0020..d6a6bbe3 100644 --- a/testbed/common/ConcaveMesh.cpp +++ b/testbed/common/ConcaveMesh.cpp @@ -109,8 +109,6 @@ ConcaveMesh::ConcaveMesh(const openglframework::Vector3 &position, float mass, // do not forget to delete it at the end mConcaveShape = new rp3d::ConcaveMeshShape(&mPhysicsTriangleMesh); - mConcaveShape->setIsSmoothMeshCollisionEnabled(false); - // Initial position and orientation of the rigid body rp3d::Vector3 initPosition(position.x, position.y, position.z); rp3d::Quaternion initOrientation = rp3d::Quaternion::identity(); diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp index a99d494d..7606a61e 100755 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp @@ -94,7 +94,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mCapsule2->setSleepingColor(mRedColorDemo); // ---------- Box 1 ---------- // - openglframework::Vector3 position5(0, -0, 0); + openglframework::Vector3 position5(-4, -7, 0); // Create a cylinder and a corresponding collision body in the dynamics world mBox1 = new Box(BOX_SIZE, position5, mCollisionWorld, mMeshFolderPath); @@ -127,14 +127,15 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mConvexMesh->setSleepingColor(mRedColorDemo); // ---------- Concave Mesh ---------- // - //openglframework::Vector3 position8(0, 0, 0); + openglframework::Vector3 position8(0, 0, 0); // Create a convex mesh and a corresponding collision body in the dynamics world - //mConcaveMesh = new ConcaveMesh(position8, mCollisionWorld, mMeshFolderPath + "city.obj"); + mConcaveMesh = new ConcaveMesh(position8, mCollisionWorld, mMeshFolderPath + "city.obj"); + mAllShapes.push_back(mConcaveMesh); // Set the color - //mConcaveMesh->setColor(mGreyColorDemo); - //mConcaveMesh->setSleepingColor(mRedColorDemo); + mConcaveMesh->setColor(mGreyColorDemo); + mConcaveMesh->setSleepingColor(mRedColorDemo); // ---------- Heightfield ---------- // //openglframework::Vector3 position9(0, 0, 0); @@ -183,6 +184,9 @@ CollisionDetectionScene::~CollisionDetectionScene() { mCollisionWorld->destroyCollisionBody(mConvexMesh->getCollisionBody()); delete mConvexMesh; + mCollisionWorld->destroyCollisionBody(mConcaveMesh->getCollisionBody()); + delete mConcaveMesh; + /* // Destroy the corresponding rigid body from the dynamics world mCollisionWorld->destroyCollisionBody(mCone->getCollisionBody()); @@ -206,12 +210,6 @@ CollisionDetectionScene::~CollisionDetectionScene() { // Destroy the dumbbell delete mDumbbell; - // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mConcaveMesh->getCollisionBody()); - - // Destroy the convex mesh - delete mConcaveMesh; - // Destroy the corresponding rigid body from the dynamics world mCollisionWorld->destroyCollisionBody(mHeightField->getCollisionBody()); @@ -256,6 +254,7 @@ void CollisionDetectionScene::renderSinglePass(openglframework::Shader& shader, if (mBox1->getCollisionBody()->isActive()) mBox1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); if (mBox2->getCollisionBody()->isActive()) mBox2->render(shader, worldToCameraMatrix, mIsWireframeEnabled); if (mConvexMesh->getCollisionBody()->isActive()) mConvexMesh->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + if (mConcaveMesh->getCollisionBody()->isActive()) mConcaveMesh->render(shader, worldToCameraMatrix, mIsWireframeEnabled); /* if (mBox->getCollisionBody()->isActive()) mBox->render(shader, worldToCameraMatrix); @@ -263,7 +262,6 @@ void CollisionDetectionScene::renderSinglePass(openglframework::Shader& shader, if (mCylinder->getCollisionBody()->isActive()) mCylinder->render(shader, worldToCameraMatrix); if (mCapsule->getCollisionBody()->isActive()) mCapsule->render(shader, worldToCameraMatrix); if (mDumbbell->getCollisionBody()->isActive()) mDumbbell->render(shader, worldToCameraMatrix); - if (mConcaveMesh->getCollisionBody()->isActive()) mConcaveMesh->render(shader, worldToCameraMatrix); if (mHeightField->getCollisionBody()->isActive()) mHeightField->render(shader, worldToCameraMatrix); */ diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.h b/testbed/scenes/collisiondetection/CollisionDetectionScene.h index d0f1b569..8e94eaf5 100755 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.h +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.h @@ -147,7 +147,7 @@ class CollisionDetectionScene : public SceneDemo { Box* mBox2; ConvexMesh* mConvexMesh; //Dumbbell* mDumbbell; - //ConcaveMesh* mConcaveMesh; + ConcaveMesh* mConcaveMesh; //HeightField* mHeightField; std::vector mAllShapes; From 673e487f141948fece1a1dbd0a35d6d78b33bb04 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Fri, 1 Sep 2017 07:37:45 +0200 Subject: [PATCH 090/248] Remove temporal coherence from SAT for sphere vs polyhedron and capsule vs polyhedron --- .../narrowphase/SAT/SATAlgorithm.cpp | 258 ++++-------------- 1 file changed, 53 insertions(+), 205 deletions(-) diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index c5210c64..b551161d 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -74,69 +74,23 @@ bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfo* narrow decimal minPenetrationDepth = DECIMAL_LARGEST; uint minFaceIndex = 0; - // True if the shapes were overlapping in the previous frame and are - // still overlapping on the same axis in this frame - bool isTemporalCoherenceValid = false; - LastFrameCollisionInfo& lastFrameInfo = narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo(); + // For each face of the convex mesh + for (uint f = 0; f < polyhedron->getNbFaces(); f++) { - // If the shapes are not triangles (no temporal coherence for triangle collision because we do not store previous - // frame collision data per triangle) - if (polyhedron->getName() != CollisionShapeName::TRIANGLE) { + // Compute the penetration depth of the shapes along the face normal direction + decimal penetrationDepth = computePolyhedronFaceVsSpherePenetrationDepth(f, polyhedron, sphere, sphereCenter); - // If the last frame collision info is valid and was also using SAT algorithm - if (lastFrameInfo.isValid && lastFrameInfo.wasUsingSAT) { + // If the penetration depth is negative, we have found a separating axis + if (penetrationDepth <= decimal(0.0)) { - // We perform temporal coherence, we check if there is still an overlapping along the previous minimum separating - // axis. If it is the case, we directly report the collision without executing the whole SAT algorithm again. If - // the shapes are still separated along this axis, we directly exit with no collision. - - // Compute the penetration depth of the shapes along the face normal direction - decimal penetrationDepth = computePolyhedronFaceVsSpherePenetrationDepth(lastFrameInfo.satMinAxisFaceIndex, polyhedron, - sphere, sphereCenter); - - // If the previous axis is a separating axis - if (penetrationDepth <= decimal(0.0)) { - - // Return no collision - return false; - } - - // The two shapes are overlapping as in the previous frame and on the same axis, therefore - // we will skip the entire SAT algorithm because the minimum separating axis did not change - isTemporalCoherenceValid = lastFrameInfo.wasColliding; - - if (isTemporalCoherenceValid) { - - minPenetrationDepth = penetrationDepth; - minFaceIndex = lastFrameInfo.satMinAxisFaceIndex; - } + return false; } - } - // We the shapes are still overlapping in the same axis as in - // the previous frame, we skip the whole SAT algorithm - if (!isTemporalCoherenceValid) { - - // For each face of the convex mesh - for (uint 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); - - // If the penetration depth is negative, we have found a separating axis - if (penetrationDepth <= decimal(0.0)) { - - lastFrameInfo.satMinAxisFaceIndex = f; - - return false; - } - - // Check if we have found a new minimum penetration axis - if (penetrationDepth < minPenetrationDepth) { - minPenetrationDepth = penetrationDepth; - minFaceIndex = f; - } + // Check if we have found a new minimum penetration axis + if (penetrationDepth < minPenetrationDepth) { + minPenetrationDepth = penetrationDepth; + minFaceIndex = f; } } @@ -161,8 +115,6 @@ bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfo* narrow isSphereShape1 ? contactPointPolyhedronLocal : contactPointSphereLocal); } - lastFrameInfo.satMinAxisFaceIndex = minFaceIndex; - return true; } @@ -217,171 +169,72 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfo* narro Vector3 separatingPolyhedronEdgeVertex1; Vector3 separatingPolyhedronEdgeVertex2; - // True if the shapes were overlapping in the previous frame and are - // still overlapping on the same axis in this frame - bool isTemporalCoherenceValid = false; + // For each face of the convex mesh + for (uint f = 0; f < polyhedron->getNbFaces(); f++) { - LastFrameCollisionInfo& lastFrameInfo = narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo(); + Vector3 outFaceNormalCapsuleSpace; - // If the shapes are not triangles (no temporal coherence for triangle collision because we do not store previous - // frame collision data per triangle) - if (polyhedron->getName() != CollisionShapeName::TRIANGLE) { + // Compute the penetration depth + const decimal penetrationDepth = computePolyhedronFaceVsCapsulePenetrationDepth(f, polyhedron, capsuleShape, + polyhedronToCapsuleTransform, + outFaceNormalCapsuleSpace); - // If the last frame collision info is valid and was also using SAT algorithm - if (lastFrameInfo.isValid && lastFrameInfo.wasUsingSAT) { + // If the penetration depth is negative, we have found a separating axis + if (penetrationDepth <= decimal(0.0)) { - // We perform temporal coherence, we check if there is still an overlapping along the previous minimum separating - // axis. If it is the case, we directly report the collision without executing the whole SAT algorithm again. If - // the shapes are still separated along this axis, we directly exit with no collision. + return false; + } - // If the previous minimum separation axis was a face normal of the polyhedron - if (lastFrameInfo.satIsAxisFacePolyhedron1) { - - Vector3 outFaceNormalCapsuleSpace; - - // Compute the penetration depth along the polyhedron face normal direction - const decimal penetrationDepth = computePolyhedronFaceVsCapsulePenetrationDepth(lastFrameInfo.satMinAxisFaceIndex, polyhedron, - capsuleShape, polyhedronToCapsuleTransform, - outFaceNormalCapsuleSpace); - - // If the previous axis is a separating axis - if (penetrationDepth <= decimal(0.0)) { - - // Return no collision - return false; - } - - // The two shapes are overlapping as in the previous frame and on the same axis, therefore - // we will skip the entire SAT algorithm because the minimum separating axis did not change - isTemporalCoherenceValid = lastFrameInfo.wasColliding; - - if (isTemporalCoherenceValid) { - - minPenetrationDepth = penetrationDepth; - minFaceIndex = lastFrameInfo.satMinAxisFaceIndex; - isMinPenetrationFaceNormal = true; - separatingAxisCapsuleSpace = outFaceNormalCapsuleSpace; - } - } - else { // If the previous minimum separation axis the cross product of the capsule inner segment and an edge of the polyhedron - - // Get an edge from the polyhedron (convert it into the capsule local-space) - HalfEdgeStructure::Edge edge = polyhedron->getHalfEdge(lastFrameInfo.satMinEdge1Index); - const Vector3 edgeVertex1 = polyhedron->getVertexPosition(edge.vertexIndex); - const Vector3 edgeVertex2 = polyhedron->getVertexPosition(polyhedron->getHalfEdge(edge.nextEdgeIndex).vertexIndex); - const Vector3 edgeDirectionCapsuleSpace = polyhedronToCapsuleTransform.getOrientation() * (edgeVertex2 - edgeVertex1); - - Vector3 outAxis; - - // Compute the penetration depth along this axis - const decimal penetrationDepth = computeEdgeVsCapsuleInnerSegmentPenetrationDepth(polyhedron, capsuleShape, - capsuleSegmentAxis, edgeVertex1, - edgeDirectionCapsuleSpace, - polyhedronToCapsuleTransform, - outAxis); - - // If the previous axis is a separating axis - if (penetrationDepth <= decimal(0.0)) { - - // Return no collision - return false; - } - - // The two shapes are overlapping as in the previous frame and on the same axis, therefore - // we will skip the entire SAT algorithm because the minimum separating axis did not change - isTemporalCoherenceValid = lastFrameInfo.wasColliding; - - if (isTemporalCoherenceValid) { - - minPenetrationDepth = penetrationDepth; - minEdgeIndex = lastFrameInfo.satMinEdge1Index; - isMinPenetrationFaceNormal = false; - separatingAxisCapsuleSpace = outAxis; - separatingPolyhedronEdgeVertex1 = edgeVertex1; - separatingPolyhedronEdgeVertex2 = edgeVertex2; - } - } + // Check if we have found a new minimum penetration axis + if (penetrationDepth < minPenetrationDepth) { + minPenetrationDepth = penetrationDepth; + minFaceIndex = f; + isMinPenetrationFaceNormal = true; + separatingAxisCapsuleSpace = outFaceNormalCapsuleSpace; } } - // If the shapes are still overlapping in the same axis as in the previous frame - // the previous frame, we skip the whole SAT algorithm - if (!isTemporalCoherenceValid) { + // 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 each face of the convex mesh - for (uint f = 0; f < polyhedron->getNbFaces(); f++) { + // Get an edge from the polyhedron (convert it into the capsule local-space) + HalfEdgeStructure::Edge edge = polyhedron->getHalfEdge(e); + const Vector3 edgeVertex1 = polyhedron->getVertexPosition(edge.vertexIndex); + const Vector3 edgeVertex2 = polyhedron->getVertexPosition(polyhedron->getHalfEdge(edge.nextEdgeIndex).vertexIndex); + const Vector3 edgeDirectionCapsuleSpace = polyhedronToCapsuleTransform.getOrientation() * (edgeVertex2 - edgeVertex1); - Vector3 outFaceNormalCapsuleSpace; + HalfEdgeStructure::Edge twinEdge = polyhedron->getHalfEdge(edge.twinEdgeIndex); + const Vector3 adjacentFace1Normal = polyhedronToCapsuleTransform.getOrientation() * polyhedron->getFaceNormal(edge.faceIndex); + const Vector3 adjacentFace2Normal = polyhedronToCapsuleTransform.getOrientation() * polyhedron->getFaceNormal(twinEdge.faceIndex); + + // Check using the Gauss Map if this edge cross product can be as separating axis + if (isMinkowskiFaceCapsuleVsEdge(capsuleSegmentAxis, adjacentFace1Normal, adjacentFace2Normal)) { + + Vector3 outAxis; // Compute the penetration depth - const decimal penetrationDepth = computePolyhedronFaceVsCapsulePenetrationDepth(f, polyhedron, capsuleShape, - polyhedronToCapsuleTransform, - outFaceNormalCapsuleSpace); + const decimal penetrationDepth = computeEdgeVsCapsuleInnerSegmentPenetrationDepth(polyhedron, capsuleShape, + capsuleSegmentAxis, edgeVertex1, + edgeDirectionCapsuleSpace, + polyhedronToCapsuleTransform, + outAxis); // If the penetration depth is negative, we have found a separating axis if (penetrationDepth <= decimal(0.0)) { - lastFrameInfo.satIsAxisFacePolyhedron1 = true; - lastFrameInfo.satMinAxisFaceIndex = f; - return false; } // Check if we have found a new minimum penetration axis if (penetrationDepth < minPenetrationDepth) { minPenetrationDepth = penetrationDepth; - minFaceIndex = f; - isMinPenetrationFaceNormal = true; - separatingAxisCapsuleSpace = outFaceNormalCapsuleSpace; + minEdgeIndex = e; + isMinPenetrationFaceNormal = false; + separatingAxisCapsuleSpace = outAxis; + separatingPolyhedronEdgeVertex1 = edgeVertex1; + separatingPolyhedronEdgeVertex2 = edgeVertex2; } } - - // 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) { - - // Get an edge from the polyhedron (convert it into the capsule local-space) - HalfEdgeStructure::Edge edge = polyhedron->getHalfEdge(e); - const Vector3 edgeVertex1 = polyhedron->getVertexPosition(edge.vertexIndex); - const Vector3 edgeVertex2 = polyhedron->getVertexPosition(polyhedron->getHalfEdge(edge.nextEdgeIndex).vertexIndex); - const Vector3 edgeDirectionCapsuleSpace = polyhedronToCapsuleTransform.getOrientation() * (edgeVertex2 - edgeVertex1); - - HalfEdgeStructure::Edge twinEdge = polyhedron->getHalfEdge(edge.twinEdgeIndex); - const Vector3 adjacentFace1Normal = polyhedronToCapsuleTransform.getOrientation() * polyhedron->getFaceNormal(edge.faceIndex); - const Vector3 adjacentFace2Normal = polyhedronToCapsuleTransform.getOrientation() * polyhedron->getFaceNormal(twinEdge.faceIndex); - - // Check using the Gauss Map if this edge cross product can be as separating axis - if (isMinkowskiFaceCapsuleVsEdge(capsuleSegmentAxis, adjacentFace1Normal, adjacentFace2Normal)) { - - Vector3 outAxis; - - // Compute the penetration depth - const decimal penetrationDepth = computeEdgeVsCapsuleInnerSegmentPenetrationDepth(polyhedron, capsuleShape, - capsuleSegmentAxis, edgeVertex1, - edgeDirectionCapsuleSpace, - polyhedronToCapsuleTransform, - outAxis); - - // If the penetration depth is negative, we have found a separating axis - if (penetrationDepth <= decimal(0.0)) { - - lastFrameInfo.satIsAxisFacePolyhedron1 = false; - lastFrameInfo.satMinEdge1Index = e; - - return false; - } - - // Check if we have found a new minimum penetration axis - if (penetrationDepth < minPenetrationDepth) { - minPenetrationDepth = penetrationDepth; - minEdgeIndex = e; - isMinPenetrationFaceNormal = false; - separatingAxisCapsuleSpace = outAxis; - separatingPolyhedronEdgeVertex1 = edgeVertex1; - separatingPolyhedronEdgeVertex2 = edgeVertex2; - } - } - } - } // Convert the inner capsule segment points into the polyhedron local-space @@ -404,8 +257,6 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfo* narro narrowPhaseInfo, isCapsuleShape1); } - lastFrameInfo.satIsAxisFacePolyhedron1 = true; - lastFrameInfo.satMinAxisFaceIndex = minFaceIndex; } else { // The separating axis is the cross product of a polyhedron edge and the inner capsule segment @@ -433,9 +284,6 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfo* narro isCapsuleShape1 ? contactPointCapsule : closestPointPolyhedronEdge, isCapsuleShape1 ? closestPointPolyhedronEdge : contactPointCapsule); } - - lastFrameInfo.satIsAxisFacePolyhedron1 = false; - lastFrameInfo.satMinEdge1Index = minEdgeIndex; } return true; From 6a22b3a81d5a128f42fa08333cef9c041fef8697 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 3 Sep 2017 10:48:39 +0200 Subject: [PATCH 091/248] Fix temporal coherence in SAT algorithm between two convex polyhedra --- .../narrowphase/SAT/SATAlgorithm.cpp | 253 +++++++++++------- src/collision/narrowphase/SAT/SATAlgorithm.h | 7 + 2 files changed, 164 insertions(+), 96 deletions(-) diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index b551161d..87be645b 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -489,6 +489,24 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn minFaceIndex = lastFrameInfo.satMinAxisFaceIndex; isMinPenetrationFaceNormal = true; isMinPenetrationFaceNormalPolyhedron1 = true; + + // Compute the contact points between two faces of two convex polyhedra. + // If contact points have been found, we report them without running the whole SAT algorithm + if(computePolyhedronVsPolyhedronFaceContactPoints(isMinPenetrationFaceNormalPolyhedron1, polyhedron1, polyhedron2, + polyhedron1ToPolyhedron2, polyhedron2ToPolyhedron1, minFaceIndex, + narrowPhaseInfo, minPenetrationDepth)) { + + lastFrameInfo.satIsAxisFacePolyhedron1 = isMinPenetrationFaceNormalPolyhedron1; + lastFrameInfo.satIsAxisFacePolyhedron2 = !isMinPenetrationFaceNormalPolyhedron1; + lastFrameInfo.satMinAxisFaceIndex = minFaceIndex; + + return true; + } + else { // Contact points have not been found (the set of clipped points was empty) + + // Therefore, we need to run the whole SAT algorithm again + isTemporalCoherenceValid = false; + } } } else if (lastFrameInfo.satIsAxisFacePolyhedron2) { // If the previous separating axis (or axis with minimum penetration depth) @@ -513,6 +531,24 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn minFaceIndex = lastFrameInfo.satMinAxisFaceIndex; isMinPenetrationFaceNormal = true; isMinPenetrationFaceNormalPolyhedron1 = false; + + // Compute the contact points between two faces of two convex polyhedra. + // If contact points have been found, we report them without running the whole SAT algorithm + if(computePolyhedronVsPolyhedronFaceContactPoints(isMinPenetrationFaceNormalPolyhedron1, polyhedron1, polyhedron2, + polyhedron1ToPolyhedron2, polyhedron2ToPolyhedron1, minFaceIndex, + narrowPhaseInfo, minPenetrationDepth)) { + + lastFrameInfo.satIsAxisFacePolyhedron1 = isMinPenetrationFaceNormalPolyhedron1; + lastFrameInfo.satIsAxisFacePolyhedron2 = !isMinPenetrationFaceNormalPolyhedron1; + lastFrameInfo.satMinAxisFaceIndex = minFaceIndex; + + return true; + } + else { // Contact points have not been found (the set of clipped points was empty) + + // Therefore, we need to run the whole SAT algorithm again + isTemporalCoherenceValid = false; + } } } else { // If the previous separating axis (or axis with minimum penetration depth) was the cross product of two edges @@ -544,6 +580,12 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn // we will skip the entire SAT algorithm because the minimum separating axis did not change isTemporalCoherenceValid = lastFrameInfo.wasColliding; + // Temporal coherence is valid only if the two edges build a minkowski + // face (and the cross product is therefore a candidate for separating axis + if (isTemporalCoherenceValid && !testEdgesBuildMinkowskiFace(polyhedron1, edge1, polyhedron2, edge2, polyhedron1ToPolyhedron2)) { + isTemporalCoherenceValid = false; + } + if (isTemporalCoherenceValid) { minPenetrationDepth = penetrationDepth; @@ -672,102 +714,11 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn if (reportContacts) { - const ConvexPolyhedronShape* referencePolyhedron = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron1 : polyhedron2; - const ConvexPolyhedronShape* incidentPolyhedron = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron2 : polyhedron1; - const Transform& referenceToIncidentTransform = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron1ToPolyhedron2 : polyhedron2ToPolyhedron1; - const Transform& incidentToReferenceTransform = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron2ToPolyhedron1 : polyhedron1ToPolyhedron2; - - assert(minPenetrationDepth > decimal(0.0)); - - const Vector3 axisReferenceSpace = referencePolyhedron->getFaceNormal(minFaceIndex); - const Vector3 axisIncidentSpace = referenceToIncidentTransform.getOrientation() * axisReferenceSpace; - - // Compute the world normal - Vector3 normalWorld = isMinPenetrationFaceNormalPolyhedron1 ? narrowPhaseInfo->shape1ToWorldTransform.getOrientation() * axisReferenceSpace : - -(narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * axisReferenceSpace); - - // Get the reference face - HalfEdgeStructure::Face referenceFace = referencePolyhedron->getFace(minFaceIndex); - - // Find the incident face on the other polyhedron (most anti-parallel face) - uint incidentFaceIndex = findMostAntiParallelFaceOnPolyhedron(incidentPolyhedron, axisIncidentSpace); - - // Get the incident face - HalfEdgeStructure::Face incidentFace = incidentPolyhedron->getFace(incidentFaceIndex); - - std::vector polygonVertices; // Vertices to clip of the incident face - std::vector planesNormals; // Normals of the clipping planes - std::vector planesPoints; // Points on the clipping planes - - // Get all the vertices of the incident face (in the reference local-space) - std::vector::const_iterator it; - for (it = incidentFace.faceVertices.begin(); it != incidentFace.faceVertices.end(); ++it) { - const Vector3 faceVertexIncidentSpace = incidentPolyhedron->getVertexPosition(*it); - polygonVertices.push_back(incidentToReferenceTransform * faceVertexIncidentSpace); - } - - // Get the reference face clipping planes - uint currentEdgeIndex = referenceFace.edgeIndex; - uint firstEdgeIndex = currentEdgeIndex; - do { - - // Get the adjacent edge - HalfEdgeStructure::Edge edge = referencePolyhedron->getHalfEdge(currentEdgeIndex); - - // Get the twin edge - HalfEdgeStructure::Edge twinEdge = referencePolyhedron->getHalfEdge(edge.twinEdgeIndex); - - // Compute the edge vertices and edge direction - Vector3 edgeV1 = referencePolyhedron->getVertexPosition(edge.vertexIndex); - Vector3 edgeV2 = referencePolyhedron->getVertexPosition(twinEdge.vertexIndex); - Vector3 edgeDirection = edgeV2 - edgeV1; - - // Compute the normal of the clipping plane for this edge - // The clipping plane is perpendicular to the edge direction and the reference face normal - Vector3 clipPlaneNormal = axisReferenceSpace.cross(edgeDirection); - - planesNormals.push_back(clipPlaneNormal); - planesPoints.push_back(edgeV1); - - // Go to the next adjacent edge of the reference face - currentEdgeIndex = edge.nextEdgeIndex; - - } while (currentEdgeIndex != firstEdgeIndex); - - assert(planesNormals.size() > 0); - assert(planesNormals.size() == planesPoints.size()); - - // Clip the reference faces with the adjacent planes of the reference face - std::vector clipPolygonVertices = clipPolygonWithPlanes(polygonVertices, planesPoints, planesNormals); - assert(clipPolygonVertices.size() > 0); - - // We only keep the clipped points that are below the reference face - const Vector3 referenceFaceVertex = referencePolyhedron->getVertexPosition(referencePolyhedron->getHalfEdge(firstEdgeIndex).vertexIndex); - std::vector::const_iterator itPoints; - for (itPoints = clipPolygonVertices.begin(); itPoints != clipPolygonVertices.end(); ++itPoints) { - - // If the clip point is bellow the reference face - if (((*itPoints) - referenceFaceVertex).dot(axisReferenceSpace) < decimal(0.0)) { - - // Convert the clip incident polyhedron vertex into the incident polyhedron local-space - Vector3 contactPointIncidentPolyhedron = referenceToIncidentTransform * (*itPoints); - - // Project the contact point onto the reference face - Vector3 contactPointReferencePolyhedron = projectPointOntoPlane(*itPoints, axisReferenceSpace, referenceFaceVertex); - - // Compute smooth triangle mesh contact if one of the two collision shapes is a triangle - TriangleShape::computeSmoothTriangleMeshContact(narrowPhaseInfo->collisionShape1, narrowPhaseInfo->collisionShape2, - isMinPenetrationFaceNormalPolyhedron1 ? contactPointReferencePolyhedron : contactPointIncidentPolyhedron, - isMinPenetrationFaceNormalPolyhedron1 ? contactPointIncidentPolyhedron : contactPointReferencePolyhedron, - narrowPhaseInfo->shape1ToWorldTransform, narrowPhaseInfo->shape2ToWorldTransform, - minPenetrationDepth, normalWorld); - - // Create a new contact point - narrowPhaseInfo->addContactPoint(normalWorld, minPenetrationDepth, - isMinPenetrationFaceNormalPolyhedron1 ? contactPointReferencePolyhedron : contactPointIncidentPolyhedron, - isMinPenetrationFaceNormalPolyhedron1 ? contactPointIncidentPolyhedron : contactPointReferencePolyhedron); - } - } + // Compute the contact points between two faces of two convex polyhedra. + bool contactsFound = computePolyhedronVsPolyhedronFaceContactPoints(isMinPenetrationFaceNormalPolyhedron1, polyhedron1, + polyhedron2, polyhedron1ToPolyhedron2, polyhedron2ToPolyhedron1, + minFaceIndex, narrowPhaseInfo, minPenetrationDepth); + assert(contactsFound); } lastFrameInfo.satIsAxisFacePolyhedron1 = isMinPenetrationFaceNormalPolyhedron1; @@ -809,6 +760,116 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn return true; } +// Compute the contact points between two faces of two convex polyhedra. +/// The method returns true if contact points have been found +bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPenetrationFaceNormalPolyhedron1, + const ConvexPolyhedronShape* polyhedron1, const ConvexPolyhedronShape* polyhedron2, + const Transform& polyhedron1ToPolyhedron2, const Transform& polyhedron2ToPolyhedron1, + uint minFaceIndex, NarrowPhaseInfo* narrowPhaseInfo, decimal minPenetrationDepth) const { + + const ConvexPolyhedronShape* referencePolyhedron = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron1 : polyhedron2; + const ConvexPolyhedronShape* incidentPolyhedron = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron2 : polyhedron1; + const Transform& referenceToIncidentTransform = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron1ToPolyhedron2 : polyhedron2ToPolyhedron1; + const Transform& incidentToReferenceTransform = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron2ToPolyhedron1 : polyhedron1ToPolyhedron2; + + assert(minPenetrationDepth > decimal(0.0)); + + const Vector3 axisReferenceSpace = referencePolyhedron->getFaceNormal(minFaceIndex); + const Vector3 axisIncidentSpace = referenceToIncidentTransform.getOrientation() * axisReferenceSpace; + + // Compute the world normal + Vector3 normalWorld = isMinPenetrationFaceNormalPolyhedron1 ? narrowPhaseInfo->shape1ToWorldTransform.getOrientation() * axisReferenceSpace : + -(narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * axisReferenceSpace); + + // Get the reference face + HalfEdgeStructure::Face referenceFace = referencePolyhedron->getFace(minFaceIndex); + + // Find the incident face on the other polyhedron (most anti-parallel face) + uint incidentFaceIndex = findMostAntiParallelFaceOnPolyhedron(incidentPolyhedron, axisIncidentSpace); + + // Get the incident face + HalfEdgeStructure::Face incidentFace = incidentPolyhedron->getFace(incidentFaceIndex); + + std::vector polygonVertices; // Vertices to clip of the incident face + std::vector planesNormals; // Normals of the clipping planes + std::vector planesPoints; // Points on the clipping planes + + // Get all the vertices of the incident face (in the reference local-space) + std::vector::const_iterator it; + for (it = incidentFace.faceVertices.begin(); it != incidentFace.faceVertices.end(); ++it) { + const Vector3 faceVertexIncidentSpace = incidentPolyhedron->getVertexPosition(*it); + polygonVertices.push_back(incidentToReferenceTransform * faceVertexIncidentSpace); + } + + // Get the reference face clipping planes + uint currentEdgeIndex = referenceFace.edgeIndex; + uint firstEdgeIndex = currentEdgeIndex; + do { + + // Get the adjacent edge + HalfEdgeStructure::Edge edge = referencePolyhedron->getHalfEdge(currentEdgeIndex); + + // Get the twin edge + HalfEdgeStructure::Edge twinEdge = referencePolyhedron->getHalfEdge(edge.twinEdgeIndex); + + // Compute the edge vertices and edge direction + Vector3 edgeV1 = referencePolyhedron->getVertexPosition(edge.vertexIndex); + Vector3 edgeV2 = referencePolyhedron->getVertexPosition(twinEdge.vertexIndex); + Vector3 edgeDirection = edgeV2 - edgeV1; + + // Compute the normal of the clipping plane for this edge + // The clipping plane is perpendicular to the edge direction and the reference face normal + Vector3 clipPlaneNormal = axisReferenceSpace.cross(edgeDirection); + + planesNormals.push_back(clipPlaneNormal); + planesPoints.push_back(edgeV1); + + // Go to the next adjacent edge of the reference face + currentEdgeIndex = edge.nextEdgeIndex; + + } while (currentEdgeIndex != firstEdgeIndex); + + assert(planesNormals.size() > 0); + assert(planesNormals.size() == planesPoints.size()); + + // Clip the reference faces with the adjacent planes of the reference face + std::vector clipPolygonVertices = clipPolygonWithPlanes(polygonVertices, planesPoints, planesNormals); + assert(clipPolygonVertices.size() > 0); + + // We only keep the clipped points that are below the reference face + const Vector3 referenceFaceVertex = referencePolyhedron->getVertexPosition(referencePolyhedron->getHalfEdge(firstEdgeIndex).vertexIndex); + std::vector::const_iterator itPoints; + bool contactPointsFound = false; + for (itPoints = clipPolygonVertices.begin(); itPoints != clipPolygonVertices.end(); ++itPoints) { + + // If the clip point is bellow the reference face + if (((*itPoints) - referenceFaceVertex).dot(axisReferenceSpace) < decimal(0.0)) { + + contactPointsFound = true; + + // Convert the clip incident polyhedron vertex into the incident polyhedron local-space + Vector3 contactPointIncidentPolyhedron = referenceToIncidentTransform * (*itPoints); + + // Project the contact point onto the reference face + Vector3 contactPointReferencePolyhedron = projectPointOntoPlane(*itPoints, axisReferenceSpace, referenceFaceVertex); + + // Compute smooth triangle mesh contact if one of the two collision shapes is a triangle + TriangleShape::computeSmoothTriangleMeshContact(narrowPhaseInfo->collisionShape1, narrowPhaseInfo->collisionShape2, + isMinPenetrationFaceNormalPolyhedron1 ? contactPointReferencePolyhedron : contactPointIncidentPolyhedron, + isMinPenetrationFaceNormalPolyhedron1 ? contactPointIncidentPolyhedron : contactPointReferencePolyhedron, + narrowPhaseInfo->shape1ToWorldTransform, narrowPhaseInfo->shape2ToWorldTransform, + minPenetrationDepth, normalWorld); + + // Create a new contact point + narrowPhaseInfo->addContactPoint(normalWorld, minPenetrationDepth, + isMinPenetrationFaceNormalPolyhedron1 ? contactPointReferencePolyhedron : contactPointIncidentPolyhedron, + isMinPenetrationFaceNormalPolyhedron1 ? contactPointIncidentPolyhedron : contactPointReferencePolyhedron); + } + } + + return contactPointsFound; +} + // Find and return the index of the polyhedron face with the most anti-parallel face normal given a direction vector // This is used to find the incident face on a polyhedron of a given reference face of another polyhedron uint SATAlgorithm::findMostAntiParallelFaceOnPolyhedron(const ConvexPolyhedronShape* polyhedron, const Vector3& direction) const { diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.h b/src/collision/narrowphase/SAT/SATAlgorithm.h index 73838d95..37e4f7d2 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.h +++ b/src/collision/narrowphase/SAT/SATAlgorithm.h @@ -96,6 +96,13 @@ class SATAlgorithm { const Vector3& edgeDirectionCapsuleSpace, const Transform& polyhedronToCapsuleTransform, Vector3& outAxis) const; + /// 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, + NarrowPhaseInfo* narrowPhaseInfo, decimal minPenetrationDepth) const; + + public : // -------------------- Methods -------------------- // From e1602f2b272c571e68d234fcf1e340e811071300 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 3 Sep 2017 17:35:09 +0200 Subject: [PATCH 092/248] Fix issues with normals computation in TriangleVertexArray --- src/collision/TriangleVertexArray.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/src/collision/TriangleVertexArray.cpp b/src/collision/TriangleVertexArray.cpp index ad59d37a..1e500001 100644 --- a/src/collision/TriangleVertexArray.cpp +++ b/src/collision/TriangleVertexArray.cpp @@ -163,9 +163,9 @@ void TriangleVertexArray::computeVerticesNormals() { Vector3 normalComponent = std::asin(sinA) * crossProduct; // Add the normal component of this vertex into the normals array - verticesNormals[verticesIndices[v]] = normalComponent.x; - verticesNormals[verticesIndices[v] + 1] = normalComponent.y; - verticesNormals[verticesIndices[v] + 2] = normalComponent.z; + verticesNormals[verticesIndices[v] * 3] = normalComponent.x; + verticesNormals[verticesIndices[v] * 3 + 1] = normalComponent.y; + verticesNormals[verticesIndices[v] * 3 + 2] = normalComponent.z; } } @@ -173,12 +173,12 @@ void TriangleVertexArray::computeVerticesNormals() { for (uint v=0; v(verticesNormals); From 8bab9c13483210a865bd96bbdf30b1e2db05f4c2 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 3 Sep 2017 18:05:23 +0200 Subject: [PATCH 093/248] Remove unused cachedCollisionData parameter --- src/collision/narrowphase/GJK/GJKAlgorithm.cpp | 17 +++++------------ src/collision/narrowphase/SAT/SATAlgorithm.cpp | 6 +++--- src/collision/shapes/BoxShape.h | 6 ++---- src/collision/shapes/CapsuleShape.h | 6 ++---- src/collision/shapes/ConvexMeshShape.cpp | 5 +---- src/collision/shapes/ConvexMeshShape.h | 3 +-- src/collision/shapes/ConvexShape.cpp | 5 ++--- src/collision/shapes/ConvexShape.h | 8 ++------ src/collision/shapes/SphereShape.h | 6 ++---- src/collision/shapes/TriangleShape.h | 5 ++--- 10 files changed, 22 insertions(+), 45 deletions(-) diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp index 609c415a..9bc1d00d 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp @@ -66,9 +66,6 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhase const ConvexShape* shape1 = static_cast(narrowPhaseInfo->collisionShape1); const ConvexShape* shape2 = static_cast(narrowPhaseInfo->collisionShape2); - void** shape1CachedCollisionData = narrowPhaseInfo->cachedCollisionData1; - void** shape2CachedCollisionData = narrowPhaseInfo->cachedCollisionData2; - bool isPolytopeShape = shape1->isPolyhedron() && shape2->isPolyhedron(); // Get the local-space to world-space transforms @@ -109,8 +106,8 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhase do { // Compute the support points for original objects (without margins) A and B - suppA = shape1->getLocalSupportPointWithoutMargin(-v, shape1CachedCollisionData); - suppB = body2Tobody1 * shape2->getLocalSupportPointWithoutMargin(rotateToBody2 * v, shape2CachedCollisionData); + suppA = shape1->getLocalSupportPointWithoutMargin(-v); + suppB = body2Tobody1 * shape2->getLocalSupportPointWithoutMargin(rotateToBody2 * v); // Compute the support point for the Minkowski difference A-B w = suppA - suppB; @@ -237,8 +234,6 @@ bool GJKAlgorithm::testPointInside(const Vector3& localPoint, ProxyShape* proxyS const ConvexShape* shape = static_cast(proxyShape->getCollisionShape()); - void** shapeCachedCollisionData = proxyShape->getCachedCollisionData(); - // Support point of object B (object B is a single point) const Vector3 suppB(localPoint); @@ -254,7 +249,7 @@ bool GJKAlgorithm::testPointInside(const Vector3& localPoint, ProxyShape* proxyS do { // Compute the support points for original objects (without margins) A and B - suppA = shape->getLocalSupportPointWithoutMargin(-v, shapeCachedCollisionData); + suppA = shape->getLocalSupportPointWithoutMargin(-v); // Compute the support point for the Minkowski difference A-B w = suppA - suppB; @@ -300,8 +295,6 @@ bool GJKAlgorithm::raycast(const Ray& ray, ProxyShape* proxyShape, RaycastInfo& const ConvexShape* shape = static_cast(proxyShape->getCollisionShape()); - void** shapeCachedCollisionData = proxyShape->getCachedCollisionData(); - Vector3 suppA; // Current lower bound point on the ray (starting at ray's origin) Vector3 suppB; // Support point on the collision shape const decimal machineEpsilonSquare = MACHINE_EPSILON * MACHINE_EPSILON; @@ -321,7 +314,7 @@ bool GJKAlgorithm::raycast(const Ray& ray, ProxyShape* proxyShape, RaycastInfo& Vector3 n(decimal(0.0), decimal(0.0), decimal(0.0)); decimal lambda = decimal(0.0); suppA = ray.point1; // Current lower bound point on the ray (starting at ray's origin) - suppB = shape->getLocalSupportPointWithoutMargin(rayDirection, shapeCachedCollisionData); + suppB = shape->getLocalSupportPointWithoutMargin(rayDirection); Vector3 v = suppA - suppB; decimal vDotW, vDotR; decimal distSquare = v.lengthSquare(); @@ -331,7 +324,7 @@ bool GJKAlgorithm::raycast(const Ray& ray, ProxyShape* proxyShape, RaycastInfo& while (distSquare > epsilon && nbIterations < MAX_ITERATIONS_GJK_RAYCAST) { // Compute the support points - suppB = shape->getLocalSupportPointWithoutMargin(v, shapeCachedCollisionData); + suppB = shape->getLocalSupportPointWithoutMargin(v); w = suppA - suppB; vDotW = v.dot(w); diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 87be645b..d1062704 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -314,7 +314,7 @@ decimal SATAlgorithm::computeEdgeVsCapsuleInnerSegmentPenetrationDepth(const Con outAxis.normalize(); // Compute the penetration depth - const Vector3 capsuleSupportPoint = capsule->getLocalSupportPointWithMargin(-outAxis, nullptr); + const Vector3 capsuleSupportPoint = capsule->getLocalSupportPointWithMargin(-outAxis); const Vector3 capsuleSupportPointToEdgePoint = pointOnPolyhedronEdge - capsuleSupportPoint; penetrationDepth = capsuleSupportPointToEdgePoint.dot(outAxis); } @@ -335,7 +335,7 @@ decimal SATAlgorithm::computePolyhedronFaceVsCapsulePenetrationDepth(uint polyhe // Compute the penetration depth (using the capsule support in the direction opposite to the face normal) outFaceNormalCapsuleSpace = polyhedronToCapsuleTransform.getOrientation() * faceNormal; - const Vector3 capsuleSupportPoint = capsule->getLocalSupportPointWithMargin(-outFaceNormalCapsuleSpace, nullptr); + const Vector3 capsuleSupportPoint = capsule->getLocalSupportPointWithMargin(-outFaceNormalCapsuleSpace); const Vector3 pointOnPolyhedronFace = polyhedronToCapsuleTransform * polyhedron->getVertexPosition(face.faceVertices[0]); const Vector3 capsuleSupportPointToFacePoint = pointOnPolyhedronFace - capsuleSupportPoint; const decimal penetrationDepth = capsuleSupportPointToFacePoint.dot(outFaceNormalCapsuleSpace); @@ -932,7 +932,7 @@ decimal SATAlgorithm::testSingleFaceDirectionPolyhedronVsPolyhedron(const Convex const Vector3 faceNormalPolyhedron2Space = polyhedron1ToPolyhedron2.getOrientation() * faceNormal; // Get the support point of polyhedron 2 in the inverse direction of face normal - const Vector3 supportPoint = polyhedron2->getLocalSupportPointWithoutMargin(-faceNormalPolyhedron2Space, nullptr); + const Vector3 supportPoint = polyhedron2->getLocalSupportPointWithoutMargin(-faceNormalPolyhedron2Space); // Compute the penetration depth const Vector3 faceVertex = polyhedron1ToPolyhedron2 * polyhedron1->getVertexPosition(face.faceVertices[0]); diff --git a/src/collision/shapes/BoxShape.h b/src/collision/shapes/BoxShape.h index 5a07b0cb..d64222ff 100644 --- a/src/collision/shapes/BoxShape.h +++ b/src/collision/shapes/BoxShape.h @@ -65,8 +65,7 @@ class BoxShape : public ConvexPolyhedronShape { // -------------------- Methods -------------------- // /// Return a local support point in a given direction without the object margin - virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const override; + virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction) const override; /// Return true if a point is inside the collision shape virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const override; @@ -170,8 +169,7 @@ inline size_t BoxShape::getSizeInBytes() const { } // Return a local support point in a given direction without the objec margin -inline Vector3 BoxShape::getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const { +inline Vector3 BoxShape::getLocalSupportPointWithoutMargin(const Vector3& direction) const { return Vector3(direction.x < 0.0 ? -mExtent.x : mExtent.x, direction.y < 0.0 ? -mExtent.y : mExtent.y, diff --git a/src/collision/shapes/CapsuleShape.h b/src/collision/shapes/CapsuleShape.h index 9c0a4545..8aebff58 100644 --- a/src/collision/shapes/CapsuleShape.h +++ b/src/collision/shapes/CapsuleShape.h @@ -56,8 +56,7 @@ class CapsuleShape : public ConvexShape { // -------------------- Methods -------------------- // /// Return a local support point in a given direction without the object margin - virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const override; + virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction) const override; /// Return true if a point is inside the collision shape virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const override; @@ -169,8 +168,7 @@ inline bool CapsuleShape::isPolyhedron() const { /// Therefore, in this method, we compute the support points of both top and bottom spheres of /// the capsule and return the point with the maximum dot product with the direction vector. Note /// that the object margin is implicitly the radius and height of the capsule. -inline Vector3 CapsuleShape::getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const { +inline Vector3 CapsuleShape::getLocalSupportPointWithoutMargin(const Vector3& direction) const { // Support point top sphere decimal dotProductTop = mHalfHeight * direction.y; diff --git a/src/collision/shapes/ConvexMeshShape.cpp b/src/collision/shapes/ConvexMeshShape.cpp index c8f03fa3..995ef9bb 100644 --- a/src/collision/shapes/ConvexMeshShape.cpp +++ b/src/collision/shapes/ConvexMeshShape.cpp @@ -56,10 +56,7 @@ ConvexMeshShape::ConvexMeshShape(PolyhedronMesh* polyhedronMesh, decimal margin) /// it as a start in a hill-climbing (local search) process to find the new support vertex which /// will be in most of the cases very close to the previous one. Using hill-climbing, this method /// runs in almost constant time. -Vector3 ConvexMeshShape::getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const { - - // TODO : Do we still need to have cachedCollisionData or we can remove it from everywhere ? +Vector3 ConvexMeshShape::getLocalSupportPointWithoutMargin(const Vector3& direction) const { double maxDotProduct = DECIMAL_SMALLEST; uint indexMaxDotProduct = 0; diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index dd2b7021..b42c02e2 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -83,8 +83,7 @@ class ConvexMeshShape : public ConvexPolyhedronShape { virtual void setLocalScaling(const Vector3& scaling) override; /// Return a local support point in a given direction without the object margin. - virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const override; + virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction) const override; /// Return true if a point is inside the collision shape virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const override; diff --git a/src/collision/shapes/ConvexShape.cpp b/src/collision/shapes/ConvexShape.cpp index 649e50f5..90c5356f 100644 --- a/src/collision/shapes/ConvexShape.cpp +++ b/src/collision/shapes/ConvexShape.cpp @@ -37,11 +37,10 @@ ConvexShape::ConvexShape(CollisionShapeName name, CollisionShapeType type, decim } // Return a local support point in a given direction with the object margin -Vector3 ConvexShape::getLocalSupportPointWithMargin(const Vector3& direction, - void** cachedCollisionData) const { +Vector3 ConvexShape::getLocalSupportPointWithMargin(const Vector3& direction) const { // Get the support point without margin - Vector3 supportPoint = getLocalSupportPointWithoutMargin(direction, cachedCollisionData); + Vector3 supportPoint = getLocalSupportPointWithoutMargin(direction); if (mMargin != decimal(0.0)) { diff --git a/src/collision/shapes/ConvexShape.h b/src/collision/shapes/ConvexShape.h index 4bf4b718..9a2b7e00 100644 --- a/src/collision/shapes/ConvexShape.h +++ b/src/collision/shapes/ConvexShape.h @@ -49,14 +49,10 @@ class ConvexShape : public CollisionShape { // -------------------- Methods -------------------- // // Return a local support point in a given direction with the object margin - // TODO : Try to remove cachedCollisionData parameter - Vector3 getLocalSupportPointWithMargin(const Vector3& direction, - void** cachedCollisionData) const; + Vector3 getLocalSupportPointWithMargin(const Vector3& direction) const; /// Return a local support point in a given direction without the object margin - // TODO : Try to remove cachedCollisionData parameter - virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const=0; + virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction) const=0; public : diff --git a/src/collision/shapes/SphereShape.h b/src/collision/shapes/SphereShape.h index fe55a7a8..70f651de 100644 --- a/src/collision/shapes/SphereShape.h +++ b/src/collision/shapes/SphereShape.h @@ -49,8 +49,7 @@ class SphereShape : public ConvexShape { // -------------------- Methods -------------------- // /// Return a local support point in a given direction without the object margin - virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const override; + virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction) const override; /// Return true if a point is inside the collision shape virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const override; @@ -123,8 +122,7 @@ inline size_t SphereShape::getSizeInBytes() const { } // Return a local support point in a given direction without the object margin -inline Vector3 SphereShape::getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const { +inline Vector3 SphereShape::getLocalSupportPointWithoutMargin(const Vector3& direction) const { // Return the center of the sphere (the radius is taken into account in the object margin) return Vector3(0.0, 0.0, 0.0); diff --git a/src/collision/shapes/TriangleShape.h b/src/collision/shapes/TriangleShape.h index 609d5892..19cedfef 100644 --- a/src/collision/shapes/TriangleShape.h +++ b/src/collision/shapes/TriangleShape.h @@ -81,8 +81,7 @@ class TriangleShape : public ConvexPolyhedronShape { // -------------------- Methods -------------------- // /// Return a local support point in a given direction without the object margin - virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction, - void** cachedCollisionData) const override; + virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction) const override; /// Get a smooth contact normal for collision for a triangle of the mesh Vector3 computeSmoothLocalContactNormalForTriangle(const Vector3& localContactPoint) const; @@ -190,7 +189,7 @@ inline size_t TriangleShape::getSizeInBytes() const { } // Return a local support point in a given direction without the object margin -inline Vector3 TriangleShape::getLocalSupportPointWithoutMargin(const Vector3& direction, void** cachedCollisionData) const { +inline Vector3 TriangleShape::getLocalSupportPointWithoutMargin(const Vector3& direction) const { Vector3 dotProducts(direction.dot(mPoints[0]), direction.dot(mPoints[1]), direction.dot(mPoints[2])); return mPoints[dotProducts.getMaxAxis()]; } From 946e62dd4bdf5d934564830a055fcbd92aaa1eaa Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 3 Sep 2017 19:06:02 +0200 Subject: [PATCH 094/248] Remove unnecessary collision margin for some shapes --- src/collision/ContactManifold.cpp | 3 --- src/collision/MiddlePhaseTriangleCallback.cpp | 3 +-- src/collision/shapes/BoxShape.cpp | 10 +++++----- src/collision/shapes/BoxShape.h | 2 +- src/collision/shapes/ConcaveMeshShape.cpp | 4 +--- src/collision/shapes/ConcaveShape.cpp | 2 +- src/collision/shapes/ConcaveShape.h | 11 ----------- src/collision/shapes/ConvexMeshShape.cpp | 4 ++-- src/collision/shapes/ConvexMeshShape.h | 4 +--- src/collision/shapes/ConvexPolyhedronShape.cpp | 4 ++-- src/collision/shapes/ConvexPolyhedronShape.h | 2 +- src/collision/shapes/ConvexShape.h | 2 +- src/collision/shapes/HeightFieldShape.cpp | 3 +-- src/collision/shapes/TriangleShape.cpp | 4 ++-- src/collision/shapes/TriangleShape.h | 2 +- src/configuration.h | 3 --- test/tests/collision/TestPointInside.h | 2 +- test/tests/collision/TestRaycast.h | 2 +- 18 files changed, 22 insertions(+), 45 deletions(-) diff --git a/src/collision/ContactManifold.cpp b/src/collision/ContactManifold.cpp index 846a418a..803a9e82 100644 --- a/src/collision/ContactManifold.cpp +++ b/src/collision/ContactManifold.cpp @@ -65,9 +65,6 @@ ContactManifold::~ContactManifold() { ContactPoint* nextContactPoint = contactPoint->getNext(); - // TODO : Delete this - bool test = mMemoryAllocator.isReleaseNeeded(); - // Delete the contact point contactPoint->~ContactPoint(); mMemoryAllocator.release(contactPoint, sizeof(ContactPoint)); diff --git a/src/collision/MiddlePhaseTriangleCallback.cpp b/src/collision/MiddlePhaseTriangleCallback.cpp index a1a183ac..de6c22ea 100644 --- a/src/collision/MiddlePhaseTriangleCallback.cpp +++ b/src/collision/MiddlePhaseTriangleCallback.cpp @@ -34,10 +34,9 @@ void MiddlePhaseTriangleCallback::testTriangle(uint meshSubPart, uint triangleIn // Create a triangle collision shape (the allocated memory for the TriangleShape will be released in the // destructor of the corresponding NarrowPhaseInfo. - decimal margin = mConcaveShape->getTriangleMargin(); TriangleShape* triangleShape = new (mAllocator.allocate(sizeof(TriangleShape))) TriangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], - verticesNormals, meshSubPart, triangleIndex, margin); + verticesNormals, meshSubPart, triangleIndex); // Create a narrow phase info for the narrow-phase collision detection NarrowPhaseInfo* firstNarrowPhaseInfo = narrowPhaseInfoList; diff --git a/src/collision/shapes/BoxShape.cpp b/src/collision/shapes/BoxShape.cpp index 54666136..01c4d965 100644 --- a/src/collision/shapes/BoxShape.cpp +++ b/src/collision/shapes/BoxShape.cpp @@ -37,11 +37,11 @@ using namespace reactphysics3d; * @param extent The vector with the three extents of the box (in meters) * @param margin The collision margin (in meters) around the collision shape */ -BoxShape::BoxShape(const Vector3& extent, decimal margin) - : ConvexPolyhedronShape(CollisionShapeName::BOX, margin), mExtent(extent - Vector3(margin, margin, margin)) { - assert(extent.x > decimal(0.0) && extent.x > margin); - assert(extent.y > decimal(0.0) && extent.y > margin); - assert(extent.z > decimal(0.0) && extent.z > margin); +BoxShape::BoxShape(const Vector3& extent) + : ConvexPolyhedronShape(CollisionShapeName::BOX), mExtent(extent) { + assert(extent.x > decimal(0.0)); + assert(extent.y > decimal(0.0)); + assert(extent.z > decimal(0.0)); // Vertices mHalfEdgeStructure.addVertex(0); diff --git a/src/collision/shapes/BoxShape.h b/src/collision/shapes/BoxShape.h index d64222ff..56c14797 100644 --- a/src/collision/shapes/BoxShape.h +++ b/src/collision/shapes/BoxShape.h @@ -81,7 +81,7 @@ class BoxShape : public ConvexPolyhedronShape { // -------------------- Methods -------------------- // /// Constructor - BoxShape(const Vector3& extent, decimal margin = OBJECT_MARGIN); + BoxShape(const Vector3& extent); /// Destructor virtual ~BoxShape() override = default; diff --git a/src/collision/shapes/ConcaveMeshShape.cpp b/src/collision/shapes/ConcaveMeshShape.cpp index 0a9e1fd6..84e95e2c 100644 --- a/src/collision/shapes/ConcaveMeshShape.cpp +++ b/src/collision/shapes/ConcaveMeshShape.cpp @@ -59,7 +59,6 @@ void ConcaveMeshShape::initBVHTree() { // Create the AABB for the triangle AABB aabb = AABB::createAABBForTriangle(trianglePoints); - aabb.inflate(mTriangleMargin, mTriangleMargin, mTriangleMargin); // Add the AABB with the index of the triangle into the dynamic AABB tree mDynamicAABBTree.addObject(aabb, subPart, triangleIndex); @@ -152,9 +151,8 @@ void ConcaveMeshRaycastCallback::raycastTriangles() { Vector3 verticesNormals[3]; mConcaveMeshShape.getTriangleVerticesNormals(data[0], data[1], verticesNormals); // Create a triangle collision shape - decimal margin = mConcaveMeshShape.getTriangleMargin(); TriangleShape triangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], - verticesNormals, data[0], data[1], margin); + verticesNormals, data[0], data[1]); triangleShape.setRaycastTestType(mConcaveMeshShape.getRaycastTestType()); // Ray casting test against the collision shape diff --git a/src/collision/shapes/ConcaveShape.cpp b/src/collision/shapes/ConcaveShape.cpp index e8c032d2..cac82e45 100644 --- a/src/collision/shapes/ConcaveShape.cpp +++ b/src/collision/shapes/ConcaveShape.cpp @@ -32,6 +32,6 @@ using namespace reactphysics3d; // Constructor ConcaveShape::ConcaveShape(CollisionShapeName name) - : CollisionShape(name, CollisionShapeType::CONCAVE_SHAPE), mTriangleMargin(0), mRaycastTestType(TriangleRaycastSide::FRONT) { + : CollisionShape(name, CollisionShapeType::CONCAVE_SHAPE), mRaycastTestType(TriangleRaycastSide::FRONT) { } diff --git a/src/collision/shapes/ConcaveShape.h b/src/collision/shapes/ConcaveShape.h index 34e347e0..abc3759b 100644 --- a/src/collision/shapes/ConcaveShape.h +++ b/src/collision/shapes/ConcaveShape.h @@ -63,9 +63,6 @@ class ConcaveShape : public CollisionShape { // -------------------- Attributes -------------------- // - // Margin use for collision detection for each triangle - decimal mTriangleMargin; - /// Raycast test type for the triangle (front, back, front-back) TriangleRaycastSide mRaycastTestType; @@ -90,9 +87,6 @@ class ConcaveShape : public CollisionShape { /// Deleted assignment operator ConcaveShape& operator=(const ConcaveShape& shape) = delete; - /// Return the triangle margin - decimal getTriangleMargin() const; - /// Return the raycast test type (front, back, front-back) TriangleRaycastSide getRaycastTestType() const; @@ -109,11 +103,6 @@ class ConcaveShape : public CollisionShape { virtual void testAllTriangles(TriangleCallback& callback, const AABB& localAABB) const=0; }; -// Return the triangle margin -inline decimal ConcaveShape::getTriangleMargin() const { - return mTriangleMargin; -} - // Return true if the collision shape is convex, false if it is concave inline bool ConcaveShape::isConvex() const { return false; diff --git a/src/collision/shapes/ConvexMeshShape.cpp b/src/collision/shapes/ConvexMeshShape.cpp index 995ef9bb..f6011375 100644 --- a/src/collision/shapes/ConvexMeshShape.cpp +++ b/src/collision/shapes/ConvexMeshShape.cpp @@ -41,8 +41,8 @@ using namespace reactphysics3d; * @param stride Stride between the beginning of two elements in the vertices array * @param margin Collision margin (in meters) around the collision shape */ -ConvexMeshShape::ConvexMeshShape(PolyhedronMesh* polyhedronMesh, decimal margin) - : ConvexPolyhedronShape(CollisionShapeName::CONVEX_MESH, margin), mPolyhedronMesh(polyhedronMesh), mMinBounds(0, 0, 0), mMaxBounds(0, 0, 0) { +ConvexMeshShape::ConvexMeshShape(PolyhedronMesh* polyhedronMesh) + : ConvexPolyhedronShape(CollisionShapeName::CONVEX_MESH), mPolyhedronMesh(polyhedronMesh), mMinBounds(0, 0, 0), mMaxBounds(0, 0, 0) { // Recalculate the bounds of the mesh recalculateBounds(); diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index b42c02e2..4ceabe11 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -99,9 +99,7 @@ class ConvexMeshShape : public ConvexPolyhedronShape { // -------------------- Methods -------------------- // /// Constructor - // TODO : Do we really need to use the margin anymore ? Maybe for raycasting ? If not, remove all the - // comments documentation about margin - ConvexMeshShape(PolyhedronMesh* polyhedronMesh, decimal margin = OBJECT_MARGIN); + ConvexMeshShape(PolyhedronMesh* polyhedronMesh); /// Destructor virtual ~ConvexMeshShape() override = default; diff --git a/src/collision/shapes/ConvexPolyhedronShape.cpp b/src/collision/shapes/ConvexPolyhedronShape.cpp index 0db54a85..ab93584d 100644 --- a/src/collision/shapes/ConvexPolyhedronShape.cpp +++ b/src/collision/shapes/ConvexPolyhedronShape.cpp @@ -31,7 +31,7 @@ using namespace reactphysics3d; // Constructor -ConvexPolyhedronShape::ConvexPolyhedronShape(CollisionShapeName name, decimal margin) - : ConvexShape(name, CollisionShapeType::CONVEX_POLYHEDRON, margin) { +ConvexPolyhedronShape::ConvexPolyhedronShape(CollisionShapeName name) + : ConvexShape(name, CollisionShapeType::CONVEX_POLYHEDRON) { } diff --git a/src/collision/shapes/ConvexPolyhedronShape.h b/src/collision/shapes/ConvexPolyhedronShape.h index fe1f07a9..96707d69 100644 --- a/src/collision/shapes/ConvexPolyhedronShape.h +++ b/src/collision/shapes/ConvexPolyhedronShape.h @@ -47,7 +47,7 @@ class ConvexPolyhedronShape : public ConvexShape { // -------------------- Methods -------------------- // /// Constructor - ConvexPolyhedronShape(CollisionShapeName name, decimal margin); + ConvexPolyhedronShape(CollisionShapeName name); /// Destructor virtual ~ConvexPolyhedronShape() override = default; diff --git a/src/collision/shapes/ConvexShape.h b/src/collision/shapes/ConvexShape.h index 9a2b7e00..04f8aad6 100644 --- a/src/collision/shapes/ConvexShape.h +++ b/src/collision/shapes/ConvexShape.h @@ -59,7 +59,7 @@ class ConvexShape : public CollisionShape { // -------------------- Methods -------------------- // /// Constructor - ConvexShape(CollisionShapeName name, CollisionShapeType type, decimal margin); + ConvexShape(CollisionShapeName name, CollisionShapeType type, decimal margin = decimal(0.0)); /// Destructor virtual ~ConvexShape() override = default; diff --git a/src/collision/shapes/HeightFieldShape.cpp b/src/collision/shapes/HeightFieldShape.cpp index b13cf69b..2afba401 100644 --- a/src/collision/shapes/HeightFieldShape.cpp +++ b/src/collision/shapes/HeightFieldShape.cpp @@ -260,9 +260,8 @@ void TriangleOverlapCallback::testTriangle(uint meshSubPart, uint triangleIndex, const Vector3* verticesNormals) { // Create a triangle collision shape - decimal margin = mHeightFieldShape.getTriangleMargin(); TriangleShape triangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], - verticesNormals, meshSubPart, triangleIndex, margin); + verticesNormals, meshSubPart, triangleIndex); triangleShape.setRaycastTestType(mHeightFieldShape.getRaycastTestType()); // Ray casting test against the collision shape diff --git a/src/collision/shapes/TriangleShape.cpp b/src/collision/shapes/TriangleShape.cpp index c72dd133..48baa225 100644 --- a/src/collision/shapes/TriangleShape.cpp +++ b/src/collision/shapes/TriangleShape.cpp @@ -44,8 +44,8 @@ using namespace reactphysics3d; * @param margin The collision margin (in meters) around the collision shape */ TriangleShape::TriangleShape(const Vector3& point1, const Vector3& point2, const Vector3& point3, - const Vector3* verticesNormals, uint meshSubPart, uint triangleIndex, decimal margin) - : ConvexPolyhedronShape(CollisionShapeName::TRIANGLE, margin), mMeshSubPart(meshSubPart), mTriangleIndex(triangleIndex) { + const Vector3* verticesNormals, uint meshSubPart, uint triangleIndex) + : ConvexPolyhedronShape(CollisionShapeName::TRIANGLE), mMeshSubPart(meshSubPart), mTriangleIndex(triangleIndex) { mPoints[0] = point1; mPoints[1] = point2; diff --git a/src/collision/shapes/TriangleShape.h b/src/collision/shapes/TriangleShape.h index 19cedfef..c31a594c 100644 --- a/src/collision/shapes/TriangleShape.h +++ b/src/collision/shapes/TriangleShape.h @@ -108,7 +108,7 @@ class TriangleShape : public ConvexPolyhedronShape { /// Constructor TriangleShape(const Vector3& point1, const Vector3& point2, const Vector3& point3, - const Vector3* verticesNormals, uint meshSubPart, uint triangleIndex, decimal margin = OBJECT_MARGIN); + const Vector3* verticesNormals, uint meshSubPart, uint triangleIndex); /// Destructor virtual ~TriangleShape() override = default; diff --git a/src/configuration.h b/src/configuration.h index 04cb0956..b2c53021 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -100,9 +100,6 @@ constexpr decimal DEFAULT_ROLLING_RESISTANCE = decimal(0.0); /// True if the spleeping technique is enabled constexpr bool SPLEEPING_ENABLED = true; -/// Object margin for collision detection in meters (for the GJK-EPA Algorithm) -constexpr decimal OBJECT_MARGIN = decimal(0.04); - /// Distance threshold for two contact points for a valid persistent contact (in meters) constexpr decimal PERSISTENT_CONTACT_DIST_THRESHOLD = decimal(0.03); diff --git a/test/tests/collision/TestPointInside.h b/test/tests/collision/TestPointInside.h index abb54791..608b439b 100644 --- a/test/tests/collision/TestPointInside.h +++ b/test/tests/collision/TestPointInside.h @@ -115,7 +115,7 @@ class TestPointInside : public Test { mLocalShapeToWorld = mBodyTransform * mShapeTransform; // Create collision shapes - mBoxShape = new BoxShape(Vector3(2, 3, 4), 0); + mBoxShape = new BoxShape(Vector3(2, 3, 4)); mBoxProxyShape = mBoxBody->addCollisionShape(mBoxShape, mShapeTransform); mSphereShape = new SphereShape(3); diff --git a/test/tests/collision/TestRaycast.h b/test/tests/collision/TestRaycast.h index 93860a1c..81013570 100644 --- a/test/tests/collision/TestRaycast.h +++ b/test/tests/collision/TestRaycast.h @@ -192,7 +192,7 @@ class TestRaycast : public Test { mLocalShapeToWorld = mBodyTransform * mShapeTransform; // Create collision shapes - mBoxShape = new BoxShape(Vector3(2, 3, 4), 0); + mBoxShape = new BoxShape(Vector3(2, 3, 4)); mBoxProxyShape = mBoxBody->addCollisionShape(mBoxShape, mShapeTransform); mSphereShape = new SphereShape(3); From 501bca5e3d7ee7b6a0b7b918eeb4e179cd15711a Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 4 Sep 2017 07:26:01 +0200 Subject: [PATCH 095/248] Fix issue in TriangleVertexArray --- src/collision/TriangleVertexArray.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/collision/TriangleVertexArray.cpp b/src/collision/TriangleVertexArray.cpp index 1e500001..fa87e684 100644 --- a/src/collision/TriangleVertexArray.cpp +++ b/src/collision/TriangleVertexArray.cpp @@ -173,12 +173,12 @@ void TriangleVertexArray::computeVerticesNormals() { for (uint v=0; v(verticesNormals); From 95ade79af5d6e8ceb9427ff5d15fe49678cda7a3 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 4 Sep 2017 21:23:07 +0200 Subject: [PATCH 096/248] Fix issue with obsolete contact points that were not removed --- src/collision/CollisionDetection.cpp | 14 +++----------- src/collision/CollisionDetection.h | 3 --- 2 files changed, 3 insertions(+), 14 deletions(-) diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 3c4b771b..3f9a45f6 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -97,9 +97,6 @@ void CollisionDetection::computeMiddlePhase() { PROFILE("CollisionDetection::computeMiddlePhase()"); - // Clear the set of overlapping pairs in narrow-phase contact - mContactOverlappingPairs.clear(); - // For each possible collision pair of bodies map::iterator it; for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ) { @@ -258,11 +255,6 @@ void CollisionDetection::computeNarrowPhase() { // Add the contact points as a potential contact manifold into the pair currentNarrowPhaseInfo->addContactPointsAsPotentialContactManifold(); - // Add the overlapping pair into the set of pairs in contact during narrow-phase - overlappingpairid pairId = OverlappingPair::computeID(currentNarrowPhaseInfo->overlappingPair->getShape1(), - currentNarrowPhaseInfo->overlappingPair->getShape2()); - mContactOverlappingPairs[pairId] = currentNarrowPhaseInfo->overlappingPair; - currentNarrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasColliding = true; } else { @@ -349,7 +341,7 @@ void CollisionDetection::addAllContactManifoldsToBodies() { // For each overlapping pairs in contact during the narrow-phase std::map::iterator it; - for (it = mContactOverlappingPairs.begin(); it != mContactOverlappingPairs.end(); ++it) { + for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ++it) { // Add all the contact manifolds of the pair into the list of contact manifolds // of the two bodies involved in the contact @@ -396,7 +388,7 @@ void CollisionDetection::processAllPotentialContacts() { // For each overlapping pairs in contact during the narrow-phase std::map::iterator it; - for (it = mContactOverlappingPairs.begin(); it != mContactOverlappingPairs.end(); ++it) { + for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ++it) { // Process the potential contacts of the overlapping pair processPotentialContacts(it->second); @@ -430,7 +422,7 @@ void CollisionDetection::reportAllContacts() { // For each overlapping pairs in contact during the narrow-phase std::map::iterator it; - for (it = mContactOverlappingPairs.begin(); it != mContactOverlappingPairs.end(); ++it) { + for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ++it) { // If there is a user callback if (mWorld->mEventListener != nullptr && it->second->hasContacts()) { diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index 49f0d56b..848e7d09 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -86,9 +86,6 @@ class CollisionDetection { /// Broad-phase overlapping pairs std::map mOverlappingPairs; - /// Overlapping pairs in contact (during the current Narrow-phase collision detection) - std::map mContactOverlappingPairs; - /// Broad-phase algorithm BroadPhaseAlgorithm mBroadPhaseAlgorithm; From dd91f6dcbf49eaba97d15b603cf3fcf36ba60426 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 4 Sep 2017 22:23:29 +0200 Subject: [PATCH 097/248] Fix typo --- src/collision/CollisionDetection.cpp | 6 +++--- src/collision/ContactManifold.cpp | 6 +++--- src/collision/ContactManifold.h | 28 ++++++++++++++-------------- src/collision/ContactManifoldSet.cpp | 16 ++++++++-------- src/collision/ContactManifoldSet.h | 8 ++++---- src/constraint/ContactPoint.cpp | 6 +++--- src/constraint/ContactPoint.h | 24 ++++++++++++------------ src/engine/OverlappingPair.h | 16 ++++++++-------- 8 files changed, 55 insertions(+), 55 deletions(-) diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 3f9a45f6..b284c034 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -103,7 +103,7 @@ void CollisionDetection::computeMiddlePhase() { OverlappingPair* pair = it->second; - // Make all the contact manifolds and contact points of the pair obselete + // Make all the contact manifolds and contact points of the pair obsolete pair->makeContactsObselete(); ProxyShape* shape1 = pair->getShape1(); @@ -410,8 +410,8 @@ void CollisionDetection::processPotentialContacts(OverlappingPair* pair) { potentialManifold = potentialManifold->mNext; } - // Clear the obselete contact manifolds and contact points - pair->clearObseleteManifoldsAndContactPoints(); + // Clear the obsolete contact manifolds and contact points + pair->clearObsoleteManifoldsAndContactPoints(); // Reset the potential contacts of the pair pair->clearPotentialContactManifolds(); diff --git a/src/collision/ContactManifold.cpp b/src/collision/ContactManifold.cpp index 803a9e82..62ca7a0c 100644 --- a/src/collision/ContactManifold.cpp +++ b/src/collision/ContactManifold.cpp @@ -34,7 +34,7 @@ ContactManifold::ContactManifold(const ContactManifoldInfo* manifoldInfo, ProxyS : mShape1(shape1), mShape2(shape2), mContactPoints(nullptr), mContactNormalId(manifoldInfo->getContactNormalId()), mNbContactPoints(0), mFrictionImpulse1(0.0), mFrictionImpulse2(0.0), mFrictionTwistImpulse(0.0), mIsAlreadyInIsland(false), - mMemoryAllocator(memoryAllocator), mNext(nullptr), mPrevious(nullptr), mIsObselete(false) { + mMemoryAllocator(memoryAllocator), mNext(nullptr), mPrevious(nullptr), mIsObsolete(false) { // For each contact point info in the manifold const ContactPointInfo* pointInfo = manifoldInfo->getFirstContactPointInfo(); @@ -87,7 +87,7 @@ void ContactManifold::addContactPoint(const ContactPointInfo* contactPointInfo) mNbContactPoints++; } -// Clear the obselete contact points +// Clear the obsolete contact points void ContactManifold::clearObseleteContactPoints() { ContactPoint* contactPoint = mContactPoints; @@ -96,7 +96,7 @@ void ContactManifold::clearObseleteContactPoints() { ContactPoint* nextContactPoint = contactPoint->getNext(); - if (contactPoint->getIsObselete()) { + if (contactPoint->getIsObsolete()) { // Delete the contact point contactPoint->~ContactPoint(); diff --git a/src/collision/ContactManifold.h b/src/collision/ContactManifold.h index ada20003..e34c4543 100644 --- a/src/collision/ContactManifold.h +++ b/src/collision/ContactManifold.h @@ -140,8 +140,8 @@ class ContactManifold { /// Pointer to the previous contact manifold in linked-list ContactManifold* mPrevious; - /// True if the contact manifold is obselete - bool mIsObselete; + /// True if the contact manifold is obsolete + bool mIsObsolete; // -------------------- Methods -------------------- // @@ -151,13 +151,13 @@ class ContactManifold { /// Set the pointer to the next element in the linked-list void setNext(ContactManifold* nextManifold); - /// Return true if the manifold is obselete - bool getIsObselete() const; + /// Return true if the manifold is obsolete + bool getIsObsolete() const; - /// Set to true to make the manifold obselete - void setIsObselete(bool isObselete, bool setContactPoints); + /// Set to true to make the manifold obsolete + void setIsObsolete(bool isObselete, bool setContactPoints); - /// Clear the obselete contact points + /// Clear the obsolete contact points void clearObseleteContactPoints(); /// Return the contact normal direction Id of the manifold @@ -384,19 +384,19 @@ inline void ContactManifold::setNext(ContactManifold* nextManifold) { mNext = nextManifold; } -// Return true if the manifold is obselete -inline bool ContactManifold::getIsObselete() const { - return mIsObselete; +// Return true if the manifold is obsolete +inline bool ContactManifold::getIsObsolete() const { + return mIsObsolete; } -// Set to true to make the manifold obselete -inline void ContactManifold::setIsObselete(bool isObselete, bool setContactPoints) { - mIsObselete = isObselete; +// Set to true to make the manifold obsolete +inline void ContactManifold::setIsObsolete(bool isObsolete, bool setContactPoints) { + mIsObsolete = isObsolete; if (setContactPoints) { ContactPoint* contactPoint = mContactPoints; while (contactPoint != nullptr) { - contactPoint->setIsObselete(isObselete); + contactPoint->setIsObsolete(isObsolete); contactPoint = contactPoint->getNext(); } diff --git a/src/collision/ContactManifoldSet.cpp b/src/collision/ContactManifoldSet.cpp index fb3beda2..5ad8ce71 100644 --- a/src/collision/ContactManifoldSet.cpp +++ b/src/collision/ContactManifoldSet.cpp @@ -131,8 +131,8 @@ void ContactManifoldSet::updateManifoldWithNewOne(ContactManifold* oldManifold, contactPointInfo = contactPointInfo->next; } - // The old manifold is no longer obselete - oldManifold->setIsObselete(false, false); + // The old manifold is no longer obsolete + oldManifold->setIsObsolete(false, false); } // Return the manifold with the smallest contact penetration depth among its points @@ -270,27 +270,27 @@ void ContactManifoldSet::removeManifold(ContactManifold* manifold) { mNbManifolds--; } -// Make all the contact manifolds and contact points obselete -void ContactManifoldSet::makeContactsObselete() { +// Make all the contact manifolds and contact points obsolete +void ContactManifoldSet::makeContactsObsolete() { ContactManifold* manifold = mManifolds; while (manifold != nullptr) { - manifold->setIsObselete(true, true); + manifold->setIsObsolete(true, true); manifold = manifold->getNext(); } } -// Clear the obselete contact manifolds and contact points -void ContactManifoldSet::clearObseleteManifoldsAndContactPoints() { +// Clear the obsolete contact manifolds and contact points +void ContactManifoldSet::clearObsoleteManifoldsAndContactPoints() { ContactManifold* manifold = mManifolds; ContactManifold* previousManifold = nullptr; while (manifold != nullptr) { ContactManifold* nextManifold = manifold->getNext(); - if (manifold->getIsObselete()) { + if (manifold->getIsObsolete()) { if (previousManifold != nullptr) { previousManifold->setNext(nextManifold); diff --git a/src/collision/ContactManifoldSet.h b/src/collision/ContactManifoldSet.h index 0990277c..1676f5a2 100644 --- a/src/collision/ContactManifoldSet.h +++ b/src/collision/ContactManifoldSet.h @@ -115,14 +115,14 @@ class ContactManifoldSet { /// Return a pointer to the first element of the linked-list of contact manifolds ContactManifold* getContactManifolds() const; - /// Make all the contact manifolds and contact points obselete - void makeContactsObselete(); + /// Make all the contact manifolds and contact points obsolete + void makeContactsObsolete(); /// Return the total number of contact points in the set of manifolds int getTotalNbContactPoints() const; - /// Clear the obselete contact manifolds and contact points - void clearObseleteManifoldsAndContactPoints(); + /// Clear the obsolete contact manifolds and contact points + void clearObsoleteManifoldsAndContactPoints(); // Map the normal vector into a cubemap face bucket (a face contains 4x4 buckets) // Each face of the cube is divided into 4x4 buckets. This method maps the diff --git a/src/constraint/ContactPoint.cpp b/src/constraint/ContactPoint.cpp index fa6838ec..2cd951b4 100644 --- a/src/constraint/ContactPoint.cpp +++ b/src/constraint/ContactPoint.cpp @@ -37,7 +37,7 @@ ContactPoint::ContactPoint(const ContactPointInfo* contactInfo, const Transform& mPenetrationDepth(contactInfo->penetrationDepth), mLocalPointOnBody1(contactInfo->localPoint1), mLocalPointOnBody2(contactInfo->localPoint2), - mIsRestingContact(false), mIsObselete(false), mNext(nullptr) { + mIsRestingContact(false), mIsObsolete(false), mNext(nullptr) { assert(mPenetrationDepth > decimal(0.0)); @@ -45,7 +45,7 @@ ContactPoint::ContactPoint(const ContactPointInfo* contactInfo, const Transform& mWorldPointOnBody1 = body1Transform * mLocalPointOnBody1; mWorldPointOnBody2 = body2Transform * mLocalPointOnBody2; - mIsObselete = false; + mIsObsolete = false; } // Update the contact point with a new one that is similar (very close) @@ -64,5 +64,5 @@ void ContactPoint::update(const ContactPointInfo* contactInfo, const Transform& mWorldPointOnBody1 = body1Transform * mLocalPointOnBody1; mWorldPointOnBody2 = body2Transform * mLocalPointOnBody2; - mIsObselete = false; + mIsObsolete = false; } diff --git a/src/constraint/ContactPoint.h b/src/constraint/ContactPoint.h index 41cc35e4..288abdcc 100644 --- a/src/constraint/ContactPoint.h +++ b/src/constraint/ContactPoint.h @@ -71,8 +71,8 @@ class ContactPoint { /// Cached penetration impulse decimal mPenetrationImpulse; - /// True if the contact point is obselete - bool mIsObselete; + /// True if the contact point is obsolete + bool mIsObsolete; /// Pointer to the next contact point in the linked-list ContactPoint* mNext; @@ -93,14 +93,14 @@ class ContactPoint { /// Set the mIsRestingContact variable void setIsRestingContact(bool isRestingContact); - /// Set to true to make the contact point obselete - void setIsObselete(bool isObselete); + /// Set to true to make the contact point obsolete + void setIsObsolete(bool isObselete); /// Set the next contact point in the linked list void setNext(ContactPoint* next); - /// Return true if the contact point is obselete - bool getIsObselete() const; + /// Return true if the contact point is obsolete + bool getIsObsolete() const; public : @@ -206,14 +206,14 @@ inline void ContactPoint::setIsRestingContact(bool isRestingContact) { mIsRestingContact = isRestingContact; } -// Return true if the contact point is obselete -inline bool ContactPoint::getIsObselete() const { - return mIsObselete; +// Return true if the contact point is obsolete +inline bool ContactPoint::getIsObsolete() const { + return mIsObsolete; } -// Set to true to make the contact point obselete -inline void ContactPoint::setIsObselete(bool isObselete) { - mIsObselete = isObselete; +// Set to true to make the contact point obsolete +inline void ContactPoint::setIsObsolete(bool isObsolete) { + mIsObsolete = isObsolete; } // Return the next contact point in the linked list diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index e8c89dda..5141b8cc 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -164,11 +164,11 @@ class OverlappingPair { /// Reduce the number of contact points of all the potential contact manifolds void reducePotentialContactManifolds(); - /// Make the contact manifolds and contact points obselete + /// Make the contact manifolds and contact points obsolete void makeContactsObselete(); - /// Clear the obselete contact manifold and contact points - void clearObseleteManifoldsAndContactPoints(); + /// Clear the obsolete contact manifold and contact points + void clearObsoleteManifoldsAndContactPoints(); /// Return the pair of bodies index static overlappingpairid computeID(ProxyShape* shape1, ProxyShape* shape2); @@ -211,10 +211,10 @@ inline const ContactManifoldSet& OverlappingPair::getContactManifoldSet() { return mContactManifoldSet; } -// Make the contact manifolds and contact points obselete +// Make the contact manifolds and contact points obsolete inline void OverlappingPair::makeContactsObselete() { - mContactManifoldSet.makeContactsObselete(); + mContactManifoldSet.makeContactsObsolete(); } // Return the pair of bodies index @@ -262,9 +262,9 @@ inline ContactManifoldInfo* OverlappingPair::getPotentialContactManifolds() { return mPotentialContactManifolds; } -// Clear the obselete contact manifold and contact points -inline void OverlappingPair::clearObseleteManifoldsAndContactPoints() { - mContactManifoldSet.clearObseleteManifoldsAndContactPoints(); +// Clear the obsolete contact manifold and contact points +inline void OverlappingPair::clearObsoleteManifoldsAndContactPoints() { + mContactManifoldSet.clearObsoleteManifoldsAndContactPoints(); } } From 1b82a3e22891ce863e94c70b8ecc842a7ed75b8c Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 7 Sep 2017 22:23:00 +0200 Subject: [PATCH 098/248] Fix issue in GJK algorithm when numerical issue occurs --- src/collision/narrowphase/GJK/GJKAlgorithm.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp index 9bc1d00d..7979f1df 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp @@ -198,7 +198,7 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhase // If the penetration depth is negative (due too numerical errors), there is no contact if (penetrationDepth <= decimal(0.0)) { - return GJKResult::INTERPENETRATE; + return GJKResult::SEPARATED; } // Do not generate a contact point with zero normal length From b8907730537bd34ea5cbff8007b1c4a7ec3f7006 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 7 Sep 2017 22:24:30 +0200 Subject: [PATCH 099/248] Fix issue when computing clipping planes in SAT algorithm --- .../narrowphase/SAT/SATAlgorithm.cpp | 23 ++++++++++++++----- 1 file changed, 17 insertions(+), 6 deletions(-) diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index d1062704..7a11fbf7 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -256,7 +256,6 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfo* narro capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, narrowPhaseInfo, isCapsuleShape1); } - } else { // The separating axis is the cross product of a polyhedron edge and the inner capsule segment @@ -352,6 +351,10 @@ void SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceI NarrowPhaseInfo* narrowPhaseInfo, bool isCapsuleShape1) const { HalfEdgeStructure::Face face = polyhedron->getFace(referenceFaceIndex); + + // Get the face normal + Vector3 faceNormal = polyhedron->getFaceNormal(referenceFaceIndex); + uint firstEdgeIndex = face.edgeIndex; uint edgeIndex = firstEdgeIndex; @@ -360,12 +363,22 @@ void SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceI // For each adjacent edge of the separating face of the polyhedron do { + HalfEdgeStructure::Edge edge = polyhedron->getHalfEdge(edgeIndex); HalfEdgeStructure::Edge twinEdge = polyhedron->getHalfEdge(edge.twinEdgeIndex); - // Construct a clippling plane for each adjacent edge of the separting face of the polyhedron + // Compute the edge vertices and edge direction + Vector3 edgeV1 = polyhedron->getVertexPosition(edge.vertexIndex); + Vector3 edgeV2 = polyhedron->getVertexPosition(twinEdge.vertexIndex); + Vector3 edgeDirection = edgeV2 - edgeV1; + + // Compute the normal of the clipping plane for this edge + // The clipping plane is perpendicular to the edge direction and the reference face normal + Vector3 clipPlaneNormal = faceNormal.cross(edgeDirection); + + // Construct a clipping plane for each adjacent edge of the separating face of the polyhedron planesPoints.push_back(polyhedron->getVertexPosition(edge.vertexIndex)); - planesNormals.push_back(-polyhedron->getFaceNormal(twinEdge.faceIndex)); + planesNormals.push_back(clipPlaneNormal); edgeIndex = edge.nextEdgeIndex; @@ -373,9 +386,7 @@ void SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceI // First we clip the inner segment of the capsule with the four planes of the adjacent faces std::vector clipSegment = clipSegmentWithPlanes(capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, planesPoints, planesNormals); - assert(clipSegment.size() == 2); - - const Vector3 faceNormal = polyhedron->getFaceNormal(referenceFaceIndex); + assert(clipSegment.size() == 2); // Project the two clipped points into the polyhedron face const Vector3 delta = faceNormal * (penetrationDepth - capsuleRadius); From 8cb2ec7e177453c3fa990d1ab6461416bbf4ea9b Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Fri, 8 Sep 2017 07:38:57 +0200 Subject: [PATCH 100/248] Remove wrong assert --- src/collision/narrowphase/SAT/SATAlgorithm.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 7a11fbf7..2f345738 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -845,7 +845,6 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene // Clip the reference faces with the adjacent planes of the reference face std::vector clipPolygonVertices = clipPolygonWithPlanes(polygonVertices, planesPoints, planesNormals); - assert(clipPolygonVertices.size() > 0); // We only keep the clipped points that are below the reference face const Vector3 referenceFaceVertex = referencePolyhedron->getVertexPosition(referencePolyhedron->getHalfEdge(firstEdgeIndex).vertexIndex); From 709bed3cec3cc5f6ec3e8ee77fc5d29bc24f8fa3 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sat, 9 Sep 2017 15:37:55 +0200 Subject: [PATCH 101/248] Fix issues with GJK algorithm --- .../narrowphase/GJK/GJKAlgorithm.cpp | 22 +++++-------------- src/engine/OverlappingPair.h | 2 ++ 2 files changed, 8 insertions(+), 16 deletions(-) diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp index 7979f1df..629811eb 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp @@ -66,8 +66,6 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhase const ConvexShape* shape1 = static_cast(narrowPhaseInfo->collisionShape1); const ConvexShape* shape2 = static_cast(narrowPhaseInfo->collisionShape2); - bool isPolytopeShape = shape1->isPolyhedron() && shape2->isPolyhedron(); - // Get the local-space to world-space transforms const Transform& transform1 = narrowPhaseInfo->shape1ToWorldTransform; const Transform& transform2 = narrowPhaseInfo->shape2ToWorldTransform; @@ -95,6 +93,7 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhase LastFrameCollisionInfo& lastFrameInfo = narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo(); if (lastFrameInfo.isValid && lastFrameInfo.wasUsingGJK) { v = lastFrameInfo.gjkSeparatingAxis; + assert(v.lengthSquare() > decimal(0.000001)); } else { v.setAllValues(0, 1, 0); @@ -140,8 +139,7 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhase // Contact point has been found contactFound = true; - - return GJKResult::INTERPENETRATE; + break; } // Compute the point of the simplex closest to the origin @@ -150,14 +148,7 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhase // Contact point has been found contactFound = true; - - return GJKResult::INTERPENETRATE; - } - - // Closest point is almost the origin, go to EPA algorithm - // Vector v to small to continue computing support points - if (v.lengthSquare() < MACHINE_EPSILON) { - return GJKResult::INTERPENETRATE; + break; } // Store and update the squared distance of the closest point @@ -177,8 +168,7 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhase break; } - } while((isPolytopeShape && !simplex.isFull()) || (!isPolytopeShape && !simplex.isFull() && - distSquare > MACHINE_EPSILON * simplex.getMaxLengthSquareOfAPoint())); + } while(!simplex.isFull() && distSquare > MACHINE_EPSILON * simplex.getMaxLengthSquareOfAPoint()); if (contactFound && distSquare > MACHINE_EPSILON) { @@ -203,7 +193,7 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhase // Do not generate a contact point with zero normal length if (normal.lengthSquare() < MACHINE_EPSILON) { - return GJKResult::INTERPENETRATE; + return GJKResult::SEPARATED; } if (reportContacts) { @@ -219,7 +209,7 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhase return GJKResult::COLLIDE_IN_MARGIN; } - return GJKResult::SEPARATED; + return GJKResult::INTERPENETRATE; } diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index 5141b8cc..bb7c1048 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -79,6 +79,8 @@ struct LastFrameCollisionInfo { wasColliding = false; wasUsingSAT = false; wasUsingGJK = false; + + gjkSeparatingAxis = Vector3(0, 1, 0); } }; From 63833621a046d58e95a99b73ed35e2beb1ed7658 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 12 Sep 2017 23:25:21 +0200 Subject: [PATCH 102/248] Fix issue with triangle shape normal computation --- src/collision/shapes/TriangleShape.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/collision/shapes/TriangleShape.cpp b/src/collision/shapes/TriangleShape.cpp index 48baa225..254bc5a1 100644 --- a/src/collision/shapes/TriangleShape.cpp +++ b/src/collision/shapes/TriangleShape.cpp @@ -52,7 +52,7 @@ TriangleShape::TriangleShape(const Vector3& point1, const Vector3& point2, const mPoints[2] = point3; // Compute the triangle normal - mNormal = (point3 - point1).cross(point2 - point1); + mNormal = (point2 - point1).cross(point3 - point1); mNormal.normalize(); mVerticesNormals[0] = verticesNormals[0]; From 643c781fa09b050bbe85e71f57b14353bc421470 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 21 Sep 2017 22:44:42 +0200 Subject: [PATCH 103/248] Fix issues with smooth triangle contact --- .../narrowphase/SAT/SATAlgorithm.cpp | 6 ++-- src/collision/shapes/TriangleShape.cpp | 34 +++++++++---------- src/collision/shapes/TriangleShape.h | 2 +- 3 files changed, 22 insertions(+), 20 deletions(-) diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 2f345738..0d2ae20e 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -857,6 +857,8 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene contactPointsFound = true; + Vector3 outWorldNormal = normalWorld; + // Convert the clip incident polyhedron vertex into the incident polyhedron local-space Vector3 contactPointIncidentPolyhedron = referenceToIncidentTransform * (*itPoints); @@ -868,10 +870,10 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene isMinPenetrationFaceNormalPolyhedron1 ? contactPointReferencePolyhedron : contactPointIncidentPolyhedron, isMinPenetrationFaceNormalPolyhedron1 ? contactPointIncidentPolyhedron : contactPointReferencePolyhedron, narrowPhaseInfo->shape1ToWorldTransform, narrowPhaseInfo->shape2ToWorldTransform, - minPenetrationDepth, normalWorld); + minPenetrationDepth, outWorldNormal); // Create a new contact point - narrowPhaseInfo->addContactPoint(normalWorld, minPenetrationDepth, + narrowPhaseInfo->addContactPoint(outWorldNormal, minPenetrationDepth, isMinPenetrationFaceNormalPolyhedron1 ? contactPointReferencePolyhedron : contactPointIncidentPolyhedron, isMinPenetrationFaceNormalPolyhedron1 ? contactPointIncidentPolyhedron : contactPointReferencePolyhedron); } diff --git a/src/collision/shapes/TriangleShape.cpp b/src/collision/shapes/TriangleShape.cpp index 254bc5a1..263595b3 100644 --- a/src/collision/shapes/TriangleShape.cpp +++ b/src/collision/shapes/TriangleShape.cpp @@ -85,14 +85,9 @@ void TriangleShape::computeSmoothTriangleMeshContact(const CollisionShape* shape triangleShape->computeSmoothMeshContact(isShape1Triangle ? localContactPointShape1 : localContactPointShape2, isShape1Triangle ? shape1ToWorld : shape2ToWorld, isShape1Triangle ? shape2ToWorld.getInverse() : shape1ToWorld.getInverse(), - penetrationDepth, + penetrationDepth, isShape1Triangle, isShape1Triangle ? localContactPointShape2 : localContactPointShape1, outSmoothVertexNormal); - - // Make sure the direction of the contact normal is from shape1 to shape2 - if (!isShape1Triangle) { - outSmoothVertexNormal = -outSmoothVertexNormal; - } } } @@ -104,25 +99,30 @@ void TriangleShape::computeSmoothTriangleMeshContact(const CollisionShape* shape // stay aligned with the new contact normal. This method will return the new smooth world contact // normal of the triangle and the the local contact point on the other shape. void TriangleShape::computeSmoothMeshContact(Vector3 localContactPointTriangle, const Transform& triangleShapeToWorldTransform, - const Transform& worldToOtherShapeTransform, decimal penetrationDepth, + const Transform& worldToOtherShapeTransform, decimal penetrationDepth, bool isTriangleShape1, Vector3& outNewLocalContactPointOtherShape, Vector3& outSmoothWorldContactTriangleNormal) const { // Get the smooth contact normal of the mesh at the contact point on the triangle - Vector3 localNormal = computeSmoothLocalContactNormalForTriangle(localContactPointTriangle); + Vector3 triangleLocalNormal = computeSmoothLocalContactNormalForTriangle(localContactPointTriangle); // Convert the local contact normal into world-space - outSmoothWorldContactTriangleNormal = triangleShapeToWorldTransform.getOrientation() * localNormal; + Vector3 triangleWorldNormal = triangleShapeToWorldTransform.getOrientation() * triangleLocalNormal; - // Convert the contact normal into the local-space of the other shape - Vector3 normalOtherShape = worldToOtherShapeTransform.getOrientation() * outSmoothWorldContactTriangleNormal; + // Penetration axis with direction from triangle to other shape + Vector3 triangleToOtherShapePenAxis = isTriangleShape1 ? outSmoothWorldContactTriangleNormal : -outSmoothWorldContactTriangleNormal; - // Convert the local contact point of the triangle into the local-space of the other shape - Vector3 trianglePointOtherShape = worldToOtherShapeTransform * triangleShapeToWorldTransform * - localContactPointTriangle; + // The triangle normal should be the one in the direction out of the current colliding face of the triangle + if (triangleWorldNormal.dot(triangleToOtherShapePenAxis) < decimal(0.0)) { + triangleWorldNormal = -triangleWorldNormal; + triangleLocalNormal = -triangleLocalNormal; + } - // Re-align the local contact point on the other shape such that it is aligned along - // the new contact normal - Vector3 otherShapePoint = trianglePointOtherShape - normalOtherShape * penetrationDepth; + // Compute the final contact normal from shape 1 to shape 2 + outSmoothWorldContactTriangleNormal = isTriangleShape1 ? triangleWorldNormal : -triangleWorldNormal; + + // Re-align the local contact point on the other shape such that it is aligned along the new contact normal + Vector3 otherShapePointTriangleSpace = localContactPointTriangle - triangleLocalNormal * penetrationDepth; + Vector3 otherShapePoint = worldToOtherShapeTransform * triangleShapeToWorldTransform * otherShapePointTriangleSpace; outNewLocalContactPointOtherShape.setAllValues(otherShapePoint.x, otherShapePoint.y, otherShapePoint.z); } diff --git a/src/collision/shapes/TriangleShape.h b/src/collision/shapes/TriangleShape.h index c31a594c..8360c32b 100644 --- a/src/collision/shapes/TriangleShape.h +++ b/src/collision/shapes/TriangleShape.h @@ -99,7 +99,7 @@ class TriangleShape : public ConvexPolyhedronShape { /// This method implements the technique described in Game Physics Pearl book void computeSmoothMeshContact(Vector3 localContactPointTriangle, const Transform& triangleShapeToWorldTransform, - const Transform& worldToOtherShapeTransform, decimal penetrationDepth, + const Transform& worldToOtherShapeTransform, decimal penetrationDepth, bool isTriangleShape1, Vector3& outNewLocalContactPointOtherShape, Vector3& outSmoothWorldContactTriangleNormal) const; public: From b33b8e0dc5e59e378839e135e09b4ca3b1e5ab9f Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 25 Sep 2017 23:06:17 +0200 Subject: [PATCH 104/248] Fix issue in SAT algorithm between polyhedron and capsule --- src/collision/narrowphase/SAT/SATAlgorithm.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 0d2ae20e..a663791c 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -391,6 +391,10 @@ void SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceI // Project the two clipped points into the polyhedron face const Vector3 delta = faceNormal * (penetrationDepth - capsuleRadius); + if (isCapsuleShape1) { + normalWorld = -normalWorld; + } + // For each of the two clipped points for (int i = 0; i<2; i++) { @@ -405,9 +409,7 @@ void SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceI // Project the clipped point into the capsule bounds Vector3 contactPointCapsule = (polyhedronToCapsuleTransform * clipSegment[i]) - separatingAxisCapsuleSpace * capsuleRadius; - if (isCapsuleShape1) { - normalWorld = -normalWorld; - } + // Compute smooth triangle mesh contact if one of the two collision shapes is a triangle TriangleShape::computeSmoothTriangleMeshContact(narrowPhaseInfo->collisionShape1, narrowPhaseInfo->collisionShape2, From 310fef1c523c67d34201cef43a9177789d6bac66 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 28 Sep 2017 08:34:45 +0200 Subject: [PATCH 105/248] Fix issue with middle phase collision detection (AABB not computed in correct space) --- src/collision/CollisionDetection.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index b284c034..f27b5ddf 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -218,10 +218,10 @@ void CollisionDetection::computeConvexVsConcaveMiddlePhase(OverlappingPair* pair concaveShape, allocator); // Compute the convex shape AABB in the local-space of the convex shape + const Transform convexToConcaveTransform = concaveProxyShape->getLocalToWorldTransform().getInverse() * + convexProxyShape->getLocalToWorldTransform(); AABB aabb; - convexShape->computeAABB(aabb, convexProxyShape->getLocalToWorldTransform()); - - // TODO : Implement smooth concave mesh collision somewhere + convexShape->computeAABB(aabb, convexToConcaveTransform); // Call the convex vs triangle callback for each triangle of the concave shape concaveShape->testAllTriangles(middlePhaseCallback, aabb); From cbfeb608df332cade904b64a744c8291cff42f5d Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 4 Oct 2017 22:38:14 +0200 Subject: [PATCH 106/248] Fix bug and clean the pointers casting in TriangleVertexArray --- src/collision/TriangleVertexArray.cpp | 90 ++++++++++++--------------- src/collision/TriangleVertexArray.h | 49 +++++++-------- src/configuration.h | 2 + 3 files changed, 67 insertions(+), 74 deletions(-) diff --git a/src/collision/TriangleVertexArray.cpp b/src/collision/TriangleVertexArray.cpp index fa87e684..56f3b422 100644 --- a/src/collision/TriangleVertexArray.cpp +++ b/src/collision/TriangleVertexArray.cpp @@ -44,20 +44,20 @@ using namespace reactphysics3d; * @param verticesStride Number of bytes between the beginning of two consecutive vertices * @param nbTriangles Number of triangles in the array * @param indexesStart Pointer to the first triangle index - * @param indexesStride Number of bytes between the beginning of two consecutive triangle indices + * @param indexesStride Number of bytes between the beginning of the three indices of two triangles * @param vertexDataType Type of data for the vertices (float, double) * @param indexDataType Type of data for the indices (short, int) */ -TriangleVertexArray::TriangleVertexArray(uint nbVertices, void* verticesStart, int verticesStride, - uint nbTriangles, void* indexesStart, int indexesStride, +TriangleVertexArray::TriangleVertexArray(uint nbVertices, const void* verticesStart, uint verticesStride, + uint nbTriangles, const void* indexesStart, uint indexesStride, VertexDataType vertexDataType, IndexDataType indexDataType) { mNbVertices = nbVertices; - mVerticesStart = reinterpret_cast(verticesStart); + mVerticesStart = static_cast(verticesStart); mVerticesStride = verticesStride; mVerticesNormalsStart = nullptr; - mVerticesNormalsStride = 0; + mVerticesNormalsStride = 3 * sizeof(float); mNbTriangles = nbTriangles; - mIndicesStart = reinterpret_cast(indexesStart); + mIndicesStart = static_cast(indexesStart); mIndicesStride = indexesStride; mVertexDataType = vertexDataType; mVertexNormaldDataType = NormalDataType::NORMAL_FLOAT_TYPE; @@ -85,19 +85,19 @@ TriangleVertexArray::TriangleVertexArray(uint nbVertices, void* verticesStart, i * @param vertexDataType Type of data for the vertices (float, double) * @param indexDataType Type of data for the indices (short, int) */ -TriangleVertexArray::TriangleVertexArray(uint nbVertices, void* verticesStart, int verticesStride, - void* verticesNormalsStart, int verticesNormalsStride, - uint nbTriangles, void* indexesStart, int indexesStride, +TriangleVertexArray::TriangleVertexArray(uint nbVertices, const void* verticesStart, uint verticesStride, + const void* verticesNormalsStart, uint verticesNormalsStride, + uint nbTriangles, const void* indexesStart, uint indexesStride, VertexDataType vertexDataType, NormalDataType normalDataType, IndexDataType indexDataType) { mNbVertices = nbVertices; - mVerticesStart = reinterpret_cast(verticesStart); + mVerticesStart = static_cast(verticesStart); mVerticesStride = verticesStride; - mVerticesNormalsStart = reinterpret_cast(verticesNormalsStart); + mVerticesNormalsStart = static_cast(verticesNormalsStart); mVerticesNormalsStride = verticesNormalsStride; mNbTriangles = nbTriangles; - mIndicesStart = reinterpret_cast(indexesStart); + mIndicesStart = static_cast(indexesStart); mIndicesStride = indexesStride; mVertexDataType = vertexDataType; mVertexNormaldDataType = normalDataType; @@ -114,7 +114,8 @@ TriangleVertexArray::~TriangleVertexArray() { if (!mAreVerticesNormalsProvidedByUser) { // Release the allocated memory - float* verticesNormals = reinterpret_cast(mVerticesNormalsStart); + const void* verticesNormalPointer = static_cast(mVerticesNormalsStart); + const float* verticesNormals = static_cast(verticesNormalPointer); delete[] verticesNormals; } } @@ -160,12 +161,15 @@ void TriangleVertexArray::computeVerticesNormals() { Vector3 crossProduct = a.cross(b); decimal sinA = crossProduct.length() / (edgesLengths[previousVertex] * edgesLengths[v]); - Vector3 normalComponent = std::asin(sinA) * crossProduct; + sinA = std::min(std::max(sinA, decimal(0.0)), decimal(1.0)); + decimal arcSinA = std::asin(sinA); + assert(arcSinA >= decimal(0.0)); + Vector3 normalComponent = arcSinA * crossProduct; // Add the normal component of this vertex into the normals array - verticesNormals[verticesIndices[v] * 3] = normalComponent.x; - verticesNormals[verticesIndices[v] * 3 + 1] = normalComponent.y; - verticesNormals[verticesIndices[v] * 3 + 2] = normalComponent.z; + verticesNormals[verticesIndices[v] * 3] += normalComponent.x; + verticesNormals[verticesIndices[v] * 3 + 1] += normalComponent.y; + verticesNormals[verticesIndices[v] * 3 + 2] += normalComponent.z; } } @@ -181,7 +185,8 @@ void TriangleVertexArray::computeVerticesNormals() { verticesNormals[v + 2] = normal.z; } - mVerticesNormalsStart = reinterpret_cast(verticesNormals); + const void* verticesNormalsPointer = static_cast(verticesNormals); + mVerticesNormalsStart = static_cast(verticesNormalsPointer); } // Return the indices of the three vertices of a given triangle in the array @@ -189,17 +194,18 @@ void TriangleVertexArray::getTriangleVerticesIndices(uint triangleIndex, uint* o assert(triangleIndex >= 0 && triangleIndex < mNbTriangles); - void* vertexIndexPointer = (mIndicesStart + triangleIndex * 3 * mIndicesStride); + const uchar* triangleIndicesPointer = mIndicesStart + triangleIndex * 3 * mIndicesStride; + const void* startTriangleIndices = static_cast(triangleIndicesPointer); // For each vertex of the triangle for (int i=0; i < 3; i++) { // Get the index of the current vertex in the triangle if (mIndexDataType == TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE) { - outVerticesIndices[i] = ((uint*)vertexIndexPointer)[i]; + outVerticesIndices[i] = static_cast(startTriangleIndices)[i]; } else if (mIndexDataType == TriangleVertexArray::IndexDataType::INDEX_SHORT_TYPE) { - outVerticesIndices[i] = ((unsigned short*)vertexIndexPointer)[i]; + outVerticesIndices[i] = static_cast(startTriangleIndices)[i]; } else { assert(false); @@ -212,32 +218,25 @@ void TriangleVertexArray::getTriangleVertices(uint triangleIndex, Vector3* outTr assert(triangleIndex >= 0 && triangleIndex < mNbTriangles); - void* vertexIndexPointer = (mIndicesStart + triangleIndex * 3 * mIndicesStride); + // Get the three vertex index of the three vertices of the triangle + uint verticesIndices[3]; + getTriangleVerticesIndices(triangleIndex, verticesIndices); // For each vertex of the triangle for (int k=0; k < 3; k++) { - // Get the index of the current vertex in the triangle - int vertexIndex = 0; - if (mIndexDataType == TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE) { - vertexIndex = ((uint*)vertexIndexPointer)[k]; - } - else if (mIndexDataType == TriangleVertexArray::IndexDataType::INDEX_SHORT_TYPE) { - vertexIndex = ((unsigned short*)vertexIndexPointer)[k]; - } - else { - assert(false); - } + const uchar* vertexPointerChar = mVerticesStart + verticesIndices[k] * mVerticesStride; + const void* vertexPointer = static_cast(vertexPointerChar); // Get the vertices components of the triangle if (mVertexDataType == TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE) { - const float* vertices = (float*)(mVerticesStart + vertexIndex * mVerticesStride); + const float* vertices = static_cast(vertexPointer); outTriangleVertices[k][0] = decimal(vertices[0]); outTriangleVertices[k][1] = decimal(vertices[1]); outTriangleVertices[k][2] = decimal(vertices[2]); } else if (mVertexDataType == TriangleVertexArray::VertexDataType::VERTEX_DOUBLE_TYPE) { - const double* vertices = (double*)(mVerticesStart + vertexIndex * mVerticesStride); + const double* vertices = static_cast(vertexPointer); outTriangleVertices[k][0] = decimal(vertices[0]); outTriangleVertices[k][1] = decimal(vertices[1]); outTriangleVertices[k][2] = decimal(vertices[2]); @@ -253,32 +252,25 @@ void TriangleVertexArray::getTriangleVerticesNormals(uint triangleIndex, Vector3 assert(triangleIndex >= 0 && triangleIndex < mNbTriangles); - void* vertexIndexPointer = (mIndicesStart + triangleIndex * 3 * mIndicesStride); + // Get the three vertex index of the three vertices of the triangle + uint verticesIndices[3]; + getTriangleVerticesIndices(triangleIndex, verticesIndices); // For each vertex of the triangle for (int k=0; k < 3; k++) { - // Get the index of the current vertex in the triangle - int vertexIndex = 0; - if (mIndexDataType == TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE) { - vertexIndex = ((uint*)vertexIndexPointer)[k]; - } - else if (mIndexDataType == TriangleVertexArray::IndexDataType::INDEX_SHORT_TYPE) { - vertexIndex = ((unsigned short*)vertexIndexPointer)[k]; - } - else { - assert(false); - } + const uchar* vertexNormalPointerChar = mVerticesNormalsStart + verticesIndices[k] * mVerticesNormalsStride; + const void* vertexNormalPointer = static_cast(vertexNormalPointerChar); // Get the normals from the array if (mVertexNormaldDataType == TriangleVertexArray::NormalDataType::NORMAL_FLOAT_TYPE) { - const float* normal = (float*)(mVerticesNormalsStart + vertexIndex * mVerticesNormalsStride); + const float* normal = static_cast(vertexNormalPointer); outTriangleVerticesNormals[k][0] = decimal(normal[0]); outTriangleVerticesNormals[k][1] = decimal(normal[1]); outTriangleVerticesNormals[k][2] = decimal(normal[2]); } else if (mVertexNormaldDataType == TriangleVertexArray::NormalDataType::NORMAL_DOUBLE_TYPE) { - const double* normal = (double*)(mVerticesNormalsStart + vertexIndex * mVerticesNormalsStride); + const double* normal = static_cast(vertexNormalPointer); outTriangleVerticesNormals[k][0] = decimal(normal[0]); outTriangleVerticesNormals[k][1] = decimal(normal[1]); outTriangleVerticesNormals[k][2] = decimal(normal[2]); diff --git a/src/collision/TriangleVertexArray.h b/src/collision/TriangleVertexArray.h index 20ae9387..3db79c7e 100644 --- a/src/collision/TriangleVertexArray.h +++ b/src/collision/TriangleVertexArray.h @@ -64,28 +64,27 @@ class TriangleVertexArray { uint mNbVertices; /// Pointer to the first vertex value in the array - unsigned char* mVerticesStart; + const uchar* mVerticesStart; /// Stride (number of bytes) between the beginning of two vertices /// values in the array - int mVerticesStride; + uint mVerticesStride; /// Pointer to the first vertex normal value in the array - unsigned char* mVerticesNormalsStart; + const uchar* mVerticesNormalsStart; /// Stride (number of bytes) between the beginning of two vertex normals /// values in the array - int mVerticesNormalsStride; + uint mVerticesNormalsStride; /// Number of triangles in the array uint mNbTriangles; /// Pointer to the first vertex index of the array - unsigned char* mIndicesStart; + const uchar* mIndicesStart; - /// Stride (number of bytes) between the beginning of two indices in - /// the array - int mIndicesStride; + /// Stride (number of bytes) between the beginning of the three indices of two triangles + uint mIndicesStride; /// Data type of the vertices in the array VertexDataType mVertexDataType; @@ -109,14 +108,14 @@ class TriangleVertexArray { // -------------------- Methods -------------------- // /// Constructor without vertices normals - TriangleVertexArray(uint nbVertices, void* verticesStart, int verticesStride, - uint nbTriangles, void* indexesStart, int indexesStride, + TriangleVertexArray(uint nbVertices, const void* verticesStart, uint verticesStride, + uint nbTriangles, const void* indexesStart, uint indexesStride, VertexDataType vertexDataType, IndexDataType indexDataType); /// Constructor with vertices normals - TriangleVertexArray(uint nbVertices, void* verticesStart, int verticesStride, - void* verticesNormalsStart, int verticesNormalsStride, - uint nbTriangles, void* indexesStart, int indexesStride, + TriangleVertexArray(uint nbVertices, const void* verticesStart, uint verticesStride, + const void* verticesNormalsStart, uint uverticesNormalsStride, + uint nbTriangles, const void* indexesStart, uint indexesStride, VertexDataType vertexDataType, NormalDataType normalDataType, IndexDataType indexDataType); @@ -139,22 +138,22 @@ class TriangleVertexArray { uint getNbTriangles() const; /// Return the vertices stride (number of bytes) - int getVerticesStride() const; + uint getVerticesStride() const; /// Return the vertex normals stride (number of bytes) - int getVerticesNormlasStride() const; + uint getVerticesNormlasStride() const; /// Return the indices stride (number of bytes) - int getIndicesStride() const; + uint getIndicesStride() const; /// Return the pointer to the start of the vertices array - unsigned char* getVerticesStart() const; + const void* getVerticesStart() const; /// Return the pointer to the start of the vertex normals array - unsigned char* getVerticesNormalsStart() const; + const void* getVerticesNormalsStart() const; /// Return the pointer to the start of the indices array - unsigned char* getIndicesStart() const; + const void* getIndicesStart() const; /// Return the vertices coordinates of a triangle void getTriangleVertices(uint triangleIndex, Vector3* outTriangleVertices) const; @@ -192,32 +191,32 @@ inline uint TriangleVertexArray::getNbTriangles() const { } // Return the vertices stride (number of bytes) -inline int TriangleVertexArray::getVerticesStride() const { +inline uint TriangleVertexArray::getVerticesStride() const { return mVerticesStride; } // Return the vertex normals stride (number of bytes) -inline int TriangleVertexArray::getVerticesNormlasStride() const { +inline uint TriangleVertexArray::getVerticesNormlasStride() const { return mVerticesNormalsStride; } // Return the indices stride (number of bytes) -inline int TriangleVertexArray::getIndicesStride() const { +inline uint TriangleVertexArray::getIndicesStride() const { return mIndicesStride; } // Return the pointer to the start of the vertices array -inline unsigned char* TriangleVertexArray::getVerticesStart() const { +inline const void* TriangleVertexArray::getVerticesStart() const { return mVerticesStart; } // Return the pointer to the start of the vertex normals array -inline unsigned char* TriangleVertexArray::getVerticesNormalsStart() const { +inline const void* TriangleVertexArray::getVerticesNormalsStart() const { return mVerticesNormalsStart; } // Return the pointer to the start of the indices array -inline unsigned char* TriangleVertexArray::getIndicesStart() const { +inline const void* TriangleVertexArray::getIndicesStart() const { return mIndicesStart; } diff --git a/src/configuration.h b/src/configuration.h index b2c53021..444bd1db 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -48,6 +48,8 @@ namespace reactphysics3d { // ------------------- Type definitions ------------------- // using uint = unsigned int; +using uchar = unsigned char; +using ushort = unsigned short; using luint = long unsigned int; using bodyindex = luint; using bodyindexpair = std::pair; From d62aa419743a68083eb61fa78dcf140b72137d3a Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 4 Oct 2017 22:38:39 +0200 Subject: [PATCH 107/248] Fix issue in ContactManifoldSet --- src/collision/ContactManifoldSet.cpp | 23 +++++++---------------- 1 file changed, 7 insertions(+), 16 deletions(-) diff --git a/src/collision/ContactManifoldSet.cpp b/src/collision/ContactManifoldSet.cpp index 5ad8ce71..2fcea3f3 100644 --- a/src/collision/ContactManifoldSet.cpp +++ b/src/collision/ContactManifoldSet.cpp @@ -253,14 +253,14 @@ void ContactManifoldSet::removeManifold(ContactManifold* manifold) { ContactManifold* next = manifold->getNext(); if (previous != nullptr) { - previous->setNext(manifold->getNext()); + previous->setNext(next); } else { mManifolds = next; } if (next != nullptr) { - next->setPrevious(manifold->getPrevious()); + next->setPrevious(previous); } // Delete the contact manifold @@ -286,30 +286,21 @@ void ContactManifoldSet::makeContactsObsolete() { void ContactManifoldSet::clearObsoleteManifoldsAndContactPoints() { ContactManifold* manifold = mManifolds; - ContactManifold* previousManifold = nullptr; while (manifold != nullptr) { + + // Get the next manifold in the linked-list ContactManifold* nextManifold = manifold->getNext(); + // If the manifold is obsolete if (manifold->getIsObsolete()) { - if (previousManifold != nullptr) { - previousManifold->setNext(nextManifold); - - if (nextManifold != nullptr) { - nextManifold->setPrevious(previousManifold); - } - } - else { - mManifolds = nextManifold; - } - // Delete the contact manifold removeManifold(manifold); - } else { + + // Clear the obsolete contact points of the manifold manifold->clearObseleteContactPoints(); - previousManifold = manifold; } manifold = nextManifold; From 38eff07d0d6b588dcbe529ba0e6d95ec0725c61d Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 9 Oct 2017 22:36:39 +0200 Subject: [PATCH 108/248] Fix issue and small changes in TriangleVertexArray --- src/collision/TriangleVertexArray.cpp | 2 +- src/collision/TriangleVertexArray.h | 10 ++++++++-- 2 files changed, 9 insertions(+), 3 deletions(-) diff --git a/src/collision/TriangleVertexArray.cpp b/src/collision/TriangleVertexArray.cpp index 56f3b422..7cfb2076 100644 --- a/src/collision/TriangleVertexArray.cpp +++ b/src/collision/TriangleVertexArray.cpp @@ -194,7 +194,7 @@ void TriangleVertexArray::getTriangleVerticesIndices(uint triangleIndex, uint* o assert(triangleIndex >= 0 && triangleIndex < mNbTriangles); - const uchar* triangleIndicesPointer = mIndicesStart + triangleIndex * 3 * mIndicesStride; + const uchar* triangleIndicesPointer = mIndicesStart + triangleIndex * mIndicesStride; const void* startTriangleIndices = static_cast(triangleIndicesPointer); // For each vertex of the triangle diff --git a/src/collision/TriangleVertexArray.h b/src/collision/TriangleVertexArray.h index 3db79c7e..3a48c2e3 100644 --- a/src/collision/TriangleVertexArray.h +++ b/src/collision/TriangleVertexArray.h @@ -122,6 +122,12 @@ class TriangleVertexArray { /// Destructor ~TriangleVertexArray(); + /// Deleted assignment operator + TriangleVertexArray& operator=(const TriangleVertexArray& triangleVertexArray) = delete; + + /// Deleted copy-constructor + TriangleVertexArray(const TriangleVertexArray& triangleVertexArray) = delete; + /// Return the vertex data type VertexDataType getVertexDataType() const; @@ -141,7 +147,7 @@ class TriangleVertexArray { uint getVerticesStride() const; /// Return the vertex normals stride (number of bytes) - uint getVerticesNormlasStride() const; + uint getVerticesNormalsStride() const; /// Return the indices stride (number of bytes) uint getIndicesStride() const; @@ -196,7 +202,7 @@ inline uint TriangleVertexArray::getVerticesStride() const { } // Return the vertex normals stride (number of bytes) -inline uint TriangleVertexArray::getVerticesNormlasStride() const { +inline uint TriangleVertexArray::getVerticesNormalsStride() const { return mVerticesNormalsStride; } From 37e2c79cf22b1a32c53e2bad390460b9e3d9dea3 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 9 Oct 2017 22:41:45 +0200 Subject: [PATCH 109/248] Fix issue in ContactManifoldSet --- src/collision/ContactManifoldSet.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/collision/ContactManifoldSet.cpp b/src/collision/ContactManifoldSet.cpp index 2fcea3f3..4e73aa9f 100644 --- a/src/collision/ContactManifoldSet.cpp +++ b/src/collision/ContactManifoldSet.cpp @@ -239,6 +239,9 @@ void ContactManifoldSet::createManifold(const ContactManifoldInfo* manifoldInfo) ContactManifold(manifoldInfo, mShape1, mShape2, mMemoryAllocator); manifold->setPrevious(nullptr); manifold->setNext(mManifolds); + if (mManifolds != nullptr) { + mManifolds->setPrevious(manifold); + } mManifolds = manifold; mNbManifolds++; @@ -248,6 +251,7 @@ void ContactManifoldSet::createManifold(const ContactManifoldInfo* manifoldInfo) void ContactManifoldSet::removeManifold(ContactManifold* manifold) { assert(mNbManifolds > 0); + assert(manifold != nullptr); ContactManifold* previous = manifold->getPrevious(); ContactManifold* next = manifold->getNext(); From 4a37ba39948ae053445f20a058815f609543c30a Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 9 Oct 2017 23:34:35 +0200 Subject: [PATCH 110/248] Add unit tests for the TriangleVertexArray --- src/mathematics/mathematics_functions.cpp | 39 ++- src/mathematics/mathematics_functions.h | 7 + test/main.cpp | 2 + test/tests/collision/TestRaycast.h | 5 +- .../tests/collision/TestTriangleVertexArray.h | 261 ++++++++++++++++++ 5 files changed, 298 insertions(+), 16 deletions(-) create mode 100644 test/tests/collision/TestTriangleVertexArray.h diff --git a/src/mathematics/mathematics_functions.cpp b/src/mathematics/mathematics_functions.cpp index d627ed7b..fd813cdc 100755 --- a/src/mathematics/mathematics_functions.cpp +++ b/src/mathematics/mathematics_functions.cpp @@ -26,14 +26,27 @@ // Libraries #include "mathematics_functions.h" #include "Vector3.h" +#include "Vector2.h" #include #include using namespace reactphysics3d; -/// Compute the barycentric coordinates u, v, w of a point p inside the triangle (a, b, c) -/// This method uses the technique described in the book Real-Time collision detection by -/// Christer Ericson. + +// Function to test if two vectors are (almost) equal +bool reactphysics3d::approxEqual(const Vector3& vec1, const Vector3& vec2, decimal epsilon) { + return approxEqual(vec1.x, vec2.x, epsilon) && approxEqual(vec1.y, vec2.y, epsilon) && + approxEqual(vec1.z, vec2.z, epsilon); +} + +// Function to test if two vectors are (almost) equal +bool reactphysics3d::approxEqual(const Vector2& vec1, const Vector2& vec2, decimal epsilon) { + return approxEqual(vec1.x, vec2.x, epsilon) && approxEqual(vec1.y, vec2.y, epsilon); +} + +// Compute the barycentric coordinates u, v, w of a point p inside the triangle (a, b, c) +// This method uses the technique described in the book Real-Time collision detection by +// Christer Ericson. void reactphysics3d::computeBarycentricCoordinatesInTriangle(const Vector3& a, const Vector3& b, const Vector3& c, const Vector3& p, decimal& u, decimal& v, decimal& w) { const Vector3 v0 = b - a; @@ -52,7 +65,7 @@ void reactphysics3d::computeBarycentricCoordinatesInTriangle(const Vector3& a, c u = decimal(1.0) - v - w; } -/// Clamp a vector such that it is no longer than a given maximum length +// Clamp a vector such that it is no longer than a given maximum length Vector3 reactphysics3d::clamp(const Vector3& vector, decimal maxLength) { if (vector.lengthSquare() > maxLength * maxLength) { return vector.getUnit() * maxLength; @@ -60,17 +73,17 @@ Vector3 reactphysics3d::clamp(const Vector3& vector, decimal maxLength) { return vector; } -/// Return true if two vectors are parallel +// Return true if two vectors are parallel bool reactphysics3d::areParallelVectors(const Vector3& vector1, const Vector3& vector2) { return vector1.cross(vector2).lengthSquare() < decimal(0.00001); } -/// Return true if two vectors are orthogonal +// Return true if two vectors are orthogonal bool reactphysics3d::areOrthogonalVectors(const Vector3& vector1, const Vector3& vector2) { return std::abs(vector1.dot(vector2)) < decimal(0.00001); } -/// Compute and return a point on segment from "segPointA" and "segPointB" that is closest to point "pointC" +// Compute and return a point on segment from "segPointA" and "segPointB" that is closest to point "pointC" Vector3 reactphysics3d::computeClosestPointOnSegment(const Vector3& segPointA, const Vector3& segPointB, const Vector3& pointC) { const Vector3 ab = segPointB - segPointA; @@ -95,9 +108,9 @@ Vector3 reactphysics3d::computeClosestPointOnSegment(const Vector3& segPointA, c return segPointA + t * ab; } -/// Compute the closest points between two segments -/// This method uses the technique described in the book Real-Time -/// collision detection by Christer Ericson. +// Compute the closest points between two segments +// This method uses the technique described in the book Real-Time +// collision detection by Christer Ericson. void reactphysics3d::computeClosestPointBetweenTwoSegments(const Vector3& seg1PointA, const Vector3& seg1PointB, const Vector3& seg2PointA, const Vector3& seg2PointB, Vector3& closestPointSeg1, Vector3& closestPointSeg2) { @@ -175,7 +188,7 @@ void reactphysics3d::computeClosestPointBetweenTwoSegments(const Vector3& seg1Po closestPointSeg2 = seg2PointA + d2 * t; } -/// Compute the intersection between a plane and a segment +// Compute the intersection between a plane and a segment // Let the plane define by the equation planeNormal.dot(X) = planeD with X a point on the plane and "planeNormal" the plane normal. This method // computes the intersection P between the plane and the segment (segA, segB). The method returns the value "t" such // that P = segA + t * (segB - segA). Note that it only returns a value in [0, 1] if there is an intersection. Otherwise, @@ -282,8 +295,8 @@ std::vector reactphysics3d::clipSegmentWithPlanes(const Vector3& segA, return outputVertices; } -/// Clip a polygon against multiple planes and return the clipped polygon vertices -/// This method implements the Sutherland–Hodgman clipping algorithm +// Clip a polygon against multiple planes and return the clipped polygon vertices +// This method implements the Sutherland–Hodgman clipping algorithm std::vector reactphysics3d::clipPolygonWithPlanes(const std::vector& polygonVertices, const std::vector& planesPoints, const std::vector& planesNormals) { diff --git a/src/mathematics/mathematics_functions.h b/src/mathematics/mathematics_functions.h index 78b5ba67..9f062826 100755 --- a/src/mathematics/mathematics_functions.h +++ b/src/mathematics/mathematics_functions.h @@ -38,6 +38,7 @@ namespace reactphysics3d { struct Vector3; +struct Vector2; // ---------- Mathematics functions ---------- // @@ -47,6 +48,12 @@ inline bool approxEqual(decimal a, decimal b, decimal epsilon = MACHINE_EPSILON) return (std::fabs(a - b) < epsilon); } +/// Function to test if two vectors are (almost) equal +bool approxEqual(const Vector3& vec1, const Vector3& vec2, decimal epsilon = MACHINE_EPSILON); + +/// Function to test if two vectors are (almost) equal +bool approxEqual(const Vector2& vec1, const Vector2& vec2, decimal epsilon = MACHINE_EPSILON); + /// Function that returns the result of the "value" clamped by /// two others values "lowerLimit" and "upperLimit" inline int clamp(int value, int lowerLimit, int upperLimit) { diff --git a/test/main.cpp b/test/main.cpp index 54bfbb8f..26d62803 100644 --- a/test/main.cpp +++ b/test/main.cpp @@ -38,6 +38,7 @@ #include "tests/collision/TestAABB.h" #include "tests/collision/TestDynamicAABBTree.h" #include "tests/collision/TestHalfEdgeStructure.h" +#include "tests/collision/TestTriangleVertexArray.h" using namespace reactphysics3d; @@ -59,6 +60,7 @@ int main() { testSuite.addTest(new TestAABB("AABB")); testSuite.addTest(new TestPointInside("IsPointInside")); + testSuite.addTest(new TestTriangleVertexArray("TriangleVertexArray")); testSuite.addTest(new TestRaycast("Raycasting")); testSuite.addTest(new TestCollisionWorld("CollisionWorld")); testSuite.addTest(new TestDynamicAABBTree("DynamicAABBTree")); diff --git a/test/tests/collision/TestRaycast.h b/test/tests/collision/TestRaycast.h index 81013570..f2ae3d6b 100644 --- a/test/tests/collision/TestRaycast.h +++ b/test/tests/collision/TestRaycast.h @@ -277,9 +277,8 @@ class TestRaycast : public Test { TriangleVertexArray::VertexDataType::VERTEX_DOUBLE_TYPE; mConcaveMeshVertexArray = new TriangleVertexArray(8, &(mConcaveMeshVertices[0]), sizeof(Vector3), - 12, &(mConcaveMeshIndices[0]), sizeof(uint), - vertexType, - TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE); + 12, &(mConcaveMeshIndices[0]), 3 * sizeof(uint), + vertexType, TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE); // Add the triangle vertex array of the subpart to the triangle mesh diff --git a/test/tests/collision/TestTriangleVertexArray.h b/test/tests/collision/TestTriangleVertexArray.h new file mode 100644 index 00000000..282b7d55 --- /dev/null +++ b/test/tests/collision/TestTriangleVertexArray.h @@ -0,0 +1,261 @@ +/******************************************************************************** +* 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 TEST_TRIANGLE_VERTEX_ARRAY_H +#define TEST_TRIANGLE_VERTEX_ARRAY_H + +// Libraries +#include "reactphysics3d.h" + +/// Reactphysics3D namespace +namespace reactphysics3d { + + +// Class TestTriangleVertexArray +/** + * Unit test for the TestTriangleArray class. + */ +class TestTriangleVertexArray : public Test { + + private : + + // ---------- Atributes ---------- // + + float mVertices1[4*3]; + double mVertices2[4*3]; + float mNormals2[4*3]; + uint mIndices1[6]; + short mIndices2[6]; + TriangleVertexArray* mTriangleVertexArray1; + TriangleVertexArray* mTriangleVertexArray2; + + Vector3 mVertex0; + Vector3 mVertex1; + Vector3 mVertex2; + Vector3 mVertex3; + Vector3 mVertex4; + Vector3 mVertex5; + Vector3 mVertex6; + Vector3 mVertex7; + + Vector3 mNormal0; + Vector3 mNormal1; + Vector3 mNormal2; + Vector3 mNormal3; + + public : + + // ---------- Methods ---------- // + + /// Constructor + TestTriangleVertexArray(const std::string& name) : Test(name) { + + mVertex0 = Vector3(0, 0, 4); + mVertex1 = Vector3(0, 0, -3); + mVertex2 = Vector3(-2, 0, 0); + mVertex3 = Vector3(0, -5, 0); + + // Initialize data + mVertices1[0] = mVertex0.x; mVertices1[1] = mVertex0.y; mVertices1[2] = mVertex0.z; + mVertices1[3] = mVertex1.x; mVertices1[4] = mVertex1.y; mVertices1[5] = mVertex1.z; + mVertices1[6] = mVertex2.x; mVertices1[7] = mVertex2.y; mVertices1[8] = mVertex2.z; + mVertices1[9] = mVertex3.x; mVertices1[10] = mVertex3.y; mVertices1[11] = mVertex3.z; + + mIndices1[0] = 0; mIndices1[1] = 1; mIndices1[2] = 2; + mIndices1[3] = 0; mIndices1[4] = 3; mIndices1[5] = 1; + + mVertex4 = Vector3(0, 0, 5); + mVertex5 = Vector3(0, 0, -7); + mVertex6 = Vector3(-2, 0, 0); + mVertex7 = Vector3(0, -5, 0); + + mVertices2[0] = static_cast(mVertex4.x); mVertices2[1] = static_cast(mVertex4.y); mVertices2[2] = static_cast(mVertex4.z); + mVertices2[3] = static_cast(mVertex5.x); mVertices2[4] = static_cast(mVertex5.y); mVertices2[5] = static_cast(mVertex5.z); + mVertices2[6] = static_cast(mVertex6.x); mVertices2[7] = static_cast(mVertex6.y); mVertices2[8] = static_cast(mVertex6.z); + mVertices2[9] = static_cast(mVertex7.x); mVertices2[10] = static_cast(mVertex7.y); mVertices2[11] = static_cast(mVertex7.z); + + mIndices2[0] = 0; mIndices2[1] = 1; mIndices2[2] = 2; + mIndices2[3] = 0; mIndices2[4] = 3; mIndices2[5] = 1; + + mNormal0 = Vector3(2, 4, 6); + mNormal1 = Vector3(1, 6, -3); + mNormal2 = Vector3(-2, 4, 7); + mNormal3 = Vector3(-5, 2, 9); + mNormal0.normalize(); + mNormal1.normalize(); + mNormal2.normalize(); + mNormal3.normalize(); + mNormals2[0] = mNormal0.x; mNormals2[1] = mNormal0.y; mNormals2[2] = mNormal0.z; + mNormals2[3] = mNormal1.x; mNormals2[4] = mNormal1.y; mNormals2[5] = mNormal1.z; + mNormals2[6] = mNormal2.x; mNormals2[7] = mNormal2.y; mNormals2[8] = mNormal2.z; + mNormals2[9] = mNormal3.x; mNormals2[10] = mNormal3.y; mNormals2[11] = mNormal3.z; + + // Create triangle vertex array with automatic normals computation + mTriangleVertexArray1 = new TriangleVertexArray(4, static_cast(mVertices1), 3 * sizeof(float), + 2, static_cast(mIndices1), 3 * sizeof(uint), + TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE, + TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE); + + // Create triangle vertex array with normals defined by the user + mTriangleVertexArray2 = new TriangleVertexArray(4, static_cast(mVertices2), 3 * sizeof(double), + static_cast(mNormals2), 3 * sizeof(float), + 2, static_cast(mIndices2), 3 * sizeof(short), + TriangleVertexArray::VertexDataType::VERTEX_DOUBLE_TYPE, + TriangleVertexArray::NormalDataType::NORMAL_FLOAT_TYPE, + TriangleVertexArray::IndexDataType::INDEX_SHORT_TYPE); + + } + + /// Destructor + virtual ~TestTriangleVertexArray() { + delete mTriangleVertexArray1; + delete mTriangleVertexArray2; + } + + /// Run the tests + void run() { + + // ----- First triangle vertex array ----- // + + test(mTriangleVertexArray1->getVertexDataType() == TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE); + test(mTriangleVertexArray1->getIndexDataType() == TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE); + test(mTriangleVertexArray1->getVertexNormalDataType() == TriangleVertexArray::NormalDataType::NORMAL_FLOAT_TYPE); + test(mTriangleVertexArray1->getNbTriangles() == 2); + test(mTriangleVertexArray1->getNbVertices() == 4); + test(mTriangleVertexArray1->getIndicesStart() == static_cast(mIndices1)); + test(mTriangleVertexArray1->getVerticesStart() == static_cast(mVertices1)); + test(mTriangleVertexArray1->getIndicesStride() == (3 * sizeof(uint))); + test(mTriangleVertexArray1->getVerticesStride() == (3 * sizeof(float))); + + // Get triangle indices + + uint triangle0Indices[3]; + mTriangleVertexArray1->getTriangleVerticesIndices(0, triangle0Indices); + + test(triangle0Indices[0] == mIndices1[0]); + test(triangle0Indices[1] == mIndices1[1]); + test(triangle0Indices[2] == mIndices1[2]); + + uint triangle1Indices[3]; + mTriangleVertexArray1->getTriangleVerticesIndices(1, triangle1Indices); + + test(triangle1Indices[0] == mIndices1[3]); + test(triangle1Indices[1] == mIndices1[4]); + test(triangle1Indices[2] == mIndices1[5]); + + // Get triangle vertices + + Vector3 triangle0Vertices[3]; + mTriangleVertexArray1->getTriangleVertices(0, triangle0Vertices); + + test(approxEqual(triangle0Vertices[0], mVertex0, decimal(0.0000001))); + test(approxEqual(triangle0Vertices[1], mVertex1, decimal(0.0000001))); + test(approxEqual(triangle0Vertices[2], mVertex2, decimal(0.0000001))); + + Vector3 triangle1Vertices[3]; + mTriangleVertexArray1->getTriangleVertices(1, triangle1Vertices); + + test(approxEqual(triangle1Vertices[0], mVertex0, decimal(0.0000001))); + test(approxEqual(triangle1Vertices[1], mVertex3, decimal(0.0000001))); + test(approxEqual(triangle1Vertices[2], mVertex1, decimal(0.0000001))); + + // Get triangle normals + + Vector3 triangle0Normals[3]; + mTriangleVertexArray1->getTriangleVerticesNormals(0, triangle0Normals); + + Vector3 triangle1Normals[3]; + mTriangleVertexArray1->getTriangleVerticesNormals(1, triangle1Normals); + + const Vector3 normal0Test(decimal(0.9792), decimal(0.20268), 0); + const Vector3 normal2Test(0, 1, 0); + const Vector3 normal3Test(1, 0, 0); + + test(approxEqual(triangle0Normals[0], normal0Test, decimal(0.0001))); + test(approxEqual(triangle0Normals[2], normal2Test, decimal(0.0001))); + test(approxEqual(triangle1Normals[1], normal3Test, decimal(0.0001))); + + // ----- Second triangle vertex array ----- // + + test(mTriangleVertexArray2->getVertexDataType() == TriangleVertexArray::VertexDataType::VERTEX_DOUBLE_TYPE); + test(mTriangleVertexArray2->getIndexDataType() == TriangleVertexArray::IndexDataType::INDEX_SHORT_TYPE); + test(mTriangleVertexArray2->getVertexNormalDataType() == TriangleVertexArray::NormalDataType::NORMAL_FLOAT_TYPE); + test(mTriangleVertexArray2->getNbTriangles() == 2); + test(mTriangleVertexArray2->getNbVertices() == 4); + test(mTriangleVertexArray2->getIndicesStart() == static_cast(mIndices2)); + test(mTriangleVertexArray2->getVerticesStart() == static_cast(mVertices2)); + test(mTriangleVertexArray2->getVerticesNormalsStart() == static_cast(mNormals2)); + test(mTriangleVertexArray2->getIndicesStride() == (3 * sizeof(short))); + test(mTriangleVertexArray2->getVerticesStride() == (3 * sizeof(double))); + test(mTriangleVertexArray2->getVerticesNormalsStride() == (3 * sizeof(float))); + + // Get triangle indices + + mTriangleVertexArray2->getTriangleVerticesIndices(0, triangle0Indices); + + test(triangle0Indices[0] == mIndices2[0]); + test(triangle0Indices[1] == mIndices2[1]); + test(triangle0Indices[2] == mIndices2[2]); + + mTriangleVertexArray2->getTriangleVerticesIndices(1, triangle1Indices); + + test(triangle1Indices[0] == mIndices2[3]); + test(triangle1Indices[1] == mIndices2[4]); + test(triangle1Indices[2] == mIndices2[5]); + + // Get triangle vertices + + mTriangleVertexArray2->getTriangleVertices(0, triangle0Vertices); + + test(approxEqual(triangle0Vertices[0], mVertex4, decimal(0.0000001))); + test(approxEqual(triangle0Vertices[1], mVertex5, decimal(0.0000001))); + test(approxEqual(triangle0Vertices[2], mVertex6, decimal(0.0000001))); + + mTriangleVertexArray2->getTriangleVertices(1, triangle1Vertices); + + test(approxEqual(triangle1Vertices[0], mVertex4, decimal(0.0000001))); + test(approxEqual(triangle1Vertices[1], mVertex7, decimal(0.0000001))); + test(approxEqual(triangle1Vertices[2], mVertex5, decimal(0.0000001))); + + // Get triangle normals + + mTriangleVertexArray2->getTriangleVerticesNormals(0, triangle0Normals); + mTriangleVertexArray2->getTriangleVerticesNormals(1, triangle1Normals); + + test(approxEqual(triangle0Normals[0], mNormal0, decimal(0.000001))); + test(approxEqual(triangle0Normals[1], mNormal1, decimal(0.000001))); + test(approxEqual(triangle0Normals[2], mNormal2, decimal(0.000001))); + + test(approxEqual(triangle1Normals[0], mNormal0, decimal(0.000001))); + test(approxEqual(triangle1Normals[1], mNormal3, decimal(0.000001))); + test(approxEqual(triangle1Normals[2], mNormal1, decimal(0.000001))); + } + +}; + +} + +#endif + From 17d1ee36813334749bc044cd44326e1c2d1618d4 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 9 Oct 2017 23:35:30 +0200 Subject: [PATCH 111/248] Change in the ConcaveMesh class of the testbed application --- testbed/common/ConcaveMesh.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/testbed/common/ConcaveMesh.cpp b/testbed/common/ConcaveMesh.cpp index d6a6bbe3..c7e162a3 100644 --- a/testbed/common/ConcaveMesh.cpp +++ b/testbed/common/ConcaveMesh.cpp @@ -46,7 +46,7 @@ ConcaveMesh::ConcaveMesh(const openglframework::Vector3 &position, // Vertex and Indices array for the triangle mesh (data in shared and not copied) rp3d::TriangleVertexArray* vertexArray = new rp3d::TriangleVertexArray(getNbVertices(), &(mVertices[0]), sizeof(openglframework::Vector3), - getNbFaces(i), &(mIndices[i][0]), sizeof(int), + getNbFaces(i), &(mIndices[i][0]), 3 * sizeof(int), rp3d::TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE, rp3d::TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE); @@ -97,7 +97,7 @@ ConcaveMesh::ConcaveMesh(const openglframework::Vector3 &position, float mass, // Vertex and Indices array for the triangle mesh (data in shared and not copied) rp3d::TriangleVertexArray* vertexArray = new rp3d::TriangleVertexArray(getNbVertices(), &(mVertices[0]), sizeof(openglframework::Vector3), - getNbFaces(i), &(mIndices[i][0]), sizeof(int), + getNbFaces(i), &(mIndices[i][0]), 3 * sizeof(int), rp3d::TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE, rp3d::TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE); From d5617526ff91baa77ca2b759994f981713a5e4a1 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 12 Oct 2017 20:07:39 +0200 Subject: [PATCH 112/248] Modify the policy to drop contact manifolds. First drop the old ones before the new ones --- src/collision/CollisionDetection.cpp | 5 ++- src/collision/ContactManifold.cpp | 3 +- src/collision/ContactManifold.h | 21 ++++++++++++ src/collision/ContactManifoldSet.cpp | 51 ++++++++++++++++++++++------ src/collision/ContactManifoldSet.h | 18 ++++++++-- src/engine/OverlappingPair.h | 9 +++++ 6 files changed, 92 insertions(+), 15 deletions(-) diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index f27b5ddf..6e0e6ed6 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -71,7 +71,7 @@ void CollisionDetection::computeCollisionDetection() { computeMiddlePhase(); // Compute the narrow-phase collision detection - computeNarrowPhase(); + computeNarrowPhase(); // Reset the linked list of narrow-phase info mNarrowPhaseInfoList = nullptr; @@ -410,6 +410,9 @@ void CollisionDetection::processPotentialContacts(OverlappingPair* pair) { potentialManifold = potentialManifold->mNext; } + // Reset the isNew status of the manifolds + pair->resetIsNewManifoldStatus(); + // Clear the obsolete contact manifolds and contact points pair->clearObsoleteManifoldsAndContactPoints(); diff --git a/src/collision/ContactManifold.cpp b/src/collision/ContactManifold.cpp index 62ca7a0c..37ad3ad8 100644 --- a/src/collision/ContactManifold.cpp +++ b/src/collision/ContactManifold.cpp @@ -34,7 +34,7 @@ ContactManifold::ContactManifold(const ContactManifoldInfo* manifoldInfo, ProxyS : mShape1(shape1), mShape2(shape2), mContactPoints(nullptr), mContactNormalId(manifoldInfo->getContactNormalId()), mNbContactPoints(0), mFrictionImpulse1(0.0), mFrictionImpulse2(0.0), mFrictionTwistImpulse(0.0), mIsAlreadyInIsland(false), - mMemoryAllocator(memoryAllocator), mNext(nullptr), mPrevious(nullptr), mIsObsolete(false) { + mMemoryAllocator(memoryAllocator), mNext(nullptr), mPrevious(nullptr), mIsObsolete(false), mIsNew(true) { // For each contact point info in the manifold const ContactPointInfo* pointInfo = manifoldInfo->getFirstContactPointInfo(); @@ -85,6 +85,7 @@ void ContactManifold::addContactPoint(const ContactPointInfo* contactPointInfo) mContactPoints = contactPoint; mNbContactPoints++; + assert(mNbContactPoints <= MAX_CONTACT_POINTS_IN_MANIFOLD); } // Clear the obsolete contact points diff --git a/src/collision/ContactManifold.h b/src/collision/ContactManifold.h index e34c4543..b24ed378 100644 --- a/src/collision/ContactManifold.h +++ b/src/collision/ContactManifold.h @@ -143,6 +143,9 @@ class ContactManifold { /// True if the contact manifold is obsolete bool mIsObsolete; + /// True if the contact manifold is new (has just been added from potential contacts) + bool mIsNew; + // -------------------- Methods -------------------- // /// Return true if the contact manifold has already been added into an island @@ -204,6 +207,12 @@ class ContactManifold { /// Return the friction twist accumulated impulse decimal getFrictionTwistImpulse() const; + + /// Return true if the manifold has just been created + bool getIsNew() const; + + /// Set the isNew attribute + void setIsNew(bool isNew); public: @@ -408,6 +417,18 @@ inline short ContactManifold::getContactNormalId() const { return mContactNormalId; } + +// Return true if the manifold has just been created +inline bool ContactManifold::getIsNew() const { + return mIsNew; +} + +// Set the isNew attribute +inline void ContactManifold::setIsNew(bool isNew) { + mIsNew = isNew; +} + + } #endif diff --git a/src/collision/ContactManifoldSet.cpp b/src/collision/ContactManifoldSet.cpp index 4e73aa9f..06ae4963 100644 --- a/src/collision/ContactManifoldSet.cpp +++ b/src/collision/ContactManifoldSet.cpp @@ -66,8 +66,9 @@ void ContactManifoldSet::addContactManifold(const ContactManifoldInfo* contactMa if (mNbManifolds >= mNbMaxManifolds) { // We need to remove a manifold from the set. - // We seach for the one with the smallest maximum penetration depth among its contact points - ContactManifold* minDepthManifold = getManifoldWithSmallestContactPenetrationDepth(contactManifoldInfo->getLargestPenetrationDepth()); + // We search for an old manifold with the smallest maximum penetration depth among its contact points. + // If we do not find an old manifold, we select a new one that has the smallest contact penetration depth. + ContactManifold* minDepthManifold = selectManifoldToRemove(contactManifoldInfo->getLargestPenetrationDepth()); // If the manifold with the minimum penetration depth is an existing one if (minDepthManifold != nullptr) { @@ -135,25 +136,53 @@ void ContactManifoldSet::updateManifoldWithNewOne(ContactManifold* oldManifold, oldManifold->setIsObsolete(false, false); } -// Return the manifold with the smallest contact penetration depth among its points -ContactManifold* ContactManifoldSet::getManifoldWithSmallestContactPenetrationDepth(decimal initDepth) const { +// Return the manifold to remove (because it is too old or has not the largest penetration depth) +ContactManifold* ContactManifoldSet::selectManifoldToRemove(decimal penDepthNewManifold) const { assert(mNbManifolds == mNbMaxManifolds); + assert(mManifolds != nullptr); - ContactManifold* minDepthManifold = nullptr; - decimal minDepth = initDepth; + // Look for a manifold that is not new and with the smallest contact penetration depth. + // At the same time, we also look for a new manifold with the smallest contact penetration depth + // in case no old manifold exists. + ContactManifold* minDepthOldManifold = nullptr; + ContactManifold* minDepthNewManifold = nullptr; + decimal minDepthOld = DECIMAL_LARGEST; + decimal minDepthNew = penDepthNewManifold; ContactManifold* manifold = mManifolds; while (manifold != nullptr) { - decimal depth = manifold->getLargestContactDepth(); - if (depth < minDepth) { - minDepth = depth; - minDepthManifold = manifold; + + // Get the largest contact point penetration depth of the manifold + const decimal depth = manifold->getLargestContactDepth(); + + // If it is a new manifold + if (manifold->getIsNew()) { + + if (depth < minDepthNew) { + minDepthNew = depth; + minDepthNewManifold = manifold; + } + } + else { + + if (depth < minDepthOld) { + minDepthOld = depth; + minDepthOldManifold = manifold; + } } manifold = manifold->getNext(); } - return minDepthManifold; + // If there was a contact manifold that was not new + if (minDepthOldManifold != nullptr) { + + // Return the old manifold with the smallest penetration depth + return minDepthOldManifold; + } + + // Otherwise, we return the new manifold with the smallest penetration depth + return minDepthNewManifold; } // Return the contact manifold with a similar average normal. diff --git a/src/collision/ContactManifoldSet.h b/src/collision/ContactManifoldSet.h index 1676f5a2..ea832cdb 100644 --- a/src/collision/ContactManifoldSet.h +++ b/src/collision/ContactManifoldSet.h @@ -74,8 +74,8 @@ class ContactManifoldSet { // Return the contact manifold with a similar average normal. ContactManifold* selectManifoldWithSimilarNormal(short int normalDirectionId) const; - /// Return the manifold with the smallest contact penetration depth - ContactManifold* getManifoldWithSmallestContactPenetrationDepth(decimal initDepth) const; + /// Return the manifold to remove (because it is too old or has not the largest penetration depth) + ContactManifold* selectManifoldToRemove(decimal penDepthNewManifold) const; /// Update a previous similar manifold with a new one void updateManifoldWithNewOne(ContactManifold* oldManifold, const ContactManifoldInfo* newManifold); @@ -124,6 +124,9 @@ class ContactManifoldSet { /// Clear the obsolete contact manifolds and contact points void clearObsoleteManifoldsAndContactPoints(); + /// Reset the isNew status of all the manifolds + void resetIsNewManifoldStatus(); + // Map the normal vector into a cubemap face bucket (a face contains 4x4 buckets) // Each face of the cube is divided into 4x4 buckets. This method maps the // normal vector into of the of the bucket and returns a unique Id for the bucket @@ -177,6 +180,17 @@ inline int ContactManifoldSet::computeNbMaxContactManifolds(const CollisionShape } } + +// Reset the isNew status of all the manifolds +inline void ContactManifoldSet::resetIsNewManifoldStatus() { + + ContactManifold* manifold = mManifolds; + while (manifold != nullptr) { + manifold->setIsNew(false); + manifold = manifold->getNext(); + } +} + } #endif diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index bb7c1048..2725a8d5 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -172,6 +172,9 @@ class OverlappingPair { /// Clear the obsolete contact manifold and contact points void clearObsoleteManifoldsAndContactPoints(); + /// Reset the isNew status of all the manifolds + void resetIsNewManifoldStatus(); + /// Return the pair of bodies index static overlappingpairid computeID(ProxyShape* shape1, ProxyShape* shape2); @@ -269,6 +272,12 @@ inline void OverlappingPair::clearObsoleteManifoldsAndContactPoints() { mContactManifoldSet.clearObsoleteManifoldsAndContactPoints(); } + +// Reset the isNew status of all the manifolds +inline void OverlappingPair::resetIsNewManifoldStatus() { + mContactManifoldSet.resetIsNewManifoldStatus(); +} + } #endif From de494bb0fd74bf5f09bde09f7eac8ea64ce4ea35 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 18 Oct 2017 00:41:32 +0200 Subject: [PATCH 113/248] Changes and bug fixes in ContactManifold and ContactManifoldSet --- src/collision/CollisionDetection.cpp | 8 +- src/collision/ContactManifold.cpp | 126 ++++++++++++++++++++------- src/collision/ContactManifold.h | 32 +++---- src/collision/ContactManifoldSet.cpp | 98 ++++++++------------- src/collision/ContactManifoldSet.h | 19 +--- src/collision/ContactPointInfo.h | 2 + src/constraint/ContactPoint.cpp | 16 +--- src/constraint/ContactPoint.h | 49 +++++------ src/engine/ContactSolver.cpp | 9 +- src/engine/OverlappingPair.h | 23 ++--- 10 files changed, 189 insertions(+), 193 deletions(-) diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 6e0e6ed6..f650351a 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -104,7 +104,7 @@ void CollisionDetection::computeMiddlePhase() { OverlappingPair* pair = it->second; // Make all the contact manifolds and contact points of the pair obsolete - pair->makeContactsObselete(); + pair->makeContactsObsolete(); ProxyShape* shape1 = pair->getShape1(); ProxyShape* shape2 = pair->getShape2(); @@ -410,12 +410,12 @@ void CollisionDetection::processPotentialContacts(OverlappingPair* pair) { potentialManifold = potentialManifold->mNext; } - // Reset the isNew status of the manifolds - pair->resetIsNewManifoldStatus(); - // Clear the obsolete contact manifolds and contact points pair->clearObsoleteManifoldsAndContactPoints(); + // Reduce the contact manifolds and contact points if there are too many of them + pair->reduceContactManifolds(); + // Reset the potential contacts of the pair pair->clearPotentialContactManifolds(); } diff --git a/src/collision/ContactManifold.cpp b/src/collision/ContactManifold.cpp index 37ad3ad8..55ce8ba3 100644 --- a/src/collision/ContactManifold.cpp +++ b/src/collision/ContactManifold.cpp @@ -34,20 +34,14 @@ ContactManifold::ContactManifold(const ContactManifoldInfo* manifoldInfo, ProxyS : mShape1(shape1), mShape2(shape2), mContactPoints(nullptr), mContactNormalId(manifoldInfo->getContactNormalId()), mNbContactPoints(0), mFrictionImpulse1(0.0), mFrictionImpulse2(0.0), mFrictionTwistImpulse(0.0), mIsAlreadyInIsland(false), - mMemoryAllocator(memoryAllocator), mNext(nullptr), mPrevious(nullptr), mIsObsolete(false), mIsNew(true) { + mMemoryAllocator(memoryAllocator), mNext(nullptr), mPrevious(nullptr), mIsObsolete(false) { // For each contact point info in the manifold const ContactPointInfo* pointInfo = manifoldInfo->getFirstContactPointInfo(); while(pointInfo != nullptr) { - // Create the new contact point - ContactPoint* contact = new (mMemoryAllocator.allocate(sizeof(ContactPoint))) - ContactPoint(pointInfo, mShape1->getLocalToWorldTransform(), mShape2->getLocalToWorldTransform()); - - // Add the new contact point into the manifold - contact->setNext(mContactPoints); - mContactPoints = contact; - mNbContactPoints++; + // Add the new contact point + addContactPoint(pointInfo); pointInfo = pointInfo->next; } @@ -73,52 +67,122 @@ ContactManifold::~ContactManifold() { } } +// Remove a contact point +void ContactManifold::removeContactPoint(ContactPoint* contactPoint) { + + assert(mNbContactPoints > 0); + assert(mContactPoints != nullptr); + assert(contactPoint != nullptr); + + ContactPoint* previous = contactPoint->getPrevious(); + ContactPoint* next = contactPoint->getNext(); + + if (previous != nullptr) { + previous->setNext(next); + } + else { + mContactPoints = next; + } + + if (next != nullptr) { + next->setPrevious(previous); + } + + // Delete the contact point + contactPoint->~ContactPoint(); + mMemoryAllocator.release(contactPoint, sizeof(ContactPoint)); + + mNbContactPoints--; + assert(mNbContactPoints >= 0); +} + // Add a contact point void ContactManifold::addContactPoint(const ContactPointInfo* contactPointInfo) { + assert(contactPointInfo != nullptr); + // Create the new contact point - ContactPoint* contactPoint = new (mMemoryAllocator.allocate(sizeof(ContactPoint))) - ContactPoint(contactPointInfo, mShape1->getLocalToWorldTransform(), mShape2->getLocalToWorldTransform()); + ContactPoint* contactPoint = new (mMemoryAllocator.allocate(sizeof(ContactPoint))) ContactPoint(contactPointInfo); // Add the new contact point into the manifold contactPoint->setNext(mContactPoints); + contactPoint->setPrevious(nullptr); + if (mContactPoints != nullptr) { + mContactPoints->setPrevious(contactPoint); + } mContactPoints = contactPoint; mNbContactPoints++; - assert(mNbContactPoints <= MAX_CONTACT_POINTS_IN_MANIFOLD); } // Clear the obsolete contact points -void ContactManifold::clearObseleteContactPoints() { +void ContactManifold::clearObsoleteContactPoints() { + assert(mContactPoints != nullptr); + + // For each contact point of the manifold ContactPoint* contactPoint = mContactPoints; - ContactPoint* previousContactPoint = nullptr; while (contactPoint != nullptr) { ContactPoint* nextContactPoint = contactPoint->getNext(); + // If the contact point is obsolete if (contactPoint->getIsObsolete()) { - // Delete the contact point - contactPoint->~ContactPoint(); - mMemoryAllocator.release(contactPoint, sizeof(ContactPoint)); - - if (previousContactPoint != nullptr) { - previousContactPoint->setNext(nextContactPoint); - } - else { - mContactPoints = nextContactPoint; - } - - mNbContactPoints--; - } - else { - previousContactPoint = contactPoint; + // Remove the contact point + removeContactPoint(contactPoint); } contactPoint = nextContactPoint; } - assert(mNbContactPoints >= 0); - assert(mNbContactPoints <= MAX_CONTACT_POINTS_IN_MANIFOLD); + assert(mNbContactPoints > 0); + assert(mContactPoints != nullptr); +} + +// Make sure we do not have too much contact points by keeping only the best +// contact points of the manifold (with largest penetration depth) +void ContactManifold::reduce() { + + assert(mContactPoints != nullptr); + + // Remove contact points while there is too much contact points + while (mNbContactPoints > MAX_CONTACT_POINTS_IN_MANIFOLD) { + removeNonOptimalContactPoint(); + } + + assert(mNbContactPoints <= MAX_CONTACT_POINTS_IN_MANIFOLD && mNbContactPoints > 0); + assert(mContactPoints != nullptr); +} + +// Remove a contact point that is not optimal (with a small penetration depth) +void ContactManifold::removeNonOptimalContactPoint() { + + assert(mContactPoints != nullptr); + assert(mNbContactPoints > MAX_CONTACT_POINTS_IN_MANIFOLD); + + // Get the contact point with the minimum penetration depth among all points + ContactPoint* contactPoint = mContactPoints; + ContactPoint* minContactPoint = nullptr; + decimal minPenetrationDepth = DECIMAL_LARGEST; + while (contactPoint != nullptr) { + + ContactPoint* nextContactPoint = contactPoint->getNext(); + + if (contactPoint->getPenetrationDepth() < minPenetrationDepth) { + + minContactPoint = contactPoint; + minPenetrationDepth = contactPoint->getPenetrationDepth(); + } + + contactPoint = nextContactPoint; + } + + assert(minContactPoint != nullptr); + + // Remove the non optimal contact point + removeContactPoint(minContactPoint); + + assert(mNbContactPoints > 0); + assert(mContactPoints != nullptr); } diff --git a/src/collision/ContactManifold.h b/src/collision/ContactManifold.h index b24ed378..b5c25cb9 100644 --- a/src/collision/ContactManifold.h +++ b/src/collision/ContactManifold.h @@ -143,9 +143,6 @@ class ContactManifold { /// True if the contact manifold is obsolete bool mIsObsolete; - /// True if the contact manifold is new (has just been added from potential contacts) - bool mIsNew; - // -------------------- Methods -------------------- // /// Return true if the contact manifold has already been added into an island @@ -161,7 +158,7 @@ class ContactManifold { void setIsObsolete(bool isObselete, bool setContactPoints); /// Clear the obsolete contact points - void clearObseleteContactPoints(); + void clearObsoleteContactPoints(); /// Return the contact normal direction Id of the manifold short getContactNormalId() const; @@ -184,6 +181,15 @@ class ContactManifold { /// Add a contact point void addContactPoint(const ContactPointInfo* contactPointInfo); + /// Make sure we do not have too much contact points by keeping only the best ones + void reduce(); + + /// Remove a contact point that is not optimal (with a small penetration depth) + void removeNonOptimalContactPoint(); + + /// Remove a contact point + void removeContactPoint(ContactPoint* contactPoint); + /// Set the friction twist accumulated impulse void setFrictionTwistImpulse(decimal frictionTwistImpulse); @@ -208,12 +214,6 @@ class ContactManifold { /// Return the friction twist accumulated impulse decimal getFrictionTwistImpulse() const; - /// Return true if the manifold has just been created - bool getIsNew() const; - - /// Set the isNew attribute - void setIsNew(bool isNew); - public: // -------------------- Methods -------------------- // @@ -417,18 +417,6 @@ inline short ContactManifold::getContactNormalId() const { return mContactNormalId; } - -// Return true if the manifold has just been created -inline bool ContactManifold::getIsNew() const { - return mIsNew; -} - -// Set the isNew attribute -inline void ContactManifold::setIsNew(bool isNew) { - mIsNew = isNew; -} - - } #endif diff --git a/src/collision/ContactManifoldSet.cpp b/src/collision/ContactManifoldSet.cpp index 06ae4963..9b8bf58b 100644 --- a/src/collision/ContactManifoldSet.cpp +++ b/src/collision/ContactManifoldSet.cpp @@ -60,43 +60,16 @@ void ContactManifoldSet::addContactManifold(const ContactManifoldInfo* contactMa } else { - bool addNewManifold = true; - - // If there are too much contact manifolds in the set - if (mNbManifolds >= mNbMaxManifolds) { - - // We need to remove a manifold from the set. - // We search for an old manifold with the smallest maximum penetration depth among its contact points. - // If we do not find an old manifold, we select a new one that has the smallest contact penetration depth. - ContactManifold* minDepthManifold = selectManifoldToRemove(contactManifoldInfo->getLargestPenetrationDepth()); - - // If the manifold with the minimum penetration depth is an existing one - if (minDepthManifold != nullptr) { - - // Remove the manifold - removeManifold(minDepthManifold); - } - else { - - // The manifold we do not want to get is the new one. Therefore, we do not add it to the set - addNewManifold = false; - } - } - - // If we need to add the new contact manifold - if (addNewManifold) { - - // Create a new contact manifold - createManifold(contactManifoldInfo); - } + // Create a new contact manifold + createManifold(contactManifoldInfo); } } // Update a previous similar manifold with a new one void ContactManifoldSet::updateManifoldWithNewOne(ContactManifold* oldManifold, const ContactManifoldInfo* newManifold) { - assert(oldManifold != nullptr); - assert(newManifold != nullptr); + assert(oldManifold != nullptr); + assert(newManifold != nullptr); // For each contact point of the new manifold ContactPointInfo* contactPointInfo = newManifold->getFirstContactPointInfo(); @@ -114,7 +87,7 @@ void ContactManifoldSet::updateManifoldWithNewOne(ContactManifold* oldManifold, if (oldContactPoint->isSimilarWithContactPoint(contactPointInfo)) { // Replace (update) the old contact point with the new one - oldContactPoint->update(contactPointInfo, mShape1->getLocalToWorldTransform(), mShape2->getLocalToWorldTransform()); + oldContactPoint->update(contactPointInfo); isSimilarPointFound = true; break; } @@ -136,53 +109,34 @@ void ContactManifoldSet::updateManifoldWithNewOne(ContactManifold* oldManifold, oldManifold->setIsObsolete(false, false); } -// Return the manifold to remove (because it is too old or has not the largest penetration depth) -ContactManifold* ContactManifoldSet::selectManifoldToRemove(decimal penDepthNewManifold) const { +// Remove a contact manifold that is the least optimal (smaller penetration depth) +void ContactManifoldSet::removeNonOptimalManifold() { - assert(mNbManifolds == mNbMaxManifolds); + assert(mNbManifolds > mNbMaxManifolds); assert(mManifolds != nullptr); // Look for a manifold that is not new and with the smallest contact penetration depth. // At the same time, we also look for a new manifold with the smallest contact penetration depth // in case no old manifold exists. - ContactManifold* minDepthOldManifold = nullptr; - ContactManifold* minDepthNewManifold = nullptr; - decimal minDepthOld = DECIMAL_LARGEST; - decimal minDepthNew = penDepthNewManifold; + ContactManifold* minDepthManifold = nullptr; + decimal minDepth = DECIMAL_LARGEST; ContactManifold* manifold = mManifolds; while (manifold != nullptr) { // Get the largest contact point penetration depth of the manifold const decimal depth = manifold->getLargestContactDepth(); - // If it is a new manifold - if (manifold->getIsNew()) { - - if (depth < minDepthNew) { - minDepthNew = depth; - minDepthNewManifold = manifold; - } - } - else { - - if (depth < minDepthOld) { - minDepthOld = depth; - minDepthOldManifold = manifold; - } + if (depth < minDepth) { + minDepth = depth; + minDepthManifold = manifold; } manifold = manifold->getNext(); } - // If there was a contact manifold that was not new - if (minDepthOldManifold != nullptr) { - - // Return the old manifold with the smallest penetration depth - return minDepthOldManifold; - } - - // Otherwise, we return the new manifold with the smallest penetration depth - return minDepthNewManifold; + // Remove the non optimal manifold + assert(minDepthManifold != nullptr); + removeManifold(minDepthManifold); } // Return the contact manifold with a similar average normal. @@ -262,7 +216,6 @@ void ContactManifoldSet::clear() { // Create a new contact manifold and add it to the set void ContactManifoldSet::createManifold(const ContactManifoldInfo* manifoldInfo) { - assert(mNbManifolds < mNbMaxManifolds); ContactManifold* manifold = new (mMemoryAllocator.allocate(sizeof(ContactManifold))) ContactManifold(manifoldInfo, mShape1, mShape2, mMemoryAllocator); @@ -333,9 +286,26 @@ void ContactManifoldSet::clearObsoleteManifoldsAndContactPoints() { else { // Clear the obsolete contact points of the manifold - manifold->clearObseleteContactPoints(); + manifold->clearObsoleteContactPoints(); } manifold = nextManifold; } } + + +// Remove some contact manifolds and contact points if there are too many of them +void ContactManifoldSet::reduce() { + + // Remove non optimal contact manifold while there are too many manifolds in the set + while (mNbManifolds > mNbMaxManifolds) { + removeNonOptimalManifold(); + } + + // Reduce all the contact manifolds in case they have too many contact points + ContactManifold* manifold = mManifolds; + while (manifold != nullptr) { + manifold->reduce(); + manifold = manifold->getNext(); + } +} diff --git a/src/collision/ContactManifoldSet.h b/src/collision/ContactManifoldSet.h index ea832cdb..4b33eb8c 100644 --- a/src/collision/ContactManifoldSet.h +++ b/src/collision/ContactManifoldSet.h @@ -74,8 +74,8 @@ class ContactManifoldSet { // Return the contact manifold with a similar average normal. ContactManifold* selectManifoldWithSimilarNormal(short int normalDirectionId) const; - /// Return the manifold to remove (because it is too old or has not the largest penetration depth) - ContactManifold* selectManifoldToRemove(decimal penDepthNewManifold) const; + /// Remove a contact manifold that is the least optimal (smaller penetration depth) + void removeNonOptimalManifold(); /// Update a previous similar manifold with a new one void updateManifoldWithNewOne(ContactManifold* oldManifold, const ContactManifoldInfo* newManifold); @@ -124,8 +124,8 @@ class ContactManifoldSet { /// Clear the obsolete contact manifolds and contact points void clearObsoleteManifoldsAndContactPoints(); - /// Reset the isNew status of all the manifolds - void resetIsNewManifoldStatus(); + // Remove some contact manifolds and contact points if there are too many of them + void reduce(); // Map the normal vector into a cubemap face bucket (a face contains 4x4 buckets) // Each face of the cube is divided into 4x4 buckets. This method maps the @@ -180,17 +180,6 @@ inline int ContactManifoldSet::computeNbMaxContactManifolds(const CollisionShape } } - -// Reset the isNew status of all the manifolds -inline void ContactManifoldSet::resetIsNewManifoldStatus() { - - ContactManifold* manifold = mManifolds; - while (manifold != nullptr) { - manifold->setIsNew(false); - manifold = manifold->getNext(); - } -} - } #endif diff --git a/src/collision/ContactPointInfo.h b/src/collision/ContactPointInfo.h index 1ff8bfdd..6fbf9834 100644 --- a/src/collision/ContactPointInfo.h +++ b/src/collision/ContactPointInfo.h @@ -77,6 +77,8 @@ struct ContactPointInfo { : normal(contactNormal), penetrationDepth(penDepth), localPoint1(localPt1), localPoint2(localPt2), next(nullptr), isUsed(false) { + assert(contactNormal.lengthSquare() > decimal(0.8)); + assert(penDepth > decimal(0.0)); } /// Destructor diff --git a/src/constraint/ContactPoint.cpp b/src/constraint/ContactPoint.cpp index 2cd951b4..b99d52f1 100644 --- a/src/constraint/ContactPoint.cpp +++ b/src/constraint/ContactPoint.cpp @@ -31,26 +31,22 @@ using namespace reactphysics3d; using namespace std; // Constructor -ContactPoint::ContactPoint(const ContactPointInfo* contactInfo, const Transform& body1Transform, - const Transform& body2Transform) +ContactPoint::ContactPoint(const ContactPointInfo* contactInfo) : mNormal(contactInfo->normal), mPenetrationDepth(contactInfo->penetrationDepth), mLocalPointOnBody1(contactInfo->localPoint1), mLocalPointOnBody2(contactInfo->localPoint2), - mIsRestingContact(false), mIsObsolete(false), mNext(nullptr) { + mIsRestingContact(false), mIsObsolete(false), mNext(nullptr), mPrevious(nullptr) { assert(mPenetrationDepth > decimal(0.0)); - - // Compute the world position of the contact points - mWorldPointOnBody1 = body1Transform * mLocalPointOnBody1; - mWorldPointOnBody2 = body2Transform * mLocalPointOnBody2; + assert(mNormal.lengthSquare() > decimal(0.8)); mIsObsolete = false; } // Update the contact point with a new one that is similar (very close) /// The idea is to keep the cache impulse (for warm starting the contact solver) -void ContactPoint::update(const ContactPointInfo* contactInfo, const Transform& body1Transform, const Transform& body2Transform) { +void ContactPoint::update(const ContactPointInfo* contactInfo) { assert(isSimilarWithContactPoint(contactInfo)); assert(contactInfo->penetrationDepth > decimal(0.0)); @@ -60,9 +56,5 @@ void ContactPoint::update(const ContactPointInfo* contactInfo, const Transform& mLocalPointOnBody1 = contactInfo->localPoint1; mLocalPointOnBody2 = contactInfo->localPoint2; - // Compute the world position of the contact points - mWorldPointOnBody1 = body1Transform * mLocalPointOnBody1; - mWorldPointOnBody2 = body2Transform * mLocalPointOnBody2; - mIsObsolete = false; } diff --git a/src/constraint/ContactPoint.h b/src/constraint/ContactPoint.h index 288abdcc..e2a9a5e5 100644 --- a/src/constraint/ContactPoint.h +++ b/src/constraint/ContactPoint.h @@ -59,12 +59,6 @@ class ContactPoint { /// Contact point on body 2 in local space of body 2 Vector3 mLocalPointOnBody2; - /// Contact point on body 1 in world space - Vector3 mWorldPointOnBody1; - - /// Contact point on body 2 in world space - Vector3 mWorldPointOnBody2; - /// True if the contact is a resting contact (exists for more than one time step) bool mIsRestingContact; @@ -74,14 +68,16 @@ class ContactPoint { /// True if the contact point is obsolete bool mIsObsolete; - /// Pointer to the next contact point in the linked-list + /// Pointer to the next contact point in the double linked-list ContactPoint* mNext; + /// Pointer to the previous contact point in the double linked-list + ContactPoint* mPrevious; + // -------------------- Methods -------------------- // /// Update the contact point with a new one that is similar (very close) - void update(const ContactPointInfo* contactInfo, const Transform& body1Transform, - const Transform& body2Transform); + void update(const ContactPointInfo* contactInfo); /// Return true if the contact point is similar (close enougth) to another given contact point bool isSimilarWithContactPoint(const ContactPointInfo* contactPoint) const; @@ -99,6 +95,9 @@ class ContactPoint { /// Set the next contact point in the linked list void setNext(ContactPoint* next); + /// Set the previous contact point in the linked list + void setPrevious(ContactPoint* previous); + /// Return true if the contact point is obsolete bool getIsObsolete() const; @@ -107,8 +106,7 @@ class ContactPoint { // -------------------- Methods -------------------- // /// Constructor - ContactPoint(const ContactPointInfo* contactInfo, const Transform& body1Transform, - const Transform& body2Transform); + ContactPoint(const ContactPointInfo* contactInfo); /// Destructor ~ContactPoint() = default; @@ -128,18 +126,15 @@ class ContactPoint { /// Return the contact local point on body 2 Vector3 getLocalPointOnBody2() const; - /// Return the contact world point on body 1 - Vector3 getWorldPointOnBody1() const; - - /// Return the contact world point on body 2 - Vector3 getWorldPointOnBody2() const; - /// Return the cached penetration impulse decimal getPenetrationImpulse() const; /// Return true if the contact is a resting contact bool getIsRestingContact() const; + /// Return the previous contact point in the linked list + inline ContactPoint* getPrevious() const; + /// Return the next contact point in the linked list ContactPoint* getNext() const; @@ -170,16 +165,6 @@ inline Vector3 ContactPoint::getLocalPointOnBody2() const { return mLocalPointOnBody2; } -// Return the contact world point on body 1 -inline Vector3 ContactPoint::getWorldPointOnBody1() const { - return mWorldPointOnBody1; -} - -// Return the contact world point on body 2 -inline Vector3 ContactPoint::getWorldPointOnBody2() const { - return mWorldPointOnBody2; -} - // Return the cached penetration impulse inline decimal ContactPoint::getPenetrationImpulse() const { return mPenetrationImpulse; @@ -226,6 +211,16 @@ inline void ContactPoint::setNext(ContactPoint* next) { mNext = next; } +// Return the previous contact point in the linked list +inline ContactPoint* ContactPoint::getPrevious() const { + return mPrevious; +} + +// Set the previous contact point in the linked list +inline void ContactPoint::setPrevious(ContactPoint* previous) { + mPrevious = previous; +} + // Return the penetration depth of the contact inline decimal ContactPoint::getPenetrationDepth() const { return mPenetrationDepth; diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index 94a82b14..819a1b76 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -120,6 +120,10 @@ void ContactSolver::initializeForIsland(Island* island) { assert(body1 != nullptr); assert(body2 != nullptr); + // Get the two contact shapes + const ProxyShape* shape1 = externalManifold->getShape1(); + const ProxyShape* shape2 = externalManifold->getShape2(); + // Get the position of the two bodies const Vector3& x1 = body1->mCenterOfMassWorld; const Vector3& x2 = body2->mCenterOfMassWorld; @@ -149,11 +153,12 @@ void ContactSolver::initializeForIsland(Island* island) { // For each contact point of the contact manifold ContactPoint* externalContact = externalManifold->getContactPoints(); + assert(externalContact != nullptr); while (externalContact != nullptr) { // Get the contact point on the two bodies - Vector3 p1 = externalContact->getWorldPointOnBody1(); - Vector3 p2 = externalContact->getWorldPointOnBody2(); + Vector3 p1 = shape1->getLocalToWorldTransform() * externalContact->getLocalPointOnBody1(); + Vector3 p2 = shape2->getLocalToWorldTransform() * externalContact->getLocalPointOnBody2(); new (mContactPoints + mNbContactPoints) ContactPointSolver(); mContactPoints[mNbContactPoints].externalContact = externalContact; diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index 2725a8d5..47f13bfb 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -136,9 +136,6 @@ class OverlappingPair { /// Return the last frame collision info LastFrameCollisionInfo& getLastFrameCollisionInfo(); - /// Return the number of contacts in the cache - uint getNbContactPoints() const; - /// Return the a reference to the contact manifold set const ContactManifoldSet& getContactManifoldSet(); @@ -167,13 +164,13 @@ class OverlappingPair { void reducePotentialContactManifolds(); /// Make the contact manifolds and contact points obsolete - void makeContactsObselete(); + void makeContactsObsolete(); /// Clear the obsolete contact manifold and contact points void clearObsoleteManifoldsAndContactPoints(); - /// Reset the isNew status of all the manifolds - void resetIsNewManifoldStatus(); + /// Reduce the contact manifolds that have too many contact points + void reduceContactManifolds(); /// Return the pair of bodies index static overlappingpairid computeID(ProxyShape* shape1, ProxyShape* shape2); @@ -206,18 +203,13 @@ inline LastFrameCollisionInfo& OverlappingPair::getLastFrameCollisionInfo() { return mLastFrameCollisionInfo; } -// Return the number of contact points in the contact manifold -inline uint OverlappingPair::getNbContactPoints() const { - return mContactManifoldSet.getTotalNbContactPoints(); -} - // Return the contact manifold inline const ContactManifoldSet& OverlappingPair::getContactManifoldSet() { return mContactManifoldSet; } // Make the contact manifolds and contact points obsolete -inline void OverlappingPair::makeContactsObselete() { +inline void OverlappingPair::makeContactsObsolete() { mContactManifoldSet.makeContactsObsolete(); } @@ -272,10 +264,9 @@ inline void OverlappingPair::clearObsoleteManifoldsAndContactPoints() { mContactManifoldSet.clearObsoleteManifoldsAndContactPoints(); } - -// Reset the isNew status of all the manifolds -inline void OverlappingPair::resetIsNewManifoldStatus() { - mContactManifoldSet.resetIsNewManifoldStatus(); +// Reduce the contact manifolds that have too many contact points +inline void OverlappingPair::reduceContactManifolds() { + mContactManifoldSet.reduce(); } } From 0250d8c4bdaca0c7eaf581e5f85839058d72055c Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 18 Oct 2017 19:35:20 +0200 Subject: [PATCH 114/248] Fix issue in SAT algorithm --- src/collision/narrowphase/SAT/SATAlgorithm.cpp | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index a663791c..4411187b 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -731,7 +731,18 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn bool contactsFound = computePolyhedronVsPolyhedronFaceContactPoints(isMinPenetrationFaceNormalPolyhedron1, polyhedron1, polyhedron2, polyhedron1ToPolyhedron2, polyhedron2ToPolyhedron1, minFaceIndex, narrowPhaseInfo, minPenetrationDepth); - assert(contactsFound); + + // There should be clipping points here. If it is not the case, it might be + // because of a numerical issue + if (!contactsFound) { + + lastFrameInfo.satIsAxisFacePolyhedron1 = isMinPenetrationFaceNormalPolyhedron1; + lastFrameInfo.satIsAxisFacePolyhedron2 = !isMinPenetrationFaceNormalPolyhedron1; + lastFrameInfo.satMinAxisFaceIndex = minFaceIndex; + + // Return no collision + return false; + } } lastFrameInfo.satIsAxisFacePolyhedron1 = isMinPenetrationFaceNormalPolyhedron1; From cdec7413c516ffe2671d0cbde45f5b60ef1d68e5 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 18 Oct 2017 21:26:53 +0200 Subject: [PATCH 115/248] Improve capsule resting on another shape stability --- .../narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp | 5 +++-- src/mathematics/mathematics_functions.cpp | 2 +- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp index 72ba2e06..d6de739a 100644 --- a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp @@ -86,14 +86,15 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPh const Vector3 capsuleSegA(0, -capsuleShape->getHeight() * decimal(0.5), 0); const Vector3 capsuleSegB(0, capsuleShape->getHeight() * decimal(0.5), 0); - const Vector3 capsuleInnerSegmentWorld = capsuleToWorld.getOrientation() * (capsuleSegB - capsuleSegA); + Vector3 capsuleInnerSegmentDirection = capsuleToWorld.getOrientation() * (capsuleSegB - capsuleSegA); + capsuleInnerSegmentDirection.normalize(); bool isFaceNormalInDirectionOfContactNormal = faceNormalWorld.dot(contactPoint->normal) > decimal(0.0); bool isFaceNormalInContactDirection = (isCapsuleShape1 && !isFaceNormalInDirectionOfContactNormal) || (!isCapsuleShape1 && isFaceNormalInDirectionOfContactNormal); // If the polyhedron face normal is orthogonal to the capsule inner segment and parallel to the contact point normal and the face normal // is in direction of the contact normal (from the polyhedron point of view). - if (isFaceNormalInContactDirection && areOrthogonalVectors(faceNormalWorld, capsuleInnerSegmentWorld) + if (isFaceNormalInContactDirection && areOrthogonalVectors(faceNormalWorld, capsuleInnerSegmentDirection) && areParallelVectors(faceNormalWorld, contactPoint->normal)) { // Remove the previous contact point computed by GJK diff --git a/src/mathematics/mathematics_functions.cpp b/src/mathematics/mathematics_functions.cpp index fd813cdc..37335abe 100755 --- a/src/mathematics/mathematics_functions.cpp +++ b/src/mathematics/mathematics_functions.cpp @@ -80,7 +80,7 @@ bool reactphysics3d::areParallelVectors(const Vector3& vector1, const Vector3& v // Return true if two vectors are orthogonal bool reactphysics3d::areOrthogonalVectors(const Vector3& vector1, const Vector3& vector2) { - return std::abs(vector1.dot(vector2)) < decimal(0.00001); + return std::abs(vector1.dot(vector2)) < decimal(0.001); } // Compute and return a point on segment from "segPointA" and "segPointB" that is closest to point "pointC" From c1295f1d7aa71f092dce03a5be2207d6f67bbe1f Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 19 Oct 2017 07:26:11 +0200 Subject: [PATCH 116/248] Remove contactNormaldId attribute and fix typo --- src/collision/ContactManifold.cpp | 2 +- src/collision/ContactManifold.h | 8 ---- src/collision/ContactManifoldInfo.cpp | 11 ++---- src/collision/ContactManifoldInfo.h | 13 +----- src/collision/ContactManifoldSet.cpp | 57 +++++++-------------------- src/collision/ContactManifoldSet.h | 9 +---- src/configuration.h | 9 ++++- src/engine/DynamicsWorld.cpp | 2 +- src/engine/OverlappingPair.cpp | 13 +++--- 9 files changed, 38 insertions(+), 86 deletions(-) diff --git a/src/collision/ContactManifold.cpp b/src/collision/ContactManifold.cpp index 55ce8ba3..c2d60422 100644 --- a/src/collision/ContactManifold.cpp +++ b/src/collision/ContactManifold.cpp @@ -31,7 +31,7 @@ using namespace reactphysics3d; // Constructor ContactManifold::ContactManifold(const ContactManifoldInfo* manifoldInfo, ProxyShape* shape1, ProxyShape* shape2, Allocator& memoryAllocator) - : mShape1(shape1), mShape2(shape2), mContactPoints(nullptr), mContactNormalId(manifoldInfo->getContactNormalId()), + : mShape1(shape1), mShape2(shape2), mContactPoints(nullptr), mNbContactPoints(0), mFrictionImpulse1(0.0), mFrictionImpulse2(0.0), mFrictionTwistImpulse(0.0), mIsAlreadyInIsland(false), mMemoryAllocator(memoryAllocator), mNext(nullptr), mPrevious(nullptr), mIsObsolete(false) { diff --git a/src/collision/ContactManifold.h b/src/collision/ContactManifold.h index b5c25cb9..80a9f456 100644 --- a/src/collision/ContactManifold.h +++ b/src/collision/ContactManifold.h @@ -104,9 +104,6 @@ class ContactManifold { /// Contact points in the manifold ContactPoint* mContactPoints; - /// Normal direction Id (Unique Id representing the normal direction) - short int mContactNormalId; - /// Number of contacts in the cache int8 mNbContactPoints; @@ -412,11 +409,6 @@ inline void ContactManifold::setIsObsolete(bool isObsolete, bool setContactPoint } } -// Return the contact normal direction Id of the manifold -inline short ContactManifold::getContactNormalId() const { - return mContactNormalId; -} - } #endif diff --git a/src/collision/ContactManifoldInfo.cpp b/src/collision/ContactManifoldInfo.cpp index a6b8c6df..f22593ac 100644 --- a/src/collision/ContactManifoldInfo.cpp +++ b/src/collision/ContactManifoldInfo.cpp @@ -30,8 +30,9 @@ using namespace reactphysics3d; // Constructor ContactManifoldInfo::ContactManifoldInfo(Allocator& allocator) - : mContactPointsList(nullptr), mNbContactPoints(0), mNext(nullptr), mAllocator(allocator), - mContactNormalId(-1) {} + : mContactPointsList(nullptr), mNbContactPoints(0), mNext(nullptr), mAllocator(allocator) { + +} // Destructor ContactManifoldInfo::~ContactManifoldInfo() { @@ -41,13 +42,9 @@ ContactManifoldInfo::~ContactManifoldInfo() { } // Add a new contact point into the manifold -void ContactManifoldInfo::addContactPoint(ContactPointInfo* contactPointInfo, short contactNormalId) { +void ContactManifoldInfo::addContactPoint(ContactPointInfo* contactPointInfo) { assert(contactPointInfo->penetrationDepth > decimal(0.0)); - assert(contactNormalId >= 0); - assert(mContactNormalId == -1 || contactNormalId == mContactNormalId); - - mContactNormalId = contactNormalId; // Add it into the linked list of contact points contactPointInfo->next = mContactPointsList; diff --git a/src/collision/ContactManifoldInfo.h b/src/collision/ContactManifoldInfo.h index 5851c375..4126f4c8 100644 --- a/src/collision/ContactManifoldInfo.h +++ b/src/collision/ContactManifoldInfo.h @@ -59,9 +59,6 @@ class ContactManifoldInfo { /// Reference the the memory allocator where the contact point infos have been allocated Allocator& mAllocator; - /// Contact normal direction Id (Identify the contact normal direction of points in manifold) - short mContactNormalId; - public: // -------------------- Methods -------------------- // @@ -79,7 +76,7 @@ class ContactManifoldInfo { ContactManifoldInfo& operator=(const ContactManifoldInfo& contactManifold) = delete; /// Add a new contact point into the manifold - void addContactPoint(ContactPointInfo* contactPointInfo, short contactNormalId); + void addContactPoint(ContactPointInfo* contactPointInfo); /// Remove all the contact points void reset(); @@ -93,9 +90,6 @@ class ContactManifoldInfo { /// Return the pointer to the next manifold info in the linked-list ContactManifoldInfo* getNext(); - /// Return the contact normal Id - short getContactNormalId() const; - /// Reduce the number of contact points of the currently computed manifold void reduce(const Transform& shape1ToWorldTransform); @@ -114,11 +108,6 @@ inline ContactManifoldInfo* ContactManifoldInfo::getNext() { return mNext; } -// Return the contact normal Id -inline short ContactManifoldInfo::getContactNormalId() const { - return mContactNormalId; -} - } #endif diff --git a/src/collision/ContactManifoldSet.cpp b/src/collision/ContactManifoldSet.cpp index 9b8bf58b..ce3e4492 100644 --- a/src/collision/ContactManifoldSet.cpp +++ b/src/collision/ContactManifoldSet.cpp @@ -50,7 +50,7 @@ void ContactManifoldSet::addContactManifold(const ContactManifoldInfo* contactMa assert(contactManifoldInfo->getFirstContactPointInfo() != nullptr); // Try to find an existing contact manifold with similar contact normal - ContactManifold* similarManifold = selectManifoldWithSimilarNormal(contactManifoldInfo->getContactNormalId()); + ContactManifold* similarManifold = selectManifoldWithSimilarNormal(contactManifoldInfo); // If a similar manifold has been found if (similarManifold != nullptr) { @@ -139,15 +139,25 @@ void ContactManifoldSet::removeNonOptimalManifold() { removeManifold(minDepthManifold); } -// Return the contact manifold with a similar average normal. -// If no manifold has close enough average normal, it returns nullptr -ContactManifold* ContactManifoldSet::selectManifoldWithSimilarNormal(short int normalDirectionId) const { +// Return the contact manifold with a similar contact normal. +// If no manifold has close enough contact normal, it returns nullptr +ContactManifold* ContactManifoldSet::selectManifoldWithSimilarNormal(const ContactManifoldInfo* contactManifold) const { + + // Get the contact normal of the first point of the manifold + const ContactPointInfo* contactPoint = contactManifold->getFirstContactPointInfo(); + assert(contactPoint != nullptr); ContactManifold* manifold = mManifolds; // Return the Id of the manifold with the same normal direction id (if exists) while (manifold != nullptr) { - if (normalDirectionId == manifold->getContactNormalId()) { + + // Get the first contact point of the current manifold + const ContactPoint* point = manifold->getContactPoints(); + assert(point != nullptr); + + // If the contact normal of the two manifolds are close enough + if (contactPoint->normal.dot(point->getNormal()) >= COS_ANGLE_SIMILAR_CONTACT_MANIFOLD) { return manifold; } @@ -157,43 +167,6 @@ ContactManifold* ContactManifoldSet::selectManifoldWithSimilarNormal(short int n return nullptr; } -// Map the normal vector into a cubemap face bucket (a face contains 4x4 buckets) -// Each face of the cube is divided into 4x4 buckets. This method maps the -// normal vector into of the of the bucket and returns a unique Id for the bucket -short int ContactManifoldSet::computeCubemapNormalId(const Vector3& normal) { - - assert(normal.lengthSquare() > MACHINE_EPSILON); - - int faceNo; - decimal u, v; - decimal max = max3(std::fabs(normal.x), std::fabs(normal.y), std::fabs(normal.z)); - Vector3 normalScaled = normal / max; - - if (normalScaled.x >= normalScaled.y && normalScaled.x >= normalScaled.z) { - faceNo = normalScaled.x > 0 ? 0 : 1; - u = normalScaled.y; - v = normalScaled.z; - } - else if (normalScaled.y >= normalScaled.x && normalScaled.y >= normalScaled.z) { - faceNo = normalScaled.y > 0 ? 2 : 3; - u = normalScaled.x; - v = normalScaled.z; - } - else { - faceNo = normalScaled.z > 0 ? 4 : 5; - u = normalScaled.x; - v = normalScaled.y; - } - - int indexU = std::floor(((u + 1)/2) * CONTACT_CUBEMAP_FACE_NB_SUBDIVISIONS); - int indexV = std::floor(((v + 1)/2) * CONTACT_CUBEMAP_FACE_NB_SUBDIVISIONS); - if (indexU == CONTACT_CUBEMAP_FACE_NB_SUBDIVISIONS) indexU--; - if (indexV == CONTACT_CUBEMAP_FACE_NB_SUBDIVISIONS) indexV--; - - const int nbSubDivInFace = CONTACT_CUBEMAP_FACE_NB_SUBDIVISIONS * CONTACT_CUBEMAP_FACE_NB_SUBDIVISIONS; - return faceNo * 200 + indexU * nbSubDivInFace + indexV; -} - // Clear the contact manifold set void ContactManifoldSet::clear() { diff --git a/src/collision/ContactManifoldSet.h b/src/collision/ContactManifoldSet.h index 4b33eb8c..13d27b70 100644 --- a/src/collision/ContactManifoldSet.h +++ b/src/collision/ContactManifoldSet.h @@ -71,8 +71,8 @@ class ContactManifoldSet { /// Create a new contact manifold and add it to the set void createManifold(const ContactManifoldInfo* manifoldInfo); - // Return the contact manifold with a similar average normal. - ContactManifold* selectManifoldWithSimilarNormal(short int normalDirectionId) const; + // Return the contact manifold with a similar contact normal. + ContactManifold* selectManifoldWithSimilarNormal(const ContactManifoldInfo* contactManifold) const; /// Remove a contact manifold that is the least optimal (smaller penetration depth) void removeNonOptimalManifold(); @@ -126,11 +126,6 @@ class ContactManifoldSet { // Remove some contact manifolds and contact points if there are too many of them void reduce(); - - // Map the normal vector into a cubemap face bucket (a face contains 4x4 buckets) - // Each face of the cube is divided into 4x4 buckets. This method maps the - // normal vector into of the of the bucket and returns a unique Id for the bucket - static short int computeCubemapNormalId(const Vector3& normal); }; // Return the first proxy shape diff --git a/src/configuration.h b/src/configuration.h index 444bd1db..779b45e2 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -99,8 +99,8 @@ constexpr decimal DEFAULT_BOUNCINESS = decimal(0.5); /// Default rolling resistance constexpr decimal DEFAULT_ROLLING_RESISTANCE = decimal(0.0); -/// True if the spleeping technique is enabled -constexpr bool SPLEEPING_ENABLED = true; +/// True if the sleeping technique is enabled +constexpr bool SLEEPING_ENABLED = true; /// Distance threshold for two contact points for a valid persistent contact (in meters) constexpr decimal PERSISTENT_CONTACT_DIST_THRESHOLD = decimal(0.03); @@ -143,6 +143,11 @@ constexpr int NB_MAX_CONTACT_MANIFOLDS_CONVEX_SHAPE = 1; /// least one concave collision shape. constexpr int NB_MAX_CONTACT_MANIFOLDS_CONCAVE_SHAPE = 3; +/// This is used to test if two contact manifold are similar (same contact normal) in order to +/// merge them. If the cosine of the angle between the normals of the two manifold are larger +/// than the value bellow, the manifold are considered to be similar. +constexpr decimal COS_ANGLE_SIMILAR_CONTACT_MANIFOLD = decimal(0.95); + /// Size (in bytes) of the single frame allocator constexpr size_t SIZE_SINGLE_FRAME_ALLOCATOR_BYTES = 15728640; // 15 Mb diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index 136d34f6..09712c3c 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -44,7 +44,7 @@ DynamicsWorld::DynamicsWorld(const Vector3 &gravity) mConstraintSolver(mMapBodyToConstrainedVelocityIndex), mNbVelocitySolverIterations(DEFAULT_VELOCITY_SOLVER_NB_ITERATIONS), mNbPositionSolverIterations(DEFAULT_POSITION_SOLVER_NB_ITERATIONS), - mIsSleepingEnabled(SPLEEPING_ENABLED), mGravity(gravity), + mIsSleepingEnabled(SLEEPING_ENABLED), mGravity(gravity), mIsGravityEnabled(true), mConstrainedLinearVelocities(nullptr), mConstrainedAngularVelocities(nullptr), mSplitLinearVelocities(nullptr), mSplitAngularVelocities(nullptr), mConstrainedPositions(nullptr), diff --git a/src/engine/OverlappingPair.cpp b/src/engine/OverlappingPair.cpp index f3f85fa1..0055e683 100644 --- a/src/engine/OverlappingPair.cpp +++ b/src/engine/OverlappingPair.cpp @@ -54,21 +54,22 @@ void OverlappingPair::addPotentialContactPoints(NarrowPhaseInfo* narrowPhaseInfo ContactPointInfo* nextContactPoint = contactPoint->next; - // Compute the contact normal id - short contactNormalId = ContactManifoldSet::computeCubemapNormalId(contactPoint->normal); - // Look if the contact point correspond to an existing potential manifold // (if the contact point normal is similar to the normal of an existing manifold) ContactManifoldInfo* manifold = mPotentialContactManifolds; bool similarManifoldFound = false; while(manifold != nullptr) { + // Get the first contact point + const ContactPointInfo* point = manifold->getFirstContactPointInfo(); + assert(point != nullptr); + // If we have found a corresponding manifold for the new contact point // (a manifold with a similar contact normal direction) - if (manifold->getContactNormalId() == contactNormalId) { + if (point->normal.dot(contactPoint->normal) >= COS_ANGLE_SIMILAR_CONTACT_MANIFOLD) { // Add the contact point to the manifold - manifold->addContactPoint(contactPoint, contactNormalId); + manifold->addContactPoint(contactPoint); similarManifoldFound = true; @@ -90,7 +91,7 @@ void OverlappingPair::addPotentialContactPoints(NarrowPhaseInfo* narrowPhaseInfo mPotentialContactManifolds = manifoldInfo; // Add the contact point to the manifold - manifoldInfo->addContactPoint(contactPoint, contactNormalId); + manifoldInfo->addContactPoint(contactPoint); } contactPoint = nextContactPoint; From cdaa297a7800a10ecd14dc0ddf7fbc4561502887 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 19 Oct 2017 17:19:33 +0200 Subject: [PATCH 117/248] Remove unused variable --- src/engine/OverlappingPair.h | 4 ---- 1 file changed, 4 deletions(-) diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index 47f13bfb..ce22bb7e 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -56,10 +56,6 @@ struct LastFrameCollisionInfo { /// True if we were using SAT algorithm to check for collision in the previous frame bool wasUsingSAT; - /// True if there was a narrow-phase collision - /// in the previous frame - bool wasCollidingLastFrame; - // ----- GJK Algorithm ----- /// Previous separating axis From b1aad2b7c493e6b46cf28e138b65d522ae624333 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 19 Oct 2017 17:42:21 +0200 Subject: [PATCH 118/248] Refactor the testbed application --- testbed/common/Box.h | 2 +- testbed/common/Capsule.h | 3 +- testbed/common/ConvexMesh.h | 3 +- testbed/common/Dumbbell.h | 4 +- testbed/common/PhysicsObject.h | 3 + testbed/common/Sphere.h | 3 +- .../CollisionDetectionScene.cpp | 60 ++---- .../CollisionDetectionScene.h | 10 +- .../collisionshapes/CollisionShapesScene.cpp | 154 +------------- .../collisionshapes/CollisionShapesScene.h | 9 +- testbed/scenes/cubes/CubesScene.cpp | 35 +--- testbed/scenes/cubes/CubesScene.h | 7 - .../scenes/heightfield/HeightFieldScene.cpp | 191 +++++++++++++----- testbed/scenes/heightfield/HeightFieldScene.h | 47 ++++- testbed/scenes/joints/JointsScene.cpp | 27 +-- testbed/scenes/joints/JointsScene.h | 3 - testbed/scenes/raycast/RaycastScene.cpp | 33 +-- testbed/scenes/raycast/RaycastScene.h | 6 +- testbed/src/SceneDemo.cpp | 32 ++- testbed/src/SceneDemo.h | 10 +- testbed/src/TestbedApplication.cpp | 2 +- 21 files changed, 281 insertions(+), 363 deletions(-) mode change 100644 => 100755 testbed/scenes/cubes/CubesScene.cpp mode change 100644 => 100755 testbed/scenes/cubes/CubesScene.h diff --git a/testbed/common/Box.h b/testbed/common/Box.h index a1f05d5e..bd7a6024 100644 --- a/testbed/common/Box.h +++ b/testbed/common/Box.h @@ -86,7 +86,7 @@ class Box : public PhysicsObject { ~Box(); /// Render the cube at the correct position and with the correct orientation - void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe); + virtual void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe) override; /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; diff --git a/testbed/common/Capsule.h b/testbed/common/Capsule.h index f117984f..5c99120b 100644 --- a/testbed/common/Capsule.h +++ b/testbed/common/Capsule.h @@ -94,8 +94,7 @@ class Capsule : public PhysicsObject { ~Capsule(); /// Render the sphere at the correct position and with the correct orientation - void render(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix, bool wireframe); + virtual void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe) override; /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; diff --git a/testbed/common/ConvexMesh.h b/testbed/common/ConvexMesh.h index e2ba5836..1b55611b 100644 --- a/testbed/common/ConvexMesh.h +++ b/testbed/common/ConvexMesh.h @@ -90,8 +90,7 @@ class ConvexMesh : public PhysicsObject { ~ConvexMesh(); /// Render the mesh at the correct position and with the correct orientation - void render(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix, bool wireframe); + virtual void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe) override; /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; diff --git a/testbed/common/Dumbbell.h b/testbed/common/Dumbbell.h index ea2d3d88..aa6bded1 100644 --- a/testbed/common/Dumbbell.h +++ b/testbed/common/Dumbbell.h @@ -89,13 +89,11 @@ class Dumbbell : public PhysicsObject { Dumbbell(const openglframework::Vector3& position, rp3d::CollisionWorld* world, const std::string& meshFolderPath); - /// Destructor ~Dumbbell(); /// Render the sphere at the correct position and with the correct orientation - void render(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix, bool wireframe); + virtual void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe) override; /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; diff --git a/testbed/common/PhysicsObject.h b/testbed/common/PhysicsObject.h index 0da224c3..7fcc612d 100644 --- a/testbed/common/PhysicsObject.h +++ b/testbed/common/PhysicsObject.h @@ -62,6 +62,9 @@ class PhysicsObject : public openglframework::Mesh { /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor)=0; + /// Render the sphere at the correct position and with the correct orientation + virtual void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe)=0; + /// Set the color of the box void setColor(const openglframework::Color& color); diff --git a/testbed/common/Sphere.h b/testbed/common/Sphere.h index 62f1809e..000cc776 100644 --- a/testbed/common/Sphere.h +++ b/testbed/common/Sphere.h @@ -90,8 +90,7 @@ class Sphere : public PhysicsObject { ~Sphere(); /// Render the sphere at the correct position and with the correct orientation - void render(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix, bool wireframe); + void virtual render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe) override; /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp index 7606a61e..3b186943 100755 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp @@ -59,6 +59,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) // Set the color mSphere1->setColor(mGreyColorDemo); mSphere1->setSleepingColor(mRedColorDemo); + mPhysicsObjects.push_back(mSphere1); // ---------- Sphere 2 ---------- // openglframework::Vector3 position2(12, 8, 0); @@ -70,6 +71,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) // Set the color mSphere2->setColor(mGreyColorDemo); mSphere2->setSleepingColor(mRedColorDemo); + mPhysicsObjects.push_back(mSphere2); // ---------- Capsule 1 ---------- // openglframework::Vector3 position3(-6, 7, 0); @@ -81,6 +83,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) // Set the color mCapsule1->setColor(mGreyColorDemo); mCapsule1->setSleepingColor(mRedColorDemo); + mPhysicsObjects.push_back(mCapsule1); // ---------- Capsule 2 ---------- // openglframework::Vector3 position4(11, -8, 0); @@ -92,6 +95,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) // Set the color mCapsule2->setColor(mGreyColorDemo); mCapsule2->setSleepingColor(mRedColorDemo); + mPhysicsObjects.push_back(mCapsule2); // ---------- Box 1 ---------- // openglframework::Vector3 position5(-4, -7, 0); @@ -103,6 +107,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) // Set the color mBox1->setColor(mGreyColorDemo); mBox1->setSleepingColor(mRedColorDemo); + mPhysicsObjects.push_back(mBox1); // ---------- Box 2 ---------- // openglframework::Vector3 position6(0, 8, 0); @@ -114,6 +119,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) // Set the color mBox2->setColor(mGreyColorDemo); mBox2->setSleepingColor(mRedColorDemo); + mPhysicsObjects.push_back(mBox2); // ---------- Convex Mesh ---------- // openglframework::Vector3 position7(-5, 0, 0); @@ -125,9 +131,10 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) // Set the color mConvexMesh->setColor(mGreyColorDemo); mConvexMesh->setSleepingColor(mRedColorDemo); + mPhysicsObjects.push_back(mConvexMesh); // ---------- Concave Mesh ---------- // - openglframework::Vector3 position8(0, 0, 0); + openglframework::Vector3 position8(0, 100, 0); // Create a convex mesh and a corresponding collision body in the dynamics world mConcaveMesh = new ConcaveMesh(position8, mCollisionWorld, mMeshFolderPath + "city.obj"); @@ -136,16 +143,18 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) // Set the color mConcaveMesh->setColor(mGreyColorDemo); mConcaveMesh->setSleepingColor(mRedColorDemo); + mPhysicsObjects.push_back(mConcaveMesh); // ---------- Heightfield ---------- // - //openglframework::Vector3 position9(0, 0, 0); + openglframework::Vector3 position9(0, -12, 0); // Create a convex mesh and a corresponding collision body in the dynamics world - //mHeightField = new HeightField(position9, mCollisionWorld); + mHeightField = new HeightField(position9, mCollisionWorld); // Set the color - //mHeightField->setColor(mGreyColorDemo); - //mHeightField->setSleepingColor(mRedColorDemo); + mHeightField->setColor(mGreyColorDemo); + mHeightField->setSleepingColor(mRedColorDemo); + mPhysicsObjects.push_back(mHeightField); mAllShapes[mSelectedShapeIndex]->setColor(mBlueColorDemo); } @@ -187,6 +196,9 @@ CollisionDetectionScene::~CollisionDetectionScene() { mCollisionWorld->destroyCollisionBody(mConcaveMesh->getCollisionBody()); delete mConcaveMesh; + mCollisionWorld->destroyCollisionBody(mHeightField->getCollisionBody()); + delete mHeightField; + /* // Destroy the corresponding rigid body from the dynamics world mCollisionWorld->destroyCollisionBody(mCone->getCollisionBody()); @@ -210,11 +222,7 @@ CollisionDetectionScene::~CollisionDetectionScene() { // Destroy the dumbbell delete mDumbbell; - // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mHeightField->getCollisionBody()); - - // Destroy the convex mesh - delete mHeightField; + */ mContactManager.resetPoints(); @@ -226,12 +234,6 @@ CollisionDetectionScene::~CollisionDetectionScene() { delete mCollisionWorld; } -// Update the physics world (take a simulation step) -void CollisionDetectionScene::updatePhysics() { - - -} - // Take a step for the simulation void CollisionDetectionScene::update() { @@ -242,32 +244,6 @@ void CollisionDetectionScene::update() { SceneDemo::update(); } -// Render the scene -void CollisionDetectionScene::renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix) { - - // Render the shapes - if (mSphere1->getCollisionBody()->isActive()) mSphere1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - if (mSphere2->getCollisionBody()->isActive()) mSphere2->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - if (mCapsule1->getCollisionBody()->isActive()) mCapsule1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - if (mCapsule2->getCollisionBody()->isActive()) mCapsule2->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - if (mBox1->getCollisionBody()->isActive()) mBox1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - if (mBox2->getCollisionBody()->isActive()) mBox2->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - if (mConvexMesh->getCollisionBody()->isActive()) mConvexMesh->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - if (mConcaveMesh->getCollisionBody()->isActive()) mConcaveMesh->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - - /* - if (mBox->getCollisionBody()->isActive()) mBox->render(shader, worldToCameraMatrix); - if (mCone->getCollisionBody()->isActive()) mCone->render(shader, worldToCameraMatrix); - if (mCylinder->getCollisionBody()->isActive()) mCylinder->render(shader, worldToCameraMatrix); - if (mCapsule->getCollisionBody()->isActive()) mCapsule->render(shader, worldToCameraMatrix); - if (mDumbbell->getCollisionBody()->isActive()) mDumbbell->render(shader, worldToCameraMatrix); - if (mHeightField->getCollisionBody()->isActive()) mHeightField->render(shader, worldToCameraMatrix); - */ - - shader.unbind(); -} - void CollisionDetectionScene::selectNextShape() { int previousIndex = mSelectedShapeIndex; diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.h b/testbed/scenes/collisiondetection/CollisionDetectionScene.h index 8e94eaf5..8473ae73 100755 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.h +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.h @@ -148,7 +148,7 @@ class CollisionDetectionScene : public SceneDemo { ConvexMesh* mConvexMesh; //Dumbbell* mDumbbell; ConcaveMesh* mConcaveMesh; - //HeightField* mHeightField; + HeightField* mHeightField; std::vector mAllShapes; @@ -170,17 +170,9 @@ class CollisionDetectionScene : public SceneDemo { /// Destructor virtual ~CollisionDetectionScene() override; - /// Update the physics world (take a simulation step) - /// Can be called several times per frame - virtual void updatePhysics() override; - /// Take a step for the simulation virtual void update() override; - /// Render the scene in a single pass - virtual void renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix) override; - /// Reset the scene virtual void reset() override; diff --git a/testbed/scenes/collisionshapes/CollisionShapesScene.cpp b/testbed/scenes/collisionshapes/CollisionShapesScene.cpp index 746942ff..e63f39d4 100644 --- a/testbed/scenes/collisionshapes/CollisionShapesScene.cpp +++ b/testbed/scenes/collisionshapes/CollisionShapesScene.cpp @@ -71,6 +71,7 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name) // Add the mesh the list of dumbbells in the scene mDumbbells.push_back(dumbbell); + mPhysicsObjects.push_back(dumbbell); } // Create all the boxes of the scene @@ -95,6 +96,7 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name) // Add the sphere the list of sphere in the scene mBoxes.push_back(box); + mPhysicsObjects.push_back(box); } // Create all the spheres of the scene @@ -123,6 +125,7 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name) // Add the sphere the list of sphere in the scene mSpheres.push_back(sphere); + mPhysicsObjects.push_back(sphere); } // Create all the capsules of the scene @@ -150,6 +153,7 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name) // Add the cylinder the list of sphere in the scene mCapsules.push_back(capsule); + mPhysicsObjects.push_back(capsule); } // Create all the convex meshes of the scene @@ -174,12 +178,14 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name) // Add the mesh the list of sphere in the scene mConvexMeshes.push_back(mesh); + mPhysicsObjects.push_back(mesh); } // ---------- Create the floor --------- openglframework::Vector3 floorPosition(0, 0, 0); mFloor = new Box(FLOOR_SIZE, floorPosition, FLOOR_MASS, mDynamicsWorld, mMeshFolderPath); + mPhysicsObjects.push_back(mFloor); // Set the box color mFloor->setColor(mGreyColorDemo); @@ -230,68 +236,16 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name) // Destructor CollisionShapesScene::~CollisionShapesScene() { - // Destroy all the boxes of the scene - for (std::vector::iterator it = mBoxes.begin(); it != mBoxes.end(); ++it) { + // Destroy all the physics objects of the scene + for (std::vector::iterator it = mPhysicsObjects.begin(); it != mPhysicsObjects.end(); ++it) { // Destroy the corresponding rigid body from the dynamics world mDynamicsWorld->destroyRigidBody((*it)->getRigidBody()); - // Destroy the box + // Destroy the object delete (*it); } - // Destroy all the sphere of the scene - for (std::vector::iterator it = mSpheres.begin(); it != mSpheres.end(); ++it) { - - // Destroy the corresponding rigid body from the dynamics world - mDynamicsWorld->destroyRigidBody((*it)->getRigidBody()); - - // Destroy the sphere - delete (*it); - } - - // Destroy all the capsules of the scene - for (std::vector::iterator it = mCapsules.begin(); it != mCapsules.end(); ++it) { - - // Destroy the corresponding rigid body from the dynamics world - mDynamicsWorld->destroyRigidBody((*it)->getRigidBody()); - - // Destroy the sphere - delete (*it); - } - - // Destroy all the convex meshes of the scene - for (std::vector::iterator it = mConvexMeshes.begin(); - it != mConvexMeshes.end(); ++it) { - - // Destroy the corresponding rigid body from the dynamics world - mDynamicsWorld->destroyRigidBody((*it)->getRigidBody()); - - // Destroy the convex mesh - delete (*it); - } - - // Destroy all the dumbbell of the scene - for (std::vector::iterator it = mDumbbells.begin(); - it != mDumbbells.end(); ++it) { - - // Destroy the corresponding rigid body from the dynamics world - mDynamicsWorld->destroyRigidBody((*it)->getRigidBody()); - - // Destroy the convex mesh - delete (*it); - } - - // Destroy the rigid body of the floor - mDynamicsWorld->destroyRigidBody(mFloor->getRigidBody()); - //mDynamicsWorld->destroyRigidBody(mConcaveMesh->getRigidBody()); - - // Destroy the floor - delete mFloor; - - // Destroy the convex mesh - //delete mConcaveMesh; - // Destroy the dynamics world delete mDynamicsWorld; } @@ -315,96 +269,6 @@ void CollisionShapesScene::updatePhysics() { mDynamicsWorld->update(mEngineSettings.timeStep); } -// Take a step for the simulation -void CollisionShapesScene::update() { - - SceneDemo::update(); - - // Update the position and orientation of the boxes - for (std::vector::iterator it = mBoxes.begin(); it != mBoxes.end(); ++it) { - - // Update the transform used for the rendering - (*it)->updateTransform(mInterpolationFactor); - } - - // Update the position and orientation of the sphere - for (std::vector::iterator it = mSpheres.begin(); it != mSpheres.end(); ++it) { - - // Update the transform used for the rendering - (*it)->updateTransform(mInterpolationFactor); - } - - // Update the position and orientation of the capsules - for (std::vector::iterator it = mCapsules.begin(); it != mCapsules.end(); ++it) { - - // Update the transform used for the rendering - (*it)->updateTransform(mInterpolationFactor); - } - - // Update the position and orientation of the convex meshes - for (std::vector::iterator it = mConvexMeshes.begin(); - it != mConvexMeshes.end(); ++it) { - - // Update the transform used for the rendering - (*it)->updateTransform(mInterpolationFactor); - } - - // Update the position and orientation of the dumbbells - for (std::vector::iterator it = mDumbbells.begin(); - it != mDumbbells.end(); ++it) { - - // Update the transform used for the rendering - (*it)->updateTransform(mInterpolationFactor); - } - - //mConcaveMesh->updateTransform(mInterpolationFactor); - - mFloor->updateTransform(mInterpolationFactor); -} - -// Render the scene -void CollisionShapesScene::renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix) { - - // Bind the shader - shader.bind(); - - // Render all the boxes of the scene - for (std::vector::iterator it = mBoxes.begin(); it != mBoxes.end(); ++it) { - (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - } - - // Render all the sphere of the scene - for (std::vector::iterator it = mSpheres.begin(); it != mSpheres.end(); ++it) { - (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - } - - // Render all the capsules of the scene - for (std::vector::iterator it = mCapsules.begin(); it != mCapsules.end(); ++it) { - (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - } - - // Render all the convex meshes of the scene - for (std::vector::iterator it = mConvexMeshes.begin(); - it != mConvexMeshes.end(); ++it) { - (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - } - - // Render all the dumbbells of the scene - for (std::vector::iterator it = mDumbbells.begin(); - it != mDumbbells.end(); ++it) { - (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - } - - // Render the floor - mFloor->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - - //mConcaveMesh->render(shader, worldToCameraMatrix); - - // Unbind the shader - shader.unbind(); -} - /// Reset the scene void CollisionShapesScene::reset() { diff --git a/testbed/scenes/collisionshapes/CollisionShapesScene.h b/testbed/scenes/collisionshapes/CollisionShapesScene.h index b253acef..70e28755 100644 --- a/testbed/scenes/collisionshapes/CollisionShapesScene.h +++ b/testbed/scenes/collisionshapes/CollisionShapesScene.h @@ -71,7 +71,7 @@ class CollisionShapesScene : public SceneDemo { // -------------------- Attributes -------------------- // - /// All the spheres of the scene + /// All the boxes of the scene std::vector mBoxes; std::vector mSpheres; @@ -104,13 +104,6 @@ class CollisionShapesScene : public SceneDemo { /// Can be called several times per frame virtual void updatePhysics() override; - /// Take a step for the simulation - virtual void update() override; - - /// Render the scene in a single pass - virtual void renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix) override; - /// Reset the scene virtual void reset() override; diff --git a/testbed/scenes/cubes/CubesScene.cpp b/testbed/scenes/cubes/CubesScene.cpp old mode 100644 new mode 100755 index 81929e58..3ddb1d61 --- a/testbed/scenes/cubes/CubesScene.cpp +++ b/testbed/scenes/cubes/CubesScene.cpp @@ -82,6 +82,7 @@ CubesScene::CubesScene(const std::string& name) // The floor must be a static rigid body mFloor->getRigidBody()->setType(rp3d::BodyType::STATIC); + mPhysicsObjects.push_back(mFloor); // Change the material properties of the floor rigid body //rp3d::Material& material = mFloor->getRigidBody()->getMaterial(); @@ -102,6 +103,7 @@ CubesScene::CubesScene(const std::string& name) // Add the box the list of box in the scene mBoxes.push_back(cube); + mPhysicsObjects.push_back(cube); // Get the physics engine parameters mEngineSettings.isGravityEnabled = mDynamicsWorld->isGravityEnabled(); @@ -157,39 +159,6 @@ void CubesScene::updatePhysics() { mDynamicsWorld->update(mEngineSettings.timeStep); } -// Update the scene -void CubesScene::update() { - - SceneDemo::update(); - - // Update the position and orientation of the boxes - for (std::vector::iterator it = mBoxes.begin(); it != mBoxes.end(); ++it) { - - // Update the transform used for the rendering - (*it)->updateTransform(mInterpolationFactor); - } - - mFloor->updateTransform(mInterpolationFactor); -} - -// Render the scene in a single pass -void CubesScene::renderSinglePass(Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) { - - // Bind the shader - shader.bind(); - - // Render all the cubes of the scene - for (std::vector::iterator it = mBoxes.begin(); it != mBoxes.end(); ++it) { - (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - } - - // Render the floor - mFloor->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - - // Unbind the shader - shader.unbind(); -} - // Reset the scene void CubesScene::reset() { diff --git a/testbed/scenes/cubes/CubesScene.h b/testbed/scenes/cubes/CubesScene.h old mode 100644 new mode 100755 index 4ad57f77..aa4b7073 --- a/testbed/scenes/cubes/CubesScene.h +++ b/testbed/scenes/cubes/CubesScene.h @@ -72,13 +72,6 @@ class CubesScene : public SceneDemo { /// Can be called several times per frame virtual void updatePhysics() override; - /// Update the scene (take a simulation step) - virtual void update() override; - - /// Render the scene in a single pass - virtual void renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix) override; - /// Reset the scene virtual void reset() override; diff --git a/testbed/scenes/heightfield/HeightFieldScene.cpp b/testbed/scenes/heightfield/HeightFieldScene.cpp index 3e4061c9..329712e9 100644 --- a/testbed/scenes/heightfield/HeightFieldScene.cpp +++ b/testbed/scenes/heightfield/HeightFieldScene.cpp @@ -33,6 +33,8 @@ using namespace heightfieldscene; // Constructor HeightFieldScene::HeightFieldScene(const std::string& name) : SceneDemo(name, SCENE_RADIUS) { + std::string meshFolderPath("meshes/"); + // Compute the radius and the center of the scene openglframework::Vector3 center(0, 5, 0); @@ -45,25 +47,138 @@ HeightFieldScene::HeightFieldScene(const std::string& name) : SceneDemo(name, SC // Create the dynamics world for the physics simulation mDynamicsWorld = new rp3d::DynamicsWorld(gravity); - // ---------- Create the boxes ----------- // + float radius = 3.0f; - // For each box - for (int i=0; isetColor(mDemoColors[2]); - mBoxes[i]->setSleepingColor(mRedColorDemo); + // Set the box color + dumbbell->setColor(mDemoColors[i % mNbDemoColors]); + dumbbell->setSleepingColor(mRedColorDemo); - // Change the material properties of the rigid body - rp3d::Material& boxMaterial = mBoxes[i]->getRigidBody()->getMaterial(); - boxMaterial.setBounciness(rp3d::decimal(0.2)); - } + // Change the material properties of the rigid body + rp3d::Material& material = dumbbell->getRigidBody()->getMaterial(); + material.setBounciness(rp3d::decimal(0.2)); + + // Add the mesh the list of dumbbells in the scene + mDumbbells.push_back(dumbbell); + mPhysicsObjects.push_back(dumbbell); + } + + // Create all the boxes of the scene + for (int i = 0; isetColor(mDemoColors[i % mNbDemoColors]); + box->setSleepingColor(mRedColorDemo); + + // Change the material properties of the rigid body + rp3d::Material& material = box->getRigidBody()->getMaterial(); + material.setBounciness(rp3d::decimal(0.2)); + + // Add the sphere the list of sphere in the scene + mBoxes.push_back(box); + mPhysicsObjects.push_back(box); + } + + // Create all the spheres of the scene + for (int i = 0; igetRigidBody()->getMaterial().setRollingResistance(0.08); + + // Set the box color + sphere->setColor(mDemoColors[i % mNbDemoColors]); + sphere->setSleepingColor(mRedColorDemo); + + // Change the material properties of the rigid body + rp3d::Material& material = sphere->getRigidBody()->getMaterial(); + material.setBounciness(rp3d::decimal(0.2)); + + // Add the sphere the list of sphere in the scene + mSpheres.push_back(sphere); + mPhysicsObjects.push_back(sphere); + } + + // Create all the capsules of the scene + for (int i = 0; igetRigidBody()->getMaterial().setRollingResistance(0.08); + + // Set the box color + capsule->setColor(mDemoColors[i % mNbDemoColors]); + capsule->setSleepingColor(mRedColorDemo); + + // Change the material properties of the rigid body + rp3d::Material& material = capsule->getRigidBody()->getMaterial(); + material.setBounciness(rp3d::decimal(0.2)); + + // Add the cylinder the list of sphere in the scene + mCapsules.push_back(capsule); + mPhysicsObjects.push_back(capsule); + } + + // Create all the convex meshes of the scene + for (int i = 0; isetColor(mDemoColors[i % mNbDemoColors]); + mesh->setSleepingColor(mRedColorDemo); + + // Change the material properties of the rigid body + rp3d::Material& material = mesh->getRigidBody()->getMaterial(); + material.setBounciness(rp3d::decimal(0.2)); + + // Add the mesh the list of sphere in the scene + mConvexMeshes.push_back(mesh); + mPhysicsObjects.push_back(mesh); + } // ---------- Create the height field ---------- // @@ -77,6 +192,8 @@ HeightFieldScene::HeightFieldScene(const std::string& name) : SceneDemo(name, SC // Set the mesh as beeing static mHeightField->getRigidBody()->setType(rp3d::BodyType::STATIC); + mPhysicsObjects.push_back(mHeightField); + // Set the color mHeightField->setColor(mGreyColorDemo); mHeightField->setSleepingColor(mGreyColorDemo); @@ -101,18 +218,15 @@ HeightFieldScene::HeightFieldScene(const std::string& name) : SceneDemo(name, SC // Destructor HeightFieldScene::~HeightFieldScene() { - // Destroy the corresponding rigid body from the dynamics world - for (int i=0; idestroyRigidBody(mBoxes[i]->getRigidBody()); - } - mDynamicsWorld->destroyRigidBody(mHeightField->getRigidBody()); + // Destroy all the physics objects of the scene + for (std::vector::iterator it = mPhysicsObjects.begin(); it != mPhysicsObjects.end(); ++it) { - for (int i=0; idestroyRigidBody((*it)->getRigidBody()); - // Destroy the convex mesh - delete mHeightField; + // Destroy the object + delete (*it); + } // Destroy the dynamics world delete mDynamicsWorld; @@ -137,35 +251,6 @@ void HeightFieldScene::updatePhysics() { mDynamicsWorld->update(mEngineSettings.timeStep); } -// Update the scene -void HeightFieldScene::update() { - - SceneDemo::update(); - - // Update the transform used for the rendering - mHeightField->updateTransform(mInterpolationFactor); - - for (int i=0; iupdateTransform(mInterpolationFactor); - } -} - -// Render the scene in a single pass -void HeightFieldScene::renderSinglePass(Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) { - - // Bind the shader - shader.bind(); - - mHeightField->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - - for (int i=0; irender(shader, worldToCameraMatrix, mIsWireframeEnabled); - } - - // Unbind the shader - shader.unbind(); -} - // Reset the scene void HeightFieldScene::reset() { diff --git a/testbed/scenes/heightfield/HeightFieldScene.h b/testbed/scenes/heightfield/HeightFieldScene.h index 7eb9527d..7306ae2c 100644 --- a/testbed/scenes/heightfield/HeightFieldScene.h +++ b/testbed/scenes/heightfield/HeightFieldScene.h @@ -30,6 +30,10 @@ #include "openglframework.h" #include "reactphysics3d.h" #include "Box.h" +#include "Sphere.h" +#include "ConvexMesh.h" +#include "Capsule.h" +#include "Dumbbell.h" #include "SceneDemo.h" #include "HeightField.h" @@ -37,17 +41,47 @@ namespace heightfieldscene { // Constants const float SCENE_RADIUS = 50.0f; +static const int NB_BOXES = 10; +static const int NB_SPHERES = 5; +static const int NB_CAPSULES = 5; +static const int NB_MESHES = 3; +static const int NB_COMPOUND_SHAPES = 3; +const openglframework::Vector3 BOX_SIZE(2, 2, 2); +const float SPHERE_RADIUS = 1.5f; +const float CONE_RADIUS = 2.0f; +const float CONE_HEIGHT = 3.0f; +const float CYLINDER_RADIUS = 1.0f; +const float CYLINDER_HEIGHT = 5.0f; +const float CAPSULE_RADIUS = 1.0f; +const float CAPSULE_HEIGHT = 1.0f; +const float DUMBBELL_HEIGHT = 1.0f; +const openglframework::Vector3 FLOOR_SIZE(50, 0.5f, 50); // Floor dimensions in meters +const float BOX_MASS = 1.0f; +const float CONE_MASS = 1.0f; +const float CYLINDER_MASS = 1.0f; +const float CAPSULE_MASS = 1.0f; +const float MESH_MASS = 1.0f; +const float FLOOR_MASS = 100.0f; // Class HeightFieldScene class HeightFieldScene : public SceneDemo { - static const int NB_BOXES = 10; - protected : // -------------------- Attributes -------------------- // - Box* mBoxes[NB_BOXES]; + /// All the boxes of the scene + std::vector mBoxes; + + std::vector mSpheres; + + std::vector mCapsules; + + /// All the convex meshes of the scene + std::vector mConvexMeshes; + + /// All the dumbbell of the scene + std::vector mDumbbells; /// Height field HeightField* mHeightField; @@ -69,13 +103,6 @@ class HeightFieldScene : public SceneDemo { /// Can be called several times per frame virtual void updatePhysics() override; - /// Update the scene (take a simulation step) - virtual void update() override; - - /// Render the scene in a single pass - virtual void renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix) override ; - /// Reset the scene virtual void reset() override ; diff --git a/testbed/scenes/joints/JointsScene.cpp b/testbed/scenes/joints/JointsScene.cpp index 23bcdb93..282f7e51 100644 --- a/testbed/scenes/joints/JointsScene.cpp +++ b/testbed/scenes/joints/JointsScene.cpp @@ -136,25 +136,6 @@ void JointsScene::updatePhysics() { mDynamicsWorld->update(mEngineSettings.timeStep); } -// Take a step for the simulation -void JointsScene::update() { - - SceneDemo::update(); - - // Update the position and orientation of the boxes - mSliderJointBottomBox->updateTransform(mInterpolationFactor); - mSliderJointTopBox->updateTransform(mInterpolationFactor); - mPropellerBox->updateTransform(mInterpolationFactor); - mFixedJointBox1->updateTransform(mInterpolationFactor); - mFixedJointBox2->updateTransform(mInterpolationFactor); - for (int i=0; iupdateTransform(mInterpolationFactor); - } - - // Update the position and orientation of the floor - mFloor->updateTransform(mInterpolationFactor); -} - // Render the scene void JointsScene::renderSinglePass(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) { @@ -281,6 +262,8 @@ void JointsScene::createBallAndSocketJoints() { rp3d::Material& material = mBallAndSocketJointChainBoxes[i]->getRigidBody()->getMaterial(); material.setBounciness(rp3d::decimal(0.4)); + mPhysicsObjects.push_back(mBallAndSocketJointChainBoxes[i]); + positionBox.y -= boxDimension.y + 0.5f; } @@ -324,6 +307,7 @@ void JointsScene::createSliderJoint() { // Change the material properties of the rigid body rp3d::Material& material1 = mSliderJointBottomBox->getRigidBody()->getMaterial(); material1.setBounciness(0.4f); + mPhysicsObjects.push_back(mSliderJointBottomBox); // --------------- Create the second box --------------- // @@ -341,6 +325,7 @@ void JointsScene::createSliderJoint() { // Change the material properties of the rigid body rp3d::Material& material2 = mSliderJointTopBox->getRigidBody()->getMaterial(); material2.setBounciness(0.4f); + mPhysicsObjects.push_back(mSliderJointTopBox); // --------------- Create the joint --------------- // @@ -381,6 +366,7 @@ void JointsScene::createPropellerHingeJoint() { // Change the material properties of the rigid body rp3d::Material& material = mPropellerBox->getRigidBody()->getMaterial(); material.setBounciness(rp3d::decimal(0.4)); + mPhysicsObjects.push_back(mPropellerBox); // --------------- Create the Hinge joint --------------- // @@ -420,6 +406,7 @@ void JointsScene::createFixedJoints() { // Change the material properties of the rigid body rp3d::Material& material1 = mFixedJointBox1->getRigidBody()->getMaterial(); material1.setBounciness(rp3d::decimal(0.4)); + mPhysicsObjects.push_back(mFixedJointBox1); // --------------- Create the second box --------------- // @@ -436,6 +423,7 @@ void JointsScene::createFixedJoints() { // Change the material properties of the rigid body rp3d::Material& material2 = mFixedJointBox2->getRigidBody()->getMaterial(); material2.setBounciness(rp3d::decimal(0.4)); + mPhysicsObjects.push_back(mFixedJointBox2); // --------------- Create the first fixed joint --------------- // @@ -478,4 +466,5 @@ void JointsScene::createFloor() { // Change the material properties of the rigid body rp3d::Material& material = mFloor->getRigidBody()->getMaterial(); material.setBounciness(rp3d::decimal(0.3)); + mPhysicsObjects.push_back(mFloor); } diff --git a/testbed/scenes/joints/JointsScene.h b/testbed/scenes/joints/JointsScene.h index a9474393..16ccfe8c 100644 --- a/testbed/scenes/joints/JointsScene.h +++ b/testbed/scenes/joints/JointsScene.h @@ -126,9 +126,6 @@ class JointsScene : public SceneDemo { /// Can be called several times per frame virtual void updatePhysics() override; - /// Take a step for the simulation - virtual void update() override; - /// Render the scene in a single pass virtual void renderSinglePass(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) override; diff --git a/testbed/scenes/raycast/RaycastScene.cpp b/testbed/scenes/raycast/RaycastScene.cpp index d420073f..2ded75d6 100644 --- a/testbed/scenes/raycast/RaycastScene.cpp +++ b/testbed/scenes/raycast/RaycastScene.cpp @@ -56,6 +56,7 @@ RaycastScene::RaycastScene(const std::string& name) // Set the box color mDumbbell->setColor(mGreyColorDemo); mDumbbell->setSleepingColor(mRedColorDemo); + mPhysicsObjects.push_back(mDumbbell); // ---------- Box ---------- // openglframework::Vector3 position2(0, 0, 0); @@ -67,6 +68,7 @@ RaycastScene::RaycastScene(const std::string& name) // Set the box color mBox->setColor(mGreyColorDemo); mBox->setSleepingColor(mRedColorDemo); + mPhysicsObjects.push_back(mBox); // ---------- Sphere ---------- // openglframework::Vector3 position3(0, 0, 0); @@ -78,6 +80,7 @@ RaycastScene::RaycastScene(const std::string& name) // Set the color mSphere->setColor(mGreyColorDemo); mSphere->setSleepingColor(mRedColorDemo); + mPhysicsObjects.push_back(mSphere); // ---------- Capsule ---------- // openglframework::Vector3 position6(0, 0, 0); @@ -89,6 +92,7 @@ RaycastScene::RaycastScene(const std::string& name) // Set the color mCapsule->setColor(mGreyColorDemo); mCapsule->setSleepingColor(mRedColorDemo); + mPhysicsObjects.push_back(mCapsule); // ---------- Convex Mesh ---------- // openglframework::Vector3 position7(0, 0, 0); @@ -99,6 +103,7 @@ RaycastScene::RaycastScene(const std::string& name) // Set the color mConvexMesh->setColor(mGreyColorDemo); mConvexMesh->setSleepingColor(mRedColorDemo); + mPhysicsObjects.push_back(mConvexMesh); // ---------- Concave Mesh ---------- // openglframework::Vector3 position8(0, 0, 0); @@ -109,6 +114,7 @@ RaycastScene::RaycastScene(const std::string& name) // Set the color mConcaveMesh->setColor(mGreyColorDemo); mConcaveMesh->setSleepingColor(mRedColorDemo); + mPhysicsObjects.push_back(mConcaveMesh); // ---------- Heightfield ---------- // openglframework::Vector3 position9(0, 0, 0); @@ -119,6 +125,7 @@ RaycastScene::RaycastScene(const std::string& name) // Set the color mHeightField->setColor(mGreyColorDemo); mHeightField->setSleepingColor(mRedColorDemo); + mPhysicsObjects.push_back(mHeightField); // Create the lines that will be used for raycasting createLines(); @@ -256,12 +263,6 @@ RaycastScene::~RaycastScene() { mVAO.destroy(); } -// Update the physics world (take a simulation step) -void RaycastScene::updatePhysics() { - - -} - // Take a step for the simulation void RaycastScene::update() { @@ -327,14 +328,18 @@ void RaycastScene::renderSinglePass(openglframework::Shader& shader, const openg mColorShader.unbind(); - // Render the shapes - if (mBox->getCollisionBody()->isActive()) mBox->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - if (mSphere->getCollisionBody()->isActive()) mSphere->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - if (mCapsule->getCollisionBody()->isActive()) mCapsule->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - if (mConvexMesh->getCollisionBody()->isActive()) mConvexMesh->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - if (mDumbbell->getCollisionBody()->isActive()) mDumbbell->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - if (mConcaveMesh->getCollisionBody()->isActive()) mConcaveMesh->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - if (mHeightField->getCollisionBody()->isActive()) mHeightField->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + // Bind the shader + shader.bind(); + + // Render all the physics objects of the scene + for (std::vector::iterator it = mPhysicsObjects.begin(); it != mPhysicsObjects.end(); ++it) { + if ((*it)->getCollisionBody()->isActive()) { + (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + } + } + + // Unbind the shader + shader.unbind(); } // Create the Vertex Buffer Objects used to render with OpenGL. diff --git a/testbed/scenes/raycast/RaycastScene.h b/testbed/scenes/raycast/RaycastScene.h index 39b73799..1400fcf7 100644 --- a/testbed/scenes/raycast/RaycastScene.h +++ b/testbed/scenes/raycast/RaycastScene.h @@ -57,7 +57,7 @@ const float CAPSULE_HEIGHT = 5.0f; const float DUMBBELL_HEIGHT = 5.0f; const int NB_RAYS = 100; const float RAY_LENGTH = 30.0f; -const int NB_BODIES = 9; +const int NB_BODIES = 7; // Raycast manager class RaycastManager : public rp3d::RaycastCallback { @@ -175,10 +175,6 @@ class RaycastScene : public SceneDemo { /// Destructor virtual ~RaycastScene() override; - /// Update the physics world (take a simulation step) - /// Can be called several times per frame - virtual void updatePhysics() override; - /// Take a step for the simulation virtual void update() override; diff --git a/testbed/src/SceneDemo.cpp b/testbed/src/SceneDemo.cpp index 85e8a66f..d406bcea 100644 --- a/testbed/src/SceneDemo.cpp +++ b/testbed/src/SceneDemo.cpp @@ -80,7 +80,7 @@ SceneDemo::SceneDemo(const std::string& name, float sceneRadius, bool isShadowMa // Destructor SceneDemo::~SceneDemo() { - + mShadowMapTexture.destroy(); mFBOShadowMap.destroy(); mVBOQuad.destroy(); @@ -101,6 +101,19 @@ void SceneDemo::update() { // Update the contact points updateContactPoints(); + + // Update the position and orientation of the physics objects + for (std::vector::iterator it = mPhysicsObjects.begin(); it != mPhysicsObjects.end(); ++it) { + + // Update the transform used for the rendering + (*it)->updateTransform(mInterpolationFactor); + } +} + +// Update the physics world (take a simulation step) +// Can be called several times per frame +void SceneDemo::updatePhysics() { + } // Render the scene (in multiple passes for shadow mapping) @@ -202,6 +215,21 @@ void SceneDemo::render() { //drawTextureQuad(); } +// Render the scene in a single pass +void SceneDemo::renderSinglePass(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) { + + // Bind the shader + shader.bind(); + + // Render all the physics objects of the scene + for (std::vector::iterator it = mPhysicsObjects.begin(); it != mPhysicsObjects.end(); ++it) { + (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + } + + // Unbind the shader + shader.unbind(); +} + // Create the Shadow map FBO and texture void SceneDemo::createShadowMapFBOAndTexture() { @@ -345,7 +373,7 @@ std::vector SceneDemo::computeContactPointsOfWorld(const rp3d::Dyn rp3d::ContactPoint* contactPoint = manifold->getContactPoints(); while (contactPoint != nullptr) { - rp3d::Vector3 point = contactPoint->getWorldPointOnBody1(); + rp3d::Vector3 point = manifold->getShape1()->getLocalToWorldTransform() * contactPoint->getLocalPointOnBody1(); rp3d::Vector3 normalWorld = contactPoint->getNormal(); openglframework::Vector3 normal = openglframework::Vector3(normalWorld.x, normalWorld.y, normalWorld.z); ContactPoint contact(openglframework::Vector3(point.x, point.y, point.z), normal, openglframework::Color::red()); diff --git a/testbed/src/SceneDemo.h b/testbed/src/SceneDemo.h index f7b5f7ce..a8b1941f 100644 --- a/testbed/src/SceneDemo.h +++ b/testbed/src/SceneDemo.h @@ -30,6 +30,7 @@ #include "Scene.h" #include "VisualContactPoint.h" #include "reactphysics3d.h" +#include "PhysicsObject.h" // Constants const int SHADOWMAP_WIDTH = 2048; @@ -95,6 +96,8 @@ class SceneDemo : public Scene { std::string mMeshFolderPath; + std::vector mPhysicsObjects; + // -------------------- Methods -------------------- // // Create the Shadow map FBO and texture @@ -128,12 +131,15 @@ class SceneDemo : public Scene { /// Update the scene virtual void update() override; + /// Update the physics world (take a simulation step) + /// Can be called several times per frame + virtual void updatePhysics() override; + /// Render the scene (possibly in multiple passes for shadow mapping) virtual void render() override; /// Render the scene in a single pass - virtual void renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix)=0 ; + virtual void renderSinglePass(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix); /// Enabled/Disable the shadow mapping virtual void setIsShadowMappingEnabled(bool isShadowMappingEnabled) override; diff --git a/testbed/src/TestbedApplication.cpp b/testbed/src/TestbedApplication.cpp index 09f464f3..2b9195e5 100644 --- a/testbed/src/TestbedApplication.cpp +++ b/testbed/src/TestbedApplication.cpp @@ -125,7 +125,7 @@ void TestbedApplication::createScenes() { mScenes.push_back(concaveMeshScene); assert(mScenes.size() > 0); - mCurrentScene = mScenes[0]; + mCurrentScene = mScenes[5]; // Get the engine settings from the scene mEngineSettings = mCurrentScene->getEngineSettings(); From 5da57a96c80be764d77e38478c33b64de2d9bc34 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 24 Oct 2017 22:47:35 +0200 Subject: [PATCH 119/248] Fix issue with sphere and capsule SAT collision detection --- .../CapsuleVsConvexPolyhedronAlgorithm.cpp | 4 ++++ src/collision/narrowphase/SAT/SATAlgorithm.cpp | 15 ++++++++------- 2 files changed, 12 insertions(+), 7 deletions(-) diff --git a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp index d6de739a..89336c4e 100644 --- a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp @@ -114,6 +114,10 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPh const Vector3 separatingAxisCapsuleSpace = polyhedronToCapsuleTransform.getOrientation() * faceNormal; + if (isCapsuleShape1) { + faceNormalWorld = -faceNormalWorld; + } + // Compute and create two contact points satAlgorithm.computeCapsulePolyhedronFaceContactPoints(f, capsuleShape->getRadius(), polyhedron, contactPoint->penetrationDepth, polyhedronToCapsuleTransform, faceNormalWorld, separatingAxisCapsuleSpace, diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 4411187b..1ba5143b 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -97,10 +97,12 @@ bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfo* narrow if (reportContacts) { const Vector3 minFaceNormal = polyhedron->getFaceNormal(minFaceIndex); - Vector3 normalWorld = -(polyhedronToWorldTransform.getOrientation() * minFaceNormal); - Vector3 contactPointSphereLocal = sphereToWorldTransform.getInverse().getOrientation() * normalWorld * sphere->getRadius(); + Vector3 minFaceNormalWorld = polyhedronToWorldTransform.getOrientation() * minFaceNormal; + Vector3 contactPointSphereLocal = sphereToWorldTransform.getInverse().getOrientation() * (-minFaceNormalWorld * sphere->getRadius()); Vector3 contactPointPolyhedronLocal = sphereCenter + minFaceNormal * (minPenetrationDepth - sphere->getRadius()); + Vector3 normalWorld = isSphereShape1 ? -minFaceNormalWorld : minFaceNormalWorld; + // Compute smooth triangle mesh contact if one of the two collision shapes is a triangle TriangleShape::computeSmoothTriangleMeshContact(narrowPhaseInfo->collisionShape1, narrowPhaseInfo->collisionShape2, isSphereShape1 ? contactPointSphereLocal : contactPointPolyhedronLocal, @@ -243,6 +245,9 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfo* narro const Vector3 capsuleSegBPolyhedronSpace = capsuleToPolyhedronTransform * capsuleSegB; Vector3 normalWorld = capsuleToWorld.getOrientation() * separatingAxisCapsuleSpace; + if (isCapsuleShape1) { + normalWorld = -normalWorld; + } const decimal capsuleRadius = capsuleShape->getRadius(); // If the separating axis is a face normal @@ -391,12 +396,8 @@ void SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceI // Project the two clipped points into the polyhedron face const Vector3 delta = faceNormal * (penetrationDepth - capsuleRadius); - if (isCapsuleShape1) { - normalWorld = -normalWorld; - } - // For each of the two clipped points - for (int i = 0; i<2; i++) { + for (uint i = 0; i<2; i++) { // Compute the penetration depth of the two clipped points (to filter out the points that does not correspond to the penetration depth) const decimal clipPointPenDepth = (planesPoints[0] - clipSegment[i]).dot(faceNormal); From 6a69ef76c5cd6467f90c4b3b20ba30704d960696 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 1 Nov 2017 23:07:56 +0100 Subject: [PATCH 120/248] Fix issue with ProxyShape::mBroadPhaseId not set when body was sleeping or inactive --- src/body/CollisionBody.cpp | 26 +- src/collision/CollisionDetection.cpp | 245 ++++++++++-------- src/collision/CollisionDetection.h | 8 +- .../broadphase/BroadPhaseAlgorithm.cpp | 6 + .../broadphase/BroadPhaseAlgorithm.h | 3 + src/engine/CollisionWorld.cpp | 11 + src/engine/CollisionWorld.h | 3 + 7 files changed, 178 insertions(+), 124 deletions(-) diff --git a/src/body/CollisionBody.cpp b/src/body/CollisionBody.cpp index 39d47de4..64ce6467 100644 --- a/src/body/CollisionBody.cpp +++ b/src/body/CollisionBody.cpp @@ -111,7 +111,7 @@ void CollisionBody::removeCollisionShape(const ProxyShape* proxyShape) { if (current == proxyShape) { mProxyCollisionShapes = current->mNext; - if (mIsActive) { + if (mIsActive && proxyShape->mBroadPhaseID != -1) { mWorld.mCollisionDetection.removeProxyCollisionShape(current); } @@ -131,7 +131,7 @@ void CollisionBody::removeCollisionShape(const ProxyShape* proxyShape) { ProxyShape* elementToRemove = current->mNext; current->mNext = elementToRemove->mNext; - if (mIsActive) { + if (mIsActive && proxyShape->mBroadPhaseID != -1) { mWorld.mCollisionDetection.removeProxyCollisionShape(elementToRemove); } @@ -157,7 +157,7 @@ void CollisionBody::removeAllCollisionShapes() { // Remove the proxy collision shape ProxyShape* nextElement = current->mNext; - if (mIsActive) { + if (mIsActive && current->mBroadPhaseID != -1) { mWorld.mCollisionDetection.removeProxyCollisionShape(current); } @@ -202,12 +202,15 @@ void CollisionBody::updateBroadPhaseState() const { // Update the broad-phase state of a proxy collision shape of the body void CollisionBody::updateProxyShapeInBroadPhase(ProxyShape* proxyShape, bool forceReinsert) const { - // Recompute the world-space AABB of the collision shape - AABB aabb; - proxyShape->getCollisionShape()->computeAABB(aabb, mTransform * proxyShape->getLocalToBodyTransform()); + if (proxyShape->mBroadPhaseID != -1) { - // Update the broad-phase state for the proxy collision shape - mWorld.mCollisionDetection.updateProxyCollisionShape(proxyShape, aabb, Vector3(0, 0, 0), forceReinsert); + // Recompute the world-space AABB of the collision shape + AABB aabb; + proxyShape->getCollisionShape()->computeAABB(aabb, mTransform * proxyShape->getLocalToBodyTransform()); + + // Update the broad-phase state for the proxy collision shape + mWorld.mCollisionDetection.updateProxyCollisionShape(proxyShape, aabb, Vector3(0, 0, 0), forceReinsert) ; + } } // Set whether or not the body is active @@ -240,8 +243,11 @@ void CollisionBody::setIsActive(bool isActive) { // For each proxy shape of the body for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) { - // Remove the proxy shape from the collision detection - mWorld.mCollisionDetection.removeProxyCollisionShape(shape); + if (shape->mBroadPhaseID != -1) { + + // Remove the proxy shape from the collision detection + mWorld.mCollisionDetection.removeProxyCollisionShape(shape); + } } // Reset the contact manifold list of the body diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index f650351a..baaf0db5 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -109,6 +109,8 @@ void CollisionDetection::computeMiddlePhase() { ProxyShape* shape1 = pair->getShape1(); ProxyShape* shape2 = pair->getShape2(); + assert(shape1->mBroadPhaseID != -1); + assert(shape2->mBroadPhaseID != -1); assert(shape1->mBroadPhaseID != shape2->mBroadPhaseID); // Check if the two shapes are still overlapping. Otherwise, we destroy the @@ -282,6 +284,8 @@ void CollisionDetection::computeNarrowPhase() { /// This method is called by the broad-phase collision detection algorithm void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, ProxyShape* shape2) { + assert(shape1->mBroadPhaseID != -1); + assert(shape2->mBroadPhaseID != -1); assert(shape1->mBroadPhaseID != shape2->mBroadPhaseID); // Check if the collision filtering allows collision between the two shapes @@ -313,6 +317,8 @@ void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, Pro // Remove a body from the collision detection void CollisionDetection::removeProxyCollisionShape(ProxyShape* proxyShape) { + assert(proxyShape->mBroadPhaseID != -1); + // Remove all the overlapping pairs involving this proxy shape std::map::iterator it; for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ) { @@ -683,87 +689,90 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl ProxyShape* bodyProxyShape = body->getProxyShapesList(); while (bodyProxyShape != nullptr) { - // Get the AABB of the shape - const AABB& shapeAABB = mBroadPhaseAlgorithm.getFatAABB(bodyProxyShape->mBroadPhaseID); + if (bodyProxyShape->mBroadPhaseID != -1) { - // Ask the broad-phase to get all the overlapping shapes - LinkedList overlappingNodes(mPoolAllocator); - mBroadPhaseAlgorithm.reportAllShapesOverlappingWithAABB(shapeAABB, overlappingNodes); + // Get the AABB of the shape + const AABB& shapeAABB = mBroadPhaseAlgorithm.getFatAABB(bodyProxyShape->mBroadPhaseID); - const bodyindex bodyId = body->getID(); + // Ask the broad-phase to get all the overlapping shapes + LinkedList overlappingNodes(mPoolAllocator); + mBroadPhaseAlgorithm.reportAllShapesOverlappingWithAABB(shapeAABB, overlappingNodes); - // For each overlaping proxy shape - LinkedList::ListElement* element = overlappingNodes.getListHead(); - while (element != nullptr) { + const bodyindex bodyId = body->getID(); - // Get the overlapping proxy shape - int broadPhaseId = element->data; - ProxyShape* proxyShape = mBroadPhaseAlgorithm.getProxyShapeForBroadPhaseId(broadPhaseId); + // For each overlaping proxy shape + LinkedList::ListElement* element = overlappingNodes.getListHead(); + while (element != nullptr) { - // If the proxy shape is from a body that we have not already reported collision and the - // two proxy collision shapes are not from the same body - if (reportedBodies.find(proxyShape->getBody()->getID()) == reportedBodies.end() && - proxyShape->getBody()->getID() != bodyId) { + // Get the overlapping proxy shape + int broadPhaseId = element->data; + ProxyShape* proxyShape = mBroadPhaseAlgorithm.getProxyShapeForBroadPhaseId(broadPhaseId); - // Check if the collision filtering allows collision between the two shapes - if ((proxyShape->getCollisionCategoryBits() & categoryMaskBits) != 0) { + // If the proxy shape is from a body that we have not already reported collision and the + // two proxy collision shapes are not from the same body + if (reportedBodies.find(proxyShape->getBody()->getID()) == reportedBodies.end() && + proxyShape->getBody()->getID() != bodyId) { - // Create a temporary overlapping pair - OverlappingPair pair(bodyProxyShape, proxyShape, mPoolAllocator, mPoolAllocator); + // Check if the collision filtering allows collision between the two shapes + if ((proxyShape->getCollisionCategoryBits() & categoryMaskBits) != 0) { - // Compute the middle-phase collision detection between the two shapes - NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); + // Create a temporary overlapping pair + OverlappingPair pair(bodyProxyShape, proxyShape, mPoolAllocator, mPoolAllocator); - bool isColliding = false; + // Compute the middle-phase collision detection between the two shapes + NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); - // For each narrow-phase info object - while (narrowPhaseInfo != nullptr) { + bool isColliding = false; - // If we have not found a collision yet - if (!isColliding) { + // For each narrow-phase info object + while (narrowPhaseInfo != nullptr) { - const CollisionShapeType shape1Type = narrowPhaseInfo->collisionShape1->getType(); - const CollisionShapeType shape2Type = narrowPhaseInfo->collisionShape2->getType(); + // If we have not found a collision yet + if (!isColliding) { - // Select the narrow phase algorithm to use according to the two collision shapes - NarrowPhaseAlgorithm* narrowPhaseAlgorithm = selectNarrowPhaseAlgorithm(shape1Type, shape2Type); + const CollisionShapeType shape1Type = narrowPhaseInfo->collisionShape1->getType(); + const CollisionShapeType shape2Type = narrowPhaseInfo->collisionShape2->getType(); - // If there is a collision algorithm for those two kinds of shapes - if (narrowPhaseAlgorithm != nullptr) { + // Select the narrow phase algorithm to use according to the two collision shapes + NarrowPhaseAlgorithm* narrowPhaseAlgorithm = selectNarrowPhaseAlgorithm(shape1Type, shape2Type); - // Use the narrow-phase collision detection algorithm to check - // if there really is a collision. If a collision occurs, the - // notifyContact() callback method will be called. - isColliding |= narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, false); + // If there is a collision algorithm for those two kinds of shapes + if (narrowPhaseAlgorithm != nullptr) { + + // Use the narrow-phase collision detection algorithm to check + // if there really is a collision. If a collision occurs, the + // notifyContact() callback method will be called. + isColliding |= narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, false); + } } + + NarrowPhaseInfo* currentNarrowPhaseInfo = narrowPhaseInfo; + narrowPhaseInfo = narrowPhaseInfo->next; + + // Call the destructor + currentNarrowPhaseInfo->~NarrowPhaseInfo(); + + // Release the allocated memory + mPoolAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); } - NarrowPhaseInfo* currentNarrowPhaseInfo = narrowPhaseInfo; - narrowPhaseInfo = narrowPhaseInfo->next; + // Return if we have found a narrow-phase collision + if (isColliding) { - // Call the destructor - currentNarrowPhaseInfo->~NarrowPhaseInfo(); + CollisionBody* overlapBody = proxyShape->getBody(); - // Release the allocated memory - mPoolAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); - } + // Add the body into the set of reported bodies + reportedBodies.insert(overlapBody->getID()); - // Return if we have found a narrow-phase collision - if (isColliding) { - - CollisionBody* overlapBody = proxyShape->getBody(); - - // Add the body into the set of reported bodies - reportedBodies.insert(overlapBody->getID()); - - // Notify the overlap to the user - overlapCallback->notifyOverlap(overlapBody); + // Notify the overlap to the user + overlapCallback->notifyOverlap(overlapBody); + } } } - } - // Go to the next overlapping proxy shape - element = element->next; + // Go to the next overlapping proxy shape + element = element->next; + } } // Go to the next proxy shape @@ -858,85 +867,88 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c ProxyShape* bodyProxyShape = body->getProxyShapesList(); while (bodyProxyShape != nullptr) { - // Get the AABB of the shape - const AABB& shapeAABB = mBroadPhaseAlgorithm.getFatAABB(bodyProxyShape->mBroadPhaseID); + if (bodyProxyShape->mBroadPhaseID != -1) { - // Ask the broad-phase to get all the overlapping shapes - LinkedList overlappingNodes(mPoolAllocator); - mBroadPhaseAlgorithm.reportAllShapesOverlappingWithAABB(shapeAABB, overlappingNodes); + // Get the AABB of the shape + const AABB& shapeAABB = mBroadPhaseAlgorithm.getFatAABB(bodyProxyShape->mBroadPhaseID); - const bodyindex bodyId = body->getID(); + // Ask the broad-phase to get all the overlapping shapes + LinkedList overlappingNodes(mPoolAllocator); + mBroadPhaseAlgorithm.reportAllShapesOverlappingWithAABB(shapeAABB, overlappingNodes); - // For each overlaping proxy shape - LinkedList::ListElement* element = overlappingNodes.getListHead(); - while (element != nullptr) { + const bodyindex bodyId = body->getID(); - // Get the overlapping proxy shape - int broadPhaseId = element->data; - ProxyShape* proxyShape = mBroadPhaseAlgorithm.getProxyShapeForBroadPhaseId(broadPhaseId); + // For each overlaping proxy shape + LinkedList::ListElement* element = overlappingNodes.getListHead(); + while (element != nullptr) { - // If the two proxy collision shapes are not from the same body - if (proxyShape->getBody()->getID() != bodyId) { + // Get the overlapping proxy shape + int broadPhaseId = element->data; + ProxyShape* proxyShape = mBroadPhaseAlgorithm.getProxyShapeForBroadPhaseId(broadPhaseId); - // Check if the collision filtering allows collision between the two shapes - if ((proxyShape->getCollisionCategoryBits() & categoryMaskBits) != 0) { + // If the two proxy collision shapes are not from the same body + if (proxyShape->getBody()->getID() != bodyId) { - // Create a temporary overlapping pair - OverlappingPair pair(bodyProxyShape, proxyShape, mPoolAllocator, mPoolAllocator); + // Check if the collision filtering allows collision between the two shapes + if ((proxyShape->getCollisionCategoryBits() & categoryMaskBits) != 0) { - // Compute the middle-phase collision detection between the two shapes - NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); + // Create a temporary overlapping pair + OverlappingPair pair(bodyProxyShape, proxyShape, mPoolAllocator, mPoolAllocator); - // For each narrow-phase info object - while (narrowPhaseInfo != nullptr) { + // Compute the middle-phase collision detection between the two shapes + NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); - const CollisionShapeType shape1Type = narrowPhaseInfo->collisionShape1->getType(); - const CollisionShapeType shape2Type = narrowPhaseInfo->collisionShape2->getType(); + // For each narrow-phase info object + while (narrowPhaseInfo != nullptr) { - // Select the narrow phase algorithm to use according to the two collision shapes - NarrowPhaseAlgorithm* narrowPhaseAlgorithm = selectNarrowPhaseAlgorithm(shape1Type, shape2Type); + const CollisionShapeType shape1Type = narrowPhaseInfo->collisionShape1->getType(); + const CollisionShapeType shape2Type = narrowPhaseInfo->collisionShape2->getType(); - // If there is a collision algorithm for those two kinds of shapes - if (narrowPhaseAlgorithm != nullptr) { + // Select the narrow phase algorithm to use according to the two collision shapes + NarrowPhaseAlgorithm* narrowPhaseAlgorithm = selectNarrowPhaseAlgorithm(shape1Type, shape2Type); - // Use the narrow-phase collision detection algorithm to check - // if there really is a collision. If a collision occurs, the - // notifyContact() callback method will be called. - if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, true)) { + // If there is a collision algorithm for those two kinds of shapes + if (narrowPhaseAlgorithm != nullptr) { - // Add the contact points as a potential contact manifold into the pair - narrowPhaseInfo->addContactPointsAsPotentialContactManifold(); + // Use the narrow-phase collision detection algorithm to check + // if there really is a collision. If a collision occurs, the + // notifyContact() callback method will be called. + if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, true)) { + + // Add the contact points as a potential contact manifold into the pair + narrowPhaseInfo->addContactPointsAsPotentialContactManifold(); + } } + + NarrowPhaseInfo* currentNarrowPhaseInfo = narrowPhaseInfo; + narrowPhaseInfo = narrowPhaseInfo->next; + + // Call the destructor + currentNarrowPhaseInfo->~NarrowPhaseInfo(); + + // Release the allocated memory + mPoolAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); } - NarrowPhaseInfo* currentNarrowPhaseInfo = narrowPhaseInfo; - narrowPhaseInfo = narrowPhaseInfo->next; + // Process the potential contacts + processPotentialContacts(&pair); - // Call the destructor - currentNarrowPhaseInfo->~NarrowPhaseInfo(); + if (pair.hasContacts()) { - // Release the allocated memory - mPoolAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); + // Report the contacts to the user + CollisionCallback::CollisionCallbackInfo collisionInfo(&pair, mPoolAllocator); + callback->notifyContact(collisionInfo); + } } - - // Process the potential contacts - processPotentialContacts(&pair); - - if (pair.hasContacts()) { - - // Report the contacts to the user - CollisionCallback::CollisionCallbackInfo collisionInfo(&pair, mPoolAllocator); - callback->notifyContact(collisionInfo); - } } + + // Go to the next overlapping proxy shape + element = element->next; } - // Go to the next overlapping proxy shape - element = element->next; + // Go to the next proxy shape + bodyProxyShape = bodyProxyShape->getNext(); } - - // Go to the next proxy shape - bodyProxyShape = bodyProxyShape->getNext(); } } @@ -1031,7 +1043,14 @@ EventListener* CollisionDetection::getWorldEventListener() { return mWorld->mEventListener; } -/// Return a reference to the world memory allocator +// Return a reference to the world memory allocator PoolAllocator& CollisionDetection::getWorldMemoryAllocator() { return mWorld->mPoolAllocator; } + + +// Return the world-space AABB of a given proxy shape +const AABB CollisionDetection::getWorldAABB(const ProxyShape* proxyShape) const { + assert(proxyShape->mBroadPhaseID > -1); + return mBroadPhaseAlgorithm.getFatAABB(proxyShape->mBroadPhaseID); +} diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index 848e7d09..6f28f788 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -219,6 +219,9 @@ class CollisionDetection { /// Return a reference to the world memory allocator PoolAllocator& getWorldMemoryAllocator(); + /// Return the world-space AABB of a given proxy shape + const AABB getWorldAABB(const ProxyShape* proxyShape) const; + // -------------------- Friendship -------------------- // friend class DynamicsWorld; @@ -259,7 +262,10 @@ inline void CollisionDetection::removeNoCollisionPair(CollisionBody* body1, /// We simply put the shape in the list of collision shape that have moved in the /// previous frame so that it is tested for collision again in the broad-phase. inline void CollisionDetection::askForBroadPhaseCollisionCheck(ProxyShape* shape) { - mBroadPhaseAlgorithm.addMovedCollisionShape(shape->mBroadPhaseID); + + if (shape->mBroadPhaseID != -1) { + mBroadPhaseAlgorithm.addMovedCollisionShape(shape->mBroadPhaseID); + } } // Update a proxy collision shape (that has moved for instance) diff --git a/src/collision/broadphase/BroadPhaseAlgorithm.cpp b/src/collision/broadphase/BroadPhaseAlgorithm.cpp index bc03f44d..c86cd0bc 100644 --- a/src/collision/broadphase/BroadPhaseAlgorithm.cpp +++ b/src/collision/broadphase/BroadPhaseAlgorithm.cpp @@ -117,6 +117,8 @@ void BroadPhaseAlgorithm::removeMovedCollisionShape(int broadPhaseID) { // Add a proxy collision shape into the broad-phase collision detection void BroadPhaseAlgorithm::addProxyCollisionShape(ProxyShape* proxyShape, const AABB& aabb) { + assert(proxyShape->mBroadPhaseID == -1); + // Add the collision shape into the dynamic AABB tree and get its broad-phase ID int nodeId = mDynamicAABBTree.addObject(aabb, proxyShape); @@ -131,8 +133,12 @@ void BroadPhaseAlgorithm::addProxyCollisionShape(ProxyShape* proxyShape, const A // Remove a proxy collision shape from the broad-phase collision detection void BroadPhaseAlgorithm::removeProxyCollisionShape(ProxyShape* proxyShape) { + assert(proxyShape->mBroadPhaseID != -1); + int broadPhaseID = proxyShape->mBroadPhaseID; + proxyShape->mBroadPhaseID = -1; + // Remove the collision shape from the dynamic AABB tree mDynamicAABBTree.removeObject(broadPhaseID); diff --git a/src/collision/broadphase/BroadPhaseAlgorithm.h b/src/collision/broadphase/BroadPhaseAlgorithm.h index 8d2cda35..94499d44 100644 --- a/src/collision/broadphase/BroadPhaseAlgorithm.h +++ b/src/collision/broadphase/BroadPhaseAlgorithm.h @@ -232,6 +232,9 @@ inline bool BroadPhasePair::smallerThan(const BroadPhasePair& pair1, const Broad // Return true if the two broad-phase collision shapes are overlapping inline bool BroadPhaseAlgorithm::testOverlappingShapes(const ProxyShape* shape1, const ProxyShape* shape2) const { + + if (shape1->mBroadPhaseID == -1 || shape2->mBroadPhaseID == -1) return false; + // Get the two AABBs of the collision shapes const AABB& aabb1 = mDynamicAABBTree.getFatAABB(shape1->mBroadPhaseID); const AABB& aabb2 = mDynamicAABBTree.getFatAABB(shape2->mBroadPhaseID); diff --git a/src/engine/CollisionWorld.cpp b/src/engine/CollisionWorld.cpp index d160021c..e8f4155a 100644 --- a/src/engine/CollisionWorld.cpp +++ b/src/engine/CollisionWorld.cpp @@ -164,3 +164,14 @@ bool CollisionWorld::testOverlap(CollisionBody* body1, CollisionBody* body2) { return mCollisionDetection.testOverlap(body1, body2); } + +// Return the current world-space AABB of given proxy shape +AABB CollisionWorld::getWorldAABB(const ProxyShape* proxyShape) const { + + if (proxyShape->mBroadPhaseID == -1) { + return AABB(); + } + + return mCollisionDetection.getWorldAABB(proxyShape); +} + diff --git a/src/engine/CollisionWorld.h b/src/engine/CollisionWorld.h index 82d2601f..d27b8018 100644 --- a/src/engine/CollisionWorld.h +++ b/src/engine/CollisionWorld.h @@ -147,6 +147,9 @@ class CollisionWorld { /// Test and report collisions between all shapes of the world void testCollision(CollisionCallback* callback); + /// Return the current world-space AABB of given proxy shape + AABB getWorldAABB(const ProxyShape* proxyShape) const; + // -------------------- Friendship -------------------- // friend class CollisionDetection; From ad0f805f53be29b0f3c7e17b5fdc1986c51a759c Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 1 Nov 2017 23:09:02 +0100 Subject: [PATCH 121/248] Fix robustness issue in SAT Algorithm (convex polyhedron vs capsule) --- .../CapsuleVsConvexPolyhedronAlgorithm.cpp | 5 ++++- src/collision/narrowphase/SAT/SATAlgorithm.cpp | 13 +++++++++---- src/collision/narrowphase/SAT/SATAlgorithm.h | 2 +- 3 files changed, 14 insertions(+), 6 deletions(-) diff --git a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp index 89336c4e..e895eef7 100644 --- a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp @@ -119,10 +119,13 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPh } // Compute and create two contact points - satAlgorithm.computeCapsulePolyhedronFaceContactPoints(f, capsuleShape->getRadius(), polyhedron, contactPoint->penetrationDepth, + bool contactsFound = satAlgorithm.computeCapsulePolyhedronFaceContactPoints(f, capsuleShape->getRadius(), polyhedron, contactPoint->penetrationDepth, polyhedronToCapsuleTransform, faceNormalWorld, separatingAxisCapsuleSpace, capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, narrowPhaseInfo, isCapsuleShape1); + if (!contactsFound) { + return false; + } break; } diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 1ba5143b..e6d09dd1 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -256,7 +256,7 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfo* narro if (reportContacts) { - computeCapsulePolyhedronFaceContactPoints(minFaceIndex, capsuleRadius, polyhedron, minPenetrationDepth, + return computeCapsulePolyhedronFaceContactPoints(minFaceIndex, capsuleRadius, polyhedron, minPenetrationDepth, polyhedronToCapsuleTransform, normalWorld, separatingAxisCapsuleSpace, capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, narrowPhaseInfo, isCapsuleShape1); @@ -349,7 +349,7 @@ 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 -void SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceIndex, decimal capsuleRadius, const ConvexPolyhedronShape* polyhedron, +bool SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceIndex, decimal capsuleRadius, const ConvexPolyhedronShape* polyhedron, decimal penetrationDepth, const Transform& polyhedronToCapsuleTransform, Vector3& normalWorld, const Vector3& separatingAxisCapsuleSpace, const Vector3& capsuleSegAPolyhedronSpace, const Vector3& capsuleSegBPolyhedronSpace, @@ -391,13 +391,14 @@ void SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceI // First we clip the inner segment of the capsule with the four planes of the adjacent faces std::vector clipSegment = clipSegmentWithPlanes(capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, planesPoints, planesNormals); - assert(clipSegment.size() == 2); // Project the two clipped points into the polyhedron face const Vector3 delta = faceNormal * (penetrationDepth - capsuleRadius); + bool contactFound = false; + // For each of the two clipped points - for (uint i = 0; i<2; i++) { + for (uint i = 0; i penetrationDepth - capsuleRadius - decimal(0.001)) { + contactFound = true; + Vector3 contactPointPolyhedron = clipSegment[i] + delta; // Project the clipped point into the capsule bounds @@ -426,6 +429,8 @@ void SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceI isCapsuleShape1 ? contactPointPolyhedron : contactPointCapsule); } } + + return contactFound; } // This method returns true if an edge of a polyhedron and a capsule forms a diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.h b/src/collision/narrowphase/SAT/SATAlgorithm.h index 37e4f7d2..5c721a00 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.h +++ b/src/collision/narrowphase/SAT/SATAlgorithm.h @@ -126,7 +126,7 @@ class SATAlgorithm { bool testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) const; /// Compute the two contact points between a polyhedron and a capsule when the separating axis is a face normal of the polyhedron - void computeCapsulePolyhedronFaceContactPoints(uint referenceFaceIndex, decimal capsuleRadius, const ConvexPolyhedronShape* polyhedron, + bool computeCapsulePolyhedronFaceContactPoints(uint referenceFaceIndex, decimal capsuleRadius, const ConvexPolyhedronShape* polyhedron, decimal penetrationDepth, const Transform& polyhedronToCapsuleTransform, Vector3& normalWorld, const Vector3& separatingAxisCapsuleSpace, const Vector3& capsuleSegAPolyhedronSpace, const Vector3& capsuleSegBPolyhedronSpace, From 7495ff6598d218ae8d8549dd7320047791f4d5a3 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 2 Nov 2017 22:58:41 +0100 Subject: [PATCH 122/248] Refactor the testbed application and display objects AABBs --- testbed/CMakeLists.txt | 2 + testbed/common/AABB.cpp | 202 +++++++++++++ testbed/common/AABB.h | 79 +++++ testbed/common/Box.cpp | 44 +-- testbed/common/Box.h | 10 +- testbed/common/Capsule.cpp | 40 +-- testbed/common/Capsule.h | 10 +- testbed/common/ConcaveMesh.cpp | 40 +-- testbed/common/ConcaveMesh.h | 10 +- testbed/common/ConvexMesh.cpp | 40 +-- testbed/common/ConvexMesh.h | 10 +- testbed/common/Dumbbell.cpp | 42 +-- testbed/common/Dumbbell.h | 10 +- testbed/common/HeightField.cpp | 38 +-- testbed/common/HeightField.h | 10 +- testbed/common/PhysicsObject.h | 2 +- testbed/common/Sphere.cpp | 39 +-- testbed/common/Sphere.h | 10 +- .../CollisionDetectionScene.cpp | 125 ++++---- .../CollisionDetectionScene.h | 7 +- .../collisionshapes/CollisionShapesScene.cpp | 208 ++++---------- .../collisionshapes/CollisionShapesScene.h | 13 +- .../scenes/concavemesh/ConcaveMeshScene.cpp | 270 +++++++++++------- testbed/scenes/concavemesh/ConcaveMeshScene.h | 57 ++-- testbed/scenes/cubes/CubesScene.cpp | 132 +++------ testbed/scenes/cubes/CubesScene.h | 13 +- .../scenes/heightfield/HeightFieldScene.cpp | 169 +++++------ testbed/scenes/heightfield/HeightFieldScene.h | 13 +- testbed/scenes/joints/JointsScene.cpp | 135 ++++----- testbed/scenes/joints/JointsScene.h | 11 +- testbed/scenes/raycast/RaycastScene.cpp | 56 ++-- testbed/scenes/raycast/RaycastScene.h | 5 +- testbed/src/Gui.cpp | 8 + testbed/src/Scene.cpp | 16 +- testbed/src/Scene.h | 53 ++-- testbed/src/SceneDemo.cpp | 86 +++++- testbed/src/SceneDemo.h | 25 +- testbed/src/TestbedApplication.cpp | 34 ++- testbed/src/TestbedApplication.h | 6 +- 39 files changed, 1066 insertions(+), 1014 deletions(-) create mode 100644 testbed/common/AABB.cpp create mode 100644 testbed/common/AABB.h diff --git a/testbed/CMakeLists.txt b/testbed/CMakeLists.txt index a5620028..e5e3b312 100644 --- a/testbed/CMakeLists.txt +++ b/testbed/CMakeLists.txt @@ -94,6 +94,8 @@ SET(COMMON_SOURCES common/VisualContactPoint.cpp common/PerlinNoise.h common/PerlinNoise.cpp + common/AABB.h + common/AABB.cpp ) # Examples scenes source files diff --git a/testbed/common/AABB.cpp b/testbed/common/AABB.cpp new file mode 100644 index 00000000..8c43700c --- /dev/null +++ b/testbed/common/AABB.cpp @@ -0,0 +1,202 @@ +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "AABB.h" + +// Macros +#define MEMBER_OFFSET(s,m) ((char *)nullptr + (offsetof(s,m))) + +// Initialize static variables +openglframework::VertexBufferObject AABB::mVBOVertices(GL_ARRAY_BUFFER); +openglframework::VertexBufferObject AABB::mVBONormals(GL_ARRAY_BUFFER); +openglframework::VertexBufferObject AABB::mVBOIndices(GL_ELEMENT_ARRAY_BUFFER); +openglframework::VertexArrayObject AABB::mVAO; + + +// Initialize the data to render AABBs +void AABB::init() { + createVBOAndVAO(); +} + +// Destroy the data used to render AABBs +void AABB::destroy() { + + // Destroy the VBOs and VAO + mVBOVertices.destroy(); + mVBONormals.destroy(); + mVAO.destroy(); +} + +// Render the AABB +void AABB::render(const openglframework::Vector3& position, const openglframework::Vector3& dimension, + openglframework::Color color, openglframework::Shader& shader, + const openglframework::Matrix4& worldToCameraMatrix) { + + // Render in wireframe mode + glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); + + // Bind the shader + shader.bind(); + + // Transform matrix + openglframework::Matrix4 transformMatrix = openglframework::Matrix4::identity(); + transformMatrix = openglframework::Matrix4::translationMatrix(position) * transformMatrix; + + // Set the normal matrix (inverse transpose of the 3x3 upper-left sub matrix of the + // model-view matrix) + const openglframework::Matrix4 localToCameraMatrix = worldToCameraMatrix * transformMatrix; + const openglframework::Matrix3 normalMatrix = + localToCameraMatrix.getUpperLeft3x3Matrix().getInverse().getTranspose(); + shader.setMatrix3x3Uniform("normalMatrix", normalMatrix, false); + + + // Compute the scaling matrix + openglframework::Matrix4 scalingMatrix = openglframework::Matrix4(dimension.x, 0, 0, 0, + 0, dimension.y, 0, 0, + 0, 0, dimension.z, 0, + 0, 0, 0, 1); + + transformMatrix = transformMatrix * scalingMatrix; + + // Set the model to camera matrix + shader.setMatrix4x4Uniform("localToWorldMatrix", transformMatrix); + shader.setMatrix4x4Uniform("worldToCameraMatrix", worldToCameraMatrix); + + // Set the vertex color + openglframework::Vector4 colorVec(color.r, color.g, color.b, color.a); + shader.setVector4Uniform("vertexColor", colorVec, false); + + // Bind the VAO + mVAO.bind(); + + mVBOVertices.bind(); + + // Get the location of shader attribute variables + GLint vertexPositionLoc = shader.getAttribLocation("vertexPosition"); + GLint vertexNormalLoc = shader.getAttribLocation("vertexNormal", false); + + glEnableVertexAttribArray(vertexPositionLoc); + glVertexAttribPointer(vertexPositionLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)nullptr); + + mVBONormals.bind(); + + if (vertexNormalLoc != -1) glVertexAttribPointer(vertexNormalLoc, 3, GL_FLOAT, GL_FALSE, 0, (char*)nullptr); + if (vertexNormalLoc != -1) glEnableVertexAttribArray(vertexNormalLoc); + + // Draw the geometry + glDrawElements(GL_LINES, 12 * 2, GL_UNSIGNED_INT, (char*)nullptr); + + glDisableVertexAttribArray(vertexPositionLoc); + if (vertexNormalLoc != -1) glDisableVertexAttribArray(vertexNormalLoc); + + mVBONormals.unbind(); + mVBOVertices.unbind(); + + // Unbind the VAO + mVAO.unbind(); + + // Unbind the shader + shader.unbind(); + + // Disable wireframe mode + glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); +} + +// Create the Vertex Buffer Objects used to render to box with OpenGL. +/// We create two VBOs (one for vertices and one for indices) +void AABB::createVBOAndVAO() { + + std::vector vertices; + std::vector normals; + std::vector indices; + + // Vertices + vertices.push_back(openglframework::Vector3(-0.5, -0.5, 0.5)); + vertices.push_back(openglframework::Vector3(0.5, -0.5, 0.5)); + vertices.push_back(openglframework::Vector3(0.5, 0.5, 0.5)); + vertices.push_back(openglframework::Vector3(-0.5, 0.5, 0.5)); + vertices.push_back(openglframework::Vector3(0.5, -0.5, -0.5)); + vertices.push_back(openglframework::Vector3(0.5, 0.5, -0.5)); + vertices.push_back(openglframework::Vector3(-0.5, 0.5, -0.5)); + vertices.push_back(openglframework::Vector3(-0.5, -0.5, -0.5)); + + // Normals + normals.push_back(openglframework::Vector3(1, -1, 1)); + normals.push_back(openglframework::Vector3(1, 1, 1)); + normals.push_back(openglframework::Vector3(-1, 1, 1)); + normals.push_back(openglframework::Vector3(-1, -1, 1)); + normals.push_back(openglframework::Vector3(1, -1, -1)); + normals.push_back(openglframework::Vector3(1, 1, -1)); + normals.push_back(openglframework::Vector3(-1, 1, -1)); + normals.push_back(openglframework::Vector3(-1, -1, -1)); + + // Indices + indices.push_back(0); indices.push_back(1); indices.push_back(1); indices.push_back(2); + indices.push_back(2); indices.push_back(3); indices.push_back(3); indices.push_back(0); + + indices.push_back(4); indices.push_back(5); indices.push_back(5); indices.push_back(6); + indices.push_back(6); indices.push_back(7); indices.push_back(7); indices.push_back(4); + + indices.push_back(1); indices.push_back(4); indices.push_back(2); indices.push_back(5); + indices.push_back(0); indices.push_back(7); indices.push_back(3); indices.push_back(6); + + // Create the VBO for the vertices data + mVBOVertices.create(); + mVBOVertices.bind(); + GLsizei sizeVertices = static_cast(vertices.size() * sizeof(openglframework::Vector3)); + mVBOVertices.copyDataIntoVBO(sizeVertices, &(vertices[0]), GL_STATIC_DRAW); + mVBOVertices.unbind(); + + // Create the VBO for the normals data + mVBONormals.create(); + mVBONormals.bind(); + GLsizei sizeNormals = static_cast(normals.size() * sizeof(openglframework::Vector3)); + mVBONormals.copyDataIntoVBO(sizeNormals, &(normals[0]), GL_STATIC_DRAW); + mVBONormals.unbind(); + + // Create th VBO for the indices data + mVBOIndices.create(); + mVBOIndices.bind(); + GLsizei sizeIndices = static_cast(indices.size() * sizeof(unsigned int)); + mVBOIndices.copyDataIntoVBO(sizeIndices, &(indices[0]), GL_STATIC_DRAW); + mVBOIndices.unbind(); + + // Create the VAO for both VBOs + mVAO.create(); + mVAO.bind(); + + // Bind the VBO of vertices + mVBOVertices.bind(); + + // Bind the VBO of normals + mVBONormals.bind(); + + // Bind the VBO of indices + mVBOIndices.bind(); + + // Unbind the VAO + mVAO.unbind(); +} diff --git a/testbed/common/AABB.h b/testbed/common/AABB.h new file mode 100644 index 00000000..e73326b5 --- /dev/null +++ b/testbed/common/AABB.h @@ -0,0 +1,79 @@ +/******************************************************************************** + * 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 AABB_H +#define AABB_H + +// Libraries +#include "openglframework.h" +#include "reactphysics3d.h" + +// Class AABB +class AABB { + + private : + + // -------------------- Attributes -------------------- // + + /// Size of each side of the box + float mSize[3]; + + /// Scaling matrix (applied to a cube to obtain the correct box dimensions) + openglframework::Matrix4 mScalingMatrix; + + /// Vertex Buffer Object for the vertices data + static openglframework::VertexBufferObject mVBOVertices; + + /// Vertex Buffer Object for the normals data + static openglframework::VertexBufferObject mVBONormals; + + /// Vertex Buffer Object for the indices + static openglframework::VertexBufferObject mVBOIndices; + + /// Vertex Array Object for the vertex data + static openglframework::VertexArrayObject mVAO; + + // -------------------- Methods -------------------- // + + /// Create a the VAO and VBOs to render to box with OpenGL + static void createVBOAndVAO(); + + public : + + // -------------------- Methods -------------------- // + + /// Initialize the data to render AABBs + static void init(); + + /// Destroy the data used to render AABBs + static void destroy(); + + /// Render the cube at the correct position and with the correct orientation + static void render(const openglframework::Vector3& position, const openglframework::Vector3& dimension, + openglframework::Color color, openglframework::Shader& shader, + const openglframework::Matrix4& worldToCameraMatrix); +}; + +#endif diff --git a/testbed/common/Box.cpp b/testbed/common/Box.cpp index 09dc388e..508fa516 100644 --- a/testbed/common/Box.cpp +++ b/testbed/common/Box.cpp @@ -38,8 +38,8 @@ openglframework::VertexArrayObject Box::mVAO; int Box::totalNbBoxes = 0; // Constructor -Box::Box(const openglframework::Vector3& size, const openglframework::Vector3 &position, - reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath) +Box::Box(const openglframework::Vector3& size, reactphysics3d::CollisionWorld* world, + const std::string& meshFolderPath) : PhysicsObject(meshFolderPath + "cube.obj") { // Initialize the size of the box @@ -53,23 +53,16 @@ Box::Box(const openglframework::Vector3& size, const openglframework::Vector3 &p 0, 0, mSize[2], 0, 0, 0, 0, 1); - // Initialize the position where the cube will be rendered - translateWorld(position); - // Create the collision shape for the rigid body (box shape) // ReactPhysics3D will clone this object to create an internal one. Therefore, // it is OK if this object is destroyed right after calling RigidBody::addCollisionShape() mBoxShape = new rp3d::BoxShape(rp3d::Vector3(mSize[0], mSize[1], mSize[2])); + //mBoxShape->setLocalScaling(rp3d::Vector3(2, 2, 2)); - // Initial position and orientation of the rigid body - rp3d::Vector3 initPosition(position.x, position.y, position.z); - rp3d::Quaternion initOrientation = rp3d::Quaternion::identity(); - rp3d::Transform transform(initPosition, initOrientation); - - mPreviousTransform = transform; + mPreviousTransform = rp3d::Transform::identity(); // Create a rigid body in the dynamics world - mBody = world->createCollisionBody(transform); + mBody = world->createCollisionBody(mPreviousTransform); // Add the collision shape to the body mProxyShape = mBody->addCollisionShape(mBoxShape, rp3d::Transform::identity()); @@ -87,8 +80,8 @@ Box::Box(const openglframework::Vector3& size, const openglframework::Vector3 &p } // Constructor -Box::Box(const openglframework::Vector3& size, const openglframework::Vector3& position, - float mass, reactphysics3d::DynamicsWorld* world, const std::string& meshFolderPath) +Box::Box(const openglframework::Vector3& size, float mass, reactphysics3d::DynamicsWorld* world, + const std::string& meshFolderPath) : PhysicsObject(meshFolderPath + "cube.obj") { // Load the mesh from a file @@ -108,23 +101,15 @@ Box::Box(const openglframework::Vector3& size, const openglframework::Vector3& p 0, 0, mSize[2], 0, 0, 0, 0, 1); - // Initialize the position where the cube will be rendered - translateWorld(position); - // Create the collision shape for the rigid body (box shape) // ReactPhysics3D will clone this object to create an internal one. Therefore, // it is OK if this object is destroyed right after calling RigidBody::addCollisionShape() mBoxShape = new rp3d::BoxShape(rp3d::Vector3(mSize[0], mSize[1], mSize[2])); - // Initial position and orientation of the rigid body - rp3d::Vector3 initPosition(position.x, position.y, position.z); - rp3d::Quaternion initOrientation = rp3d::Quaternion::identity(); - rp3d::Transform transform(initPosition, initOrientation); - - mPreviousTransform = transform; + mPreviousTransform = rp3d::Transform::identity(); // Create a rigid body in the dynamics world - rp3d::RigidBody* body = world->createRigidBody(transform); + rp3d::RigidBody* body = world->createRigidBody(mPreviousTransform); // Add the collision shape to the body mProxyShape = body->addCollisionShape(mBoxShape, rp3d::Transform::identity(), mass); @@ -158,12 +143,7 @@ Box::~Box() { } // Render the cube at the correct position and with the correct orientation -void Box::render(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix, bool wireframe) { - - if (wireframe) { - glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); - } +void Box::render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) { // Bind the shader shader.bind(); @@ -217,10 +197,6 @@ void Box::render(openglframework::Shader& shader, // Unbind the shader shader.unbind(); - - if (wireframe) { - glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); - } } // Create the Vertex Buffer Objects used to render to box with OpenGL. diff --git a/testbed/common/Box.h b/testbed/common/Box.h index bd7a6024..42d234f9 100644 --- a/testbed/common/Box.h +++ b/testbed/common/Box.h @@ -75,24 +75,22 @@ class Box : public PhysicsObject { // -------------------- Methods -------------------- // /// Constructor - Box(const openglframework::Vector3& size, const openglframework::Vector3& position, - reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath); + Box(const openglframework::Vector3& size, reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath); /// Constructor - Box(const openglframework::Vector3& size, const openglframework::Vector3& position, - float mass, reactphysics3d::DynamicsWorld *world, const std::string& meshFolderPath); + Box(const openglframework::Vector3& size, float mass, reactphysics3d::DynamicsWorld *world, const std::string& meshFolderPath); /// Destructor ~Box(); /// Render the cube at the correct position and with the correct orientation - virtual void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe) override; + virtual void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) override; /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; /// Set the scaling of the object - void setScaling(const openglframework::Vector3& scaling); + void setScaling(const openglframework::Vector3& scaling) override; }; // Update the transform matrix of the object diff --git a/testbed/common/Capsule.cpp b/testbed/common/Capsule.cpp index 413d6eb2..b48baf69 100644 --- a/testbed/common/Capsule.cpp +++ b/testbed/common/Capsule.cpp @@ -34,9 +34,7 @@ openglframework::VertexArrayObject Capsule::mVAO; int Capsule::totalNbCapsules = 0; // Constructor -Capsule::Capsule(float radius, float height, const openglframework::Vector3& position, - reactphysics3d::CollisionWorld* world, - const std::string& meshFolderPath) +Capsule::Capsule(float radius, float height, rp3d::CollisionWorld* world, const std::string& meshFolderPath) : PhysicsObject(meshFolderPath + "capsule.obj"), mRadius(radius), mHeight(height) { // Compute the scaling matrix @@ -45,23 +43,16 @@ Capsule::Capsule(float radius, float height, const openglframework::Vector3& pos 0, 0, mRadius, 0, 0, 0, 0, 1.0f); - // Initialize the position where the sphere will be rendered - translateWorld(position); - // Create the collision shape for the rigid body (sphere shape) // ReactPhysics3D will clone this object to create an internal one. Therefore, // it is OK if this object is destroyed right after calling RigidBody::addCollisionShape() mCapsuleShape = new rp3d::CapsuleShape(mRadius, mHeight); + //mCapsuleShape->setLocalScaling(rp3d::Vector3(2, 2, 2)); - // Initial position and orientation of the rigid body - rp3d::Vector3 initPosition(position.x, position.y, position.z); - rp3d::Quaternion initOrientation = rp3d::Quaternion::identity(); - rp3d::Transform transform(initPosition, initOrientation); - - mPreviousTransform = transform; + mPreviousTransform = rp3d::Transform::identity(); // Create a rigid body corresponding in the dynamics world - mBody = world->createCollisionBody(transform); + mBody = world->createCollisionBody(mPreviousTransform); // Add a collision shape to the body and specify the mass of the shape mProxyShape = mBody->addCollisionShape(mCapsuleShape, rp3d::Transform::identity()); @@ -77,8 +68,7 @@ Capsule::Capsule(float radius, float height, const openglframework::Vector3& pos } // Constructor -Capsule::Capsule(float radius, float height, const openglframework::Vector3& position, - float mass, reactphysics3d::DynamicsWorld* dynamicsWorld, +Capsule::Capsule(float radius, float height, float mass, rp3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath) : PhysicsObject(meshFolderPath + "capsule.obj"), mRadius(radius), mHeight(height) { @@ -88,21 +78,15 @@ Capsule::Capsule(float radius, float height, const openglframework::Vector3& pos 0, 0, mRadius, 0, 0, 0, 0, 1.0f); - // Initialize the position where the sphere will be rendered - translateWorld(position); + mPreviousTransform = rp3d::Transform::identity(); // Create the collision shape for the rigid body (sphere shape) // ReactPhysics3D will clone this object to create an internal one. Therefore, // it is OK if this object is destroyed right after calling RigidBody::addCollisionShape() mCapsuleShape = new rp3d::CapsuleShape(mRadius, mHeight); - // Initial position and orientation of the rigid body - rp3d::Vector3 initPosition(position.x, position.y, position.z); - rp3d::Quaternion initOrientation = rp3d::Quaternion::identity(); - rp3d::Transform transform(initPosition, initOrientation); - // Create a rigid body corresponding in the dynamics world - rp3d::RigidBody* body = dynamicsWorld->createRigidBody(transform); + rp3d::RigidBody* body = dynamicsWorld->createRigidBody(mPreviousTransform); // Add a collision shape to the body and specify the mass of the shape mProxyShape = body->addCollisionShape(mCapsuleShape, rp3d::Transform::identity(), mass); @@ -140,11 +124,7 @@ Capsule::~Capsule() { // Render the sphere at the correct position and with the correct orientation void Capsule::render(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix, bool wireframe) { - - if (wireframe) { - glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); - } + const openglframework::Matrix4& worldToCameraMatrix) { // Bind the shader shader.bind(); @@ -198,10 +178,6 @@ void Capsule::render(openglframework::Shader& shader, // Unbind the shader shader.unbind(); - - if (wireframe) { - glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); - } } // Create the Vertex Buffer Objects used to render with OpenGL. diff --git a/testbed/common/Capsule.h b/testbed/common/Capsule.h index 5c99120b..d0e74436 100644 --- a/testbed/common/Capsule.h +++ b/testbed/common/Capsule.h @@ -82,25 +82,23 @@ class Capsule : public PhysicsObject { // -------------------- Methods -------------------- // /// Constructor - Capsule(float radius, float height, const openglframework::Vector3& position, - reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath); + Capsule(float radius, float height, rp3d::CollisionWorld* world, const std::string& meshFolderPath); /// Constructor - Capsule(float radius, float height, const openglframework::Vector3& position, - float mass, reactphysics3d::DynamicsWorld* dynamicsWorld, + Capsule(float radius, float height, float mass, rp3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath); /// Destructor ~Capsule(); /// Render the sphere at the correct position and with the correct orientation - virtual void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe) override; + virtual void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) override; /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; /// Set the scaling of the object - void setScaling(const openglframework::Vector3& scaling); + void setScaling(const openglframework::Vector3& scaling) override; }; // Update the transform matrix of the object diff --git a/testbed/common/ConcaveMesh.cpp b/testbed/common/ConcaveMesh.cpp index c7e162a3..f6b04b9c 100644 --- a/testbed/common/ConcaveMesh.cpp +++ b/testbed/common/ConcaveMesh.cpp @@ -27,16 +27,11 @@ #include "ConcaveMesh.h" // Constructor -ConcaveMesh::ConcaveMesh(const openglframework::Vector3 &position, - reactphysics3d::CollisionWorld* world, - const std::string& meshPath) +ConcaveMesh::ConcaveMesh(rp3d::CollisionWorld* world, const std::string& meshPath) : PhysicsObject(meshPath), mVBOVertices(GL_ARRAY_BUFFER), mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER), mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) { - // Initialize the position where the sphere will be rendered - translateWorld(position); - // Compute the scaling matrix mScalingMatrix = openglframework::Matrix4::identity(); @@ -58,15 +53,10 @@ ConcaveMesh::ConcaveMesh(const openglframework::Vector3 &position, // do not forget to delete it at the end mConcaveShape = new rp3d::ConcaveMeshShape(&mPhysicsTriangleMesh); - // Initial position and orientation of the rigid body - rp3d::Vector3 initPosition(position.x, position.y, position.z); - rp3d::Quaternion initOrientation = rp3d::Quaternion::identity(); - rp3d::Transform transform(initPosition, initOrientation); - - mPreviousTransform = transform; + mPreviousTransform = rp3d::Transform::identity(); // Create a rigid body corresponding to the sphere in the dynamics world - mBody = world->createCollisionBody(transform); + mBody = world->createCollisionBody(mPreviousTransform); // Add a collision shape to the body and specify the mass of the collision shape mProxyShape = mBody->addCollisionShape(mConcaveShape, rp3d::Transform::identity()); @@ -78,16 +68,11 @@ ConcaveMesh::ConcaveMesh(const openglframework::Vector3 &position, } // Constructor -ConcaveMesh::ConcaveMesh(const openglframework::Vector3 &position, float mass, - reactphysics3d::DynamicsWorld* dynamicsWorld, - const std::string& meshPath) +ConcaveMesh::ConcaveMesh(float mass, rp3d::DynamicsWorld* dynamicsWorld, const std::string& meshPath) : PhysicsObject(meshPath), mVBOVertices(GL_ARRAY_BUFFER), mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER), mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) { - // Initialize the position where the sphere will be rendered - translateWorld(position); - // Compute the scaling matrix mScalingMatrix = openglframework::Matrix4::identity(); @@ -109,13 +94,10 @@ ConcaveMesh::ConcaveMesh(const openglframework::Vector3 &position, float mass, // do not forget to delete it at the end mConcaveShape = new rp3d::ConcaveMeshShape(&mPhysicsTriangleMesh); - // Initial position and orientation of the rigid body - rp3d::Vector3 initPosition(position.x, position.y, position.z); - rp3d::Quaternion initOrientation = rp3d::Quaternion::identity(); - rp3d::Transform transform(initPosition, initOrientation); + mPreviousTransform = rp3d::Transform::identity(); // Create a rigid body corresponding to the sphere in the dynamics world - rp3d::RigidBody* body = dynamicsWorld->createRigidBody(transform); + rp3d::RigidBody* body = dynamicsWorld->createRigidBody(mPreviousTransform); // Add a collision shape to the body and specify the mass of the collision shape mProxyShape = body->addCollisionShape(mConcaveShape, rp3d::Transform::identity(), mass); @@ -151,11 +133,7 @@ ConcaveMesh::~ConcaveMesh() { // Render the sphere at the correct position and with the correct orientation void ConcaveMesh::render(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix, bool wireframe) { - - if (wireframe) { - glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); - } + const openglframework::Matrix4& worldToCameraMatrix) { // Bind the shader shader.bind(); @@ -209,10 +187,6 @@ void ConcaveMesh::render(openglframework::Shader& shader, // Unbind the shader shader.unbind(); - - if (wireframe) { - glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); - } } // Create the Vertex Buffer Objects used to render with OpenGL. diff --git a/testbed/common/ConcaveMesh.h b/testbed/common/ConcaveMesh.h index afda3d45..17755352 100644 --- a/testbed/common/ConcaveMesh.h +++ b/testbed/common/ConcaveMesh.h @@ -76,25 +76,23 @@ class ConcaveMesh : public PhysicsObject { // -------------------- Methods -------------------- // /// Constructor - ConcaveMesh(const openglframework::Vector3& position, - rp3d::CollisionWorld* world, const std::string& meshPath); + ConcaveMesh(rp3d::CollisionWorld* world, const std::string& meshPath); /// Constructor - ConcaveMesh(const openglframework::Vector3& position, float mass, - rp3d::DynamicsWorld* dynamicsWorld, const std::string& meshPath); + ConcaveMesh(float mass, rp3d::DynamicsWorld* dynamicsWorld, const std::string& meshPath); /// Destructor ~ConcaveMesh(); /// Render the mesh at the correct position and with the correct orientation void render(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix, bool wireframe); + const openglframework::Matrix4& worldToCameraMatrix) override; /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; /// Set the scaling of the object - void setScaling(const openglframework::Vector3& scaling); + void setScaling(const openglframework::Vector3& scaling) override; }; // Update the transform matrix of the object diff --git a/testbed/common/ConvexMesh.cpp b/testbed/common/ConvexMesh.cpp index b3cb3b95..a59c2f3d 100644 --- a/testbed/common/ConvexMesh.cpp +++ b/testbed/common/ConvexMesh.cpp @@ -27,16 +27,11 @@ #include "ConvexMesh.h" // Constructor -ConvexMesh::ConvexMesh(const openglframework::Vector3 &position, - reactphysics3d::CollisionWorld* world, - const std::string& meshPath) +ConvexMesh::ConvexMesh(rp3d::CollisionWorld* world, const std::string& meshPath) : PhysicsObject(meshPath), mVBOVertices(GL_ARRAY_BUFFER), mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER), mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) { - // Initialize the position where the sphere will be rendered - translateWorld(position); - // Compute the scaling matrix mScalingMatrix = openglframework::Matrix4::identity(); @@ -64,15 +59,10 @@ ConvexMesh::ConvexMesh(const openglframework::Vector3 &position, // do not forget to delete it at the end mConvexShape = new rp3d::ConvexMeshShape(mPolyhedronMesh); - // Initial position and orientation of the rigid body - rp3d::Vector3 initPosition(position.x, position.y, position.z); - rp3d::Quaternion initOrientation = rp3d::Quaternion::identity(); - rp3d::Transform transform(initPosition, initOrientation); - - mPreviousTransform = transform; + mPreviousTransform = rp3d::Transform::identity(); // Create a rigid body corresponding to the sphere in the dynamics world - mBody = world->createCollisionBody(transform); + mBody = world->createCollisionBody(mPreviousTransform); // Add a collision shape to the body and specify the mass of the collision shape mProxyShape = mBody->addCollisionShape(mConvexShape, rp3d::Transform::identity()); @@ -84,16 +74,11 @@ ConvexMesh::ConvexMesh(const openglframework::Vector3 &position, } // Constructor -ConvexMesh::ConvexMesh(const openglframework::Vector3 &position, float mass, - reactphysics3d::DynamicsWorld* dynamicsWorld, - const std::string& meshPath) +ConvexMesh::ConvexMesh(float mass, rp3d::DynamicsWorld* dynamicsWorld, const std::string& meshPath) : PhysicsObject(meshPath), mVBOVertices(GL_ARRAY_BUFFER), mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER), mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) { - // Initialize the position where the sphere will be rendered - translateWorld(position); - // Compute the scaling matrix mScalingMatrix = openglframework::Matrix4::identity(); @@ -121,13 +106,10 @@ ConvexMesh::ConvexMesh(const openglframework::Vector3 &position, float mass, // not forget to delete it at the end mConvexShape = new rp3d::ConvexMeshShape(mPolyhedronMesh); - // Initial position and orientation of the rigid body - rp3d::Vector3 initPosition(position.x, position.y, position.z); - rp3d::Quaternion initOrientation = rp3d::Quaternion::identity(); - rp3d::Transform transform(initPosition, initOrientation); + mPreviousTransform = rp3d::Transform::identity(); // Create a rigid body corresponding to the sphere in the dynamics world - rp3d::RigidBody* body = dynamicsWorld->createRigidBody(transform); + rp3d::RigidBody* body = dynamicsWorld->createRigidBody(mPreviousTransform); // Add a collision shape to the body and specify the mass of the collision shape mProxyShape = body->addCollisionShape(mConvexShape, rp3d::Transform::identity(), mass); @@ -161,11 +143,7 @@ ConvexMesh::~ConvexMesh() { // Render the sphere at the correct position and with the correct orientation void ConvexMesh::render(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix, bool wireframe) { - - if (wireframe) { - glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); - } + const openglframework::Matrix4& worldToCameraMatrix) { // Bind the shader shader.bind(); @@ -219,10 +197,6 @@ void ConvexMesh::render(openglframework::Shader& shader, // Unbind the shader shader.unbind(); - - if (wireframe) { - glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); - } } // Create the Vertex Buffer Objects used to render with OpenGL. diff --git a/testbed/common/ConvexMesh.h b/testbed/common/ConvexMesh.h index 1b55611b..865921ca 100644 --- a/testbed/common/ConvexMesh.h +++ b/testbed/common/ConvexMesh.h @@ -79,24 +79,22 @@ class ConvexMesh : public PhysicsObject { // -------------------- Methods -------------------- // /// Constructor - ConvexMesh(const openglframework::Vector3& position, - rp3d::CollisionWorld* world, const std::string& meshPath); + ConvexMesh(rp3d::CollisionWorld* world, const std::string& meshPath); /// Constructor - ConvexMesh(const openglframework::Vector3& position, float mass, - rp3d::DynamicsWorld* dynamicsWorld, const std::string& meshPath); + ConvexMesh(float mass, rp3d::DynamicsWorld* dynamicsWorld, const std::string& meshPath); /// Destructor ~ConvexMesh(); /// Render the mesh at the correct position and with the correct orientation - virtual void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe) override; + virtual void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) override; /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; /// Set the scaling of the object - void setScaling(const openglframework::Vector3& scaling); + void setScaling(const openglframework::Vector3& scaling) override; }; // Update the transform matrix of the object diff --git a/testbed/common/Dumbbell.cpp b/testbed/common/Dumbbell.cpp index 02afe091..f90f0cc9 100644 --- a/testbed/common/Dumbbell.cpp +++ b/testbed/common/Dumbbell.cpp @@ -34,8 +34,7 @@ openglframework::VertexArrayObject Dumbbell::mVAO; int Dumbbell::totalNbDumbbells = 0; // Constructor -Dumbbell::Dumbbell(const openglframework::Vector3 &position, - reactphysics3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath) +Dumbbell::Dumbbell(rp3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath) : PhysicsObject(meshFolderPath + "dumbbell.obj") { // Identity scaling matrix @@ -43,9 +42,6 @@ Dumbbell::Dumbbell(const openglframework::Vector3 &position, mDistanceBetweenSphere = 8.0f; - // Initialize the position where the sphere will be rendered - translateWorld(position); - // Create a sphere collision shape for the two ends of the dumbbell // ReactPhysics3D will clone this object to create an internal one. Therefore, // it is OK if this object is destroyed right after calling RigidBody::addCollisionShape() @@ -61,13 +57,7 @@ Dumbbell::Dumbbell(const openglframework::Vector3 &position, const rp3d::decimal massCylinder = rp3d::decimal(1.0); mCapsuleShape = new rp3d::CapsuleShape(radiusCapsule, heightCapsule); - // Initial position and orientation of the rigid body - rp3d::Vector3 initPosition(position.x, position.y, position.z); - rp3d::decimal angleAroundX = 0;//rp3d::PI / 2; - rp3d::Quaternion initOrientation(angleAroundX, 0, 0); - rp3d::Transform transformBody(initPosition, initOrientation); - - mPreviousTransform = transformBody; + mPreviousTransform = rp3d::Transform::identity(); // Initial transform of the first sphere collision shape of the dumbbell (in local-space) rp3d::Transform transformSphereShape1(rp3d::Vector3(0, mDistanceBetweenSphere / 2.0f, 0), rp3d::Quaternion::identity()); @@ -79,7 +69,7 @@ Dumbbell::Dumbbell(const openglframework::Vector3 &position, rp3d::Transform transformCylinderShape(rp3d::Vector3(0, 0, 0), rp3d::Quaternion::identity()); // Create a rigid body corresponding to the dumbbell in the dynamics world - rp3d::RigidBody* body = dynamicsWorld->createRigidBody(transformBody); + rp3d::RigidBody* body = dynamicsWorld->createRigidBody(mPreviousTransform); // Add the three collision shapes to the body and specify the mass and transform of the shapes mProxyShapeSphere1 = body->addCollisionShape(mSphereShape, transformSphereShape1, massSphere); @@ -99,8 +89,7 @@ Dumbbell::Dumbbell(const openglframework::Vector3 &position, } // Constructor -Dumbbell::Dumbbell(const openglframework::Vector3 &position, - reactphysics3d::CollisionWorld* world, const std::string& meshFolderPath) +Dumbbell::Dumbbell(rp3d::CollisionWorld* world, const std::string& meshFolderPath) : PhysicsObject(meshFolderPath + "dumbbell.obj"){ // Identity scaling matrix @@ -108,9 +97,6 @@ Dumbbell::Dumbbell(const openglframework::Vector3 &position, mDistanceBetweenSphere = 8.0f; - // Initialize the position where the sphere will be rendered - translateWorld(position); - // Create a sphere collision shape for the two ends of the dumbbell // ReactPhysics3D will clone this object to create an internal one. Therefore, // it is OK if this object is destroyed right after calling RigidBody::addCollisionShape() @@ -124,12 +110,6 @@ Dumbbell::Dumbbell(const openglframework::Vector3 &position, const rp3d::decimal heightCapsule = rp3d::decimal(7.0); mCapsuleShape = new rp3d::CapsuleShape(radiusCapsule, heightCapsule); - // Initial position and orientation of the rigid body - rp3d::Vector3 initPosition(position.x, position.y, position.z); - rp3d::decimal angleAroundX = 0;//rp3d::PI / 2; - rp3d::Quaternion initOrientation(angleAroundX, 0, 0); - rp3d::Transform transformBody(initPosition, initOrientation); - // Initial transform of the first sphere collision shape of the dumbbell (in local-space) rp3d::Transform transformSphereShape1(rp3d::Vector3(0, mDistanceBetweenSphere / 2.0f, 0), rp3d::Quaternion::identity()); @@ -139,8 +119,10 @@ Dumbbell::Dumbbell(const openglframework::Vector3 &position, // Initial transform of the cylinder collision shape of the dumbell (in local-space) rp3d::Transform transformCylinderShape(rp3d::Vector3(0, 0, 0), rp3d::Quaternion::identity()); + mPreviousTransform = rp3d::Transform::identity(); + // Create a rigid body corresponding to the dumbbell in the dynamics world - mBody = world->createCollisionBody(transformBody); + mBody = world->createCollisionBody(mPreviousTransform); // Add the three collision shapes to the body and specify the mass and transform of the shapes mProxyShapeSphere1 = mBody->addCollisionShape(mSphereShape, transformSphereShape1); @@ -179,11 +161,7 @@ Dumbbell::~Dumbbell() { // Render the sphere at the correct position and with the correct orientation void Dumbbell::render(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix, bool wireframe) { - - if (wireframe) { - glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); - } + const openglframework::Matrix4& worldToCameraMatrix) { // Bind the shader shader.bind(); @@ -237,10 +215,6 @@ void Dumbbell::render(openglframework::Shader& shader, // Unbind the shader shader.unbind(); - - if (wireframe) { - glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); - } } // Create the Vertex Buffer Objects used to render with OpenGL. diff --git a/testbed/common/Dumbbell.h b/testbed/common/Dumbbell.h index aa6bded1..135beabc 100644 --- a/testbed/common/Dumbbell.h +++ b/testbed/common/Dumbbell.h @@ -82,24 +82,22 @@ class Dumbbell : public PhysicsObject { // -------------------- Methods -------------------- // /// Constructor - Dumbbell(const openglframework::Vector3& position, rp3d::DynamicsWorld* dynamicsWorld, - const std::string& meshFolderPath); + Dumbbell(rp3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath); /// Constructor - Dumbbell(const openglframework::Vector3& position, rp3d::CollisionWorld* world, - const std::string& meshFolderPath); + Dumbbell(rp3d::CollisionWorld* world, const std::string& meshFolderPath); /// Destructor ~Dumbbell(); /// Render the sphere at the correct position and with the correct orientation - virtual void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe) override; + virtual void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) override; /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; /// Set the scaling of the object - void setScaling(const openglframework::Vector3& scaling); + void setScaling(const openglframework::Vector3& scaling) override; }; // Update the transform matrix of the object diff --git a/testbed/common/HeightField.cpp b/testbed/common/HeightField.cpp index 377cab07..e979936d 100644 --- a/testbed/common/HeightField.cpp +++ b/testbed/common/HeightField.cpp @@ -28,15 +28,11 @@ #include "PerlinNoise.h" // Constructor -HeightField::HeightField(const openglframework::Vector3 &position, - reactphysics3d::CollisionWorld* world) +HeightField::HeightField(rp3d::CollisionWorld* world) : mVBOVertices(GL_ARRAY_BUFFER), mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER), mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) { - // Initialize the position where the sphere will be rendered - translateWorld(position); - // Compute the scaling matrix mScalingMatrix = openglframework::Matrix4::identity(); @@ -51,15 +47,10 @@ HeightField::HeightField(const openglframework::Vector3 &position, mHeightFieldShape = new rp3d::HeightFieldShape(NB_POINTS_WIDTH, NB_POINTS_LENGTH, mMinHeight, mMaxHeight, mHeightData, rp3d::HeightFieldShape::HeightDataType::HEIGHT_FLOAT_TYPE); - // Initial position and orientation of the rigid body - rp3d::Vector3 initPosition(position.x, position.y, position.z); - rp3d::Quaternion initOrientation = rp3d::Quaternion::identity(); - rp3d::Transform transform(initPosition, initOrientation); - - mPreviousTransform = transform; + mPreviousTransform = rp3d::Transform::identity(); // Create a rigid body corresponding to the sphere in the dynamics world - mBody = world->createCollisionBody(transform); + mBody = world->createCollisionBody(mPreviousTransform); // Add a collision shape to the body and specify the mass of the collision shape mProxyShape = mBody->addCollisionShape(mHeightFieldShape, rp3d::Transform::identity()); @@ -71,15 +62,11 @@ HeightField::HeightField(const openglframework::Vector3 &position, } // Constructor -HeightField::HeightField(const openglframework::Vector3 &position, float mass, - reactphysics3d::DynamicsWorld* dynamicsWorld) +HeightField::HeightField(float mass, rp3d::DynamicsWorld* dynamicsWorld) : mVBOVertices(GL_ARRAY_BUFFER), mVBONormals(GL_ARRAY_BUFFER), mVBOTextureCoords(GL_ARRAY_BUFFER), mVBOIndices(GL_ELEMENT_ARRAY_BUFFER) { - // Initialize the position where the sphere will be rendered - translateWorld(position); - // Compute the scaling matrix mScalingMatrix = openglframework::Matrix4::identity(); @@ -94,13 +81,10 @@ HeightField::HeightField(const openglframework::Vector3 &position, float mass, mHeightFieldShape = new rp3d::HeightFieldShape(NB_POINTS_WIDTH, NB_POINTS_LENGTH, mMinHeight, mMaxHeight, mHeightData, rp3d::HeightFieldShape::HeightDataType::HEIGHT_FLOAT_TYPE); - // Initial position and orientation of the rigid body - rp3d::Vector3 initPosition(position.x, position.y, position.z); - rp3d::Quaternion initOrientation = rp3d::Quaternion::identity(); - rp3d::Transform transform(initPosition, initOrientation); + mPreviousTransform = rp3d::Transform::identity(); // Create a rigid body corresponding to the sphere in the dynamics world - rp3d::RigidBody* body = dynamicsWorld->createRigidBody(transform); + rp3d::RigidBody* body = dynamicsWorld->createRigidBody(mPreviousTransform); // Add a collision shape to the body and specify the mass of the collision shape mProxyShape = body->addCollisionShape(mHeightFieldShape, rp3d::Transform::identity(), mass); @@ -131,11 +115,7 @@ HeightField::~HeightField() { // Render the sphere at the correct position and with the correct orientation void HeightField::render(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix, bool wireframe) { - - if (wireframe) { - glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); - } + const openglframework::Matrix4& worldToCameraMatrix) { // Bind the shader shader.bind(); @@ -189,10 +169,6 @@ void HeightField::render(openglframework::Shader& shader, // Unbind the shader shader.unbind(); - - if (wireframe) { - glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); - } } // Compute the heights of the height field diff --git a/testbed/common/HeightField.h b/testbed/common/HeightField.h index acb39163..1ff390ee 100644 --- a/testbed/common/HeightField.h +++ b/testbed/common/HeightField.h @@ -89,25 +89,23 @@ class HeightField : public PhysicsObject { // -------------------- Methods -------------------- // /// Constructor - HeightField(const openglframework::Vector3& position, - rp3d::CollisionWorld* world); + HeightField(rp3d::CollisionWorld* world); /// Constructor - HeightField(const openglframework::Vector3& position, float mass, - rp3d::DynamicsWorld* dynamicsWorld); + HeightField(float mass, rp3d::DynamicsWorld* dynamicsWorld); /// Destructor ~HeightField(); /// Render the mesh at the correct position and with the correct orientation void render(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix, bool wireframe); + const openglframework::Matrix4& worldToCameraMatrix) override; /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; /// Set the scaling of the object - void setScaling(const openglframework::Vector3& scaling); + void setScaling(const openglframework::Vector3& scaling) override; }; // Update the transform matrix of the object diff --git a/testbed/common/PhysicsObject.h b/testbed/common/PhysicsObject.h index 7fcc612d..e1714048 100644 --- a/testbed/common/PhysicsObject.h +++ b/testbed/common/PhysicsObject.h @@ -63,7 +63,7 @@ class PhysicsObject : public openglframework::Mesh { virtual void updateTransform(float interpolationFactor)=0; /// Render the sphere at the correct position and with the correct orientation - virtual void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe)=0; + virtual void render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix)=0; /// Set the color of the box void setColor(const openglframework::Color& color); diff --git a/testbed/common/Sphere.cpp b/testbed/common/Sphere.cpp index 9eaf62c2..f7c53579 100644 --- a/testbed/common/Sphere.cpp +++ b/testbed/common/Sphere.cpp @@ -34,8 +34,7 @@ openglframework::VertexArrayObject Sphere::mVAO; int Sphere::totalNbSpheres = 0; // Constructor -Sphere::Sphere(float radius, const openglframework::Vector3 &position, - reactphysics3d::CollisionWorld* world, +Sphere::Sphere(float radius, rp3d::CollisionWorld* world, const std::string& meshFolderPath) : PhysicsObject(meshFolderPath + "sphere.obj"), mRadius(radius) { @@ -45,23 +44,16 @@ Sphere::Sphere(float radius, const openglframework::Vector3 &position, 0, 0, mRadius, 0, 0, 0, 0, 1); - // Initialize the position where the sphere will be rendered - translateWorld(position); - // Create the collision shape for the rigid body (sphere shape) // ReactPhysics3D will clone this object to create an internal one. Therefore, // it is OK if this object is destroyed right after calling RigidBody::addCollisionShape() mCollisionShape = new rp3d::SphereShape(mRadius); + //mCollisionShape->setLocalScaling(rp3d::Vector3(2, 2, 2)); - // Initial position and orientation of the rigid body - rp3d::Vector3 initPosition(position.x, position.y, position.z); - rp3d::Quaternion initOrientation = rp3d::Quaternion::identity(); - rp3d::Transform transform(initPosition, initOrientation); - - mPreviousTransform = transform; + mPreviousTransform = rp3d::Transform::identity(); // Create a rigid body corresponding to the sphere in the dynamics world - mBody = world->createCollisionBody(transform); + mBody = world->createCollisionBody(mPreviousTransform); // Add a collision shape to the body and specify the mass of the shape mProxyShape = mBody->addCollisionShape(mCollisionShape, rp3d::Transform::identity()); @@ -77,8 +69,7 @@ Sphere::Sphere(float radius, const openglframework::Vector3 &position, } // Constructor -Sphere::Sphere(float radius, const openglframework::Vector3 &position, - float mass, reactphysics3d::DynamicsWorld* world, +Sphere::Sphere(float radius, float mass, reactphysics3d::DynamicsWorld* world, const std::string& meshFolderPath) : PhysicsObject(meshFolderPath + "sphere.obj"), mRadius(radius) { @@ -88,21 +79,15 @@ Sphere::Sphere(float radius, const openglframework::Vector3 &position, 0, 0, mRadius, 0, 0, 0, 0, 1); - // Initialize the position where the sphere will be rendered - translateWorld(position); - // Create the collision shape for the rigid body (sphere shape) // ReactPhysics3D will clone this object to create an internal one. Therefore, // it is OK if this object is destroyed right after calling RigidBody::addCollisionShape() mCollisionShape = new rp3d::SphereShape(mRadius); - // Initial position and orientation of the rigid body - rp3d::Vector3 initPosition(position.x, position.y, position.z); - rp3d::Quaternion initOrientation = rp3d::Quaternion::identity(); - rp3d::Transform transform(initPosition, initOrientation); + mPreviousTransform = rp3d::Transform::identity(); // Create a rigid body corresponding to the sphere in the dynamics world - rp3d::RigidBody* body = world->createRigidBody(transform); + rp3d::RigidBody* body = world->createRigidBody(mPreviousTransform); // Add a collision shape to the body and specify the mass of the shape mProxyShape = body->addCollisionShape(mCollisionShape, rp3d::Transform::identity(), mass); @@ -138,11 +123,7 @@ Sphere::~Sphere() { } // Render the sphere at the correct position and with the correct orientation -void Sphere::render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireFrame) { - - if (wireFrame) { - glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); - } +void Sphere::render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) { // Bind the shader shader.bind(); @@ -196,10 +177,6 @@ void Sphere::render(openglframework::Shader& shader, const openglframework::Matr // Unbind the shader shader.unbind(); - - if (wireFrame) { - glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); - } } // Create the Vertex Buffer Objects used to render with OpenGL. diff --git a/testbed/common/Sphere.h b/testbed/common/Sphere.h index 000cc776..fe2b3f83 100644 --- a/testbed/common/Sphere.h +++ b/testbed/common/Sphere.h @@ -79,24 +79,22 @@ class Sphere : public PhysicsObject { // -------------------- Methods -------------------- // /// Constructor - Sphere(float radius, const openglframework::Vector3& position, - rp3d::CollisionWorld* world, const std::string& meshFolderPath); + Sphere(float radius, rp3d::CollisionWorld* world, const std::string& meshFolderPath); /// Constructor - Sphere(float radius, const openglframework::Vector3& position, - float mass, rp3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath); + Sphere(float radius, float mass, rp3d::DynamicsWorld* dynamicsWorld, const std::string& meshFolderPath); /// Destructor ~Sphere(); /// Render the sphere at the correct position and with the correct orientation - void virtual render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix, bool wireframe) override; + void virtual render(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) override; /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; /// Set the scaling of the object - void setScaling(const openglframework::Vector3& scaling); + void setScaling(const openglframework::Vector3& scaling) override; }; // Update the transform matrix of the object diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp index 3b186943..f00dbdba 100755 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp @@ -31,8 +31,8 @@ using namespace openglframework; using namespace collisiondetectionscene; // Constructor -CollisionDetectionScene::CollisionDetectionScene(const std::string& name) - : SceneDemo(name, SCENE_RADIUS, false), mMeshFolderPath("meshes/"), +CollisionDetectionScene::CollisionDetectionScene(const std::string& name, EngineSettings& settings) + : SceneDemo(name, settings, SCENE_RADIUS, false), mMeshFolderPath("meshes/"), mContactManager(mPhongShader, mMeshFolderPath), mAreNormalsDisplayed(false) { @@ -47,61 +47,57 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) setScenePosition(center, SCENE_RADIUS); // Create the dynamics world for the physics simulation - mCollisionWorld = new rp3d::CollisionWorld(); + mPhysicsWorld = new rp3d::CollisionWorld(); // ---------- Sphere 1 ---------- // - openglframework::Vector3 position1(12, 0, 0); // Create a sphere and a corresponding collision body in the dynamics world - mSphere1 = new Sphere(4, position1, mCollisionWorld, mMeshFolderPath); + mSphere1 = new Sphere(4, mPhysicsWorld, mMeshFolderPath); mAllShapes.push_back(mSphere1); // Set the color mSphere1->setColor(mGreyColorDemo); mSphere1->setSleepingColor(mRedColorDemo); - mPhysicsObjects.push_back(mSphere1); + //mSphere1->setScaling(0.5f); + mPhysicsObjects.push_back(mSphere1); // ---------- Sphere 2 ---------- // - openglframework::Vector3 position2(12, 8, 0); // Create a sphere and a corresponding collision body in the dynamics world - mSphere2 = new Sphere(2, position2, mCollisionWorld, mMeshFolderPath); + mSphere2 = new Sphere(2, mPhysicsWorld, mMeshFolderPath); mAllShapes.push_back(mSphere2); // Set the color mSphere2->setColor(mGreyColorDemo); mSphere2->setSleepingColor(mRedColorDemo); - mPhysicsObjects.push_back(mSphere2); + mPhysicsObjects.push_back(mSphere2); - // ---------- Capsule 1 ---------- // - openglframework::Vector3 position3(-6, 7, 0); - - // Create a cylinder and a corresponding collision body in the dynamics world - mCapsule1 = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, position3, mCollisionWorld, mMeshFolderPath); - mAllShapes.push_back(mCapsule1); - - // Set the color - mCapsule1->setColor(mGreyColorDemo); - mCapsule1->setSleepingColor(mRedColorDemo); - mPhysicsObjects.push_back(mCapsule1); - - // ---------- Capsule 2 ---------- // - openglframework::Vector3 position4(11, -8, 0); + // ---------- Capsule 1 ---------- // // Create a cylinder and a corresponding collision body in the dynamics world - mCapsule2 = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, position4, mCollisionWorld, mMeshFolderPath); + mCapsule1 = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, mPhysicsWorld, mMeshFolderPath); + mAllShapes.push_back(mCapsule1); + + // Set the color + mCapsule1->setColor(mGreyColorDemo); + mCapsule1->setSleepingColor(mRedColorDemo); + mPhysicsObjects.push_back(mCapsule1); + + // ---------- Capsule 2 ---------- // + + // Create a cylinder and a corresponding collision body in the dynamics world + mCapsule2 = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, mPhysicsWorld, mMeshFolderPath); mAllShapes.push_back(mCapsule2); // Set the color mCapsule2->setColor(mGreyColorDemo); mCapsule2->setSleepingColor(mRedColorDemo); - mPhysicsObjects.push_back(mCapsule2); + mPhysicsObjects.push_back(mCapsule2); - // ---------- Box 1 ---------- // - openglframework::Vector3 position5(-4, -7, 0); + // ---------- Box 1 ---------- // // Create a cylinder and a corresponding collision body in the dynamics world - mBox1 = new Box(BOX_SIZE, position5, mCollisionWorld, mMeshFolderPath); + mBox1 = new Box(BOX_SIZE, mPhysicsWorld, mMeshFolderPath); mAllShapes.push_back(mBox1); // Set the color @@ -110,10 +106,9 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mPhysicsObjects.push_back(mBox1); // ---------- Box 2 ---------- // - openglframework::Vector3 position6(0, 8, 0); // Create a cylinder and a corresponding collision body in the dynamics world - mBox2 = new Box(openglframework::Vector3(3, 2, 5), position6, mCollisionWorld, mMeshFolderPath); + mBox2 = new Box(openglframework::Vector3(3, 2, 5), mPhysicsWorld, mMeshFolderPath); mAllShapes.push_back(mBox2); // Set the color @@ -122,10 +117,9 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mPhysicsObjects.push_back(mBox2); // ---------- Convex Mesh ---------- // - openglframework::Vector3 position7(-5, 0, 0); // Create a convex mesh and a corresponding collision body in the dynamics world - mConvexMesh = new ConvexMesh(position7, mCollisionWorld, mMeshFolderPath + "convexmesh.obj"); + mConvexMesh = new ConvexMesh(mPhysicsWorld, mMeshFolderPath + "convexmesh.obj"); mAllShapes.push_back(mConvexMesh); // Set the color @@ -134,10 +128,9 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mPhysicsObjects.push_back(mConvexMesh); // ---------- Concave Mesh ---------- // - openglframework::Vector3 position8(0, 100, 0); // Create a convex mesh and a corresponding collision body in the dynamics world - mConcaveMesh = new ConcaveMesh(position8, mCollisionWorld, mMeshFolderPath + "city.obj"); + mConcaveMesh = new ConcaveMesh(mPhysicsWorld, mMeshFolderPath + "city.obj"); mAllShapes.push_back(mConcaveMesh); // Set the color @@ -146,10 +139,9 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) mPhysicsObjects.push_back(mConcaveMesh); // ---------- Heightfield ---------- // - openglframework::Vector3 position9(0, -12, 0); // Create a convex mesh and a corresponding collision body in the dynamics world - mHeightField = new HeightField(position9, mCollisionWorld); + mHeightField = new HeightField(mPhysicsWorld); // Set the color mHeightField->setColor(mGreyColorDemo); @@ -162,76 +154,59 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name) // Reset the scene void CollisionDetectionScene::reset() { + mSphere1->setTransform(rp3d::Transform(rp3d::Vector3(12, 0, 0), rp3d::Quaternion::identity())); + mSphere2->setTransform(rp3d::Transform(rp3d::Vector3(12, 8, 0), rp3d::Quaternion::identity())); + mCapsule1->setTransform(rp3d::Transform(rp3d::Vector3(-6, 7, 0), rp3d::Quaternion::identity())); + mCapsule2->setTransform(rp3d::Transform(rp3d::Vector3(11, -8, 0), rp3d::Quaternion::identity())); + mBox1->setTransform(rp3d::Transform(rp3d::Vector3(-4, -7, 0), rp3d::Quaternion::identity())); + mBox2->setTransform(rp3d::Transform(rp3d::Vector3(0, 8, 0), rp3d::Quaternion::identity())); + mConvexMesh->setTransform(rp3d::Transform(rp3d::Vector3(-5, 0, 0), rp3d::Quaternion::identity())); + mConcaveMesh->setTransform(rp3d::Transform(rp3d::Vector3(0, 100, 0), rp3d::Quaternion::identity())); + mHeightField->setTransform(rp3d::Transform(rp3d::Vector3(0, -12, 0), rp3d::Quaternion::identity())); } // Destructor CollisionDetectionScene::~CollisionDetectionScene() { // Destroy the box rigid body from the dynamics world - //mCollisionWorld->destroyCollisionBody(mBox->getCollisionBody()); + //mPhysicsWorld->destroyCollisionBody(mBox->getCollisionBody()); //delete mBox; // Destroy the spheres - mCollisionWorld->destroyCollisionBody(mSphere1->getCollisionBody()); + mPhysicsWorld->destroyCollisionBody(mSphere1->getCollisionBody()); delete mSphere1; - mCollisionWorld->destroyCollisionBody(mSphere2->getCollisionBody()); + mPhysicsWorld->destroyCollisionBody(mSphere2->getCollisionBody()); delete mSphere2; - mCollisionWorld->destroyCollisionBody(mCapsule1->getCollisionBody()); + mPhysicsWorld->destroyCollisionBody(mCapsule1->getCollisionBody()); delete mCapsule1; - mCollisionWorld->destroyCollisionBody(mCapsule2->getCollisionBody()); + mPhysicsWorld->destroyCollisionBody(mCapsule2->getCollisionBody()); delete mCapsule2; - mCollisionWorld->destroyCollisionBody(mBox1->getCollisionBody()); + mPhysicsWorld->destroyCollisionBody(mBox1->getCollisionBody()); delete mBox1; - mCollisionWorld->destroyCollisionBody(mBox2->getCollisionBody()); + mPhysicsWorld->destroyCollisionBody(mBox2->getCollisionBody()); delete mBox2; - mCollisionWorld->destroyCollisionBody(mConvexMesh->getCollisionBody()); + mPhysicsWorld->destroyCollisionBody(mConvexMesh->getCollisionBody()); delete mConvexMesh; - mCollisionWorld->destroyCollisionBody(mConcaveMesh->getCollisionBody()); + mPhysicsWorld->destroyCollisionBody(mConcaveMesh->getCollisionBody()); delete mConcaveMesh; - mCollisionWorld->destroyCollisionBody(mHeightField->getCollisionBody()); + mPhysicsWorld->destroyCollisionBody(mHeightField->getCollisionBody()); delete mHeightField; - /* - // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mCone->getCollisionBody()); - delete mCone; - - // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mCylinder->getCollisionBody()); - - // Destroy the sphere - delete mCylinder; - - // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mCapsule->getCollisionBody()); - - // Destroy the sphere - delete mCapsule; - - // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mDumbbell->getCollisionBody()); - - // Destroy the dumbbell - delete mDumbbell; - - - */ - mContactManager.resetPoints(); // Destroy the static data for the visual contact points VisualContactPoint::destroyStaticData(); // Destroy the collision world - delete mCollisionWorld; + delete mPhysicsWorld; } // Take a step for the simulation @@ -239,14 +214,14 @@ void CollisionDetectionScene::update() { mContactManager.resetPoints(); - mCollisionWorld->testCollision(&mContactManager); + mPhysicsWorld->testCollision(&mContactManager); SceneDemo::update(); } void CollisionDetectionScene::selectNextShape() { - int previousIndex = mSelectedShapeIndex; + uint previousIndex = mSelectedShapeIndex; mSelectedShapeIndex++; if (mSelectedShapeIndex >= mAllShapes.size()) { mSelectedShapeIndex = 0; diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.h b/testbed/scenes/collisiondetection/CollisionDetectionScene.h index 8473ae73..4bea0c0b 100755 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.h +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.h @@ -152,10 +152,7 @@ class CollisionDetectionScene : public SceneDemo { std::vector mAllShapes; - int mSelectedShapeIndex; - - /// Collision world used for the physics simulation - rp3d::CollisionWorld* mCollisionWorld; + uint mSelectedShapeIndex; /// Select the next shape void selectNextShape(); @@ -165,7 +162,7 @@ class CollisionDetectionScene : public SceneDemo { // -------------------- Methods -------------------- // /// Constructor - CollisionDetectionScene(const std::string& name); + CollisionDetectionScene(const std::string& name, EngineSettings& settings); /// Destructor virtual ~CollisionDetectionScene() override; diff --git a/testbed/scenes/collisionshapes/CollisionShapesScene.cpp b/testbed/scenes/collisionshapes/CollisionShapesScene.cpp index e63f39d4..a6fd6662 100644 --- a/testbed/scenes/collisionshapes/CollisionShapesScene.cpp +++ b/testbed/scenes/collisionshapes/CollisionShapesScene.cpp @@ -31,8 +31,8 @@ using namespace openglframework; using namespace collisionshapesscene; // Constructor -CollisionShapesScene::CollisionShapesScene(const std::string& name) - : SceneDemo(name, SCENE_RADIUS) { +CollisionShapesScene::CollisionShapesScene(const std::string& name, EngineSettings& settings) + : SceneDemo(name, settings, SCENE_RADIUS) { std::string meshFolderPath("meshes/"); @@ -43,23 +43,15 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name) setScenePosition(center, SCENE_RADIUS); // Gravity vector in the dynamics world - rp3d::Vector3 gravity(0, -9.81, 0); + rp3d::Vector3 gravity(0, -9.81f, 0); // Create the dynamics world for the physics simulation - mDynamicsWorld = new rp3d::DynamicsWorld(gravity); - - float radius = 3.0f; + mPhysicsWorld = new rp3d::DynamicsWorld(gravity); for (int i=0; isetColor(mDemoColors[i % mNbDemoColors]); @@ -77,14 +69,8 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name) // Create all the boxes of the scene for (int i=0; isetColor(mDemoColors[i % mNbDemoColors]); @@ -102,18 +88,11 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name) // Create all the spheres of the scene for (int i=0; igetRigidBody()->getMaterial().setRollingResistance(0.08); + sphere->getRigidBody()->getMaterial().setRollingResistance(rp3d::decimal(0.08)); // Set the box color sphere->setColor(mDemoColors[i % mNbDemoColors]); @@ -131,17 +110,11 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name) // Create all the capsules of the scene for (int i=0; igetRigidBody()->getMaterial().setRollingResistance(0.08); + capsule->getRigidBody()->getMaterial().setRollingResistance(rp3d::decimal(0.08f)); // Set the box color capsule->setColor(mDemoColors[i % mNbDemoColors]); @@ -159,14 +132,8 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name) // Create all the convex meshes of the scene for (int i=0; isetColor(mDemoColors[i % mNbDemoColors]); @@ -183,8 +150,7 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name) // ---------- Create the floor --------- - openglframework::Vector3 floorPosition(0, 0, 0); - mFloor = new Box(FLOOR_SIZE, floorPosition, FLOOR_MASS, mDynamicsWorld, mMeshFolderPath); + mFloor = new Box(FLOOR_SIZE, FLOOR_MASS, getDynamicsWorld(), mMeshFolderPath); mPhysicsObjects.push_back(mFloor); // Set the box color @@ -198,39 +164,16 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name) rp3d::Material& material = mFloor->getRigidBody()->getMaterial(); material.setBounciness(rp3d::decimal(0.2)); - // ---------- Create the triangular mesh ---------- // - - /* - // Position - openglframework::Vector3 position(0, 0, 0); - rp3d::decimal mass = 1.0; - - // Create a convex mesh and a corresponding rigid in the dynamics world - mConcaveMesh = new ConcaveMesh(position, mass, mDynamicsWorld, meshFolderPath); - - // Set the mesh as beeing static - mConcaveMesh->getRigidBody()->setType(rp3d::STATIC); - - // Set the box color - mConcaveMesh->setColor(mDemoColors[0]); - mConcaveMesh->setSleepingColor(mRedColorDemo); - - // Change the material properties of the rigid body - rp3d::Material& material = mConcaveMesh->getRigidBody()->getMaterial(); - material.setBounciness(rp3d::decimal(0.2)); - material.setFrictionCoefficient(0.1); - */ - // Get the physics engine parameters - mEngineSettings.isGravityEnabled = mDynamicsWorld->isGravityEnabled(); - rp3d::Vector3 gravityVector = mDynamicsWorld->getGravity(); + mEngineSettings.isGravityEnabled = getDynamicsWorld()->isGravityEnabled(); + rp3d::Vector3 gravityVector = getDynamicsWorld()->getGravity(); mEngineSettings.gravity = openglframework::Vector3(gravityVector.x, gravityVector.y, gravityVector.z); - mEngineSettings.isSleepingEnabled = mDynamicsWorld->isSleepingEnabled(); - mEngineSettings.sleepLinearVelocity = mDynamicsWorld->getSleepLinearVelocity(); - mEngineSettings.sleepAngularVelocity = mDynamicsWorld->getSleepAngularVelocity(); - mEngineSettings.nbPositionSolverIterations = mDynamicsWorld->getNbIterationsPositionSolver(); - mEngineSettings.nbVelocitySolverIterations = mDynamicsWorld->getNbIterationsVelocitySolver(); - mEngineSettings.timeBeforeSleep = mDynamicsWorld->getTimeBeforeSleep(); + mEngineSettings.isSleepingEnabled = getDynamicsWorld()->isSleepingEnabled(); + mEngineSettings.sleepLinearVelocity = getDynamicsWorld()->getSleepLinearVelocity(); + mEngineSettings.sleepAngularVelocity = getDynamicsWorld()->getSleepAngularVelocity(); + mEngineSettings.nbPositionSolverIterations = getDynamicsWorld()->getNbIterationsPositionSolver(); + mEngineSettings.nbVelocitySolverIterations = getDynamicsWorld()->getNbIterationsVelocitySolver(); + mEngineSettings.timeBeforeSleep = getDynamicsWorld()->getTimeBeforeSleep(); } // Destructor @@ -240,126 +183,81 @@ CollisionShapesScene::~CollisionShapesScene() { for (std::vector::iterator it = mPhysicsObjects.begin(); it != mPhysicsObjects.end(); ++it) { // Destroy the corresponding rigid body from the dynamics world - mDynamicsWorld->destroyRigidBody((*it)->getRigidBody()); + getDynamicsWorld()->destroyRigidBody((*it)->getRigidBody()); // Destroy the object delete (*it); } // Destroy the dynamics world - delete mDynamicsWorld; -} - -// Update the physics world (take a simulation step) -void CollisionShapesScene::updatePhysics() { - - // Update the physics engine parameters - mDynamicsWorld->setIsGratityEnabled(mEngineSettings.isGravityEnabled); - rp3d::Vector3 gravity(mEngineSettings.gravity.x, mEngineSettings.gravity.y, - mEngineSettings.gravity.z); - mDynamicsWorld->setGravity(gravity); - mDynamicsWorld->enableSleeping(mEngineSettings.isSleepingEnabled); - mDynamicsWorld->setSleepLinearVelocity(mEngineSettings.sleepLinearVelocity); - mDynamicsWorld->setSleepAngularVelocity(mEngineSettings.sleepAngularVelocity); - mDynamicsWorld->setNbIterationsPositionSolver(mEngineSettings.nbPositionSolverIterations); - mDynamicsWorld->setNbIterationsVelocitySolver(mEngineSettings.nbVelocitySolverIterations); - mDynamicsWorld->setTimeBeforeSleep(mEngineSettings.timeBeforeSleep); - - // Take a simulation step - mDynamicsWorld->update(mEngineSettings.timeStep); + delete mPhysicsWorld; } /// Reset the scene void CollisionShapesScene::reset() { - float radius = 3.0f; + const float radius = 3.0f; - for (int i=0; isetTransform(transform); + mDumbbells[i]->setTransform(rp3d::Transform(position, rp3d::Quaternion::identity())); } // Create all the boxes of the scene - for (int i=0; isetTransform(transform); + mBoxes[i]->setTransform(rp3d::Transform(position, rp3d::Quaternion::identity())); } // Create all the spheres of the scene - for (int i=0; isetTransform(transform); + mSpheres[i]->setTransform(rp3d::Transform(position, rp3d::Quaternion::identity())); } // Create all the capsules of the scene - for (int i=0; isetTransform(transform); + mCapsules[i]->setTransform(rp3d::Transform(position, rp3d::Quaternion::identity())); } // Create all the convex meshes of the scene - for (int i=0; isetTransform(transform); + mConvexMeshes[i]->setTransform(rp3d::Transform(position, rp3d::Quaternion::identity())); } + + // ---------- Create the triangular mesh ---------- // + + mFloor->setTransform(rp3d::Transform::identity()); } diff --git a/testbed/scenes/collisionshapes/CollisionShapesScene.h b/testbed/scenes/collisionshapes/CollisionShapesScene.h index 70e28755..b22d8429 100644 --- a/testbed/scenes/collisionshapes/CollisionShapesScene.h +++ b/testbed/scenes/collisionshapes/CollisionShapesScene.h @@ -45,7 +45,7 @@ const float SCENE_RADIUS = 30.0f; const int NB_BOXES = 5; const int NB_SPHERES = 5; const int NB_CAPSULES = 5; -const int NB_MESHES = 3; +const int NB_MESHES = 4; const int NB_COMPOUND_SHAPES = 3; const openglframework::Vector3 BOX_SIZE(2, 2, 2); const float SPHERE_RADIUS = 1.5f; @@ -87,23 +87,16 @@ class CollisionShapesScene : public SceneDemo { /// Box for the floor Box* mFloor; - /// Dynamics world used for the physics simulation - rp3d::DynamicsWorld* mDynamicsWorld; - public: // -------------------- Methods -------------------- // /// Constructor - CollisionShapesScene(const std::string& name); + CollisionShapesScene(const std::string& name, EngineSettings& settings); /// Destructor virtual ~CollisionShapesScene() override; - /// Update the physics world (take a simulation step) - /// Can be called several times per frame - virtual void updatePhysics() override; - /// Reset the scene virtual void reset() override; @@ -113,7 +106,7 @@ class CollisionShapesScene : public SceneDemo { // Return all the contact points of the scene inline std::vector CollisionShapesScene::getContactPoints() const { - return computeContactPointsOfWorld(mDynamicsWorld); + return computeContactPointsOfWorld(getDynamicsWorld()); } } diff --git a/testbed/scenes/concavemesh/ConcaveMeshScene.cpp b/testbed/scenes/concavemesh/ConcaveMeshScene.cpp index 11474819..d70a02af 100644 --- a/testbed/scenes/concavemesh/ConcaveMeshScene.cpp +++ b/testbed/scenes/concavemesh/ConcaveMeshScene.cpp @@ -31,8 +31,8 @@ using namespace openglframework; using namespace trianglemeshscene; // Constructor -ConcaveMeshScene::ConcaveMeshScene(const std::string& name) - : SceneDemo(name, SCENE_RADIUS) { +ConcaveMeshScene::ConcaveMeshScene(const std::string& name, EngineSettings& settings) + : SceneDemo(name, settings, SCENE_RADIUS) { std::string meshFolderPath("meshes/"); @@ -46,38 +46,115 @@ ConcaveMeshScene::ConcaveMeshScene(const std::string& name) rp3d::Vector3 gravity(0, rp3d::decimal(-9.81), 0); // Create the dynamics world for the physics simulation - mDynamicsWorld = new rp3d::DynamicsWorld(gravity); + mPhysicsWorld = new rp3d::DynamicsWorld(gravity); - // ---------- Create the boxes ----------- // + for (int i = 0; isetColor(mDemoColors[i % mNbDemoColors]); + dumbbell->setSleepingColor(mRedColorDemo); - // Position - openglframework::Vector3 boxPosition(-NB_BOXES_X * BOX_SIZE * BOXES_SPACE / 2 + i * BOX_SIZE * BOXES_SPACE, 30, -NB_BOXES_Z * BOX_SIZE * BOXES_SPACE / 2 + j * BOX_SIZE * BOXES_SPACE); + // Change the material properties of the rigid body + rp3d::Material& material = dumbbell->getRigidBody()->getMaterial(); + material.setBounciness(rp3d::decimal(0.2)); - // Create a sphere and a corresponding rigid in the dynamics world - mBoxes[i * NB_BOXES_Z + j] = new Box(Vector3(BOX_SIZE, BOX_SIZE, BOX_SIZE) * 0.5f, boxPosition, 80.1, mDynamicsWorld, mMeshFolderPath); + // Add the mesh the list of dumbbells in the scene + mDumbbells.push_back(dumbbell); + mPhysicsObjects.push_back(dumbbell); + } - // Set the sphere color - mBoxes[i * NB_BOXES_Z + j]->setColor(mDemoColors[0]); - mBoxes[i * NB_BOXES_Z + j]->setSleepingColor(mRedColorDemo); + // Create all the boxes of the scene + for (int i = 0; igetRigidBody()->getMaterial(); - boxMaterial.setBounciness(rp3d::decimal(0.2)); - } + // Create a sphere and a corresponding rigid in the dynamics world + Box* box = new Box(BOX_SIZE, BOX_MASS, getDynamicsWorld(), mMeshFolderPath); + + // Set the box color + box->setColor(mDemoColors[i % mNbDemoColors]); + box->setSleepingColor(mRedColorDemo); + + // Change the material properties of the rigid body + rp3d::Material& material = box->getRigidBody()->getMaterial(); + material.setBounciness(rp3d::decimal(0.2)); + + // Add the sphere the list of sphere in the scene + mBoxes.push_back(box); + mPhysicsObjects.push_back(box); + } + + // Create all the spheres of the scene + for (int i = 0; igetRigidBody()->getMaterial().setRollingResistance(rp3d::decimal(0.08)); + + // Set the box color + sphere->setColor(mDemoColors[i % mNbDemoColors]); + sphere->setSleepingColor(mRedColorDemo); + + // Change the material properties of the rigid body + rp3d::Material& material = sphere->getRigidBody()->getMaterial(); + material.setBounciness(rp3d::decimal(0.2)); + + // Add the sphere the list of sphere in the scene + mSpheres.push_back(sphere); + mPhysicsObjects.push_back(sphere); + } + + // Create all the capsules of the scene + for (int i = 0; igetRigidBody()->getMaterial().setRollingResistance(rp3d::decimal(0.08)); + + // Set the box color + capsule->setColor(mDemoColors[i % mNbDemoColors]); + capsule->setSleepingColor(mRedColorDemo); + + // Change the material properties of the rigid body + rp3d::Material& material = capsule->getRigidBody()->getMaterial(); + material.setBounciness(rp3d::decimal(0.2)); + + // Add the cylinder the list of sphere in the scene + mCapsules.push_back(capsule); + mPhysicsObjects.push_back(capsule); + } + + // Create all the convex meshes of the scene + for (int i = 0; isetColor(mDemoColors[i % mNbDemoColors]); + mesh->setSleepingColor(mRedColorDemo); + + // Change the material properties of the rigid body + rp3d::Material& material = mesh->getRigidBody()->getMaterial(); + material.setBounciness(rp3d::decimal(0.2)); + + // Add the mesh the list of sphere in the scene + mConvexMeshes.push_back(mesh); + mPhysicsObjects.push_back(mesh); } // ---------- Create the triangular mesh ---------- // // Position - openglframework::Vector3 position(0, 0, 0); rp3d::decimal mass = 1.0; // Create a convex mesh and a corresponding rigid in the dynamics world - mConcaveMesh = new ConcaveMesh(position, mass, mDynamicsWorld, meshFolderPath + "city.obj"); + mConcaveMesh = new ConcaveMesh(mass, getDynamicsWorld(), meshFolderPath + "city.obj"); // Set the mesh as beeing static mConcaveMesh->getRigidBody()->setType(rp3d::BodyType::STATIC); @@ -86,106 +163,107 @@ ConcaveMeshScene::ConcaveMeshScene(const std::string& name) mConcaveMesh->setColor(mGreyColorDemo); mConcaveMesh->setSleepingColor(mGreyColorDemo); + mPhysicsObjects.push_back(mConcaveMesh); + // Change the material properties of the rigid body rp3d::Material& material = mConcaveMesh->getRigidBody()->getMaterial(); material.setBounciness(rp3d::decimal(0.2)); - material.setFrictionCoefficient(0.1); + material.setFrictionCoefficient(rp3d::decimal(0.1)); // Get the physics engine parameters - mEngineSettings.isGravityEnabled = mDynamicsWorld->isGravityEnabled(); - rp3d::Vector3 gravityVector = mDynamicsWorld->getGravity(); + mEngineSettings.isGravityEnabled = getDynamicsWorld()->isGravityEnabled(); + rp3d::Vector3 gravityVector = getDynamicsWorld()->getGravity(); mEngineSettings.gravity = openglframework::Vector3(gravityVector.x, gravityVector.y, gravityVector.z); - mEngineSettings.isSleepingEnabled = mDynamicsWorld->isSleepingEnabled(); - mEngineSettings.sleepLinearVelocity = mDynamicsWorld->getSleepLinearVelocity(); - mEngineSettings.sleepAngularVelocity = mDynamicsWorld->getSleepAngularVelocity(); - mEngineSettings.nbPositionSolverIterations = mDynamicsWorld->getNbIterationsPositionSolver(); - mEngineSettings.nbVelocitySolverIterations = mDynamicsWorld->getNbIterationsVelocitySolver(); - mEngineSettings.timeBeforeSleep = mDynamicsWorld->getTimeBeforeSleep(); + mEngineSettings.isSleepingEnabled = getDynamicsWorld()->isSleepingEnabled(); + mEngineSettings.sleepLinearVelocity = getDynamicsWorld()->getSleepLinearVelocity(); + mEngineSettings.sleepAngularVelocity = getDynamicsWorld()->getSleepAngularVelocity(); + mEngineSettings.nbPositionSolverIterations = getDynamicsWorld()->getNbIterationsPositionSolver(); + mEngineSettings.nbVelocitySolverIterations = getDynamicsWorld()->getNbIterationsVelocitySolver(); + mEngineSettings.timeBeforeSleep = getDynamicsWorld()->getTimeBeforeSleep(); } // Destructor ConcaveMeshScene::~ConcaveMeshScene() { - // Destroy the corresponding rigid body from the dynamics world - mDynamicsWorld->destroyRigidBody(mConcaveMesh->getRigidBody()); + // Destroy all the physics objects of the scene + for (std::vector::iterator it = mPhysicsObjects.begin(); it != mPhysicsObjects.end(); ++it) { - // Destroy the boxes - for (int i=0; idestroyRigidBody(mBoxes[i]->getRigidBody()); - delete mBoxes[i]; + // Destroy the corresponding rigid body from the dynamics world + getDynamicsWorld()->destroyRigidBody((*it)->getRigidBody()); + + // Destroy the object + delete (*it); } - // Destroy the convex mesh - delete mConcaveMesh; - // Destroy the dynamics world - delete mDynamicsWorld; -} - -// Update the physics world (take a simulation step) -void ConcaveMeshScene::updatePhysics() { - - // Update the physics engine parameters - mDynamicsWorld->setIsGratityEnabled(mEngineSettings.isGravityEnabled); - rp3d::Vector3 gravity(mEngineSettings.gravity.x, mEngineSettings.gravity.y, - mEngineSettings.gravity.z); - mDynamicsWorld->setGravity(gravity); - mDynamicsWorld->enableSleeping(mEngineSettings.isSleepingEnabled); - mDynamicsWorld->setSleepLinearVelocity(mEngineSettings.sleepLinearVelocity); - mDynamicsWorld->setSleepAngularVelocity(mEngineSettings.sleepAngularVelocity); - mDynamicsWorld->setNbIterationsPositionSolver(mEngineSettings.nbPositionSolverIterations); - mDynamicsWorld->setNbIterationsVelocitySolver(mEngineSettings.nbVelocitySolverIterations); - mDynamicsWorld->setTimeBeforeSleep(mEngineSettings.timeBeforeSleep); - - // Take a simulation step - mDynamicsWorld->update(mEngineSettings.timeStep); -} - -// Update the scene -void ConcaveMeshScene::update() { - - SceneDemo::update(); - - // Update the transform used for the rendering - mConcaveMesh->updateTransform(mInterpolationFactor); - - for (int i=0; iupdateTransform(mInterpolationFactor); - } -} - -// Render the scene in a single pass -void ConcaveMeshScene::renderSinglePass(Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) { - - // Bind the shader - shader.bind(); - - mConcaveMesh->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - - for (int i=0; irender(shader, worldToCameraMatrix, mIsWireframeEnabled); - } - - // Unbind the shader - shader.unbind(); + delete getDynamicsWorld(); } // Reset the scene void ConcaveMeshScene::reset() { - // Reset the transform - rp3d::Transform transform(rp3d::Vector3::zero(), rp3d::Quaternion::identity()); - mConcaveMesh->setTransform(transform); + const float radius = 15.0f; - for (int i=0; isetTransform(boxTransform); - } + mDumbbells[i]->setTransform(rp3d::Transform(position, rp3d::Quaternion::identity())); } + // Create all the boxes of the scene + for (uint i = 0; isetTransform(rp3d::Transform(position, rp3d::Quaternion::identity())); + } + + // Create all the spheres of the scene + for (uint i = 0; isetTransform(rp3d::Transform(position, rp3d::Quaternion::identity())); + } + + // Create all the capsules of the scene + for (uint i = 0; isetTransform(rp3d::Transform(position, rp3d::Quaternion::identity())); + } + + // Create all the convex meshes of the scene + for (uint i = 0; isetTransform(rp3d::Transform(position, rp3d::Quaternion::identity())); + } + + // ---------- Create the triangular mesh ---------- // + + mConcaveMesh->setTransform(rp3d::Transform::identity()); } diff --git a/testbed/scenes/concavemesh/ConcaveMeshScene.h b/testbed/scenes/concavemesh/ConcaveMeshScene.h index 5943fe6c..a8d566a1 100644 --- a/testbed/scenes/concavemesh/ConcaveMeshScene.h +++ b/testbed/scenes/concavemesh/ConcaveMeshScene.h @@ -33,15 +33,34 @@ #include "SceneDemo.h" #include "ConcaveMesh.h" #include "Box.h" +#include "Capsule.h" +#include "Dumbbell.h" +#include "Sphere.h" +#include "ConvexMesh.h" namespace trianglemeshscene { // Constants const float SCENE_RADIUS = 70.0f; // Radius of the scene in meters -const int NB_BOXES_X = 8; -const int NB_BOXES_Z = 8; -const float BOX_SIZE = 3.0f; -const float BOXES_SPACE = 2.0f; +static const int NB_BOXES = 10; +static const int NB_SPHERES = 5; +static const int NB_CAPSULES = 5; +static const int NB_MESHES = 3; +static const int NB_COMPOUND_SHAPES = 3; +const openglframework::Vector3 BOX_SIZE(2, 2, 2); +const float SPHERE_RADIUS = 1.5f; +const float CONE_RADIUS = 2.0f; +const float CONE_HEIGHT = 3.0f; +const float CYLINDER_RADIUS = 1.0f; +const float CYLINDER_HEIGHT = 5.0f; +const float CAPSULE_RADIUS = 1.0f; +const float CAPSULE_HEIGHT = 1.0f; +const float DUMBBELL_HEIGHT = 1.0f; +const float BOX_MASS = 1.0f; +const float CONE_MASS = 1.0f; +const float CYLINDER_MASS = 1.0f; +const float CAPSULE_MASS = 1.0f; +const float MESH_MASS = 1.0f; // Class TriangleMeshScene class ConcaveMeshScene : public SceneDemo { @@ -50,35 +69,31 @@ class ConcaveMeshScene : public SceneDemo { // -------------------- Attributes -------------------- // - Box* mBoxes[NB_BOXES_X * NB_BOXES_Z]; + std::vector mBoxes; + + std::vector mSpheres; + + std::vector mCapsules; + + /// All the convex meshes of the scene + std::vector mConvexMeshes; + + /// All the dumbbell of the scene + std::vector mDumbbells; /// Concave triangles mesh ConcaveMesh* mConcaveMesh; - /// Dynamics world used for the physics simulation - rp3d::DynamicsWorld* mDynamicsWorld; - public: // -------------------- Methods -------------------- // /// Constructor - ConcaveMeshScene(const std::string& name); + ConcaveMeshScene(const std::string& name, EngineSettings& settings); /// Destructor virtual ~ConcaveMeshScene() override; - /// Update the physics world (take a simulation step) - /// Can be called several times per frame - virtual void updatePhysics() override; - - /// Update the scene (take a simulation step) - virtual void update() override; - - /// Render the scene in a single pass - virtual void renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix) override; - /// Reset the scene virtual void reset() override; @@ -88,7 +103,7 @@ class ConcaveMeshScene : public SceneDemo { // Return all the contact points of the scene inline std::vector ConcaveMeshScene::getContactPoints() const { - return computeContactPointsOfWorld(mDynamicsWorld); + return computeContactPointsOfWorld(getDynamicsWorld()); } } diff --git a/testbed/scenes/cubes/CubesScene.cpp b/testbed/scenes/cubes/CubesScene.cpp index 3ddb1d61..fa7f4ba5 100755 --- a/testbed/scenes/cubes/CubesScene.cpp +++ b/testbed/scenes/cubes/CubesScene.cpp @@ -31,8 +31,8 @@ using namespace openglframework; using namespace cubesscene; // Constructor -CubesScene::CubesScene(const std::string& name) - : SceneDemo(name, SCENE_RADIUS) { +CubesScene::CubesScene(const std::string& name, EngineSettings& settings) + : SceneDemo(name, settings, SCENE_RADIUS) { // Compute the radius and the center of the scene openglframework::Vector3 center(0, 5, 0); @@ -44,39 +44,31 @@ CubesScene::CubesScene(const std::string& name) rp3d::Vector3 gravity(0, rp3d::decimal(-9.81), 0); // Create the dynamics world for the physics simulation - mDynamicsWorld = new rp3d::DynamicsWorld(gravity); + mPhysicsWorld = new rp3d::DynamicsWorld(gravity); - float radius = 2.0f; + // Create all the cubes of the scene + for (int i=0; isetColor(mDemoColors[i % mNbDemoColors]); + cube->setSleepingColor(mRedColorDemo); - // // Create a cube and a corresponding rigid in the dynamics world - // Box* cube = new Box(BOX_SIZE, position , BOX_MASS, mDynamicsWorld); + // Change the material properties of the rigid body + rp3d::Material& material = cube->getRigidBody()->getMaterial(); + material.setBounciness(rp3d::decimal(0.4)); - // // Set the box color - // cube->setColor(mDemoColors[i % mNbDemoColors]); - // cube->setSleepingColor(mRedColorDemo); - - // // Change the material properties of the rigid body - // rp3d::Material& material = cube->getRigidBody()->getMaterial(); - // material.setBounciness(rp3d::decimal(0.4)); - - // // Add the box the list of box in the scene - // mBoxes.push_back(cube); - //} + // Add the box the list of box in the scene + mBoxes.push_back(cube); + mPhysicsObjects.push_back(cube); + } // ------------------------- FLOOR ----------------------- // // Create the floor - openglframework::Vector3 floorPosition(0, 0, 0); - mFloor = new Box(FLOOR_SIZE, floorPosition, FLOOR_MASS, mDynamicsWorld, mMeshFolderPath); + mFloor = new Box(FLOOR_SIZE, FLOOR_MASS, getDynamicsWorld(), mMeshFolderPath); mFloor->setColor(mGreyColorDemo); mFloor->setSleepingColor(mGreyColorDemo); @@ -84,37 +76,16 @@ CubesScene::CubesScene(const std::string& name) mFloor->getRigidBody()->setType(rp3d::BodyType::STATIC); mPhysicsObjects.push_back(mFloor); - // Change the material properties of the floor rigid body - //rp3d::Material& material = mFloor->getRigidBody()->getMaterial(); - //material.setBounciness(rp3d::decimal(0.3)); - - // ------------------------- BOX ----------------------- // - - // Create a cube and a corresponding rigid in the dynamics world - Box* cube = new Box(BOX_SIZE, Vector3(0, 10, 0), BOX_MASS, mDynamicsWorld, mMeshFolderPath); - - // Set the box color - cube->setColor(mDemoColors[0]); - cube->setSleepingColor(mRedColorDemo); - - // Change the material properties of the rigid body - //rp3d::Material& material = cube->getRigidBody()->getMaterial(); - //material.setBounciness(rp3d::decimal(0.4)); - - // Add the box the list of box in the scene - mBoxes.push_back(cube); - mPhysicsObjects.push_back(cube); - // Get the physics engine parameters - mEngineSettings.isGravityEnabled = mDynamicsWorld->isGravityEnabled(); - rp3d::Vector3 gravityVector = mDynamicsWorld->getGravity(); + mEngineSettings.isGravityEnabled = getDynamicsWorld()->isGravityEnabled(); + rp3d::Vector3 gravityVector = getDynamicsWorld()->getGravity(); mEngineSettings.gravity = openglframework::Vector3(gravityVector.x, gravityVector.y, gravityVector.z); - mEngineSettings.isSleepingEnabled = mDynamicsWorld->isSleepingEnabled(); - mEngineSettings.sleepLinearVelocity = mDynamicsWorld->getSleepLinearVelocity(); - mEngineSettings.sleepAngularVelocity = mDynamicsWorld->getSleepAngularVelocity(); - mEngineSettings.nbPositionSolverIterations = mDynamicsWorld->getNbIterationsPositionSolver(); - mEngineSettings.nbVelocitySolverIterations = mDynamicsWorld->getNbIterationsVelocitySolver(); - mEngineSettings.timeBeforeSleep = mDynamicsWorld->getTimeBeforeSleep(); + mEngineSettings.isSleepingEnabled = getDynamicsWorld()->isSleepingEnabled(); + mEngineSettings.sleepLinearVelocity = getDynamicsWorld()->getSleepLinearVelocity(); + mEngineSettings.sleepAngularVelocity = getDynamicsWorld()->getSleepAngularVelocity(); + mEngineSettings.nbPositionSolverIterations = getDynamicsWorld()->getNbIterationsPositionSolver(); + mEngineSettings.nbVelocitySolverIterations = getDynamicsWorld()->getNbIterationsVelocitySolver(); + mEngineSettings.timeBeforeSleep = getDynamicsWorld()->getTimeBeforeSleep(); } // Destructor @@ -124,39 +95,20 @@ CubesScene::~CubesScene() { for (std::vector::iterator it = mBoxes.begin(); it != mBoxes.end(); ++it) { // Destroy the corresponding rigid body from the dynamics world - mDynamicsWorld->destroyRigidBody((*it)->getRigidBody()); + getDynamicsWorld()->destroyRigidBody((*it)->getRigidBody()); // Destroy the cube delete (*it); } // Destroy the rigid body of the floor - mDynamicsWorld->destroyRigidBody(mFloor->getRigidBody()); + getDynamicsWorld()->destroyRigidBody(mFloor->getRigidBody()); // Destroy the floor delete mFloor; // Destroy the dynamics world - delete mDynamicsWorld; -} - -// Update the physics world (take a simulation step) -void CubesScene::updatePhysics() { - - // Update the physics engine parameters - mDynamicsWorld->setIsGratityEnabled(mEngineSettings.isGravityEnabled); - rp3d::Vector3 gravity(mEngineSettings.gravity.x, mEngineSettings.gravity.y, - mEngineSettings.gravity.z); - mDynamicsWorld->setGravity(gravity); - mDynamicsWorld->enableSleeping(mEngineSettings.isSleepingEnabled); - mDynamicsWorld->setSleepLinearVelocity(mEngineSettings.sleepLinearVelocity); - mDynamicsWorld->setSleepAngularVelocity(mEngineSettings.sleepAngularVelocity); - mDynamicsWorld->setNbIterationsPositionSolver(mEngineSettings.nbPositionSolverIterations); - mDynamicsWorld->setNbIterationsVelocitySolver(mEngineSettings.nbVelocitySolverIterations); - mDynamicsWorld->setTimeBeforeSleep(mEngineSettings.timeBeforeSleep); - - // Take a simulation step - mDynamicsWorld->update(mEngineSettings.timeStep); + delete getDynamicsWorld(); } // Reset the scene @@ -164,19 +116,21 @@ void CubesScene::reset() { float radius = 2.0f; -// for (int i=0; i::iterator it; + int i = 0; + for (it = mBoxes.begin(); it != mBoxes.end(); ++it) { -// // Position of the cubes -// float angle = i * 30.0f; -// openglframework::Vector3 position(radius * cos(angle), -// 10 + i * (BOX_SIZE.y + 0.3f), -// 0); + // Position of the cubes + float angle = i * 30.0f; + rp3d::Vector3 position(radius * std::cos(angle), + 10 + i * (BOX_SIZE.y + 0.3f), + 0); -// // Initial position and orientation of the rigid body -// rp3d::Vector3 initPosition(position.x, position.y, position.z); -// rp3d::Quaternion initOrientation = rp3d::Quaternion::identity(); -// rp3d::Transform transform(initPosition, initOrientation); + (*it)->setTransform(rp3d::Transform(position, rp3d::Quaternion::identity())); -// mBoxes[i]->resetTransform(transform); -// } + i++; + } + + mFloor->setTransform(rp3d::Transform(rp3d::Vector3::zero(), rp3d::Quaternion::identity())); } diff --git a/testbed/scenes/cubes/CubesScene.h b/testbed/scenes/cubes/CubesScene.h index aa4b7073..6d553835 100755 --- a/testbed/scenes/cubes/CubesScene.h +++ b/testbed/scenes/cubes/CubesScene.h @@ -38,7 +38,7 @@ namespace cubesscene { const float SCENE_RADIUS = 30.0f; // Radius of the scene in meters const int NB_CUBES = 30; // Number of boxes in the scene const openglframework::Vector3 BOX_SIZE(2, 2, 2); // Box dimensions in meters -const openglframework::Vector3 FLOOR_SIZE(5, 5.0, 5); // Floor dimensions in meters +const openglframework::Vector3 FLOOR_SIZE(50, 1, 50); // Floor dimensions in meters const float BOX_MASS = 1.0f; // Box mass in kilograms const float FLOOR_MASS = 100.0f; // Floor mass in kilograms @@ -55,23 +55,16 @@ class CubesScene : public SceneDemo { /// Box for the floor Box* mFloor; - /// Dynamics world used for the physics simulation - rp3d::DynamicsWorld* mDynamicsWorld; - public: // -------------------- Methods -------------------- // /// Constructor - CubesScene(const std::string& name); + CubesScene(const std::string& name, EngineSettings& settings); /// Destructor virtual ~CubesScene() override; - /// Update the physics world (take a simulation step) - /// Can be called several times per frame - virtual void updatePhysics() override; - /// Reset the scene virtual void reset() override; @@ -81,7 +74,7 @@ class CubesScene : public SceneDemo { // Return all the contact points of the scene inline std::vector CubesScene::getContactPoints() const { - return computeContactPointsOfWorld(mDynamicsWorld); + return computeContactPointsOfWorld(getDynamicsWorld()); } } diff --git a/testbed/scenes/heightfield/HeightFieldScene.cpp b/testbed/scenes/heightfield/HeightFieldScene.cpp index 329712e9..238018dd 100644 --- a/testbed/scenes/heightfield/HeightFieldScene.cpp +++ b/testbed/scenes/heightfield/HeightFieldScene.cpp @@ -31,7 +31,8 @@ using namespace openglframework; using namespace heightfieldscene; // Constructor -HeightFieldScene::HeightFieldScene(const std::string& name) : SceneDemo(name, SCENE_RADIUS) { +HeightFieldScene::HeightFieldScene(const std::string& name, EngineSettings& settings) + : SceneDemo(name, settings, SCENE_RADIUS) { std::string meshFolderPath("meshes/"); @@ -45,20 +46,12 @@ HeightFieldScene::HeightFieldScene(const std::string& name) : SceneDemo(name, SC rp3d::Vector3 gravity(0, rp3d::decimal(-9.81), 0); // Create the dynamics world for the physics simulation - mDynamicsWorld = new rp3d::DynamicsWorld(gravity); - - float radius = 3.0f; + mPhysicsWorld = new rp3d::DynamicsWorld(gravity); for (int i = 0; isetColor(mDemoColors[i % mNbDemoColors]); @@ -76,14 +69,8 @@ HeightFieldScene::HeightFieldScene(const std::string& name) : SceneDemo(name, SC // Create all the boxes of the scene for (int i = 0; isetColor(mDemoColors[i % mNbDemoColors]); @@ -101,18 +88,11 @@ HeightFieldScene::HeightFieldScene(const std::string& name) : SceneDemo(name, SC // Create all the spheres of the scene for (int i = 0; igetRigidBody()->getMaterial().setRollingResistance(0.08); + sphere->getRigidBody()->getMaterial().setRollingResistance(0.08f); // Set the box color sphere->setColor(mDemoColors[i % mNbDemoColors]); @@ -130,17 +110,11 @@ HeightFieldScene::HeightFieldScene(const std::string& name) : SceneDemo(name, SC // Create all the capsules of the scene for (int i = 0; igetRigidBody()->getMaterial().setRollingResistance(0.08); + capsule->getRigidBody()->getMaterial().setRollingResistance(0.08f); // Set the box color capsule->setColor(mDemoColors[i % mNbDemoColors]); @@ -158,14 +132,8 @@ HeightFieldScene::HeightFieldScene(const std::string& name) : SceneDemo(name, SC // Create all the convex meshes of the scene for (int i = 0; isetColor(mDemoColors[i % mNbDemoColors]); @@ -183,11 +151,10 @@ HeightFieldScene::HeightFieldScene(const std::string& name) : SceneDemo(name, SC // ---------- Create the height field ---------- // // Position - openglframework::Vector3 position(0, 0, 0); rp3d::decimal mass = 1.0; // Create a convex mesh and a corresponding rigid in the dynamics world - mHeightField = new HeightField(position, mass, mDynamicsWorld); + mHeightField = new HeightField(mass, getDynamicsWorld()); // Set the mesh as beeing static mHeightField->getRigidBody()->setType(rp3d::BodyType::STATIC); @@ -201,18 +168,18 @@ HeightFieldScene::HeightFieldScene(const std::string& name) : SceneDemo(name, SC // Change the material properties of the rigid body rp3d::Material& material = mHeightField->getRigidBody()->getMaterial(); material.setBounciness(rp3d::decimal(0.2)); - material.setFrictionCoefficient(0.1); + material.setFrictionCoefficient(0.1f); // Get the physics engine parameters - mEngineSettings.isGravityEnabled = mDynamicsWorld->isGravityEnabled(); - rp3d::Vector3 gravityVector = mDynamicsWorld->getGravity(); + mEngineSettings.isGravityEnabled = getDynamicsWorld()->isGravityEnabled(); + rp3d::Vector3 gravityVector = getDynamicsWorld()->getGravity(); mEngineSettings.gravity = openglframework::Vector3(gravityVector.x, gravityVector.y, gravityVector.z); - mEngineSettings.isSleepingEnabled = mDynamicsWorld->isSleepingEnabled(); - mEngineSettings.sleepLinearVelocity = mDynamicsWorld->getSleepLinearVelocity(); - mEngineSettings.sleepAngularVelocity = mDynamicsWorld->getSleepAngularVelocity(); - mEngineSettings.nbPositionSolverIterations = mDynamicsWorld->getNbIterationsPositionSolver(); - mEngineSettings.nbVelocitySolverIterations = mDynamicsWorld->getNbIterationsVelocitySolver(); - mEngineSettings.timeBeforeSleep = mDynamicsWorld->getTimeBeforeSleep(); + mEngineSettings.isSleepingEnabled = getDynamicsWorld()->isSleepingEnabled(); + mEngineSettings.sleepLinearVelocity = getDynamicsWorld()->getSleepLinearVelocity(); + mEngineSettings.sleepAngularVelocity = getDynamicsWorld()->getSleepAngularVelocity(); + mEngineSettings.nbPositionSolverIterations = getDynamicsWorld()->getNbIterationsPositionSolver(); + mEngineSettings.nbVelocitySolverIterations = getDynamicsWorld()->getNbIterationsVelocitySolver(); + mEngineSettings.timeBeforeSleep = getDynamicsWorld()->getTimeBeforeSleep(); } // Destructor @@ -222,47 +189,81 @@ HeightFieldScene::~HeightFieldScene() { for (std::vector::iterator it = mPhysicsObjects.begin(); it != mPhysicsObjects.end(); ++it) { // Destroy the corresponding rigid body from the dynamics world - mDynamicsWorld->destroyRigidBody((*it)->getRigidBody()); + getDynamicsWorld()->destroyRigidBody((*it)->getRigidBody()); // Destroy the object delete (*it); } // Destroy the dynamics world - delete mDynamicsWorld; -} - -// Update the physics world (take a simulation step) -void HeightFieldScene::updatePhysics() { - - // Update the physics engine parameters - mDynamicsWorld->setIsGratityEnabled(mEngineSettings.isGravityEnabled); - rp3d::Vector3 gravity(mEngineSettings.gravity.x, mEngineSettings.gravity.y, - mEngineSettings.gravity.z); - mDynamicsWorld->setGravity(gravity); - mDynamicsWorld->enableSleeping(mEngineSettings.isSleepingEnabled); - mDynamicsWorld->setSleepLinearVelocity(mEngineSettings.sleepLinearVelocity); - mDynamicsWorld->setSleepAngularVelocity(mEngineSettings.sleepAngularVelocity); - mDynamicsWorld->setNbIterationsPositionSolver(mEngineSettings.nbPositionSolverIterations); - mDynamicsWorld->setNbIterationsVelocitySolver(mEngineSettings.nbVelocitySolverIterations); - mDynamicsWorld->setTimeBeforeSleep(mEngineSettings.timeBeforeSleep); - - // Take a simulation step - mDynamicsWorld->update(mEngineSettings.timeStep); + delete getDynamicsWorld(); } // Reset the scene void HeightFieldScene::reset() { - // Reset the transform - rp3d::Transform transform(rp3d::Vector3(0, 0, 0), rp3d::Quaternion::identity()); - mHeightField->setTransform(transform); + const float radius = 3.0f; - float heightFieldWidth = 10.0f; - float stepDist = heightFieldWidth / (NB_BOXES + 1); - for (int i=0; isetTransform(boxTransform); + for (uint i = 0; isetTransform(rp3d::Transform(position, rp3d::Quaternion::identity())); } + + // Create all the boxes of the scene + for (uint i = 0; isetTransform(rp3d::Transform(position, rp3d::Quaternion::identity())); + } + + // Create all the spheres of the scene + for (uint i = 0; isetTransform(rp3d::Transform(position, rp3d::Quaternion::identity())); + } + + // Create all the capsules of the scene + for (uint i = 0; isetTransform(rp3d::Transform(position, rp3d::Quaternion::identity())); + } + + // Create all the convex meshes of the scene + for (uint i = 0; isetTransform(rp3d::Transform(position, rp3d::Quaternion::identity())); + } + + // ---------- Create the triangular mesh ---------- // + + mHeightField->setTransform(rp3d::Transform::identity()); } diff --git a/testbed/scenes/heightfield/HeightFieldScene.h b/testbed/scenes/heightfield/HeightFieldScene.h index 7306ae2c..2a3e68f5 100644 --- a/testbed/scenes/heightfield/HeightFieldScene.h +++ b/testbed/scenes/heightfield/HeightFieldScene.h @@ -44,7 +44,7 @@ const float SCENE_RADIUS = 50.0f; static const int NB_BOXES = 10; static const int NB_SPHERES = 5; static const int NB_CAPSULES = 5; -static const int NB_MESHES = 3; +static const int NB_MESHES = 4; static const int NB_COMPOUND_SHAPES = 3; const openglframework::Vector3 BOX_SIZE(2, 2, 2); const float SPHERE_RADIUS = 1.5f; @@ -86,23 +86,16 @@ class HeightFieldScene : public SceneDemo { /// Height field HeightField* mHeightField; - /// Dynamics world used for the physics simulation - rp3d::DynamicsWorld* mDynamicsWorld; - public: // -------------------- Methods -------------------- // /// Constructor - HeightFieldScene(const std::string& name); + HeightFieldScene(const std::string& name, EngineSettings& settings); /// Destructor virtual ~HeightFieldScene() override; - /// Update the physics world (take a simulation step) - /// Can be called several times per frame - virtual void updatePhysics() override; - /// Reset the scene virtual void reset() override ; @@ -112,7 +105,7 @@ class HeightFieldScene : public SceneDemo { // Return all the contact points of the scene inline std::vector HeightFieldScene::getContactPoints() const { - return computeContactPointsOfWorld(mDynamicsWorld); + return computeContactPointsOfWorld(getDynamicsWorld()); } } diff --git a/testbed/scenes/joints/JointsScene.cpp b/testbed/scenes/joints/JointsScene.cpp index 282f7e51..3252e90e 100644 --- a/testbed/scenes/joints/JointsScene.cpp +++ b/testbed/scenes/joints/JointsScene.cpp @@ -32,8 +32,8 @@ using namespace openglframework; using namespace jointsscene; // Constructor -JointsScene::JointsScene(const std::string& name) - : SceneDemo(name, SCENE_RADIUS) { +JointsScene::JointsScene(const std::string& name, EngineSettings& settings) + : SceneDemo(name, settings, SCENE_RADIUS) { // Compute the radius and the center of the scene openglframework::Vector3 center(0, 5, 0); @@ -45,7 +45,7 @@ JointsScene::JointsScene(const std::string& name) rp3d::Vector3 gravity(0, rp3d::decimal(-9.81), 0); // Create the dynamics world for the physics simulation - mDynamicsWorld = new rp3d::DynamicsWorld(gravity); + mPhysicsWorld = new rp3d::DynamicsWorld(gravity); // Create the Ball-and-Socket joint createBallAndSocketJoints(); @@ -63,37 +63,37 @@ JointsScene::JointsScene(const std::string& name) createFloor(); // Get the physics engine parameters - mEngineSettings.isGravityEnabled = mDynamicsWorld->isGravityEnabled(); - rp3d::Vector3 gravityVector = mDynamicsWorld->getGravity(); + mEngineSettings.isGravityEnabled = getDynamicsWorld()->isGravityEnabled(); + rp3d::Vector3 gravityVector = getDynamicsWorld()->getGravity(); mEngineSettings.gravity = openglframework::Vector3(gravityVector.x, gravityVector.y, gravityVector.z); - mEngineSettings.isSleepingEnabled = mDynamicsWorld->isSleepingEnabled(); - mEngineSettings.sleepLinearVelocity = mDynamicsWorld->getSleepLinearVelocity(); - mEngineSettings.sleepAngularVelocity = mDynamicsWorld->getSleepAngularVelocity(); - mEngineSettings.nbPositionSolverIterations = mDynamicsWorld->getNbIterationsPositionSolver(); - mEngineSettings.nbVelocitySolverIterations = mDynamicsWorld->getNbIterationsVelocitySolver(); - mEngineSettings.timeBeforeSleep = mDynamicsWorld->getTimeBeforeSleep(); + mEngineSettings.isSleepingEnabled = getDynamicsWorld()->isSleepingEnabled(); + mEngineSettings.sleepLinearVelocity = getDynamicsWorld()->getSleepLinearVelocity(); + mEngineSettings.sleepAngularVelocity = getDynamicsWorld()->getSleepAngularVelocity(); + mEngineSettings.nbPositionSolverIterations = getDynamicsWorld()->getNbIterationsPositionSolver(); + mEngineSettings.nbVelocitySolverIterations = getDynamicsWorld()->getNbIterationsVelocitySolver(); + mEngineSettings.timeBeforeSleep = getDynamicsWorld()->getTimeBeforeSleep(); } // Destructor JointsScene::~JointsScene() { // Destroy the joints - mDynamicsWorld->destroyJoint(mSliderJoint); - mDynamicsWorld->destroyJoint(mPropellerHingeJoint); - mDynamicsWorld->destroyJoint(mFixedJoint1); - mDynamicsWorld->destroyJoint(mFixedJoint2); + getDynamicsWorld()->destroyJoint(mSliderJoint); + getDynamicsWorld()->destroyJoint(mPropellerHingeJoint); + getDynamicsWorld()->destroyJoint(mFixedJoint1); + getDynamicsWorld()->destroyJoint(mFixedJoint2); for (int i=0; idestroyJoint(mBallAndSocketJoints[i]); + getDynamicsWorld()->destroyJoint(mBallAndSocketJoints[i]); } // Destroy all the rigid bodies of the scene - mDynamicsWorld->destroyRigidBody(mSliderJointBottomBox->getRigidBody()); - mDynamicsWorld->destroyRigidBody(mSliderJointTopBox->getRigidBody()); - mDynamicsWorld->destroyRigidBody(mPropellerBox->getRigidBody()); - mDynamicsWorld->destroyRigidBody(mFixedJointBox1->getRigidBody()); - mDynamicsWorld->destroyRigidBody(mFixedJointBox2->getRigidBody()); + getDynamicsWorld()->destroyRigidBody(mSliderJointBottomBox->getRigidBody()); + getDynamicsWorld()->destroyRigidBody(mSliderJointTopBox->getRigidBody()); + getDynamicsWorld()->destroyRigidBody(mPropellerBox->getRigidBody()); + getDynamicsWorld()->destroyRigidBody(mFixedJointBox1->getRigidBody()); + getDynamicsWorld()->destroyRigidBody(mFixedJointBox2->getRigidBody()); for (int i=0; idestroyRigidBody(mBallAndSocketJointChainBoxes[i]->getRigidBody()); + getDynamicsWorld()->destroyRigidBody(mBallAndSocketJointChainBoxes[i]->getRigidBody()); } delete mSliderJointBottomBox; @@ -106,58 +106,21 @@ JointsScene::~JointsScene() { } // Destroy the floor - mDynamicsWorld->destroyRigidBody(mFloor->getRigidBody()); + getDynamicsWorld()->destroyRigidBody(mFloor->getRigidBody()); delete mFloor; // Destroy the dynamics world - delete mDynamicsWorld; + delete getDynamicsWorld(); } // Update the physics world (take a simulation step) void JointsScene::updatePhysics() { - // Update the physics engine parameters - mDynamicsWorld->setIsGratityEnabled(mEngineSettings.isGravityEnabled); - rp3d::Vector3 gravity(mEngineSettings.gravity.x, mEngineSettings.gravity.y, - mEngineSettings.gravity.z); - mDynamicsWorld->setGravity(gravity); - mDynamicsWorld->enableSleeping(mEngineSettings.isSleepingEnabled); - mDynamicsWorld->setSleepLinearVelocity(mEngineSettings.sleepLinearVelocity); - mDynamicsWorld->setSleepAngularVelocity(mEngineSettings.sleepAngularVelocity); - mDynamicsWorld->setNbIterationsPositionSolver(mEngineSettings.nbPositionSolverIterations); - mDynamicsWorld->setNbIterationsVelocitySolver(mEngineSettings.nbVelocitySolverIterations); - mDynamicsWorld->setTimeBeforeSleep(mEngineSettings.timeBeforeSleep); - // Update the motor speed of the Slider Joint (to move up and down) - long double motorSpeed = 2 * cos(mEngineSettings.elapsedTime * 1.5); + double motorSpeed = 2.0 * std::cos(static_cast(mEngineSettings.elapsedTime) * 1.5); mSliderJoint->setMotorSpeed(rp3d::decimal(motorSpeed)); - // Take a simulation step - mDynamicsWorld->update(mEngineSettings.timeStep); -} - -// Render the scene -void JointsScene::renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix) { - - // Bind the shader - shader.bind(); - - // Render all the boxes - mSliderJointBottomBox->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - mSliderJointTopBox->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - mPropellerBox->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - mFixedJointBox1->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - mFixedJointBox2->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - for (int i=0; irender(shader, worldToCameraMatrix, mIsWireframeEnabled); - } - - // Render the floor - mFloor->render(shader, worldToCameraMatrix, mIsWireframeEnabled); - - // Unbind the shader - shader.unbind(); + SceneDemo::updatePhysics(); } // Reset the scene @@ -236,15 +199,16 @@ void JointsScene::createBallAndSocketJoints() { // --------------- Create the boxes --------------- // - openglframework::Vector3 positionBox(0, 15, 5); + rp3d::Vector3 positionBox(0, 15, 5); openglframework::Vector3 boxDimension(1, 1, 1); const float boxMass = 0.5f; for (int i=0; isetTransform(rp3d::Transform(positionBox, rp3d::Quaternion::identity())); // Set the box color mBallAndSocketJointChainBoxes[i]->setColor(mDemoColors[i % mNbDemoColors]); @@ -281,7 +245,7 @@ void JointsScene::createBallAndSocketJoints() { // Create the joint in the dynamics world mBallAndSocketJoints[i] = dynamic_cast( - mDynamicsWorld->createJoint(jointInfo)); + getDynamicsWorld()->createJoint(jointInfo)); } } @@ -291,11 +255,12 @@ void JointsScene::createSliderJoint() { // --------------- Create the first box --------------- // // Position of the box - openglframework::Vector3 positionBox1(0, 2.1f, 0); + rp3d::Vector3 positionBox1(0, 2.1f, 0); // Create a box and a corresponding rigid in the dynamics world openglframework::Vector3 box1Dimension(2, 4, 2); - mSliderJointBottomBox = new Box(box1Dimension, positionBox1 , BOX_MASS, mDynamicsWorld, mMeshFolderPath); + mSliderJointBottomBox = new Box(box1Dimension , BOX_MASS, getDynamicsWorld(), mMeshFolderPath); + mSliderJointBottomBox->setTransform(rp3d::Transform(positionBox1, rp3d::Quaternion::identity())); // Set the box color mSliderJointBottomBox->setColor(mBlueColorDemo); @@ -312,11 +277,12 @@ void JointsScene::createSliderJoint() { // --------------- Create the second box --------------- // // Position of the box - openglframework::Vector3 positionBox2(0, 4.2f, 0); + rp3d::Vector3 positionBox2(0, 4.2f, 0); // Create a box and a corresponding rigid in the dynamics world openglframework::Vector3 box2Dimension(1.5f, 4, 1.5f); - mSliderJointTopBox = new Box(box2Dimension, positionBox2, BOX_MASS, mDynamicsWorld, mMeshFolderPath); + mSliderJointTopBox = new Box(box2Dimension, BOX_MASS, getDynamicsWorld(), mMeshFolderPath); + mSliderJointTopBox->setTransform(rp3d::Transform(positionBox2, rp3d::Quaternion::identity())); // Set the box color mSliderJointTopBox->setColor(mOrangeColorDemo); @@ -344,7 +310,7 @@ void JointsScene::createSliderJoint() { jointInfo.isCollisionEnabled = false; // Create the joint in the dynamics world - mSliderJoint = dynamic_cast(mDynamicsWorld->createJoint(jointInfo)); + mSliderJoint = dynamic_cast(getDynamicsWorld()->createJoint(jointInfo)); } /// Create the boxes and joint for the Hinge joint example @@ -353,11 +319,12 @@ void JointsScene::createPropellerHingeJoint() { // --------------- Create the propeller box --------------- // // Position of the box - openglframework::Vector3 positionBox1(0, 7, 0); + rp3d::Vector3 positionBox1(0, 7, 0); // Create a box and a corresponding rigid in the dynamics world openglframework::Vector3 boxDimension(10, 1, 1); - mPropellerBox = new Box(boxDimension, positionBox1 , BOX_MASS, mDynamicsWorld, mMeshFolderPath); + mPropellerBox = new Box(boxDimension, BOX_MASS, getDynamicsWorld(), mMeshFolderPath); + mPropellerBox->setTransform(rp3d::Transform(positionBox1, rp3d::Quaternion::identity())); // Set the box color mPropellerBox->setColor(mYellowColorDemo); @@ -384,7 +351,7 @@ void JointsScene::createPropellerHingeJoint() { jointInfo.isCollisionEnabled = false; // Create the joint in the dynamics world - mPropellerHingeJoint = dynamic_cast(mDynamicsWorld->createJoint(jointInfo)); + mPropellerHingeJoint = dynamic_cast(getDynamicsWorld()->createJoint(jointInfo)); } /// Create the boxes and joints for the fixed joints @@ -393,11 +360,12 @@ void JointsScene::createFixedJoints() { // --------------- Create the first box --------------- // // Position of the box - openglframework::Vector3 positionBox1(5, 7, 0); + rp3d::Vector3 positionBox1(5, 7, 0); // Create a box and a corresponding rigid in the dynamics world openglframework::Vector3 boxDimension(1.5, 1.5, 1.5); - mFixedJointBox1 = new Box(boxDimension, positionBox1 , BOX_MASS, mDynamicsWorld, mMeshFolderPath); + mFixedJointBox1 = new Box(boxDimension, BOX_MASS, getDynamicsWorld(), mMeshFolderPath); + mFixedJointBox1->setTransform(rp3d::Transform(positionBox1, rp3d::Quaternion::identity())); // Set the box color mFixedJointBox1->setColor(mPinkColorDemo); @@ -411,10 +379,11 @@ void JointsScene::createFixedJoints() { // --------------- Create the second box --------------- // // Position of the box - openglframework::Vector3 positionBox2(-5, 7, 0); + rp3d::Vector3 positionBox2(-5, 7, 0); // Create a box and a corresponding rigid in the dynamics world - mFixedJointBox2 = new Box(boxDimension, positionBox2 , BOX_MASS, mDynamicsWorld, mMeshFolderPath); + mFixedJointBox2 = new Box(boxDimension, BOX_MASS, getDynamicsWorld(), mMeshFolderPath); + mFixedJointBox2->setTransform(rp3d::Transform(positionBox2, rp3d::Quaternion::identity())); // Set the box color mFixedJointBox2->setColor(mBlueColorDemo); @@ -435,7 +404,7 @@ void JointsScene::createFixedJoints() { jointInfo1.isCollisionEnabled = false; // Create the joint in the dynamics world - mFixedJoint1 = dynamic_cast(mDynamicsWorld->createJoint(jointInfo1)); + mFixedJoint1 = dynamic_cast(getDynamicsWorld()->createJoint(jointInfo1)); // --------------- Create the second fixed joint --------------- // @@ -446,15 +415,15 @@ void JointsScene::createFixedJoints() { jointInfo2.isCollisionEnabled = false; // Create the joint in the dynamics world - mFixedJoint2 = dynamic_cast(mDynamicsWorld->createJoint(jointInfo2)); + mFixedJoint2 = dynamic_cast(getDynamicsWorld()->createJoint(jointInfo2)); } // Create the floor void JointsScene::createFloor() { // Create the floor - openglframework::Vector3 floorPosition(0, 0, 0); - mFloor = new Box(FLOOR_SIZE, floorPosition, FLOOR_MASS, mDynamicsWorld, mMeshFolderPath); + rp3d::Vector3 floorPosition(0, 0, 0); + mFloor = new Box(FLOOR_SIZE, FLOOR_MASS, getDynamicsWorld(), mMeshFolderPath); // Set the box color mFloor->setColor(mGreyColorDemo); diff --git a/testbed/scenes/joints/JointsScene.h b/testbed/scenes/joints/JointsScene.h index 16ccfe8c..dad9af38 100644 --- a/testbed/scenes/joints/JointsScene.h +++ b/testbed/scenes/joints/JointsScene.h @@ -92,9 +92,6 @@ class JointsScene : public SceneDemo { /// Box for the floor Box* mFloor; - /// Dynamics world used for the physics simulation - rp3d::DynamicsWorld* mDynamicsWorld; - // -------------------- Methods -------------------- // /// Create the boxes and joints for the Ball-and-Socket joint example @@ -117,7 +114,7 @@ class JointsScene : public SceneDemo { // -------------------- Methods -------------------- // /// Constructor - JointsScene(const std::string& name); + JointsScene(const std::string& name, EngineSettings& settings); /// Destructor virtual ~JointsScene() override ; @@ -126,10 +123,6 @@ class JointsScene : public SceneDemo { /// Can be called several times per frame virtual void updatePhysics() override; - /// Render the scene in a single pass - virtual void renderSinglePass(openglframework::Shader& shader, - const openglframework::Matrix4& worldToCameraMatrix) override; - /// Reset the scene virtual void reset() override; @@ -139,7 +132,7 @@ class JointsScene : public SceneDemo { // Return all the contact points of the scene inline std::vector JointsScene::getContactPoints() const { - return computeContactPointsOfWorld(mDynamicsWorld); + return computeContactPointsOfWorld(getDynamicsWorld()); } } diff --git a/testbed/scenes/raycast/RaycastScene.cpp b/testbed/scenes/raycast/RaycastScene.cpp index 2ded75d6..bf806183 100644 --- a/testbed/scenes/raycast/RaycastScene.cpp +++ b/testbed/scenes/raycast/RaycastScene.cpp @@ -31,8 +31,8 @@ using namespace openglframework; using namespace raycastscene; // Constructor -RaycastScene::RaycastScene(const std::string& name) - : SceneDemo(name, SCENE_RADIUS, false), mMeshFolderPath("meshes/"), +RaycastScene::RaycastScene(const std::string& name, EngineSettings& settings) + : SceneDemo(name, settings, SCENE_RADIUS, false), mMeshFolderPath("meshes/"), mRaycastManager(mPhongShader, mMeshFolderPath), mCurrentBodyIndex(-1), mAreNormalsDisplayed(false), mVBOVertices(GL_ARRAY_BUFFER) { @@ -45,13 +45,12 @@ RaycastScene::RaycastScene(const std::string& name) setScenePosition(center, SCENE_RADIUS); // Create the dynamics world for the physics simulation - mCollisionWorld = new rp3d::CollisionWorld(); + mPhysicsWorld = new rp3d::CollisionWorld(); // ---------- Dumbbell ---------- // - openglframework::Vector3 position1(0, 0, 0); // Create a convex mesh and a corresponding collision body in the dynamics world - mDumbbell = new Dumbbell(position1, mCollisionWorld, mMeshFolderPath); + mDumbbell = new Dumbbell(mPhysicsWorld, mMeshFolderPath); // Set the box color mDumbbell->setColor(mGreyColorDemo); @@ -59,10 +58,9 @@ RaycastScene::RaycastScene(const std::string& name) mPhysicsObjects.push_back(mDumbbell); // ---------- Box ---------- // - openglframework::Vector3 position2(0, 0, 0); // Create a box and a corresponding collision body in the dynamics world - mBox = new Box(BOX_SIZE, position2, mCollisionWorld, mMeshFolderPath); + mBox = new Box(BOX_SIZE, mPhysicsWorld, mMeshFolderPath); mBox->getCollisionBody()->setIsActive(false); // Set the box color @@ -71,11 +69,9 @@ RaycastScene::RaycastScene(const std::string& name) mPhysicsObjects.push_back(mBox); // ---------- Sphere ---------- // - openglframework::Vector3 position3(0, 0, 0); // Create a sphere and a corresponding collision body in the dynamics world - mSphere = new Sphere(SPHERE_RADIUS, position3, mCollisionWorld, - mMeshFolderPath); + mSphere = new Sphere(SPHERE_RADIUS, mPhysicsWorld, mMeshFolderPath); // Set the color mSphere->setColor(mGreyColorDemo); @@ -86,8 +82,7 @@ RaycastScene::RaycastScene(const std::string& name) openglframework::Vector3 position6(0, 0, 0); // Create a cylinder and a corresponding collision body in the dynamics world - mCapsule = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, position6 , - mCollisionWorld, mMeshFolderPath); + mCapsule = new Capsule(CAPSULE_RADIUS, CAPSULE_HEIGHT, mPhysicsWorld, mMeshFolderPath); // Set the color mCapsule->setColor(mGreyColorDemo); @@ -95,10 +90,9 @@ RaycastScene::RaycastScene(const std::string& name) mPhysicsObjects.push_back(mCapsule); // ---------- Convex Mesh ---------- // - openglframework::Vector3 position7(0, 0, 0); // Create a convex mesh and a corresponding collision body in the dynamics world - mConvexMesh = new ConvexMesh(position7, mCollisionWorld, mMeshFolderPath + "convexmesh.obj"); + mConvexMesh = new ConvexMesh(mPhysicsWorld, mMeshFolderPath + "convexmesh.obj"); // Set the color mConvexMesh->setColor(mGreyColorDemo); @@ -106,10 +100,9 @@ RaycastScene::RaycastScene(const std::string& name) mPhysicsObjects.push_back(mConvexMesh); // ---------- Concave Mesh ---------- // - openglframework::Vector3 position8(0, 0, 0); // Create a convex mesh and a corresponding collision body in the dynamics world - mConcaveMesh = new ConcaveMesh(position8, mCollisionWorld, mMeshFolderPath + "city.obj"); + mConcaveMesh = new ConcaveMesh(mPhysicsWorld, mMeshFolderPath + "city.obj"); // Set the color mConcaveMesh->setColor(mGreyColorDemo); @@ -117,10 +110,9 @@ RaycastScene::RaycastScene(const std::string& name) mPhysicsObjects.push_back(mConcaveMesh); // ---------- Heightfield ---------- // - openglframework::Vector3 position9(0, 0, 0); // Create a convex mesh and a corresponding collision body in the dynamics world - mHeightField = new HeightField(position9, mCollisionWorld); + mHeightField = new HeightField(mPhysicsWorld); // Set the color mHeightField->setColor(mGreyColorDemo); @@ -139,7 +131,7 @@ RaycastScene::RaycastScene(const std::string& name) // Create the raycast lines void RaycastScene::createLines() { - int nbRaysOneDimension = std::sqrt(float(NB_RAYS)); + int nbRaysOneDimension = static_cast(std::sqrt(float(NB_RAYS))); for (int i=0; i::iterator it; + for (it = mPhysicsObjects.begin(); it != mPhysicsObjects.end(); ++it) { + (*it)->setTransform(rp3d::Transform(rp3d::Vector3::zero(), rp3d::Quaternion::identity())); + } } // Destructor RaycastScene::~RaycastScene() { // Destroy the box rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mBox->getCollisionBody()); + mPhysicsWorld->destroyCollisionBody(mBox->getCollisionBody()); delete mBox; // Destroy the sphere - mCollisionWorld->destroyCollisionBody(mSphere->getCollisionBody()); + mPhysicsWorld->destroyCollisionBody(mSphere->getCollisionBody()); delete mSphere; // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mCapsule->getCollisionBody()); + mPhysicsWorld->destroyCollisionBody(mCapsule->getCollisionBody()); // Destroy the sphere delete mCapsule; // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mConvexMesh->getCollisionBody()); + mPhysicsWorld->destroyCollisionBody(mConvexMesh->getCollisionBody()); // Destroy the convex mesh delete mConvexMesh; // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mDumbbell->getCollisionBody()); + mPhysicsWorld->destroyCollisionBody(mDumbbell->getCollisionBody()); // Destroy the dumbbell delete mDumbbell; // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mConcaveMesh->getCollisionBody()); + mPhysicsWorld->destroyCollisionBody(mConcaveMesh->getCollisionBody()); // Destroy the convex mesh delete mConcaveMesh; // Destroy the corresponding rigid body from the dynamics world - mCollisionWorld->destroyCollisionBody(mHeightField->getCollisionBody()); + mPhysicsWorld->destroyCollisionBody(mHeightField->getCollisionBody()); // Destroy the convex mesh delete mHeightField; @@ -250,7 +246,7 @@ RaycastScene::~RaycastScene() { VisualContactPoint::destroyStaticData(); // Destroy the collision world - delete mCollisionWorld; + delete mPhysicsWorld; // Destroy the lines for (std::vector::iterator it = mLines.begin(); it != mLines.end(); @@ -284,7 +280,7 @@ void RaycastScene::update() { // Perform a raycast query on the physics world by passing a raycast // callback class in argument. - mCollisionWorld->raycast(ray, &mRaycastManager); + mPhysicsWorld->raycast(ray, &mRaycastManager); } SceneDemo::update(); @@ -307,7 +303,7 @@ void RaycastScene::renderSinglePass(openglframework::Shader& shader, const openg mColorShader.setMatrix4x4Uniform("worldToCameraMatrix", worldToCameraMatrix); // Set the vertex color - openglframework::Vector4 color(1, 0.55, 0, 1); + openglframework::Vector4 color(1, 0.55f, 0, 1); mColorShader.setVector4Uniform("vertexColor", color, false); // Get the location of shader attribute variables @@ -334,7 +330,7 @@ void RaycastScene::renderSinglePass(openglframework::Shader& shader, const openg // Render all the physics objects of the scene for (std::vector::iterator it = mPhysicsObjects.begin(); it != mPhysicsObjects.end(); ++it) { if ((*it)->getCollisionBody()->isActive()) { - (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + (*it)->render(shader, worldToCameraMatrix); } } diff --git a/testbed/scenes/raycast/RaycastScene.h b/testbed/scenes/raycast/RaycastScene.h index 1400fcf7..8024ff1a 100644 --- a/testbed/scenes/raycast/RaycastScene.h +++ b/testbed/scenes/raycast/RaycastScene.h @@ -146,9 +146,6 @@ class RaycastScene : public SceneDemo { ConcaveMesh* mConcaveMesh; HeightField* mHeightField; - /// Collision world used for the physics simulation - rp3d::CollisionWorld* mCollisionWorld; - /// All the points to render the lines std::vector mLinePoints; @@ -170,7 +167,7 @@ class RaycastScene : public SceneDemo { // -------------------- Methods -------------------- // /// Constructor - RaycastScene(const std::string& name); + RaycastScene(const std::string& name, EngineSettings& settings); /// Destructor virtual ~RaycastScene() override; diff --git a/testbed/src/Gui.cpp b/testbed/src/Gui.cpp index cd9f8f4e..6ad24335 100644 --- a/testbed/src/Gui.cpp +++ b/testbed/src/Gui.cpp @@ -388,6 +388,14 @@ void Gui::createSettingsPanel() { mApp->mIsContactPointsDisplayed = value; }); + + // Display/Hide the AABBs + CheckBox* checkboxAABBs = new CheckBox(mRenderingPanel, "AABBs"); + checkboxAABBs->setChecked(mApp->mIsAABBsDisplayed); + checkboxAABBs->setCallback([&](bool value) { + mApp->mIsAABBsDisplayed = value; + }); + // Enabled/Disable VSync CheckBox* checkboxVSync = new CheckBox(mRenderingPanel, "V-Sync"); checkboxVSync->setChecked(mApp->mIsVSyncEnabled); diff --git a/testbed/src/Scene.cpp b/testbed/src/Scene.cpp index e872b3bc..b6668649 100644 --- a/testbed/src/Scene.cpp +++ b/testbed/src/Scene.cpp @@ -30,10 +30,10 @@ using namespace openglframework; // Constructor -Scene::Scene(const std::string& name, bool isShadowMappingEnabled) - : mName(name), mInterpolationFactor(0.0f), mViewportX(0), mViewportY(0), +Scene::Scene(const std::string& name, EngineSettings& engineSettings, bool isShadowMappingEnabled) + : mName(name), mEngineSettings(engineSettings), mInterpolationFactor(0.0f), mViewportX(0), mViewportY(0), mViewportWidth(0), mViewportHeight(0), mIsShadowMappingEnabled(isShadowMappingEnabled), - mIsContactPointsDisplayed(true), mIsWireframeEnabled(false) { + mIsContactPointsDisplayed(true), mIsAABBsDisplayed(false), mIsWireframeEnabled(false) { } @@ -74,14 +74,14 @@ bool Scene::mapMouseCoordinatesToSphere(double xMouse, double yMouse, if ((xMouse >= 0) && (xMouse <= mWindowWidth) && (yMouse >= 0) && (yMouse <= mWindowHeight)) { float x = float(xMouse - 0.5f * mWindowWidth) / float(mWindowWidth); float y = float(0.5f * mWindowHeight - yMouse) / float(mWindowHeight); - float sinx = sin(PI * x * 0.5f); - float siny = sin(PI * y * 0.5f); + float sinx = std::sin(PI * x * 0.5f); + float siny = std::sin(PI * y * 0.5f); float sinx2siny2 = sinx * sinx + siny * siny; // Compute the point on the sphere spherePoint.x = sinx; spherePoint.y = siny; - spherePoint.z = (sinx2siny2 < 1.0) ? sqrt(1.0f - sinx2siny2) : 0.0f; + spherePoint.z = (sinx2siny2 < 1.0f) ? std::sqrt(1.0f - sinx2siny2) : 0.0f; return true; } @@ -175,9 +175,9 @@ void Scene::rotate(int xMouse, int yMouse) { float cosAngle = mLastPointOnSphere.dot(newPoint3D); float epsilon = std::numeric_limits::epsilon(); - if (fabs(cosAngle) < 1.0f && axis.length() > epsilon) { + if (std::abs(cosAngle) < 1.0f && axis.length() > epsilon) { axis.normalize(); - float angle = 2.0f * acos(cosAngle); + float angle = 2.0f * std::acos(cosAngle); // Rotate the camera around the center of the scene mCamera.rotateAroundLocalPoint(axis, -angle, mCenterScene); diff --git a/testbed/src/Scene.h b/testbed/src/Scene.h index aa29b9e5..e33e9da9 100644 --- a/testbed/src/Scene.h +++ b/testbed/src/Scene.h @@ -28,6 +28,7 @@ // Libraries #include "openglframework.h" +#include "reactphysics3d.h" // Structure ContactPoint struct ContactPoint { @@ -52,8 +53,8 @@ struct EngineSettings { long double elapsedTime; // Elapsed time (in seconds) float timeStep; // Current time step (in seconds) - int nbVelocitySolverIterations; // Nb of velocity solver iterations - int nbPositionSolverIterations; // Nb of position solver iterations + uint nbVelocitySolverIterations; // Nb of velocity solver iterations + uint nbPositionSolverIterations; // Nb of position solver iterations bool isSleepingEnabled; // True if sleeping technique is enabled float timeBeforeSleep; // Time of inactivity before a body sleep float sleepLinearVelocity; // Sleep linear velocity @@ -65,6 +66,23 @@ struct EngineSettings { EngineSettings() : elapsedTime(0.0f), timeStep(0.0f) { } + + /// Return default engine settings + static EngineSettings defaultSettings() { + + EngineSettings defaultSettings; + + defaultSettings.timeStep = 1.0f / 60.0f; + defaultSettings.nbVelocitySolverIterations = rp3d::DEFAULT_VELOCITY_SOLVER_NB_ITERATIONS; + defaultSettings.nbPositionSolverIterations = rp3d::DEFAULT_POSITION_SOLVER_NB_ITERATIONS; + defaultSettings.isSleepingEnabled = rp3d::SLEEPING_ENABLED; + defaultSettings.timeBeforeSleep = rp3d::DEFAULT_TIME_BEFORE_SLEEP; + defaultSettings.sleepLinearVelocity = rp3d::DEFAULT_SLEEP_LINEAR_VELOCITY; + defaultSettings.sleepAngularVelocity = rp3d::DEFAULT_SLEEP_ANGULAR_VELOCITY; + defaultSettings.isGravityEnabled = true; + + return defaultSettings; + } }; // Class Scene @@ -79,7 +97,7 @@ class Scene { std::string mName; /// Physics engine settings - EngineSettings mEngineSettings; + EngineSettings& mEngineSettings; /// Camera openglframework::Camera mCamera; @@ -111,6 +129,9 @@ class Scene { /// True if contact points are displayed bool mIsContactPointsDisplayed; + /// True if the AABBs of the phycis objects are displayed + bool mIsAABBsDisplayed; + /// True if we render shapes in wireframe mode bool mIsWireframeEnabled; @@ -140,7 +161,7 @@ class Scene { // -------------------- Methods -------------------- // /// Constructor - Scene(const std::string& name, bool isShadowMappingEnabled = false); + Scene(const std::string& name, EngineSettings& engineSettings, bool isShadowMappingEnabled = false); /// Destructor virtual ~Scene(); @@ -184,12 +205,6 @@ class Scene { /// Return a reference to the camera const openglframework::Camera& getCamera() const; - /// Get the engine settings - EngineSettings getEngineSettings() const; - - /// Set the engine settings - void setEngineSettings(const EngineSettings& settings); - /// Set the interpolation factor void setInterpolationFactor(float interpolationFactor); @@ -205,6 +220,9 @@ class Scene { /// Display/Hide the contact points void virtual setIsContactPointsDisplayed(bool display); + /// Display/Hide the AABBs + void setIsAABBsDisplayed(bool display); + /// Return true if wireframe rendering is enabled bool getIsWireframeEnabled() const; @@ -244,16 +262,6 @@ inline void Scene::setViewport(int x, int y, int width, int height) { mViewportHeight = height; } -// Get the engine settings -inline EngineSettings Scene::getEngineSettings() const { - return mEngineSettings; -} - -// Set the engine settings -inline void Scene::setEngineSettings(const EngineSettings& settings) { - mEngineSettings = settings; -} - // Set the interpolation factor inline void Scene::setInterpolationFactor(float interpolationFactor) { mInterpolationFactor = interpolationFactor; @@ -279,6 +287,11 @@ inline void Scene::setIsContactPointsDisplayed(bool display) { mIsContactPointsDisplayed = display; } +// Display/Hide the AABBs +inline void Scene::setIsAABBsDisplayed(bool display) { + mIsAABBsDisplayed = display; +} + // Return true if wireframe rendering is enabled inline bool Scene::getIsWireframeEnabled() const { return mIsWireframeEnabled; diff --git a/testbed/src/SceneDemo.cpp b/testbed/src/SceneDemo.cpp index d406bcea..db5d030e 100644 --- a/testbed/src/SceneDemo.cpp +++ b/testbed/src/SceneDemo.cpp @@ -26,27 +26,28 @@ // Libraries #include "SceneDemo.h" #include +#include "AABB.h" using namespace openglframework; int SceneDemo::shadowMapTextureLevel = 0; -openglframework::Color SceneDemo::mGreyColorDemo = Color(0.70f, 0.70f, 0.7f, 1.0); -openglframework::Color SceneDemo::mYellowColorDemo = Color(0.9, 0.88, 0.145, 1.0); -openglframework::Color SceneDemo::mBlueColorDemo = Color(0, 0.66, 0.95, 1.0); -openglframework::Color SceneDemo::mOrangeColorDemo = Color(0.9, 0.35, 0, 1.0); -openglframework::Color SceneDemo::mPinkColorDemo = Color(0.83, 0.48, 0.64, 1.0); -openglframework::Color SceneDemo::mRedColorDemo = Color(0.95, 0, 0, 1.0); +openglframework::Color SceneDemo::mGreyColorDemo = Color(0.70f, 0.70f, 0.7f, 1.0f); +openglframework::Color SceneDemo::mYellowColorDemo = Color(0.9f, 0.88f, 0.145f, 1.0f); +openglframework::Color SceneDemo::mBlueColorDemo = Color(0, 0.66f, 0.95f, 1.0f); +openglframework::Color SceneDemo::mOrangeColorDemo = Color(0.9f, 0.35f, 0, 1.0f); +openglframework::Color SceneDemo::mPinkColorDemo = Color(0.83f, 0.48f, 0.64f, 1.0f); +openglframework::Color SceneDemo::mRedColorDemo = Color(0.95f, 0, 0, 1.0f); int SceneDemo::mNbDemoColors = 4; openglframework::Color SceneDemo::mDemoColors[] = {SceneDemo::mYellowColorDemo, SceneDemo::mBlueColorDemo, SceneDemo::mOrangeColorDemo, SceneDemo::mPinkColorDemo}; // Constructor -SceneDemo::SceneDemo(const std::string& name, float sceneRadius, bool isShadowMappingEnabled) - : Scene(name, isShadowMappingEnabled), mIsShadowMappingInitialized(false), +SceneDemo::SceneDemo(const std::string& name, EngineSettings& settings, float sceneRadius, bool isShadowMappingEnabled) + : Scene(name, settings, isShadowMappingEnabled), mIsShadowMappingInitialized(false), mDepthShader("shaders/depth.vert", "shaders/depth.frag"), mPhongShader("shaders/phong.vert", "shaders/phong.frag"), - mQuadShader("shaders/quad.vert", "shaders/quad.frag"), mColorShader("shaders/color.vert", "shaders/color.frag"), + mQuadShader("shaders/quad.vert", "shaders/quad.frag"), mVBOQuad(GL_ARRAY_BUFFER), mMeshFolderPath("meshes/") { shadowMapTextureLevel++; @@ -75,6 +76,9 @@ SceneDemo::SceneDemo(const std::string& name, float sceneRadius, bool isShadowMa createQuadVBO(); + // Init rendering for the AABBs + AABB::init(); + VisualContactPoint::createStaticData(mMeshFolderPath); } @@ -93,6 +97,9 @@ SceneDemo::~SceneDemo() { // Destroy the contact points removeAllContactPoints(); + // Destroy rendering data for the AABB + AABB::destroy(); + VisualContactPoint::destroyStaticData(); } @@ -114,6 +121,23 @@ void SceneDemo::update() { // Can be called several times per frame void SceneDemo::updatePhysics() { + if (getDynamicsWorld() != nullptr) { + + // Update the physics engine parameters + getDynamicsWorld()->setIsGratityEnabled(mEngineSettings.isGravityEnabled); + rp3d::Vector3 gravity(mEngineSettings.gravity.x, mEngineSettings.gravity.y, + mEngineSettings.gravity.z); + getDynamicsWorld()->setGravity(gravity); + getDynamicsWorld()->enableSleeping(mEngineSettings.isSleepingEnabled); + getDynamicsWorld()->setSleepLinearVelocity(mEngineSettings.sleepLinearVelocity); + getDynamicsWorld()->setSleepAngularVelocity(mEngineSettings.sleepAngularVelocity); + getDynamicsWorld()->setNbIterationsPositionSolver(mEngineSettings.nbPositionSolverIterations); + getDynamicsWorld()->setNbIterationsVelocitySolver(mEngineSettings.nbVelocitySolverIterations); + getDynamicsWorld()->setTimeBeforeSleep(mEngineSettings.timeBeforeSleep); + + // Take a simulation step + getDynamicsWorld()->update(mEngineSettings.timeStep); + } } // Render the scene (in multiple passes for shadow mapping) @@ -209,6 +233,11 @@ void SceneDemo::render() { renderContactPoints(mPhongShader, worldToCameraMatrix); } + // Render the AABBs + if (mIsAABBsDisplayed) { + renderAABBs(worldToCameraMatrix); + } + if (mIsShadowMappingEnabled) mShadowMapTexture.unbind(); mPhongShader.unbind(); @@ -218,16 +247,24 @@ void SceneDemo::render() { // Render the scene in a single pass void SceneDemo::renderSinglePass(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) { - // Bind the shader + if (mIsWireframeEnabled) { + glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); + } + + // Bind the shader shader.bind(); // Render all the physics objects of the scene for (std::vector::iterator it = mPhysicsObjects.begin(); it != mPhysicsObjects.end(); ++it) { - (*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled); + (*it)->render(mIsWireframeEnabled ? mColorShader : shader, worldToCameraMatrix); } // Unbind the shader shader.unbind(); + + if (mIsWireframeEnabled) { + glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); + } } // Create the Shadow map FBO and texture @@ -338,13 +375,38 @@ void SceneDemo::updateContactPoints() { // Render the contact points void SceneDemo::renderContactPoints(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix) { - // Render all the raycast hit points + // Render all the contact points for (std::vector::iterator it = mContactPoints.begin(); it != mContactPoints.end(); ++it) { (*it)->render(mColorShader, worldToCameraMatrix); } } +// Render the AABBs +void SceneDemo::renderAABBs(const openglframework::Matrix4& worldToCameraMatrix) { + + // For each physics object of the scene + for (std::vector::iterator it = mPhysicsObjects.begin(); it != mPhysicsObjects.end(); ++it) { + + // For each proxy shape of the object + rp3d::ProxyShape* proxyShape = (*it)->getCollisionBody()->getProxyShapesList(); + while (proxyShape != nullptr) { + + // Get the broad-phase AABB corresponding to the proxy shape + rp3d::AABB aabb = mPhysicsWorld->getWorldAABB(proxyShape); + + openglframework::Vector3 aabbCenter(aabb.getCenter().x, aabb.getCenter().y, aabb.getCenter().z); + openglframework::Vector3 aabbMin(aabb.getMin().x, aabb.getMin().y, aabb.getMin().z); + openglframework::Vector3 aabbMax(aabb.getMax().x, aabb.getMax().y, aabb.getMax().z); + + // Render the AABB + AABB::render(aabbCenter, aabbMax - aabbMin, Color::green(), mColorShader, worldToCameraMatrix); + + proxyShape = proxyShape->getNext(); + } + } +} + void SceneDemo::removeAllContactPoints() { // Destroy all the visual contact points diff --git a/testbed/src/SceneDemo.h b/testbed/src/SceneDemo.h index a8b1941f..359c2374 100644 --- a/testbed/src/SceneDemo.h +++ b/testbed/src/SceneDemo.h @@ -98,6 +98,8 @@ class SceneDemo : public Scene { std::vector mPhysicsObjects; + rp3d::CollisionWorld* mPhysicsWorld; + // -------------------- Methods -------------------- // // Create the Shadow map FBO and texture @@ -116,14 +118,25 @@ class SceneDemo : public Scene { void renderContactPoints(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix); + + /// Render the AABBs + void renderAABBs(const openglframework::Matrix4& worldToCameraMatrix); + + /// Remove all contact points void removeAllContactPoints(); + /// Return a reference to the dynamics world + rp3d::DynamicsWorld* getDynamicsWorld(); + + /// Return a reference to the dynamics world + const rp3d::DynamicsWorld* getDynamicsWorld() const; + public: // -------------------- Methods -------------------- // /// Constructor - SceneDemo(const std::string& name, float sceneRadius, bool isShadowMappingEnabled = true); + SceneDemo(const std::string& name, EngineSettings& settings, float sceneRadius, bool isShadowMappingEnabled = true); /// Destructor virtual ~SceneDemo() override; @@ -158,6 +171,16 @@ inline void SceneDemo::setIsShadowMappingEnabled(bool isShadowMappingEnabled) { } } +// Return a reference to the dynamics world +inline rp3d::DynamicsWorld* SceneDemo::getDynamicsWorld() { + return dynamic_cast(mPhysicsWorld); +} + +// Return a reference to the dynamics world +inline const rp3d::DynamicsWorld* SceneDemo::getDynamicsWorld() const { + return dynamic_cast(mPhysicsWorld); +} + #endif diff --git a/testbed/src/TestbedApplication.cpp b/testbed/src/TestbedApplication.cpp index 2b9195e5..d94103ef 100644 --- a/testbed/src/TestbedApplication.cpp +++ b/testbed/src/TestbedApplication.cpp @@ -59,12 +59,14 @@ TestbedApplication::TestbedApplication(bool isFullscreen) mIsMultisamplingActive = true; mWidth = 1280; mHeight = 720; + mEngineSettings = EngineSettings::defaultSettings(); mSinglePhysicsStepEnabled = false; mSinglePhysicsStepDone = false; mWindowToFramebufferRatio = Vector2(1, 1); mIsShadowMappingEnabled = true; mIsVSyncEnabled = false; mIsContactPointsDisplayed = false; + mIsAABBsDisplayed = false; mIsWireframeEnabled = false; init(); @@ -97,39 +99,38 @@ void TestbedApplication::init() { void TestbedApplication::createScenes() { // Cubes scene - CubesScene* cubeScene = new CubesScene("Cubes"); + CubesScene* cubeScene = new CubesScene("Cubes", mEngineSettings); mScenes.push_back(cubeScene); // Joints scene - JointsScene* jointsScene = new JointsScene("Joints"); + JointsScene* jointsScene = new JointsScene("Joints", mEngineSettings); mScenes.push_back(jointsScene); // Collision shapes scene - CollisionShapesScene* collisionShapesScene = new CollisionShapesScene("Collision Shapes"); + CollisionShapesScene* collisionShapesScene = new CollisionShapesScene("Collision Shapes", mEngineSettings); mScenes.push_back(collisionShapesScene); // Heightfield shape scene - HeightFieldScene* heightFieldScene = new HeightFieldScene("Heightfield"); + HeightFieldScene* heightFieldScene = new HeightFieldScene("Heightfield", mEngineSettings); mScenes.push_back(heightFieldScene); // Raycast scene - RaycastScene* raycastScene = new RaycastScene("Raycast"); + RaycastScene* raycastScene = new RaycastScene("Raycast", mEngineSettings); mScenes.push_back(raycastScene); // Collision Detection scene - CollisionDetectionScene* collisionDetectionScene = new CollisionDetectionScene("Collision Detection"); + CollisionDetectionScene* collisionDetectionScene = new CollisionDetectionScene("Collision Detection", mEngineSettings); mScenes.push_back(collisionDetectionScene); // Concave Mesh scene - ConcaveMeshScene* concaveMeshScene = new ConcaveMeshScene("Concave Mesh"); + ConcaveMeshScene* concaveMeshScene = new ConcaveMeshScene("Concave Mesh", mEngineSettings); mScenes.push_back(concaveMeshScene); assert(mScenes.size() > 0); - mCurrentScene = mScenes[5]; - // Get the engine settings from the scene - mEngineSettings = mCurrentScene->getEngineSettings(); - mEngineSettings.timeStep = DEFAULT_TIMESTEP; + const int firstSceneIndex = 0; + + switchScene(mScenes[firstSceneIndex]); } // Remove all the scenes @@ -152,9 +153,8 @@ void TestbedApplication::updateSinglePhysicsStep() { // Update the physics of the current scene void TestbedApplication::updatePhysics() { - // Set the engine settings + // Update the elapsed time mEngineSettings.elapsedTime = mTimer.getPhysicsTime(); - mCurrentScene->setEngineSettings(mEngineSettings); if (mTimer.isRunning()) { @@ -202,6 +202,9 @@ void TestbedApplication::update() { // Display/Hide contact points mCurrentScene->setIsContactPointsDisplayed(mIsContactPointsDisplayed); + // Display/Hide the AABBs + mCurrentScene->setIsAABBsDisplayed(mIsAABBsDisplayed); + // Enable/Disable wireframe mode mCurrentScene->setIsWireframeEnabled(mIsWireframeEnabled); @@ -259,11 +262,6 @@ void TestbedApplication::switchScene(Scene* newScene) { mCurrentScene = newScene; - // Get the engine settings of the scene - float currentTimeStep = mEngineSettings.timeStep; - mEngineSettings = mCurrentScene->getEngineSettings(); - mEngineSettings.timeStep = currentTimeStep; - // Reset the scene mCurrentScene->reset(); diff --git a/testbed/src/TestbedApplication.h b/testbed/src/TestbedApplication.h index 8790a1f7..3a9fe071 100644 --- a/testbed/src/TestbedApplication.h +++ b/testbed/src/TestbedApplication.h @@ -38,9 +38,6 @@ using namespace nanogui; // Macro for OpenGL errors #define checkOpenGLErrors() checkOpenGLErrorsInternal(__FILE__,__LINE__) -// Constants -const float DEFAULT_TIMESTEP = 1.0f / 60.0f; - /// Class TestbedApplication class TestbedApplication : public Screen { @@ -109,6 +106,9 @@ class TestbedApplication : public Screen { /// True if contact points are displayed bool mIsContactPointsDisplayed; + /// True if the AABBs of physics objects are displayed + bool mIsAABBsDisplayed; + /// True if the wireframe rendering is enabled bool mIsWireframeEnabled; From 002264a5a14dbcaad67ce5364b4aabd32d29d184 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 2 Nov 2017 23:01:32 +0100 Subject: [PATCH 123/248] Remove unused files --- .../narrowphase/ConcaveVsConvexAlgorithm.cpp | 302 ------------------ .../narrowphase/ConcaveVsConvexAlgorithm.h | 196 ------------ 2 files changed, 498 deletions(-) delete mode 100644 src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp delete mode 100644 src/collision/narrowphase/ConcaveVsConvexAlgorithm.h diff --git a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp deleted file mode 100644 index 8a2475a2..00000000 --- a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp +++ /dev/null @@ -1,302 +0,0 @@ -/******************************************************************************** -* 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. * -* * -********************************************************************************/ -/* -// Libraries -#include "collision/shapes/ConcaveShape.h" -#include "collision/shapes/TriangleShape.h" -#include "ConcaveVsConvexAlgorithm.h" -#include "collision/CollisionDetection.h" -#include "engine/CollisionWorld.h" -#include - -using namespace reactphysics3d; - -// Report collision between a triangle of a concave shape and the convex mesh shape (for middle-phase) -void MiddlePhaseTriangleCallback::testTriangle(uint meshSubPart, uint triangleIndex, const Vector3* trianglePoints, - const Vector3* verticesNormals) { - - // Create a triangle collision shape - decimal margin = mConcaveShape->getTriangleMargin(); - TriangleShape* triangleShape = new (mAllocator.allocate(sizeof(TriangleShape))) - TriangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], - verticesNormals, meshSubPart, triangleIndex, margin); - - // Create a narrow phase info for the narrow-phase collision detection - NarrowPhaseInfo* firstNarrowPhaseInfo = narrowPhaseInfoList; - narrowPhaseInfoList = new (mAllocator.allocate(sizeof(NarrowPhaseInfo))) - NarrowPhaseInfo(mOverlappingPair, mConvexProxyShape->getCollisionShape(), - triangleShape, mConvexProxyShape->getLocalToWorldTransform(), - mConcaveProxyShape->getLocalToWorldTransform(), mConvexProxyShape->getCachedCollisionData(), - mConcaveProxyShape->getCachedCollisionData()); - narrowPhaseInfoList->next = firstNarrowPhaseInfo; -} - -// Return true and compute a contact info if the two bounding volumes collide -void ConcaveVsConvexAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - NarrowPhaseCallback* narrowPhaseCallback) { - -// ProxyShape* convexProxyShape; -// ProxyShape* concaveProxyShape; -// const ConvexShape* convexShape; -// const ConcaveShape* concaveShape; - -// // Collision shape 1 is convex, collision shape 2 is concave -// if (shape1Info.collisionShape->isConvex()) { -// convexProxyShape = shape1Info.proxyShape; -// convexShape = static_cast(shape1Info.collisionShape); -// concaveProxyShape = shape2Info.proxyShape; -// concaveShape = static_cast(shape2Info.collisionShape); -// } -// else { // Collision shape 2 is convex, collision shape 1 is concave -// convexProxyShape = shape2Info.proxyShape; -// convexShape = static_cast(shape2Info.collisionShape); -// concaveProxyShape = shape1Info.proxyShape; -// concaveShape = static_cast(shape1Info.collisionShape); -// } - -// // Set the parameters of the callback object -// ConvexVsTriangleCallback convexVsTriangleCallback; -// convexVsTriangleCallback.setCollisionDetection(mCollisionDetection); -// convexVsTriangleCallback.setConvexShape(convexShape); -// convexVsTriangleCallback.setConcaveShape(concaveShape); -// convexVsTriangleCallback.setProxyShapes(convexProxyShape, concaveProxyShape); -// convexVsTriangleCallback.setOverlappingPair(shape1Info.overlappingPair); - -// // Compute the convex shape AABB in the local-space of the convex shape -// AABB aabb; -// convexShape->computeAABB(aabb, convexProxyShape->getLocalToWorldTransform()); - -// // If smooth mesh collision is enabled for the concave mesh -// if (concaveShape->getIsSmoothMeshCollisionEnabled()) { - -// std::vector contactPoints; - -// SmoothCollisionNarrowPhaseCallback smoothNarrowPhaseCallback(contactPoints); - -// convexVsTriangleCallback.setNarrowPhaseCallback(&smoothNarrowPhaseCallback); - -// // Call the convex vs triangle callback for each triangle of the concave shape -// concaveShape->testAllTriangles(convexVsTriangleCallback, aabb); - -// // Run the smooth mesh collision algorithm -// processSmoothMeshCollision(shape1Info.overlappingPair, contactPoints, narrowPhaseCallback); -// } -// else { - -// convexVsTriangleCallback.setNarrowPhaseCallback(narrowPhaseCallback); - -// // Call the convex vs triangle callback for each triangle of the concave shape -// concaveShape->testAllTriangles(convexVsTriangleCallback, aabb); -// } -} - -//// Test collision between a triangle and the convex mesh shape -//void ConvexVsTriangleCallback::testTriangle(const Vector3* trianglePoints) { - -// // Create a triangle collision shape -// decimal margin = mConcaveShape->getTriangleMargin(); -// TriangleShape triangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], margin); - -// // Select the collision algorithm to use between the triangle and the convex shape -// NarrowPhaseAlgorithm* algo = mCollisionDetection->getCollisionAlgorithm(triangleShape.getType(), -// mConvexShape->getType()); - -// // If there is no collision algorithm between those two kinds of shapes -// if (algo == nullptr) return; - -// // Notify the narrow-phase algorithm about the overlapping pair we are going to test -// algo->setCurrentOverlappingPair(mOverlappingPair); - -// // Create the CollisionShapeInfo objects -// CollisionShapeInfo shapeConvexInfo(mConvexProxyShape, mConvexShape, mConvexProxyShape->getLocalToWorldTransform(), -// mOverlappingPair, mConvexProxyShape->getCachedCollisionData()); -// CollisionShapeInfo shapeConcaveInfo(mConcaveProxyShape, &triangleShape, -// mConcaveProxyShape->getLocalToWorldTransform(), -// mOverlappingPair, mConcaveProxyShape->getCachedCollisionData()); - -// // Use the collision algorithm to test collision between the triangle and the other convex shape -// algo->testCollision(shapeConvexInfo, shapeConcaveInfo, mNarrowPhaseCallback); -//} - -// Process the concave triangle mesh collision using the smooth mesh collision algorithm described -// by Pierre Terdiman (http://www.codercorner.com/MeshContacts.pdf). This is used to avoid the collision -// issue with some internal edges. -//void ConcaveVsConvexAlgorithm::processSmoothMeshCollision(OverlappingPair* overlappingPair, -// std::vector contactPoints, -// NarrowPhaseCallback* narrowPhaseCallback) { - -// // Set with the triangle vertices already processed to void further contacts with same triangle -// std::unordered_multimap processTriangleVertices; - -// // Sort the list of narrow-phase contacts according to their penetration depth -// std::sort(contactPoints.begin(), contactPoints.end(), ContactsDepthCompare()); - -// // For each contact point (from smaller penetration depth to larger) -// std::vector::const_iterator it; -// for (it = contactPoints.begin(); it != contactPoints.end(); ++it) { - -// const SmoothMeshContactInfo info = *it; -// const Vector3& contactPoint = info.isFirstShapeTriangle ? info.contactInfo.localPoint1 : info.contactInfo.localPoint2; - -// // Compute the barycentric coordinates of the point in the triangle -// decimal u, v, w; -// computeBarycentricCoordinatesInTriangle(info.triangleVertices[0], -// info.triangleVertices[1], -// info.triangleVertices[2], -// contactPoint, u, v, w); -// int nbZeros = 0; -// bool isUZero = approxEqual(u, 0, 0.0001); -// bool isVZero = approxEqual(v, 0, 0.0001); -// bool isWZero = approxEqual(w, 0, 0.0001); -// if (isUZero) nbZeros++; -// if (isVZero) nbZeros++; -// if (isWZero) nbZeros++; - -// // If it is a vertex contact -// if (nbZeros == 2) { - -// Vector3 contactVertex = !isUZero ? info.triangleVertices[0] : (!isVZero ? info.triangleVertices[1] : info.triangleVertices[2]); - -// // Check that this triangle vertex has not been processed yet -// if (!hasVertexBeenProcessed(processTriangleVertices, contactVertex)) { - -// // Keep the contact as it is and report it -// narrowPhaseCallback->notifyContact(overlappingPair, info.contactInfo); -// } -// } -// else if (nbZeros == 1) { // If it is an edge contact - -// Vector3 contactVertex1 = isUZero ? info.triangleVertices[1] : (isVZero ? info.triangleVertices[0] : info.triangleVertices[0]); -// Vector3 contactVertex2 = isUZero ? info.triangleVertices[2] : (isVZero ? info.triangleVertices[2] : info.triangleVertices[1]); - -// // Check that this triangle edge has not been processed yet -// if (!hasVertexBeenProcessed(processTriangleVertices, contactVertex1) && -// !hasVertexBeenProcessed(processTriangleVertices, contactVertex2)) { - -// // Keep the contact as it is and report it -// narrowPhaseCallback->notifyContact(overlappingPair, info.contactInfo); -// } - -// } -// else { // If it is a face contact - -// ContactPointInfo newContactInfo(info.contactInfo); - -// ProxyShape* firstShape; -// ProxyShape* secondShape; -// if (info.isFirstShapeTriangle) { -// firstShape = overlappingPair->getShape1(); -// secondShape = overlappingPair->getShape2(); -// } -// else { -// firstShape = overlappingPair->getShape2(); -// secondShape = overlappingPair->getShape1(); -// } - -// // We use the triangle normal as the contact normal -// Vector3 a = info.triangleVertices[1] - info.triangleVertices[0]; -// Vector3 b = info.triangleVertices[2] - info.triangleVertices[0]; -// Vector3 localNormal = a.cross(b); -// newContactInfo.normal = firstShape->getLocalToWorldTransform().getOrientation() * localNormal; -// Vector3 firstLocalPoint = info.isFirstShapeTriangle ? info.contactInfo.localPoint1 : info.contactInfo.localPoint2; -// Vector3 firstWorldPoint = firstShape->getLocalToWorldTransform() * firstLocalPoint; -// newContactInfo.normal.normalize(); -// if (newContactInfo.normal.dot(info.contactInfo.normal) < 0) { -// newContactInfo.normal = -newContactInfo.normal; -// } - -// // We recompute the contact point on the second body with the new normal as described in -// // the Smooth Mesh Contacts with GJK of the Game Physics Pearls book (from Gino van Den Bergen and -// // Dirk Gregorius) to avoid adding torque -// Transform worldToLocalSecondPoint = secondShape->getLocalToWorldTransform().getInverse(); -// if (info.isFirstShapeTriangle) { -// Vector3 newSecondWorldPoint = firstWorldPoint + newContactInfo.normal; -// newContactInfo.localPoint2 = worldToLocalSecondPoint * newSecondWorldPoint; -// } -// else { -// Vector3 newSecondWorldPoint = firstWorldPoint - newContactInfo.normal; -// newContactInfo.localPoint1 = worldToLocalSecondPoint * newSecondWorldPoint; -// } - -// // Report the contact -// narrowPhaseCallback->notifyContact(overlappingPair, newContactInfo); -// } - -// // Add the three vertices of the triangle to the set of processed -// // triangle vertices -// addProcessedVertex(processTriangleVertices, info.triangleVertices[0]); -// addProcessedVertex(processTriangleVertices, info.triangleVertices[1]); -// addProcessedVertex(processTriangleVertices, info.triangleVertices[2]); -// } -//} - -// Return true if the vertex is in the set of already processed vertices -bool ConcaveVsConvexAlgorithm::hasVertexBeenProcessed(const std::unordered_multimap& processTriangleVertices, const Vector3& vertex) const { - - int key = int(vertex.x * vertex.y * vertex.z); - - auto range = processTriangleVertices.equal_range(key); - for (auto it = range.first; it != range.second; ++it) { - if (vertex.x == it->second.x && vertex.y == it->second.y && vertex.z == it->second.z) return true; - } - - return false; -} - - -//// Called by a narrow-phase collision algorithm when a new contact has been found -//void SmoothCollisionNarrowPhaseCallback::notifyContact(OverlappingPair* overlappingPair, -// const ContactPointInfo& contactInfo) { -// Vector3 triangleVertices[3]; -// bool isFirstShapeTriangle; - -// // If the collision shape 1 is the triangle -// if (contactInfo.collisionShape1->getType() == CollisionShapeType::TRIANGLE) { -// assert(contactInfo.collisionShape2->getType() != CollisionShapeType::TRIANGLE); - -// const TriangleShape* triangleShape = static_cast(contactInfo.collisionShape1); -// triangleVertices[0] = triangleShape->getVertex(0); -// triangleVertices[1] = triangleShape->getVertex(1); -// triangleVertices[2] = triangleShape->getVertex(2); - -// isFirstShapeTriangle = true; -// } -// else { // If the collision shape 2 is the triangle -// assert(contactInfo.collisionShape2->getType() == CollisionShapeType::TRIANGLE); - -// const TriangleShape* triangleShape = static_cast(contactInfo.collisionShape2); -// triangleVertices[0] = triangleShape->getVertex(0); -// triangleVertices[1] = triangleShape->getVertex(1); -// triangleVertices[2] = triangleShape->getVertex(2); - -// isFirstShapeTriangle = false; -// } -// SmoothMeshContactInfo smoothContactInfo(contactInfo, isFirstShapeTriangle, triangleVertices[0], triangleVertices[1], triangleVertices[2]); - -// // Add the narrow-phase contact into the list of contact to process for -// // smooth mesh collision -// mContactPoints.push_back(smoothContactInfo); -//} -*/ diff --git a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h b/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h deleted file mode 100644 index 70cd3dbc..00000000 --- a/src/collision/narrowphase/ConcaveVsConvexAlgorithm.h +++ /dev/null @@ -1,196 +0,0 @@ -/******************************************************************************** -* 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_CONCAVE_VS_CONVEX_ALGORITHM_H -#define REACTPHYSICS3D_CONCAVE_VS_CONVEX_ALGORITHM_H - -// Libraries -#include "NarrowPhaseAlgorithm.h" -#include "collision/shapes/ConvexShape.h" -#include "collision/shapes/ConcaveShape.h" -#include "memory/SingleFrameAllocator.h" -#include - -/// Namespace ReactPhysics3D -namespace reactphysics3d { - -// Class ConvexVsTriangleCallback -class MiddlePhaseTriangleCallback : public TriangleCallback { - - protected: - - /// Broadphase overlapping pair - OverlappingPair* mOverlappingPair; - - /// Pointer to the concave proxy shape - ProxyShape* mConcaveProxyShape; - - /// Pointer to the convex proxy shape - ProxyShape* mConvexProxyShape; - - /// Pointer to the concave collision shape - const ConcaveShape* mConcaveShape; - - /// Reference to the single-frame memory allocator - Allocator& mAllocator; - - public: - - /// Pointer to the first element of the linked-list of narrow-phase info - NarrowPhaseInfo* narrowPhaseInfoList; - - /// Constructor - MiddlePhaseTriangleCallback(OverlappingPair* overlappingPair, - ProxyShape* concaveProxyShape, - ProxyShape* convexProxyShape, const ConcaveShape* concaveShape, - Allocator& allocator) - :mOverlappingPair(overlappingPair), mConcaveProxyShape(concaveProxyShape), - mConvexProxyShape(convexProxyShape), mConcaveShape(concaveShape), - mAllocator(allocator), narrowPhaseInfoList(nullptr) { - - } - - /// Test collision between a triangle and the convex mesh shape - virtual void testTriangle(uint meshSubpart, uint triangleIndex, const Vector3* trianglePoints, - const Vector3* verticesNormals) override; -}; - -// Class SmoothMeshContactInfo -struct SmoothMeshContactInfo { - - public: - - ContactManifoldInfo* contactManifoldInfo; - ContactPointInfo* contactInfo; - bool isFirstShapeTriangle; - Vector3 triangleVertices[3]; - bool isUVWZero[3]; - - /// Constructor - SmoothMeshContactInfo(ContactManifoldInfo* manifoldInfo, ContactPointInfo* contactPointInfo, - bool firstShapeTriangle, - const Vector3& trianglePoint1, const Vector3& trianglePoint2, - const Vector3& trianglePoint3, bool isUZero, bool isVZero, bool isWZero) - : contactManifoldInfo(manifoldInfo), contactInfo(contactPointInfo) { - - isFirstShapeTriangle = firstShapeTriangle; - - triangleVertices[0] = trianglePoint1; - triangleVertices[1] = trianglePoint2; - triangleVertices[2] = trianglePoint3; - - isUVWZero[0] = isUZero; - isUVWZero[1] = isVZero; - isUVWZero[2] = isWZero; - } - -}; - -struct ContactsDepthCompare { - bool operator()(const SmoothMeshContactInfo& contact1, const SmoothMeshContactInfo& contact2) - { - return contact1.contactInfo->penetrationDepth < contact2.contactInfo->penetrationDepth; - } -}; - -/// Method used to compare two smooth mesh contact info to sort them -//inline static bool contactsDepthCompare(const SmoothMeshContactInfo& contact1, -// const SmoothMeshContactInfo& contact2) { -// return contact1.contactInfo.penetrationDepth < contact2.contactInfo.penetrationDepth; -//} - -// TODO : Delete this -// Class SmoothCollisionNarrowPhaseCallback -class SmoothCollisionNarrowPhaseCallback { - - private: - - std::vector& mContactPoints; - - - public: - - // Constructor - SmoothCollisionNarrowPhaseCallback(std::vector& contactPoints) - : mContactPoints(contactPoints) { - - } - -}; - -// TODO : Delete this -// Class ConcaveVsConvexAlgorithm -class ConcaveVsConvexAlgorithm { - - protected : - - // -------------------- Attributes -------------------- // - - // -------------------- Methods -------------------- // - - /// Process the concave triangle mesh collision using the smooth mesh collision algorithm - void processSmoothMeshCollision(OverlappingPair* overlappingPair, - std::vector contactPoints, - NarrowPhaseCallback* narrowPhaseCallback); - - /// Add a triangle vertex into the set of processed triangles - void addProcessedVertex(std::unordered_multimap& processTriangleVertices, - const Vector3& vertex); - - /// Return true if the vertex is in the set of already processed vertices - bool hasVertexBeenProcessed(const std::unordered_multimap& processTriangleVertices, - const Vector3& vertex) const; - - public : - - // -------------------- Methods -------------------- // - - /// Constructor - ConcaveVsConvexAlgorithm() = default; - - /// Destructor - ~ConcaveVsConvexAlgorithm() = default; - - /// Private copy-constructor - ConcaveVsConvexAlgorithm(const ConcaveVsConvexAlgorithm& algorithm) = delete; - - /// Private assignment operator - ConcaveVsConvexAlgorithm& operator=(const ConcaveVsConvexAlgorithm& algorithm) = delete; - - /// Compute a contact info if the two bounding volume collide - void testCollision(const NarrowPhaseInfo* narrowPhaseInfo, - NarrowPhaseCallback* narrowPhaseCallback); -}; - -// Add a triangle vertex into the set of processed triangles -inline void ConcaveVsConvexAlgorithm::addProcessedVertex(std::unordered_multimap& processTriangleVertices, const Vector3& vertex) { - processTriangleVertices.insert(std::make_pair(int(vertex.x * vertex.y * vertex.z), vertex)); -} - -} - -#endif - -*/ From fd427c0337b58422d1a4bd5e575ba10fc29f0968 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Fri, 3 Nov 2017 07:11:19 +0100 Subject: [PATCH 124/248] Fix compilation errors because of removed files --- CMakeLists.txt | 2 -- src/collision/narrowphase/DefaultCollisionDispatch.h | 1 - 2 files changed, 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index dcc2e4bf..c4cfde6e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -83,8 +83,6 @@ SET (REACTPHYSICS3D_SOURCES "src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp" "src/collision/narrowphase/SphereVsCapsuleAlgorithm.h" "src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp" - "src/collision/narrowphase/ConcaveVsConvexAlgorithm.h" - "src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp" "src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h" "src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp" "src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h" diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.h b/src/collision/narrowphase/DefaultCollisionDispatch.h index 7b3945d3..779f7048 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.h +++ b/src/collision/narrowphase/DefaultCollisionDispatch.h @@ -28,7 +28,6 @@ // Libraries #include "CollisionDispatch.h" -#include "ConcaveVsConvexAlgorithm.h" #include "SphereVsSphereAlgorithm.h" #include "SphereVsConvexPolyhedronAlgorithm.h" #include "SphereVsCapsuleAlgorithm.h" From 6e322882eb21e66a44a1f055beb75f4b52f9408e Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 5 Nov 2017 23:10:55 +0100 Subject: [PATCH 125/248] Fix wrong world AABB computation that caused broad-phase collision misses --- src/collision/shapes/CollisionShape.cpp | 50 +++++++++++++++++-------- 1 file changed, 34 insertions(+), 16 deletions(-) diff --git a/src/collision/shapes/CollisionShape.cpp b/src/collision/shapes/CollisionShape.cpp index d03b4a1c..9622e795 100644 --- a/src/collision/shapes/CollisionShape.cpp +++ b/src/collision/shapes/CollisionShape.cpp @@ -32,15 +32,19 @@ using namespace reactphysics3d; // Constructor -CollisionShape::CollisionShape(CollisionShapeName name, CollisionShapeType type) : mName(name), mType(type), mScaling(1.0, 1.0, 1.0) { +CollisionShape::CollisionShape(CollisionShapeName name, CollisionShapeType type) + : mType(type), mName(name), mScaling(1.0, 1.0, 1.0) { } -// Compute the world-space AABB of the collision shape given a transform +// Compute the world-space AABB of the collision shape given a transform from shape +// local-space to world-space. The technique is described in the book Real-Time Collision +// Detection by Christer Ericson. /** * @param[out] aabb The axis-aligned bounding box (AABB) of the collision shape * computed in world-space coordinates - * @param transform Transform used to compute the AABB of the collision shape + * @param transform Transform from shape local-space to world-space used to compute + * the AABB of the collision shape */ void CollisionShape::computeAABB(AABB& aabb, const Transform& transform) const { @@ -51,20 +55,34 @@ void CollisionShape::computeAABB(AABB& aabb, const Transform& transform) const { Vector3 maxBounds; getLocalBounds(minBounds, maxBounds); - // Rotate the local bounds according to the orientation of the body - Matrix3x3 worldAxis = transform.getOrientation().getMatrix().getAbsoluteMatrix(); - Vector3 worldMinBounds(worldAxis.getColumn(0).dot(minBounds), - worldAxis.getColumn(1).dot(minBounds), - worldAxis.getColumn(2).dot(minBounds)); - Vector3 worldMaxBounds(worldAxis.getColumn(0).dot(maxBounds), - worldAxis.getColumn(1).dot(maxBounds), - worldAxis.getColumn(2).dot(maxBounds)); + const Vector3 translation = transform.getPosition(); + Matrix3x3 matrix = transform.getOrientation().getMatrix(); + Vector3 resultMin; + Vector3 resultMax; - // Compute the minimum and maximum coordinates of the rotated extents - Vector3 minCoordinates = transform.getPosition() + worldMinBounds; - Vector3 maxCoordinates = transform.getPosition() + worldMaxBounds; + // For each of the three axis + for (int i=0; i<3; i++) { + + // Add translation component + resultMin[i] = translation[i]; + resultMax[i] = translation[i]; + + for (int j=0; j<3; j++) { + decimal e = matrix[i][j] * minBounds[j]; + decimal f = matrix[i][j] * maxBounds[j]; + + if (e < f) { + resultMin[i] += e; + resultMax[i] += f; + } + else { + resultMin[i] += f; + resultMax[i] += e; + } + } + } // Update the AABB with the new minimum and maximum coordinates - aabb.setMin(minCoordinates); - aabb.setMax(maxCoordinates); + aabb.setMin(resultMin); + aabb.setMax(resultMax); } From e91cded83161106314db4d5f9680595d66a6b2c0 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 5 Nov 2017 23:15:47 +0100 Subject: [PATCH 126/248] Update code documentation and fix warnings --- src/collision/shapes/BoxShape.cpp | 1 - src/collision/shapes/BoxShape.h | 15 ++++----------- src/collision/shapes/ConcaveMeshShape.h | 2 +- src/mathematics/Matrix3x3.h | 6 +++--- 4 files changed, 8 insertions(+), 16 deletions(-) diff --git a/src/collision/shapes/BoxShape.cpp b/src/collision/shapes/BoxShape.cpp index 01c4d965..6b8c8d6b 100644 --- a/src/collision/shapes/BoxShape.cpp +++ b/src/collision/shapes/BoxShape.cpp @@ -35,7 +35,6 @@ using namespace reactphysics3d; // Constructor /** * @param extent The vector with the three extents of the box (in meters) - * @param margin The collision margin (in meters) around the collision shape */ BoxShape::BoxShape(const Vector3& extent) : ConvexPolyhedronShape(CollisionShapeName::BOX), mExtent(extent) { diff --git a/src/collision/shapes/BoxShape.h b/src/collision/shapes/BoxShape.h index 56c14797..5643a5c8 100644 --- a/src/collision/shapes/BoxShape.h +++ b/src/collision/shapes/BoxShape.h @@ -41,14 +41,7 @@ namespace reactphysics3d { * This class represents a 3D box shape. Those axis are unit length. * The three extents are half-widths of the box along the three * axis x, y, z local axis. The "transform" of the corresponding - * rigid body will give an orientation and a position to the box. This - * collision shape uses an extra margin distance around it for collision - * detection purpose. The default margin is 4cm (if your units are meters, - * which is recommended). In case, you want to simulate small objects - * (smaller than the margin distance), you might want to reduce the margin by - * specifying your own margin distance using the "margin" parameter in the - * constructor of the box shape. Otherwise, it is recommended to use the - * default margin distance by not using the "margin" parameter in the constructor. + * body will give an orientation and a position to the box. */ class BoxShape : public ConvexPolyhedronShape { @@ -171,9 +164,9 @@ inline size_t BoxShape::getSizeInBytes() const { // Return a local support point in a given direction without the objec margin inline Vector3 BoxShape::getLocalSupportPointWithoutMargin(const Vector3& direction) const { - return Vector3(direction.x < 0.0 ? -mExtent.x : mExtent.x, - direction.y < 0.0 ? -mExtent.y : mExtent.y, - direction.z < 0.0 ? -mExtent.z : mExtent.z); + return Vector3(direction.x < decimal(0.0) ? -mExtent.x : mExtent.x, + direction.y < decimal(0.0) ? -mExtent.y : mExtent.y, + direction.z < decimal(0.0) ? -mExtent.z : mExtent.z); } // Return true if a point is inside the collision shape diff --git a/src/collision/shapes/ConcaveMeshShape.h b/src/collision/shapes/ConcaveMeshShape.h index b99f2b4a..82c08794 100644 --- a/src/collision/shapes/ConcaveMeshShape.h +++ b/src/collision/shapes/ConcaveMeshShape.h @@ -103,7 +103,7 @@ class ConcaveMeshRaycastCallback : public DynamicAABBTreeRaycastCallback { // Class ConcaveMeshShape /** * This class represents a static concave mesh shape. Note that collision detection - * with a concave mesh shape can be very expensive. You should use only use + * with a concave mesh shape can be very expensive. You should only use * this shape for a static mesh. */ class ConcaveMeshShape : public ConcaveShape { diff --git a/src/mathematics/Matrix3x3.h b/src/mathematics/Matrix3x3.h index dfa23085..ebb8792d 100644 --- a/src/mathematics/Matrix3x3.h +++ b/src/mathematics/Matrix3x3.h @@ -233,9 +233,9 @@ inline Matrix3x3 Matrix3x3::computeSkewSymmetricMatrixForCrossProduct(const Vect // Return the matrix with absolute values inline Matrix3x3 Matrix3x3::getAbsoluteMatrix() const { - return Matrix3x3(fabs(mRows[0][0]), fabs(mRows[0][1]), fabs(mRows[0][2]), - fabs(mRows[1][0]), fabs(mRows[1][1]), fabs(mRows[1][2]), - fabs(mRows[2][0]), fabs(mRows[2][1]), fabs(mRows[2][2])); + return Matrix3x3(std::fabs(mRows[0][0]), std::fabs(mRows[0][1]), std::fabs(mRows[0][2]), + std::fabs(mRows[1][0]), std::fabs(mRows[1][1]), std::fabs(mRows[1][2]), + std::fabs(mRows[2][0]), std::fabs(mRows[2][1]), std::fabs(mRows[2][2])); } // Overloaded operator for addition From c6f93789975013df309f735516515ff6c2b91636 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 8 Nov 2017 21:13:02 +0100 Subject: [PATCH 127/248] Enable vsync in the testbed application --- testbed/src/TestbedApplication.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/testbed/src/TestbedApplication.cpp b/testbed/src/TestbedApplication.cpp index d94103ef..f2a43bc1 100644 --- a/testbed/src/TestbedApplication.cpp +++ b/testbed/src/TestbedApplication.cpp @@ -64,7 +64,7 @@ TestbedApplication::TestbedApplication(bool isFullscreen) mSinglePhysicsStepDone = false; mWindowToFramebufferRatio = Vector2(1, 1); mIsShadowMappingEnabled = true; - mIsVSyncEnabled = false; + mIsVSyncEnabled = true; mIsContactPointsDisplayed = false; mIsAABBsDisplayed = false; mIsWireframeEnabled = false; From b39bb3ba37f4ae068d31afeb8ce169fa2b1f5bb6 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 8 Nov 2017 21:14:21 +0100 Subject: [PATCH 128/248] Initialize the timestep in the DynamicsWorld constructor --- src/engine/DynamicsWorld.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index 09712c3c..26835166 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -44,7 +44,7 @@ DynamicsWorld::DynamicsWorld(const Vector3 &gravity) mConstraintSolver(mMapBodyToConstrainedVelocityIndex), mNbVelocitySolverIterations(DEFAULT_VELOCITY_SOLVER_NB_ITERATIONS), mNbPositionSolverIterations(DEFAULT_POSITION_SOLVER_NB_ITERATIONS), - mIsSleepingEnabled(SLEEPING_ENABLED), mGravity(gravity), + mIsSleepingEnabled(SLEEPING_ENABLED), mGravity(gravity), mTimeStep(decimal(1.0f / 60.0f)), mIsGravityEnabled(true), mConstrainedLinearVelocities(nullptr), mConstrainedAngularVelocities(nullptr), mSplitLinearVelocities(nullptr), mSplitAngularVelocities(nullptr), mConstrainedPositions(nullptr), From 013431487eb633f4df09ed6c4292091ae0ef6e4e Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 8 Nov 2017 21:17:16 +0100 Subject: [PATCH 129/248] Rename setScaling() to setLocalScaling() --- src/collision/ProxyShape.h | 2 +- src/collision/shapes/CollisionShape.h | 4 ++-- src/collision/shapes/ConvexMeshShape.h | 21 ++++++--------------- 3 files changed, 9 insertions(+), 18 deletions(-) diff --git a/src/collision/ProxyShape.h b/src/collision/ProxyShape.h index 36bec740..8282af01 100644 --- a/src/collision/ProxyShape.h +++ b/src/collision/ProxyShape.h @@ -332,7 +332,7 @@ inline void ProxyShape::setCollideWithMaskBits(unsigned short collideWithMaskBit * @return The local scaling vector */ inline Vector3 ProxyShape::getLocalScaling() const { - return mCollisionShape->getScaling(); + return mCollisionShape->getLocalScaling(); } // Set the local scaling vector of the collision shape diff --git a/src/collision/shapes/CollisionShape.h b/src/collision/shapes/CollisionShape.h index 77f96dfb..f6690c58 100644 --- a/src/collision/shapes/CollisionShape.h +++ b/src/collision/shapes/CollisionShape.h @@ -113,7 +113,7 @@ class CollisionShape { virtual void getLocalBounds(Vector3& min, Vector3& max) const=0; /// Return the scaling vector of the collision shape - Vector3 getScaling() const; + Vector3 getLocalScaling() const; /// Set the local scaling vector of the collision shape virtual void setLocalScaling(const Vector3& scaling); @@ -147,7 +147,7 @@ inline CollisionShapeType CollisionShape::getType() const { } // Return the scaling vector of the collision shape -inline Vector3 CollisionShape::getScaling() const { +inline Vector3 CollisionShape::getLocalScaling() const { return mScaling; } diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index 4ceabe11..71077af2 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -46,18 +46,9 @@ class CollisionWorld; // Class ConvexMeshShape /** * This class represents a convex mesh shape. In order to create a convex mesh shape, you - * need to indicate the local-space position of the mesh vertices. You do it either by - * passing a vertices array to the constructor or using the addVertex() method. Make sure - * that the set of vertices that you use to create the shape are indeed part of a convex - * mesh. The center of mass of the shape will be at the origin of the local-space geometry - * that you use to create the mesh. The method used for collision detection with a convex - * mesh shape has an O(n) running time with "n" beeing the number of vertices in the mesh. - * Therefore, you should try not to use too many vertices. However, it is possible to speed - * up the collision detection by using the edges information of your mesh. The running time - * of the collision detection that uses the edges is almost O(1) constant time at the cost - * of additional memory used to store the vertices. You can indicate edges information - * with the addEdge() method. Then, you must use the setIsEdgesInformationUsed(true) method - * in order to use the edges information for collision detection. + * need to indicate the local-space position of the mesh vertices. The center of mass + * of the shape will be at the origin of the local-space geometry that you use to create + * the mesh. */ class ConvexMeshShape : public ConvexPolyhedronShape { @@ -79,9 +70,6 @@ class ConvexMeshShape : public ConvexPolyhedronShape { /// Recompute the bounds of the mesh void recalculateBounds(); - /// Set the scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling) override; - /// Return a local support point in a given direction without the object margin. virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction) const override; @@ -110,6 +98,9 @@ class ConvexMeshShape : public ConvexPolyhedronShape { /// Deleted assignment operator ConvexMeshShape& operator=(const ConvexMeshShape& shape) = delete; + /// Set the scaling vector of the collision shape + virtual void setLocalScaling(const Vector3& scaling) override; + /// Return the local bounds of the shape in x, y and z directions virtual void getLocalBounds(Vector3& min, Vector3& max) const override; From 8bfa6dd137d49e448cc5a5565e5deffac6b8388c Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 8 Nov 2017 21:26:15 +0100 Subject: [PATCH 130/248] Fix issue : the scaling factor was not used when recomputing AABB tree for concave mesh shape --- src/collision/shapes/ConcaveMeshShape.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/collision/shapes/ConcaveMeshShape.cpp b/src/collision/shapes/ConcaveMeshShape.cpp index 84e95e2c..566b7bc4 100644 --- a/src/collision/shapes/ConcaveMeshShape.cpp +++ b/src/collision/shapes/ConcaveMeshShape.cpp @@ -57,6 +57,11 @@ void ConcaveMeshShape::initBVHTree() { // Get the triangle vertices triangleVertexArray->getTriangleVertices(triangleIndex, trianglePoints); + // Apply the scaling factor to the vertices + trianglePoints[0] *= mScaling.x; + trianglePoints[1] *= mScaling.y; + trianglePoints[2] *= mScaling.z; + // Create the AABB for the triangle AABB aabb = AABB::createAABBForTriangle(trianglePoints); From de95e15147e8edf8d72a2f1177e7f8de06ebb0c5 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 8 Nov 2017 21:28:00 +0100 Subject: [PATCH 131/248] Fix issue with the shape order in concave vs convex middle-phase collision detection --- src/collision/MiddlePhaseTriangleCallback.cpp | 15 +++++++++++---- 1 file changed, 11 insertions(+), 4 deletions(-) diff --git a/src/collision/MiddlePhaseTriangleCallback.cpp b/src/collision/MiddlePhaseTriangleCallback.cpp index de6c22ea..9d163799 100644 --- a/src/collision/MiddlePhaseTriangleCallback.cpp +++ b/src/collision/MiddlePhaseTriangleCallback.cpp @@ -38,12 +38,19 @@ void MiddlePhaseTriangleCallback::testTriangle(uint meshSubPart, uint triangleIn TriangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], verticesNormals, meshSubPart, triangleIndex); + bool isShape1Convex = mOverlappingPair->getShape1()->getCollisionShape()->isConvex(); + ProxyShape* shape1 = isShape1Convex ? mConvexProxyShape : mConcaveProxyShape; + ProxyShape* shape2 = isShape1Convex ? mConcaveProxyShape : mConvexProxyShape; + // Create a narrow phase info for the narrow-phase collision detection NarrowPhaseInfo* firstNarrowPhaseInfo = narrowPhaseInfoList; narrowPhaseInfoList = new (mAllocator.allocate(sizeof(NarrowPhaseInfo))) - NarrowPhaseInfo(mOverlappingPair, mConvexProxyShape->getCollisionShape(), - triangleShape, mConvexProxyShape->getLocalToWorldTransform(), - mConcaveProxyShape->getLocalToWorldTransform(), mConvexProxyShape->getCachedCollisionData(), - mConcaveProxyShape->getCachedCollisionData(), mAllocator); + NarrowPhaseInfo(mOverlappingPair, + isShape1Convex ? mConvexProxyShape->getCollisionShape() : triangleShape, + isShape1Convex ? triangleShape : mConvexProxyShape->getCollisionShape(), + shape1->getLocalToWorldTransform(), + shape2->getLocalToWorldTransform(), + shape1->getCachedCollisionData(), + shape2->getCachedCollisionData(), mAllocator); narrowPhaseInfoList->next = firstNarrowPhaseInfo; } From 222636391e89ad3718cb00985120de8ba1eb18c9 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Fri, 10 Nov 2017 17:51:02 +0100 Subject: [PATCH 132/248] Use the true triangle face normal if contact is not on an edge in smooth triangle contact --- src/collision/shapes/TriangleShape.cpp | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/src/collision/shapes/TriangleShape.cpp b/src/collision/shapes/TriangleShape.cpp index 263595b3..142ba181 100644 --- a/src/collision/shapes/TriangleShape.cpp +++ b/src/collision/shapes/TriangleShape.cpp @@ -133,13 +133,22 @@ void TriangleShape::computeSmoothMeshContact(Vector3 localContactPointTriangle, /// normal of the mesh at this point. The idea to solve this problem is to use the real (smooth) surface /// normal of the mesh at this point as the contact normal. This technique is described in the chapter 5 /// of the Game Physics Pearl book by Gino van der Bergen and Dirk Gregorius. The vertices normals of the -/// mesh are either provided by the user or precomputed if the user did not provide them. +/// mesh are either provided by the user or precomputed if the user did not provide them. Note that we only +/// use the interpolated normal if the contact point is on an edge of the triangle. If the contact is in the +/// middle of the triangle, we return the true triangle normal. Vector3 TriangleShape::computeSmoothLocalContactNormalForTriangle(const Vector3& localContactPoint) const { // Compute the barycentric coordinates of the point in the triangle decimal u, v, w; computeBarycentricCoordinatesInTriangle(mPoints[0], mPoints[1], mPoints[2], localContactPoint, u, v, w); + // If the contact is in the middle of the triangle face (not on the edges) + if (u > MACHINE_EPSILON && v > MACHINE_EPSILON && w > MACHINE_EPSILON) { + + // We return the true triangle face normal (not the interpolated one) + return mNormal; + } + // We compute the contact normal as the barycentric interpolation of the three vertices normals return (u * mVerticesNormals[0] + v * mVerticesNormals[1] + w * mVerticesNormals[2]).getUnit(); } From e9709c3db50add07cb4b9de05aedb4d8dbba983f Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Fri, 10 Nov 2017 19:57:50 +0100 Subject: [PATCH 133/248] Refactor the Profiler. Now there is one profiler instance per CollisionWorld/DynamicsWorld instance instead of a static one --- src/body/CollisionBody.cpp | 7 ++ src/body/CollisionBody.h | 24 ++++ src/body/RigidBody.cpp | 28 ++++- src/body/RigidBody.h | 7 ++ src/collision/CollisionDetection.cpp | 106 +++--------------- src/collision/CollisionDetection.h | 36 +++++- src/collision/MiddlePhaseTriangleCallback.cpp | 7 ++ src/collision/MiddlePhaseTriangleCallback.h | 17 +++ src/collision/ProxyShape.h | 26 +++++ .../broadphase/BroadPhaseAlgorithm.cpp | 7 ++ .../broadphase/BroadPhaseAlgorithm.h | 30 ++++- src/collision/broadphase/DynamicAABBTree.cpp | 4 +- src/collision/broadphase/DynamicAABBTree.h | 24 ++++ .../CapsuleVsConvexPolyhedronAlgorithm.cpp | 10 +- src/collision/narrowphase/CollisionDispatch.h | 29 ++++- ...xPolyhedronVsConvexPolyhedronAlgorithm.cpp | 7 ++ .../narrowphase/DefaultCollisionDispatch.h | 25 +++++ .../narrowphase/GJK/GJKAlgorithm.cpp | 2 +- src/collision/narrowphase/GJK/GJKAlgorithm.h | 24 ++++ .../narrowphase/NarrowPhaseAlgorithm.h | 24 ++++ .../narrowphase/SAT/SATAlgorithm.cpp | 6 +- src/collision/narrowphase/SAT/SATAlgorithm.h | 25 +++++ .../SphereVsConvexPolyhedronAlgorithm.cpp | 14 +++ src/collision/shapes/CollisionShape.cpp | 2 +- src/collision/shapes/CollisionShape.h | 25 +++++ src/collision/shapes/ConcaveMeshShape.cpp | 16 ++- src/collision/shapes/ConcaveMeshShape.h | 35 ++++++ src/collision/shapes/HeightFieldShape.cpp | 16 ++- src/collision/shapes/HeightFieldShape.h | 17 +++ src/collision/shapes/TriangleShape.cpp | 3 +- src/engine/CollisionWorld.cpp | 13 +++ src/engine/CollisionWorld.h | 21 ++++ src/engine/ConstraintSolver.cpp | 12 +- src/engine/ConstraintSolver.h | 23 ++++ src/engine/ContactSolver.cpp | 12 +- src/engine/ContactSolver.h | 24 ++++ src/engine/DynamicsWorld.cpp | 43 ++++--- src/engine/DynamicsWorld.h | 14 --- src/engine/Profiler.cpp | 35 +++++- src/engine/Profiler.h | 82 +++++++++----- .../CollisionDetectionScene.cpp | 69 +++++++----- .../CollisionDetectionScene.h | 2 +- .../collisionshapes/CollisionShapesScene.cpp | 9 +- .../scenes/concavemesh/ConcaveMeshScene.cpp | 7 ++ testbed/scenes/cubes/CubesScene.cpp | 6 + .../scenes/heightfield/HeightFieldScene.cpp | 9 +- testbed/scenes/joints/JointsScene.cpp | 6 + testbed/scenes/raycast/RaycastScene.cpp | 6 + testbed/src/Scene.h | 4 +- 49 files changed, 790 insertions(+), 210 deletions(-) mode change 100755 => 100644 testbed/scenes/collisiondetection/CollisionDetectionScene.h mode change 100755 => 100644 testbed/scenes/cubes/CubesScene.cpp diff --git a/src/body/CollisionBody.cpp b/src/body/CollisionBody.cpp index 64ce6467..e588f93c 100644 --- a/src/body/CollisionBody.cpp +++ b/src/body/CollisionBody.cpp @@ -74,6 +74,13 @@ ProxyShape* CollisionBody::addCollisionShape(CollisionShape* collisionShape, sizeof(ProxyShape))) ProxyShape(this, collisionShape, transform, decimal(1)); +#ifdef IS_PROFILING_ACTIVE + + // Set the profiler + proxyShape->setProfiler(mProfiler); + +#endif + // Add it to the list of proxy collision shapes of the body if (mProxyCollisionShapes == nullptr) { mProxyCollisionShapes = proxyShape; diff --git a/src/body/CollisionBody.h b/src/body/CollisionBody.h index 2d5101b9..9943dc86 100644 --- a/src/body/CollisionBody.h +++ b/src/body/CollisionBody.h @@ -36,6 +36,7 @@ #include "collision/RaycastInfo.h" #include "memory/PoolAllocator.h" #include "configuration.h" +#include "engine/Profiler.h" /// Namespace reactphysics3d namespace reactphysics3d { @@ -85,6 +86,13 @@ class CollisionBody : public Body { /// Reference to the world the body belongs to CollisionWorld& mWorld; +#ifdef IS_PROFILING_ACTIVE + + /// Pointer to the profiler + Profiler* mProfiler; + +#endif + // -------------------- Methods -------------------- // /// Reset the contact manifold lists @@ -177,6 +185,13 @@ class CollisionBody : public Body { /// Return the body local-space coordinates of a vector given in the world-space coordinates Vector3 getLocalVector(const Vector3& worldVector) const; +#ifdef IS_PROFILING_ACTIVE + + /// Set the profiler + virtual void setProfiler(Profiler* profiler); + +#endif + // -------------------- Friendship -------------------- // friend class CollisionWorld; @@ -313,6 +328,15 @@ inline bool CollisionBody::testAABBOverlap(const AABB& worldAABB) const { return worldAABB.testCollision(getAABB()); } +#ifdef IS_PROFILING_ACTIVE + +// Set the profiler +inline void CollisionBody::setProfiler(Profiler* profiler) { + mProfiler = profiler; +} + +#endif + } #endif diff --git a/src/body/RigidBody.cpp b/src/body/RigidBody.cpp index 6e6a55e6..d0f0c782 100644 --- a/src/body/RigidBody.cpp +++ b/src/body/RigidBody.cpp @@ -228,6 +228,13 @@ ProxyShape* RigidBody::addCollisionShape(CollisionShape* collisionShape, sizeof(ProxyShape))) ProxyShape(this, collisionShape, transform, mass); +#ifdef IS_PROFILING_ACTIVE + + // Set the profiler + proxyShape->setProfiler(mProfiler); + +#endif + // Add it to the list of proxy collision shapes of the body if (mProxyCollisionShapes == nullptr) { mProxyCollisionShapes = proxyShape; @@ -410,7 +417,7 @@ void RigidBody::recomputeMassInformation() { // Update the broad-phase state for this body (because it has moved for instance) void RigidBody::updateBroadPhaseState() const { - PROFILE("RigidBody::updateBroadPhaseState()"); + PROFILE("RigidBody::updateBroadPhaseState()", mProfiler); DynamicsWorld& world = static_cast(mWorld); const Vector3 displacement = world.mTimeStep * mLinearVelocity; @@ -427,3 +434,22 @@ void RigidBody::updateBroadPhaseState() const { } } +#ifdef IS_PROFILING_ACTIVE + +// Set the profiler +void RigidBody::setProfiler(Profiler* profiler) { + + CollisionBody::setProfiler(profiler); + + // Set the profiler for each proxy shape + ProxyShape* proxyShape = getProxyShapesList(); + while (proxyShape != nullptr) { + + proxyShape->setProfiler(profiler); + + proxyShape = proxyShape->getNext(); + } +} + +#endif + diff --git a/src/body/RigidBody.h b/src/body/RigidBody.h index a38b53d5..6ba7a596 100644 --- a/src/body/RigidBody.h +++ b/src/body/RigidBody.h @@ -227,6 +227,13 @@ class RigidBody : public CollisionBody { /// the collision shapes attached to the body. void recomputeMassInformation(); +#ifdef IS_PROFILING_ACTIVE + + /// Set the profiler + void setProfiler(Profiler* profiler) override; + +#endif + // -------------------- Friendship -------------------- // friend class DynamicsWorld; diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index baaf0db5..7cb865f9 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -57,12 +57,19 @@ CollisionDetection::CollisionDetection(CollisionWorld* world, PoolAllocator& mem // Fill-in the collision detection matrix with algorithms fillInCollisionMatrix(); + +#ifdef IS_PROFILING_ACTIVE + + mProfiler = nullptr; + +#endif + } // Compute the collision detection void CollisionDetection::computeCollisionDetection() { - PROFILE("CollisionDetection::computeCollisionDetection()"); + PROFILE("CollisionDetection::computeCollisionDetection()", mProfiler); // Compute the broad-phase collision detection computeBroadPhase(); @@ -80,7 +87,7 @@ void CollisionDetection::computeCollisionDetection() { // Compute the broad-phase collision detection void CollisionDetection::computeBroadPhase() { - PROFILE("CollisionDetection::computeBroadPhase()"); + PROFILE("CollisionDetection::computeBroadPhase()", mProfiler); // If new collision shapes have been added to bodies if (mIsCollisionShapesAdded) { @@ -95,7 +102,7 @@ void CollisionDetection::computeBroadPhase() { // Compute the middle-phase collision detection void CollisionDetection::computeMiddlePhase() { - PROFILE("CollisionDetection::computeMiddlePhase()"); + PROFILE("CollisionDetection::computeMiddlePhase()", mProfiler); // For each possible collision pair of bodies map::iterator it; @@ -219,6 +226,13 @@ void CollisionDetection::computeConvexVsConcaveMiddlePhase(OverlappingPair* pair MiddlePhaseTriangleCallback middlePhaseCallback(pair, concaveProxyShape, convexProxyShape, concaveShape, allocator); +#ifdef IS_PROFILING_ACTIVE + + // Set the profiler + middlePhaseCallback.setProfiler(mProfiler); + +#endif + // Compute the convex shape AABB in the local-space of the convex shape const Transform convexToConcaveTransform = concaveProxyShape->getLocalToWorldTransform().getInverse() * convexProxyShape->getLocalToWorldTransform(); @@ -236,7 +250,7 @@ void CollisionDetection::computeConvexVsConcaveMiddlePhase(OverlappingPair* pair // Compute the narrow-phase collision detection void CollisionDetection::computeNarrowPhase() { - PROFILE("CollisionDetection::computeNarrowPhase()"); + PROFILE("CollisionDetection::computeNarrowPhase()", mProfiler); NarrowPhaseInfo* currentNarrowPhaseInfo = mNarrowPhaseInfoList; while (currentNarrowPhaseInfo != nullptr) { @@ -444,90 +458,6 @@ void CollisionDetection::reportAllContacts() { } } -// Process the potential contacts where one collion is a concave shape. -// This method processes the concave triangle mesh collision using the smooth mesh collision algorithm described -// by Pierre Terdiman (http://www.codercorner.com/MeshContacts.pdf). This is used to avoid the collision -// issue with some internal edges. -void CollisionDetection::processSmoothMeshContacts(OverlappingPair* pair) { - -// // Set with the triangle vertices already processed to void further contacts with same triangle -// std::unordered_multimap processTriangleVertices; - -// std::vector smoothContactPoints; - -// // If the collision shape 1 is the triangle -// bool isFirstShapeTriangle = pair->getShape1()->getCollisionShape()->getType() == CollisionShapeType::TRIANGLE; -// assert(isFirstShapeTriangle || pair->getShape2()->getCollisionShape()->getType() == CollisionShapeType::TRIANGLE); -// assert(!isFirstShapeTriangle || pair->getShape2()->getCollisionShape()->getType() != CollisionShapeType::TRIANGLE); - -// const TriangleShape* triangleShape = nullptr; -// if (isFirstShapeTriangle) { -// triangleShape = static_cast(pair->getShape1()->getCollisionShape()); -// } -// else { -// triangleShape = static_cast(pair->getShape2()->getCollisionShape()); -// } -// assert(triangleShape != nullptr); - -// // Get the temporary memory allocator -// Allocator& allocator = pair->getTemporaryAllocator(); - -// // For each potential contact manifold of the pair -// ContactManifoldInfo* potentialManifold = pair->getPotentialContactManifolds(); -// while (potentialManifold != nullptr) { - -// // For each contact point of the potential manifold -// ContactPointInfo* contactPointInfo = potentialManifold->getFirstContactPointInfo(); -// while (contactPointInfo != nullptr) { - -// // Compute the barycentric coordinates of the point in the triangle -// decimal u, v, w; -// computeBarycentricCoordinatesInTriangle(triangleShape->getVertexPosition(0), -// triangleShape->getVertexPosition(1), -// triangleShape->getVertexPosition(2), -// isFirstShapeTriangle ? contactPointInfo->localPoint1 : contactPointInfo->localPoint2, -// u, v, w); -// int nbZeros = 0; -// bool isUZero = approxEqual(u, 0, 0.0001); -// bool isVZero = approxEqual(v, 0, 0.0001); -// bool isWZero = approxEqual(w, 0, 0.0001); -// if (isUZero) nbZeros++; -// if (isVZero) nbZeros++; -// if (isWZero) nbZeros++; - -// // If the triangle contact point is on a triangle vertex of a triangle edge -// if (nbZeros == 1 || nbZeros == 2) { - - -// // Create a smooth mesh contact info -// SmoothMeshContactInfo* smoothContactInfo = new (allocator.allocate(sizeof(SmoothMeshContactInfo))) -// SmoothMeshContactInfo(potentialManifold, contactInfo, isFirstShapeTriangle, -// triangleShape->getVertexPosition(0), -// triangleShape->getVertexPosition(1), -// triangleShape->getVertexPosition(2)); - -// smoothContactPoints.push_back(smoothContactInfo); - -// // Remove the contact point info from the manifold. If the contact point will be kept in the future, we -// // will put the contact point back in the manifold. -// ... -// } - -// // Note that we do not remove the contact points that are not on the vertices or edges of the triangle -// // from the contact manifold because we know we will keep to contact points. We only remove the vertices -// // and edges contact points for the moment. If those points will be kept in the future, we will have to -// // put them back again in the contact manifold -// } - -// potentialManifold = potentialManifold->mNext; -// } - -// // Sort the list of narrow-phase contacts according to their penetration depth -// std::sort(smoothContactPoints.begin(), smoothContactPoints.end(), ContactsDepthCompare()); - -// ... -} - // Compute the middle-phase collision detection between two proxy shapes NarrowPhaseInfo* CollisionDetection::computeMiddlePhaseForProxyShapes(OverlappingPair* pair) { diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index 6f28f788..fc33c00f 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -100,6 +100,13 @@ class CollisionDetection { /// True if some collision shapes have been added previously bool mIsCollisionShapesAdded; +#ifdef IS_PROFILING_ACTIVE + + /// Pointer to the profiler + Profiler* mProfiler; + +#endif + // -------------------- Methods -------------------- // /// Compute the broad-phase collision detection @@ -143,6 +150,7 @@ class CollisionDetection { /// Process the potential contacts where one collion is a concave shape void processSmoothMeshContacts(OverlappingPair* pair); + public : @@ -219,6 +227,13 @@ class CollisionDetection { /// Return a reference to the world memory allocator PoolAllocator& getWorldMemoryAllocator(); +#ifdef IS_PROFILING_ACTIVE + + /// Set the profiler + void setProfiler(Profiler* profiler); + +#endif + /// Return the world-space AABB of a given proxy shape const AABB getWorldAABB(const ProxyShape* proxyShape) const; @@ -234,6 +249,14 @@ inline void CollisionDetection::setCollisionDispatch(CollisionDispatch* collisio // Fill-in the collision matrix with the new algorithms to use fillInCollisionMatrix(); + +#ifdef IS_PROFILING_ACTIVE + + // Set the profiler + mCollisionDispatch->setProfiler(mProfiler); + +#endif + } // Add a body to the collision detection @@ -298,7 +321,7 @@ inline void CollisionDetection::raycast(RaycastCallback* raycastCallback, const Ray& ray, unsigned short raycastWithCategoryMaskBits) const { - PROFILE("CollisionDetection::raycast()"); + PROFILE("CollisionDetection::raycast()", mProfiler); RaycastTest rayCastTest(raycastCallback); @@ -312,6 +335,17 @@ inline CollisionWorld* CollisionDetection::getWorld() { return mWorld; } +#ifdef IS_PROFILING_ACTIVE + +// Set the profiler +inline void CollisionDetection::setProfiler(Profiler* profiler) { + mProfiler = profiler; + mBroadPhaseAlgorithm.setProfiler(profiler); + mCollisionDispatch->setProfiler(profiler); +} + +#endif + } #endif diff --git a/src/collision/MiddlePhaseTriangleCallback.cpp b/src/collision/MiddlePhaseTriangleCallback.cpp index 9d163799..0bda49d4 100644 --- a/src/collision/MiddlePhaseTriangleCallback.cpp +++ b/src/collision/MiddlePhaseTriangleCallback.cpp @@ -38,6 +38,13 @@ void MiddlePhaseTriangleCallback::testTriangle(uint meshSubPart, uint triangleIn TriangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], verticesNormals, meshSubPart, triangleIndex); +#ifdef IS_PROFILING_ACTIVE + + // Set the profiler to the triangle shape + triangleShape->setProfiler(mProfiler); + +#endif + bool isShape1Convex = mOverlappingPair->getShape1()->getCollisionShape()->isConvex(); ProxyShape* shape1 = isShape1Convex ? mConvexProxyShape : mConcaveProxyShape; ProxyShape* shape2 = isShape1Convex ? mConcaveProxyShape : mConvexProxyShape; diff --git a/src/collision/MiddlePhaseTriangleCallback.h b/src/collision/MiddlePhaseTriangleCallback.h index 36bfac24..4927c6e0 100644 --- a/src/collision/MiddlePhaseTriangleCallback.h +++ b/src/collision/MiddlePhaseTriangleCallback.h @@ -58,6 +58,13 @@ class MiddlePhaseTriangleCallback : public TriangleCallback { /// Reference to the single-frame memory allocator Allocator& mAllocator; +#ifdef IS_PROFILING_ACTIVE + + /// Pointer to the profiler + Profiler* mProfiler; + +#endif + public: /// Pointer to the first element of the linked-list of narrow-phase info @@ -77,6 +84,16 @@ class MiddlePhaseTriangleCallback : public TriangleCallback { /// Test collision between a triangle and the convex mesh shape virtual void testTriangle(uint meshSubpart, uint triangleIndex, const Vector3* trianglePoints, const Vector3* verticesNormals) override; + +#ifdef IS_PROFILING_ACTIVE + + /// Set the profiler + void setProfiler(Profiler* profiler) { + mProfiler = profiler; + } + +#endif + }; } diff --git a/src/collision/ProxyShape.h b/src/collision/ProxyShape.h index 8282af01..574758d4 100644 --- a/src/collision/ProxyShape.h +++ b/src/collision/ProxyShape.h @@ -85,6 +85,13 @@ class ProxyShape { /// proxy shape will collide with every collision categories by default. unsigned short mCollideWithMaskBits; +#ifdef IS_PROFILING_ACTIVE + + /// Pointer to the profiler + Profiler* mProfiler; + +#endif + // -------------------- Methods -------------------- // /// Return the collision shape @@ -170,6 +177,13 @@ class ProxyShape { /// Set the local scaling vector of the collision shape virtual void setLocalScaling(const Vector3& scaling); +#ifdef IS_PROFILING_ACTIVE + + /// Set the profiler + void setProfiler(Profiler* profiler); + +#endif + // -------------------- Friendship -------------------- // friend class OverlappingPair; @@ -359,6 +373,18 @@ inline bool ProxyShape::testAABBOverlap(const AABB& worldAABB) const { return worldAABB.testCollision(getWorldAABB()); } +#ifdef IS_PROFILING_ACTIVE + +// Set the profiler +inline void ProxyShape::setProfiler(Profiler* profiler) { + + mProfiler = profiler; + + mCollisionShape->setProfiler(profiler); +} + +#endif + } #endif diff --git a/src/collision/broadphase/BroadPhaseAlgorithm.cpp b/src/collision/broadphase/BroadPhaseAlgorithm.cpp index c86cd0bc..c1484434 100644 --- a/src/collision/broadphase/BroadPhaseAlgorithm.cpp +++ b/src/collision/broadphase/BroadPhaseAlgorithm.cpp @@ -44,6 +44,13 @@ BroadPhaseAlgorithm::BroadPhaseAlgorithm(CollisionDetection& collisionDetection) // Allocate memory for the array of potential overlapping pairs mPotentialPairs = (BroadPhasePair*) malloc(mNbAllocatedPotentialPairs * sizeof(BroadPhasePair)); assert(mPotentialPairs != nullptr); + +#ifdef IS_PROFILING_ACTIVE + + mProfiler = nullptr; + +#endif + } // Destructor diff --git a/src/collision/broadphase/BroadPhaseAlgorithm.h b/src/collision/broadphase/BroadPhaseAlgorithm.h index 94499d44..7e1ff262 100644 --- a/src/collision/broadphase/BroadPhaseAlgorithm.h +++ b/src/collision/broadphase/BroadPhaseAlgorithm.h @@ -162,6 +162,13 @@ class BroadPhaseAlgorithm { /// Reference to the collision detection object CollisionDetection& mCollisionDetection; +#ifdef IS_PROFILING_ACTIVE + + /// Pointer to the profiler + Profiler* mProfiler; + +#endif + public : // -------------------- Methods -------------------- // @@ -215,8 +222,15 @@ class BroadPhaseAlgorithm { const AABB& getFatAABB(int broadPhaseId) const; /// Ray casting method - void raycast(const Ray& ray, RaycastTest& raycastTest, - unsigned short raycastWithCategoryMaskBits) const; + void raycast(const Ray& ray, RaycastTest& raycastTest, unsigned short raycastWithCategoryMaskBits) const; + +#ifdef IS_PROFILING_ACTIVE + + /// Set the profiler + void setProfiler(Profiler* profiler); + +#endif + }; // Method used to compare two pairs for sorting algorithm @@ -252,7 +266,7 @@ inline const AABB& BroadPhaseAlgorithm::getFatAABB(int broadPhaseId) const { inline void BroadPhaseAlgorithm::raycast(const Ray& ray, RaycastTest& raycastTest, unsigned short raycastWithCategoryMaskBits) const { - PROFILE("BroadPhaseAlgorithm::raycast()"); + PROFILE("BroadPhaseAlgorithm::raycast()", mProfiler); BroadPhaseRaycastCallback broadPhaseRaycastCallback(mDynamicAABBTree, raycastWithCategoryMaskBits, raycastTest); @@ -264,6 +278,16 @@ inline ProxyShape* BroadPhaseAlgorithm::getProxyShapeForBroadPhaseId(int broadPh return static_cast(mDynamicAABBTree.getNodeDataPointer(broadPhaseId)); } +#ifdef IS_PROFILING_ACTIVE + +// Set the profiler +inline void BroadPhaseAlgorithm::setProfiler(Profiler* profiler) { + mProfiler = profiler; + mDynamicAABBTree.setProfiler(profiler); +} + +#endif + } #endif diff --git a/src/collision/broadphase/DynamicAABBTree.cpp b/src/collision/broadphase/DynamicAABBTree.cpp index f829c000..5fa33d9d 100644 --- a/src/collision/broadphase/DynamicAABBTree.cpp +++ b/src/collision/broadphase/DynamicAABBTree.cpp @@ -171,7 +171,7 @@ void DynamicAABBTree::removeObject(int nodeID) { /// (this can be useful if the shape AABB has become much smaller than the previous one for instance). bool DynamicAABBTree::updateObject(int nodeID, const AABB& newAABB, const Vector3& displacement, bool forceReinsert) { - PROFILE("DynamicAABBTree::updateObject()"); + PROFILE("DynamicAABBTree::updateObject()", mProfiler); assert(nodeID >= 0 && nodeID < mNbAllocatedNodes); assert(mNodes[nodeID].isLeaf()); @@ -633,7 +633,7 @@ void DynamicAABBTree::reportAllShapesOverlappingWithAABB(const AABB& aabb, // Ray casting method void DynamicAABBTree::raycast(const Ray& ray, DynamicAABBTreeRaycastCallback &callback) const { - PROFILE("DynamicAABBTree::raycast()"); + PROFILE("DynamicAABBTree::raycast()", mProfiler); decimal maxFraction = ray.maxFraction; diff --git a/src/collision/broadphase/DynamicAABBTree.h b/src/collision/broadphase/DynamicAABBTree.h index 8025e4f9..54751138 100644 --- a/src/collision/broadphase/DynamicAABBTree.h +++ b/src/collision/broadphase/DynamicAABBTree.h @@ -155,6 +155,13 @@ class DynamicAABBTree { /// without triggering a large modification of the tree which can be costly decimal mExtraAABBGap; +#ifdef IS_PROFILING_ACTIVE + + /// Pointer to the profiler + Profiler* mProfiler; + +#endif + // -------------------- Methods -------------------- // /// Allocate and return a node to use in the tree @@ -237,6 +244,14 @@ class DynamicAABBTree { /// Clear all the nodes and reset the tree void reset(); + +#ifdef IS_PROFILING_ACTIVE + + /// Set the profiler + void setProfiler(Profiler* profiler); + +#endif + }; // Return true if the node is a leaf of the tree @@ -292,6 +307,15 @@ inline int DynamicAABBTree::addObject(const AABB& aabb, void* data) { return nodeId; } +#ifdef IS_PROFILING_ACTIVE + +// Set the profiler +inline void DynamicAABBTree::setProfiler(Profiler* profiler) { + mProfiler = profiler; +} + +#endif + } #endif diff --git a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp index e895eef7..315dcf7a 100644 --- a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp @@ -41,7 +41,15 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPh // First, we run the GJK algorithm GJKAlgorithm gjkAlgorithm; - SATAlgorithm satAlgorithm; + SATAlgorithm satAlgorithm; + +#ifdef IS_PROFILING_ACTIVE + + gjkAlgorithm.setProfiler(mProfiler); + satAlgorithm.setProfiler(mProfiler); + +#endif + GJKAlgorithm::GJKResult result = gjkAlgorithm.testCollision(narrowPhaseInfo, reportContacts); narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = true; diff --git a/src/collision/narrowphase/CollisionDispatch.h b/src/collision/narrowphase/CollisionDispatch.h index 230ebbb3..d8351d6a 100644 --- a/src/collision/narrowphase/CollisionDispatch.h +++ b/src/collision/narrowphase/CollisionDispatch.h @@ -41,6 +41,13 @@ class CollisionDispatch { protected: +#ifdef IS_PROFILING_ACTIVE + + /// Pointer to the profiler + Profiler* mProfiler; + +#endif + public: /// Constructor @@ -49,13 +56,29 @@ class CollisionDispatch { /// Destructor virtual ~CollisionDispatch() = default; - /// Select and return the narrow-phase collision detection algorithm to /// use between two types of collision shapes. - virtual NarrowPhaseAlgorithm* selectAlgorithm(int shape1Type, - int shape2Type)=0; + virtual NarrowPhaseAlgorithm* selectAlgorithm(int shape1Type, int shape2Type)=0; + +#ifdef IS_PROFILING_ACTIVE + + /// Set the profiler + virtual void setProfiler(Profiler* profiler); + +#endif + }; +#ifdef IS_PROFILING_ACTIVE + +// Set the profiler +inline void CollisionDispatch::setProfiler(Profiler* profiler) { + + mProfiler = profiler; +} + +#endif + } #endif diff --git a/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp index c6297fb2..9f2bb47e 100644 --- a/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp @@ -38,6 +38,13 @@ bool ConvexPolyhedronVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* // Run the SAT algorithm to find the separating axis and compute contact point SATAlgorithm satAlgorithm; + +#ifdef IS_PROFILING_ACTIVE + + satAlgorithm.setProfiler(mProfiler); + +#endif + bool isColliding = satAlgorithm.testCollisionConvexPolyhedronVsConvexPolyhedron(narrowPhaseInfo, reportContacts); narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = true; diff --git a/src/collision/narrowphase/DefaultCollisionDispatch.h b/src/collision/narrowphase/DefaultCollisionDispatch.h index 779f7048..fe22b4a9 100644 --- a/src/collision/narrowphase/DefaultCollisionDispatch.h +++ b/src/collision/narrowphase/DefaultCollisionDispatch.h @@ -77,8 +77,33 @@ class DefaultCollisionDispatch : public CollisionDispatch { /// Select and return the narrow-phase collision detection algorithm to /// use between two types of collision shapes. virtual NarrowPhaseAlgorithm* selectAlgorithm(int type1, int type2) override; + +#ifdef IS_PROFILING_ACTIVE + + /// Set the profiler + virtual void setProfiler(Profiler* profiler) override; + +#endif + }; +#ifdef IS_PROFILING_ACTIVE + +// Set the profiler +inline void DefaultCollisionDispatch::setProfiler(Profiler* profiler) { + + CollisionDispatch::setProfiler(profiler); + + mSphereVsSphereAlgorithm.setProfiler(profiler); + mCapsuleVsCapsuleAlgorithm.setProfiler(profiler); + mSphereVsCapsuleAlgorithm.setProfiler(profiler); + mSphereVsConvexPolyhedronAlgorithm.setProfiler(profiler); + mCapsuleVsConvexPolyhedronAlgorithm.setProfiler(profiler); + mConvexPolyhedronVsConvexPolyhedronAlgorithm.setProfiler(profiler); +} + +#endif + } #endif diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp index 629811eb..c0f436a6 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp @@ -49,7 +49,7 @@ using namespace reactphysics3d; /// the correct penetration depth and contact points between the enlarged objects. GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) { - PROFILE("GJKAlgorithm::testCollision()"); + PROFILE("GJKAlgorithm::testCollision()", mProfiler); Vector3 suppA; // Support point of object A Vector3 suppB; // Support point of object B diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.h b/src/collision/narrowphase/GJK/GJKAlgorithm.h index b8c7319c..a9daa897 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.h +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.h @@ -62,6 +62,13 @@ class GJKAlgorithm { // -------------------- Attributes -------------------- // +#ifdef IS_PROFILING_ACTIVE + + /// Pointer to the profiler + Profiler* mProfiler; + +#endif + // -------------------- Methods -------------------- // public : @@ -94,8 +101,25 @@ class GJKAlgorithm { /// Ray casting algorithm agains a convex collision shape using the GJK Algorithm bool raycast(const Ray& ray, ProxyShape* proxyShape, RaycastInfo& raycastInfo); + +#ifdef IS_PROFILING_ACTIVE + + /// Set the profiler + void setProfiler(Profiler* profiler); + +#endif + }; +#ifdef IS_PROFILING_ACTIVE + +// Set the profiler +inline void GJKAlgorithm::setProfiler(Profiler* profiler) { + mProfiler = profiler; +} + +#endif + } #endif diff --git a/src/collision/narrowphase/NarrowPhaseAlgorithm.h b/src/collision/narrowphase/NarrowPhaseAlgorithm.h index 6a8746c6..34fa5962 100644 --- a/src/collision/narrowphase/NarrowPhaseAlgorithm.h +++ b/src/collision/narrowphase/NarrowPhaseAlgorithm.h @@ -67,6 +67,13 @@ class NarrowPhaseAlgorithm { // -------------------- Attributes -------------------- // +#ifdef IS_PROFILING_ACTIVE + + /// Pointer to the profiler + Profiler* mProfiler; + +#endif + public : // -------------------- Methods -------------------- // @@ -85,8 +92,25 @@ class NarrowPhaseAlgorithm { /// Compute a contact info if the two bounding volume collide virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts)=0; + +#ifdef IS_PROFILING_ACTIVE + + /// Set the profiler + void setProfiler(Profiler* profiler); + +#endif + }; +#ifdef IS_PROFILING_ACTIVE + +// Set the profiler +inline void NarrowPhaseAlgorithm::setProfiler(Profiler* profiler) { + mProfiler = profiler; +} + +#endif + } #endif diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index e6d09dd1..47953f1a 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -47,7 +47,7 @@ const decimal SATAlgorithm::SAME_SEPARATING_AXIS_BIAS = decimal(0.001); // Test collision between a sphere and a convex mesh bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) const { - PROFILE("SATAlgorithm::testCollisionSphereVsConvexPolyhedron()"); + PROFILE("SATAlgorithm::testCollisionSphereVsConvexPolyhedron()", mProfiler); bool isSphereShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE; @@ -139,7 +139,7 @@ decimal SATAlgorithm::computePolyhedronFaceVsSpherePenetrationDepth(uint faceInd // Test collision between a capsule and a convex mesh bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) const { - PROFILE("SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron()"); + PROFILE("SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron()", mProfiler); bool isCapsuleShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE; @@ -448,7 +448,7 @@ bool SATAlgorithm::isMinkowskiFaceCapsuleVsEdge(const Vector3& capsuleSegment, c // Test collision between two convex polyhedrons bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) const { - PROFILE("SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron()"); + PROFILE("SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron()", mProfiler); assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON); assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.h b/src/collision/narrowphase/SAT/SATAlgorithm.h index 5c721a00..60f7a091 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.h +++ b/src/collision/narrowphase/SAT/SATAlgorithm.h @@ -50,6 +50,13 @@ class SATAlgorithm { /// make sure the contact manifold does not change too much between frames. static const decimal SAME_SEPARATING_AXIS_BIAS; +#ifdef IS_PROFILING_ACTIVE + + /// Pointer to the profiler + Profiler* mProfiler; + +#endif + // -------------------- Methods -------------------- // /// Return true if two edges of two polyhedrons build a minkowski face (and can therefore be a separating axis) @@ -138,8 +145,26 @@ class SATAlgorithm { /// Test collision between two convex meshes bool testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) const; + +#ifdef IS_PROFILING_ACTIVE + + /// Set the profiler + void setProfiler(Profiler* profiler); + +#endif + }; +#ifdef IS_PROFILING_ACTIVE + +// Set the profiler +inline void SATAlgorithm::setProfiler(Profiler* profiler) { + + mProfiler = profiler; +} + +#endif + } #endif diff --git a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp index 7ecda325..ae3764ab 100644 --- a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp @@ -43,6 +43,13 @@ bool SphereVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPha // First, we run the GJK algorithm GJKAlgorithm gjkAlgorithm; + +#ifdef IS_PROFILING_ACTIVE + + gjkAlgorithm.setProfiler(mProfiler); + +#endif + GJKAlgorithm::GJKResult result = gjkAlgorithm.testCollision(narrowPhaseInfo, reportContacts); narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = true; @@ -60,6 +67,13 @@ bool SphereVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPha // Run the SAT algorithm to find the separating axis and compute contact point SATAlgorithm satAlgorithm; + +#ifdef IS_PROFILING_ACTIVE + + satAlgorithm.setProfiler(mProfiler); + +#endif + bool isColliding = satAlgorithm.testCollisionSphereVsConvexPolyhedron(narrowPhaseInfo, reportContacts); narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = false; diff --git a/src/collision/shapes/CollisionShape.cpp b/src/collision/shapes/CollisionShape.cpp index 9622e795..a89747c9 100644 --- a/src/collision/shapes/CollisionShape.cpp +++ b/src/collision/shapes/CollisionShape.cpp @@ -48,7 +48,7 @@ CollisionShape::CollisionShape(CollisionShapeName name, CollisionShapeType type) */ void CollisionShape::computeAABB(AABB& aabb, const Transform& transform) const { - PROFILE("CollisionShape::computeAABB()"); + PROFILE("CollisionShape::computeAABB()", mProfiler); // Get the local bounds in x,y and z direction Vector3 minBounds; diff --git a/src/collision/shapes/CollisionShape.h b/src/collision/shapes/CollisionShape.h index f6690c58..feb4c502 100644 --- a/src/collision/shapes/CollisionShape.h +++ b/src/collision/shapes/CollisionShape.h @@ -35,6 +35,7 @@ #include "AABB.h" #include "collision/RaycastInfo.h" #include "memory/PoolAllocator.h" +#include "engine/Profiler.h" /// ReactPhysics3D namespace namespace reactphysics3d { @@ -69,6 +70,13 @@ class CollisionShape { /// Scaling vector of the collision shape Vector3 mScaling; + +#ifdef IS_PROFILING_ACTIVE + + /// Pointer to the profiler + Profiler* mProfiler; + +#endif // -------------------- Methods -------------------- // @@ -124,6 +132,13 @@ class CollisionShape { /// Compute the world-space AABB of the collision shape given a transform virtual void computeAABB(AABB& aabb, const Transform& transform) const; +#ifdef IS_PROFILING_ACTIVE + + /// Set the profiler + virtual void setProfiler(Profiler* profiler); + +#endif + // -------------------- Friendship -------------------- // friend class ProxyShape; @@ -156,6 +171,16 @@ inline void CollisionShape::setLocalScaling(const Vector3& scaling) { mScaling = scaling; } +#ifdef IS_PROFILING_ACTIVE + +// Set the profiler +inline void CollisionShape::setProfiler(Profiler* profiler) { + + mProfiler = profiler; +} + +#endif + } #endif diff --git a/src/collision/shapes/ConcaveMeshShape.cpp b/src/collision/shapes/ConcaveMeshShape.cpp index 566b7bc4..646638dd 100644 --- a/src/collision/shapes/ConcaveMeshShape.cpp +++ b/src/collision/shapes/ConcaveMeshShape.cpp @@ -113,11 +113,18 @@ void ConcaveMeshShape::testAllTriangles(TriangleCallback& callback, const AABB& /// the ray hits many triangles. bool ConcaveMeshShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const { - PROFILE("ConcaveMeshShape::raycast()"); + PROFILE("ConcaveMeshShape::raycast()", mProfiler); // Create the callback object that will compute ray casting against triangles ConcaveMeshRaycastCallback raycastCallback(mDynamicAABBTree, *this, proxyShape, raycastInfo, ray); +#ifdef IS_PROFILING_ACTIVE + + // Set the profiler + raycastCallback.setProfiler(mProfiler); + +#endif + // Ask the Dynamic AABB Tree to report all AABB nodes that are hit by the ray. // The raycastCallback object will then compute ray casting against the triangles // in the hit AABBs. @@ -159,6 +166,13 @@ void ConcaveMeshRaycastCallback::raycastTriangles() { TriangleShape triangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], verticesNormals, data[0], data[1]); triangleShape.setRaycastTestType(mConcaveMeshShape.getRaycastTestType()); + +#ifdef IS_PROFILING_ACTIVE + + // Set the profiler to the triangle shape + triangleShape.setProfiler(mProfiler); + +#endif // Ray casting test against the collision shape RaycastInfo raycastInfo; diff --git a/src/collision/shapes/ConcaveMeshShape.h b/src/collision/shapes/ConcaveMeshShape.h index 82c08794..678d5325 100644 --- a/src/collision/shapes/ConcaveMeshShape.h +++ b/src/collision/shapes/ConcaveMeshShape.h @@ -78,6 +78,13 @@ class ConcaveMeshRaycastCallback : public DynamicAABBTreeRaycastCallback { const Ray& mRay; bool mIsHit; +#ifdef IS_PROFILING_ACTIVE + + /// Pointer to the profiler + Profiler* mProfiler; + +#endif + public: // Constructor @@ -98,6 +105,15 @@ class ConcaveMeshRaycastCallback : public DynamicAABBTreeRaycastCallback { bool getIsHit() const { return mIsHit; } + +#ifdef IS_PROFILING_ACTIVE + + /// Set the profiler + void setProfiler(Profiler* profiler) { + mProfiler = profiler; + } + +#endif }; // Class ConcaveMeshShape @@ -165,6 +181,13 @@ class ConcaveMeshShape : public ConcaveShape { /// Use a callback method on all triangles of the concave shape inside a given AABB virtual void testAllTriangles(TriangleCallback& callback, const AABB& localAABB) const override; +#ifdef IS_PROFILING_ACTIVE + + /// Set the profiler + virtual void setProfiler(Profiler* profiler) override; + +#endif + // ---------- Friendship ----------- // friend class ConvexTriangleAABBOverlapCallback; @@ -239,6 +262,18 @@ inline void ConvexTriangleAABBOverlapCallback::notifyOverlappingNode(int nodeId) mTriangleTestCallback.testTriangle(data[0], data[1], trianglePoints, verticesNormals); } +#ifdef IS_PROFILING_ACTIVE + +// Set the profiler +inline void ConcaveMeshShape::setProfiler(Profiler* profiler) { + + CollisionShape::setProfiler(profiler); + + mDynamicAABBTree.setProfiler(profiler); +} + +#endif + } #endif diff --git a/src/collision/shapes/HeightFieldShape.cpp b/src/collision/shapes/HeightFieldShape.cpp index 2afba401..08ec19a4 100644 --- a/src/collision/shapes/HeightFieldShape.cpp +++ b/src/collision/shapes/HeightFieldShape.cpp @@ -217,10 +217,17 @@ bool HeightFieldShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxySh // TODO : Implement raycasting without using an AABB for the ray // but using a dynamic AABB tree or octree instead - PROFILE("HeightFieldShape::raycast()"); + PROFILE("HeightFieldShape::raycast()", mProfiler); TriangleOverlapCallback triangleCallback(ray, proxyShape, raycastInfo, *this); +#ifdef IS_PROFILING_ACTIVE + + // Set the profiler + triangleCallback.setProfiler(mProfiler); + +#endif + // Compute the AABB for the ray const Vector3 rayEnd = ray.point1 + ray.maxFraction * (ray.point2 - ray.point1); const AABB rayAABB(Vector3::min(ray.point1, rayEnd), Vector3::max(ray.point1, rayEnd)); @@ -264,6 +271,13 @@ void TriangleOverlapCallback::testTriangle(uint meshSubPart, uint triangleIndex, verticesNormals, meshSubPart, triangleIndex); triangleShape.setRaycastTestType(mHeightFieldShape.getRaycastTestType()); +#ifdef IS_PROFILING_ACTIVE + + // Set the profiler to the triangle shape + triangleShape.setProfiler(mProfiler); + +#endif + // Ray casting test against the collision shape RaycastInfo raycastInfo; bool isTriangleHit = triangleShape.raycast(mRay, raycastInfo, mProxyShape); diff --git a/src/collision/shapes/HeightFieldShape.h b/src/collision/shapes/HeightFieldShape.h index aa0cd787..80c18d9c 100644 --- a/src/collision/shapes/HeightFieldShape.h +++ b/src/collision/shapes/HeightFieldShape.h @@ -49,6 +49,13 @@ class TriangleOverlapCallback : public TriangleCallback { bool mIsHit; decimal mSmallestHitFraction; const HeightFieldShape& mHeightFieldShape; + +#ifdef IS_PROFILING_ACTIVE + + /// Pointer to the profiler + Profiler* mProfiler; + +#endif public: @@ -66,6 +73,16 @@ class TriangleOverlapCallback : public TriangleCallback { /// Raycast test between a ray and a triangle of the heightfield virtual void testTriangle(uint meshSubPart, uint triangleIndex, const Vector3* trianglePoints, const Vector3* verticesNormals) override; + +#ifdef IS_PROFILING_ACTIVE + + /// Set the profiler + void setProfiler(Profiler* profiler) { + mProfiler = profiler; + } + +#endif + }; diff --git a/src/collision/shapes/TriangleShape.cpp b/src/collision/shapes/TriangleShape.cpp index 142ba181..020053b6 100644 --- a/src/collision/shapes/TriangleShape.cpp +++ b/src/collision/shapes/TriangleShape.cpp @@ -153,13 +153,12 @@ Vector3 TriangleShape::computeSmoothLocalContactNormalForTriangle(const Vector3& return (u * mVerticesNormals[0] + v * mVerticesNormals[1] + w * mVerticesNormals[2]).getUnit(); } - // 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 { - PROFILE("TriangleShape::raycast()"); + PROFILE("TriangleShape::raycast()", mProfiler); const Vector3 pq = ray.point2 - ray.point1; const Vector3 pa = mPoints[0] - ray.point1; diff --git a/src/engine/CollisionWorld.cpp b/src/engine/CollisionWorld.cpp index e8f4155a..eeb06305 100644 --- a/src/engine/CollisionWorld.cpp +++ b/src/engine/CollisionWorld.cpp @@ -37,6 +37,13 @@ CollisionWorld::CollisionWorld() mCollisionDetection(this, mPoolAllocator, mSingleFrameAllocator), mCurrentBodyID(0), mEventListener(nullptr) { +#ifdef IS_PROFILING_ACTIVE + + // Set the profiler + mCollisionDetection.setProfiler(&mProfiler); + +#endif + } // Destructor @@ -75,6 +82,12 @@ CollisionBody* CollisionWorld::createCollisionBody(const Transform& transform) { // Add the collision body to the world mBodies.insert(collisionBody); +#ifdef IS_PROFILING_ACTIVE + + collisionBody->setProfiler(&mProfiler); + +#endif + // Return the pointer to the rigid body return collisionBody; } diff --git a/src/engine/CollisionWorld.h b/src/engine/CollisionWorld.h index d27b8018..f523d169 100644 --- a/src/engine/CollisionWorld.h +++ b/src/engine/CollisionWorld.h @@ -82,6 +82,12 @@ class CollisionWorld { /// Pointer to an event listener object EventListener* mEventListener; +#ifdef IS_PROFILING_ACTIVE + + /// Real-time hierarchical profiler + Profiler mProfiler; +#endif + // -------------------- Methods -------------------- // /// Return the next available body ID @@ -147,6 +153,12 @@ class CollisionWorld { /// Test and report collisions between all shapes of the world void testCollision(CollisionCallback* callback); +#ifdef IS_PROFILING_ACTIVE + + /// Set the name of the profiler + void setProfilerName(std::string name); +#endif + /// Return the current world-space AABB of given proxy shape AABB getWorldAABB(const ProxyShape* proxyShape) const; @@ -236,6 +248,15 @@ inline void CollisionWorld::testOverlap(CollisionBody* body, OverlapCallback* ov mCollisionDetection.testOverlap(body, overlapCallback, categoryMaskBits); } +#ifdef IS_PROFILING_ACTIVE + +// Set the name of the profiler +inline void CollisionWorld::setProfilerName(std::string name) { + mProfiler.setName(name); +} + +#endif + } #endif diff --git a/src/engine/ConstraintSolver.cpp b/src/engine/ConstraintSolver.cpp index 547aea6e..458c39a7 100644 --- a/src/engine/ConstraintSolver.cpp +++ b/src/engine/ConstraintSolver.cpp @@ -34,12 +34,18 @@ ConstraintSolver::ConstraintSolver(const std::map& mapBodyToVe : mMapBodyToConstrainedVelocityIndex(mapBodyToVelocityIndex), mIsWarmStartingActive(true), mConstraintSolverData(mapBodyToVelocityIndex) { +#ifdef IS_PROFILING_ACTIVE + + mProfiler = nullptr; + +#endif + } // Initialize the constraint solver for a given island void ConstraintSolver::initializeForIsland(decimal dt, Island* island) { - PROFILE("ConstraintSolver::initializeForIsland()"); + PROFILE("ConstraintSolver::initializeForIsland()", mProfiler); assert(island != nullptr); assert(island->getNbBodies() > 0); @@ -69,7 +75,7 @@ void ConstraintSolver::initializeForIsland(decimal dt, Island* island) { // Solve the velocity constraints void ConstraintSolver::solveVelocityConstraints(Island* island) { - PROFILE("ConstraintSolver::solveVelocityConstraints()"); + PROFILE("ConstraintSolver::solveVelocityConstraints()", mProfiler); assert(island != nullptr); assert(island->getNbJoints() > 0); @@ -86,7 +92,7 @@ void ConstraintSolver::solveVelocityConstraints(Island* island) { // Solve the position constraints void ConstraintSolver::solvePositionConstraints(Island* island) { - PROFILE("ConstraintSolver::solvePositionConstraints()"); + PROFILE("ConstraintSolver::solvePositionConstraints()", mProfiler); assert(island != nullptr); assert(island->getNbJoints() > 0); diff --git a/src/engine/ConstraintSolver.h b/src/engine/ConstraintSolver.h index b40cc983..fbb54ed1 100644 --- a/src/engine/ConstraintSolver.h +++ b/src/engine/ConstraintSolver.h @@ -165,6 +165,12 @@ class ConstraintSolver { /// Constraint solver data used to initialize and solve the constraints ConstraintSolverData mConstraintSolverData; +#ifdef IS_PROFILING_ACTIVE + + /// Pointer to the profiler + Profiler* mProfiler; +#endif + public : // -------------------- Methods -------------------- // @@ -197,6 +203,14 @@ class ConstraintSolver { /// Set the constrained positions/orientations arrays void setConstrainedPositionsArrays(Vector3* constrainedPositions, Quaternion* constrainedOrientations); + +#ifdef IS_PROFILING_ACTIVE + + /// Set the profiler + void setProfiler(Profiler* profiler); + +#endif + }; // Set the constrained velocities arrays @@ -221,6 +235,15 @@ inline void ConstraintSolver::setConstrainedPositionsArrays(Vector3* constrained mConstraintSolverData.orientations = constrainedOrientations; } +#ifdef IS_PROFILING_ACTIVE + +// Set the profiler +inline void ConstraintSolver::setProfiler(Profiler* profiler) { + mProfiler = profiler; +} + +#endif + } #endif diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index 819a1b76..1e5b5401 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -52,7 +52,7 @@ ContactSolver::ContactSolver(const std::map& mapBodyToVelocity // Initialize the contact constraints void ContactSolver::init(Island** islands, uint nbIslands, decimal timeStep) { - PROFILE("ContactSolver::init()"); + PROFILE("ContactSolver::init()", mProfiler); mTimeStep = timeStep; @@ -98,7 +98,7 @@ void ContactSolver::init(Island** islands, uint nbIslands, decimal timeStep) { // Initialize the constraint solver for a given island void ContactSolver::initializeForIsland(Island* island) { - PROFILE("ContactSolver::initializeForIsland()"); + PROFILE("ContactSolver::initializeForIsland()", mProfiler); assert(island != nullptr); assert(island->getNbBodies() > 0); @@ -270,7 +270,7 @@ void ContactSolver::initializeForIsland(Island* island) { /// the solution of the linear system void ContactSolver::warmStart() { - PROFILE("ContactSolver::warmStart()"); + PROFILE("ContactSolver::warmStart()", mProfiler); uint contactPointIndex = 0; @@ -387,7 +387,7 @@ void ContactSolver::warmStart() { // Solve the contacts void ContactSolver::solve() { - PROFILE("ContactSolver::solve()"); + PROFILE("ContactSolver::solve()", mProfiler); decimal deltaLambda; decimal lambdaTemp; @@ -586,7 +586,7 @@ void ContactSolver::solve() { // warm start the solver at the next iteration void ContactSolver::storeImpulses() { - PROFILE("ContactSolver::storeImpulses()"); + PROFILE("ContactSolver::storeImpulses()", mProfiler); uint contactPointIndex = 0; @@ -614,7 +614,7 @@ void ContactSolver::storeImpulses() { void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, ContactManifoldSolver& contact) const { - PROFILE("ContactSolver::computeFrictionVectors()"); + PROFILE("ContactSolver::computeFrictionVectors()", mProfiler); assert(contact.normal.length() > decimal(0.0)); diff --git a/src/engine/ContactSolver.h b/src/engine/ContactSolver.h index 40e0721d..0a2850f5 100644 --- a/src/engine/ContactSolver.h +++ b/src/engine/ContactSolver.h @@ -308,6 +308,13 @@ class ContactSolver { /// True if the split impulse position correction is active bool mIsSplitImpulseActive; +#ifdef IS_PROFILING_ACTIVE + + /// Pointer to the profiler + Profiler* mProfiler; + +#endif + // -------------------- Methods -------------------- // /// Compute the collision restitution factor from the restitution factor of each body @@ -367,6 +374,13 @@ class ContactSolver { /// Activate or Deactivate the split impulses for contacts void setIsSplitImpulseActive(bool isActive); + +#ifdef IS_PROFILING_ACTIVE + + /// Set the profiler + void setProfiler(Profiler* profiler); + +#endif }; // Set the split velocities arrays @@ -425,6 +439,16 @@ inline decimal ContactSolver::computeMixedRollingResistance(RigidBody* body1, return decimal(0.5f) * (body1->getMaterial().getRollingResistance() + body2->getMaterial().getRollingResistance()); } +#ifdef IS_PROFILING_ACTIVE + +// Set the profiler +inline void ContactSolver::setProfiler(Profiler* profiler) { + + mProfiler = profiler; +} + +#endif + } #endif diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index 26835166..bb824228 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -29,6 +29,7 @@ #include "constraint/SliderJoint.h" #include "constraint/HingeJoint.h" #include "constraint/FixedJoint.h" +#include // Namespaces using namespace reactphysics3d; @@ -53,6 +54,14 @@ DynamicsWorld::DynamicsWorld(const Vector3 &gravity) mSleepAngularVelocity(DEFAULT_SLEEP_ANGULAR_VELOCITY), mTimeBeforeSleep(DEFAULT_TIME_BEFORE_SLEEP) { +#ifdef IS_PROFILING_ACTIVE + + // Set the profiler + mConstraintSolver.setProfiler(&mProfiler); + mContactSolver.setProfiler(&mProfiler); + +#endif + } // Destructor @@ -80,10 +89,10 @@ DynamicsWorld::~DynamicsWorld() { #ifdef IS_PROFILING_ACTIVE // Print the profiling report - Profiler::printReport(std::cout); - - // Destroy the profiler (release the allocated memory) - Profiler::destroy(); + ofstream myfile; + myfile.open(mProfiler.getName() + ".txt"); + mProfiler.printReport(myfile); + myfile.close(); #endif } @@ -96,10 +105,10 @@ void DynamicsWorld::update(decimal timeStep) { #ifdef IS_PROFILING_ACTIVE // Increment the frame counter of the profiler - Profiler::incrementFrameCounter(); + mProfiler.incrementFrameCounter(); #endif - PROFILE("DynamicsWorld::update()"); + PROFILE("DynamicsWorld::update()", &mProfiler); mTimeStep = timeStep; @@ -147,7 +156,7 @@ void DynamicsWorld::update(decimal timeStep) { /// the sympletic Euler time stepping scheme. void DynamicsWorld::integrateRigidBodiesPositions() { - PROFILE("DynamicsWorld::integrateRigidBodiesPositions()"); + PROFILE("DynamicsWorld::integrateRigidBodiesPositions()", &mProfiler); // For each island of the world for (uint i=0; i < mNbIslands; i++) { @@ -186,7 +195,7 @@ void DynamicsWorld::integrateRigidBodiesPositions() { // Update the postion/orientation of the bodies void DynamicsWorld::updateBodiesState() { - PROFILE("DynamicsWorld::updateBodiesState()"); + PROFILE("DynamicsWorld::updateBodiesState()", &mProfiler); // For each island of the world for (uint islandIndex = 0; islandIndex < mNbIslands; islandIndex++) { @@ -223,7 +232,7 @@ void DynamicsWorld::updateBodiesState() { // Initialize the bodies velocities arrays for the next simulation step. void DynamicsWorld::initVelocityArrays() { - PROFILE("DynamicsWorld::initVelocityArrays()"); + PROFILE("DynamicsWorld::initVelocityArrays()", &mProfiler); // Allocate memory for the bodies velocity arrays uint nbBodies = mRigidBodies.size(); @@ -266,7 +275,7 @@ void DynamicsWorld::initVelocityArrays() { /// contact solver. void DynamicsWorld::integrateRigidBodiesVelocities() { - PROFILE("DynamicsWorld::integrateRigidBodiesVelocities()"); + PROFILE("DynamicsWorld::integrateRigidBodiesVelocities()", &mProfiler); // Initialize the bodies velocity arrays initVelocityArrays(); @@ -328,7 +337,7 @@ void DynamicsWorld::integrateRigidBodiesVelocities() { // Solve the contacts and constraints void DynamicsWorld::solveContactsAndConstraints() { - PROFILE("DynamicsWorld::solveContactsAndConstraints()"); + PROFILE("DynamicsWorld::solveContactsAndConstraints()", &mProfiler); // Set the velocities arrays mContactSolver.setSplitVelocitiesArrays(mSplitLinearVelocities, mSplitAngularVelocities); @@ -401,7 +410,7 @@ void DynamicsWorld::solveContactsAndConstraints() { // Solve the position error correction of the constraints void DynamicsWorld::solvePositionCorrection() { - PROFILE("DynamicsWorld::solvePositionCorrection()"); + PROFILE("DynamicsWorld::solvePositionCorrection()", &mProfiler); // Do not continue if there is no constraints if (mJoints.empty()) return; @@ -442,6 +451,12 @@ RigidBody* DynamicsWorld::createRigidBody(const Transform& transform) { mBodies.insert(rigidBody); mRigidBodies.insert(rigidBody); +#ifdef IS_PROFILING_ACTIVE + + rigidBody->setProfiler(&mProfiler); + +#endif + // Return the pointer to the rigid body return rigidBody; } @@ -613,7 +628,7 @@ void DynamicsWorld::addJointToBody(Joint* joint) { /// it). Then, we create an island with this group of connected bodies. void DynamicsWorld::computeIslands() { - PROFILE("DynamicsWorld::computeIslands()"); + PROFILE("DynamicsWorld::computeIslands()", &mProfiler); uint nbBodies = mRigidBodies.size(); @@ -757,7 +772,7 @@ void DynamicsWorld::computeIslands() { /// time, we put all the bodies of the island to sleep. void DynamicsWorld::updateSleepingBodies() { - PROFILE("DynamicsWorld::updateSleepingBodies()"); + PROFILE("DynamicsWorld::updateSleepingBodies()", &mProfiler); const decimal sleepLinearVelocitySquare = mSleepLinearVelocity * mSleepLinearVelocity; const decimal sleepAngularVelocitySquare = mSleepAngularVelocity * mSleepAngularVelocity; diff --git a/src/engine/DynamicsWorld.h b/src/engine/DynamicsWorld.h index b632dcf2..366b2770 100644 --- a/src/engine/DynamicsWorld.h +++ b/src/engine/DynamicsWorld.h @@ -124,19 +124,9 @@ class DynamicsWorld : public CollisionWorld { /// Integrate the positions and orientations of rigid bodies. void integrateRigidBodiesPositions(); - /// Update the AABBs of the bodies - void updateRigidBodiesAABB(); - /// Reset the external force and torque applied to the bodies void resetBodiesForceAndTorque(); - /// Update the position and orientation of a body - void updatePositionAndOrientationOfBody(RigidBody* body, Vector3 newLinVelocity, - Vector3 newAngVelocity); - - /// Compute and set the interpolation factor to all bodies - void setInterpolationFactorToAllBodies(); - /// Initialize the bodies velocities arrays for the next simulation step. void initVelocityArrays(); @@ -149,9 +139,6 @@ class DynamicsWorld : public CollisionWorld { /// Solve the position error correction of the constraints void solvePositionCorrection(); - /// Cleanup the constrained velocities array at each step - void cleanupConstrainedVelocitiesArray(); - /// Compute the islands of awake bodies. void computeIslands(); @@ -478,7 +465,6 @@ inline void DynamicsWorld::setEventListener(EventListener* eventListener) { mEventListener = eventListener; } - } #endif diff --git a/src/engine/Profiler.cpp b/src/engine/Profiler.cpp index 9437dca0..3212e4a1 100644 --- a/src/engine/Profiler.cpp +++ b/src/engine/Profiler.cpp @@ -27,14 +27,12 @@ // Libraries #include "Profiler.h" +#include using namespace reactphysics3d; // Initialization of static variables -ProfileNode Profiler::mRootNode("Root", nullptr); -ProfileNode* Profiler::mCurrentNode = &Profiler::mRootNode; -long double Profiler::mProfilingStartTime = Timer::getCurrentSystemTime() * 1000.0; -uint Profiler::mFrameCounter = 0; +int Profiler::mNbProfilers = 0; // Constructor ProfileNode::ProfileNode(const char* name, ProfileNode* parentNode) @@ -157,6 +155,35 @@ void ProfileNodeIterator::enterParent() { mCurrentChildNode = mCurrentParentNode->getChildNode(); } +// Constructor +Profiler::Profiler(std::string name) :mRootNode("Root", nullptr) { + + // Set the name of the profiler + if (name == "") { + + if (mNbProfilers == 0) { + mName = "profiler"; + } + else { + mName = std::string("profiler") + std::to_string(mNbProfilers); + } + } + else { + mName = name; + } + + mCurrentNode = &mRootNode; + mProfilingStartTime = Timer::getCurrentSystemTime() * 1000.0; + mFrameCounter = 0; + + mNbProfilers++; +} + +// Destructor +Profiler::~Profiler() { + destroy(); +} + // Method called when we want to start profiling a block of code. void Profiler::startProfilingBlock(const char* name) { diff --git a/src/engine/Profiler.h b/src/engine/Profiler.h index 818d6cc8..45b9b2e9 100644 --- a/src/engine/Profiler.h +++ b/src/engine/Profiler.h @@ -184,57 +184,73 @@ class Profiler { // -------------------- Attributes -------------------- // + /// Profiler name + std::string mName; + + /// Total number of profilers + static int mNbProfilers; + /// Root node of the profiler tree - static ProfileNode mRootNode; + ProfileNode mRootNode; /// Current node in the current execution - static ProfileNode* mCurrentNode; + ProfileNode* mCurrentNode; /// Frame counter - static uint mFrameCounter; + uint mFrameCounter; /// Starting profiling time - static long double mProfilingStartTime; + long double mProfilingStartTime; /// Recursively print the report of a given node of the profiler tree - static void printRecursiveNodeReport(ProfileNodeIterator* iterator, - int spacing, - std::ostream& outputStream); + void printRecursiveNodeReport(ProfileNodeIterator* iterator, int spacing, std::ostream& outputStream); + + /// Destroy a previously allocated iterator + void destroyIterator(ProfileNodeIterator* iterator); + + /// Destroy the profiler (release the memory) + void destroy(); public : // -------------------- Methods -------------------- // + /// Constructor + Profiler(std::string name = ""); + + /// Destructor + ~Profiler(); + /// Method called when we want to start profiling a block of code. - static void startProfilingBlock(const char *name); + void startProfilingBlock(const char *name); /// Method called at the end of the scope where the /// startProfilingBlock() method has been called. - static void stopProfilingBlock(); + void stopProfilingBlock(); /// Reset the timing data of the profiler (but not the profiler tree structure) - static void reset(); + void reset(); /// Return the number of frames - static uint getNbFrames(); + uint getNbFrames(); + + /// Get the name of the profiler + std::string getName() const; + + /// Set the name of the profiler + void setName(std::string name); /// Return the elasped time since the start/reset of the profiling - static long double getElapsedTimeSinceStart(); + long double getElapsedTimeSinceStart(); /// Increment the frame counter - static void incrementFrameCounter(); + void incrementFrameCounter(); /// Return an iterator over the profiler tree starting at the root - static ProfileNodeIterator* getIterator(); + ProfileNodeIterator* getIterator(); /// Print the report of the profiler in a given output stream - static void printReport(std::ostream& outputStream); - - /// Destroy a previously allocated iterator - static void destroyIterator(ProfileNodeIterator* iterator); - - /// Destroy the profiler (release the memory) - static void destroy(); + void printReport(std::ostream& outputStream); }; // Class ProfileSample @@ -245,27 +261,33 @@ class Profiler { */ class ProfileSample { + private: + + Profiler* mProfiler; + public : // -------------------- Methods -------------------- // /// Constructor - ProfileSample(const char* name) { + ProfileSample(const char* name, Profiler* profiler) :mProfiler(profiler) { + + assert(profiler != nullptr); // Ask the profiler to start profiling a block of code - Profiler::startProfilingBlock(name); + mProfiler->startProfilingBlock(name); } /// Destructor ~ProfileSample() { // Tell the profiler to stop profiling a block of code - Profiler::stopProfilingBlock(); + mProfiler->stopProfilingBlock(); } }; // Use this macro to start profile a block of code -#define PROFILE(name) ProfileSample profileSample(name) +#define PROFILE(name, profiler) ProfileSample profileSample(name, profiler) // Return true if we are at the root of the profiler tree inline bool ProfileNodeIterator::isRoot() { @@ -352,6 +374,16 @@ inline uint Profiler::getNbFrames() { return mFrameCounter; } +// Get the name of the profiler +inline std::string Profiler::getName() const { + return mName; +} + +// Set the name of the profiler +inline void Profiler::setName(std::string name) { + mName = name; +} + // Return the elasped time since the start/reset of the profiling inline long double Profiler::getElapsedTimeSinceStart() { long double currentTime = Timer::getCurrentSystemTime() * 1000.0; diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp index f00dbdba..1241b701 100755 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp @@ -49,6 +49,12 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name, Engine // Create the dynamics world for the physics simulation mPhysicsWorld = new rp3d::CollisionWorld(); +#ifdef IS_PROFILING_ACTIVE + + mPhysicsWorld->setProfilerName(name + "_profiler"); + +#endif + // ---------- Sphere 1 ---------- // // Create a sphere and a corresponding collision body in the dynamics world @@ -72,6 +78,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name, Engine mSphere2->setSleepingColor(mRedColorDemo); mPhysicsObjects.push_back(mSphere2); + // ---------- Capsule 1 ---------- // // Create a cylinder and a corresponding collision body in the dynamics world @@ -94,49 +101,49 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name, Engine mCapsule2->setSleepingColor(mRedColorDemo); mPhysicsObjects.push_back(mCapsule2); + // ---------- Concave Mesh ---------- // + + // Create a convex mesh and a corresponding collision body in the dynamics world + mConcaveMesh = new ConcaveMesh(mPhysicsWorld, mMeshFolderPath + "city.obj"); + mAllShapes.push_back(mConcaveMesh); + + // Set the color + mConcaveMesh->setColor(mGreyColorDemo); + mConcaveMesh->setSleepingColor(mRedColorDemo); + mPhysicsObjects.push_back(mConcaveMesh); + // ---------- Box 1 ---------- // - // Create a cylinder and a corresponding collision body in the dynamics world + // Create a cylinder and a corresponding collision body in the dynamics world mBox1 = new Box(BOX_SIZE, mPhysicsWorld, mMeshFolderPath); - mAllShapes.push_back(mBox1); + mAllShapes.push_back(mBox1); - // Set the color - mBox1->setColor(mGreyColorDemo); - mBox1->setSleepingColor(mRedColorDemo); - mPhysicsObjects.push_back(mBox1); + // Set the color + mBox1->setColor(mGreyColorDemo); + mBox1->setSleepingColor(mRedColorDemo); + mPhysicsObjects.push_back(mBox1); - // ---------- Box 2 ---------- // + // ---------- Box 2 ---------- // - // Create a cylinder and a corresponding collision body in the dynamics world + // Create a cylinder and a corresponding collision body in the dynamics world mBox2 = new Box(openglframework::Vector3(3, 2, 5), mPhysicsWorld, mMeshFolderPath); - mAllShapes.push_back(mBox2); + mAllShapes.push_back(mBox2); - // Set the color - mBox2->setColor(mGreyColorDemo); - mBox2->setSleepingColor(mRedColorDemo); - mPhysicsObjects.push_back(mBox2); + // Set the color + mBox2->setColor(mGreyColorDemo); + mBox2->setSleepingColor(mRedColorDemo); + mPhysicsObjects.push_back(mBox2); // ---------- Convex Mesh ---------- // // Create a convex mesh and a corresponding collision body in the dynamics world mConvexMesh = new ConvexMesh(mPhysicsWorld, mMeshFolderPath + "convexmesh.obj"); - mAllShapes.push_back(mConvexMesh); + mAllShapes.push_back(mConvexMesh); // Set the color mConvexMesh->setColor(mGreyColorDemo); mConvexMesh->setSleepingColor(mRedColorDemo); - mPhysicsObjects.push_back(mConvexMesh); - - // ---------- Concave Mesh ---------- // - - // Create a convex mesh and a corresponding collision body in the dynamics world - mConcaveMesh = new ConcaveMesh(mPhysicsWorld, mMeshFolderPath + "city.obj"); - mAllShapes.push_back(mConcaveMesh); - - // Set the color - mConcaveMesh->setColor(mGreyColorDemo); - mConcaveMesh->setSleepingColor(mRedColorDemo); - mPhysicsObjects.push_back(mConcaveMesh); + mPhysicsObjects.push_back(mConvexMesh); // ---------- Heightfield ---------- // @@ -154,14 +161,14 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name, Engine // Reset the scene void CollisionDetectionScene::reset() { - mSphere1->setTransform(rp3d::Transform(rp3d::Vector3(12, 0, 0), rp3d::Quaternion::identity())); - mSphere2->setTransform(rp3d::Transform(rp3d::Vector3(12, 8, 0), rp3d::Quaternion::identity())); - mCapsule1->setTransform(rp3d::Transform(rp3d::Vector3(-6, 7, 0), rp3d::Quaternion::identity())); + mSphere1->setTransform(rp3d::Transform(rp3d::Vector3(15, 5, 0), rp3d::Quaternion::identity())); + mSphere2->setTransform(rp3d::Transform(rp3d::Vector3(0, 6, 0), rp3d::Quaternion::identity())); + mCapsule1->setTransform(rp3d::Transform(rp3d::Vector3(-8, 7, 0), rp3d::Quaternion::identity())); mCapsule2->setTransform(rp3d::Transform(rp3d::Vector3(11, -8, 0), rp3d::Quaternion::identity())); mBox1->setTransform(rp3d::Transform(rp3d::Vector3(-4, -7, 0), rp3d::Quaternion::identity())); - mBox2->setTransform(rp3d::Transform(rp3d::Vector3(0, 8, 0), rp3d::Quaternion::identity())); + mBox2->setTransform(rp3d::Transform(rp3d::Vector3(0, 9, 0), rp3d::Quaternion::identity())); mConvexMesh->setTransform(rp3d::Transform(rp3d::Vector3(-5, 0, 0), rp3d::Quaternion::identity())); - mConcaveMesh->setTransform(rp3d::Transform(rp3d::Vector3(0, 100, 0), rp3d::Quaternion::identity())); + mConcaveMesh->setTransform(rp3d::Transform(rp3d::Vector3(0, 0, 0), rp3d::Quaternion::identity())); mHeightField->setTransform(rp3d::Transform(rp3d::Vector3(0, -12, 0), rp3d::Quaternion::identity())); } diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.h b/testbed/scenes/collisiondetection/CollisionDetectionScene.h old mode 100755 new mode 100644 index 4bea0c0b..e5bd8db9 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.h +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.h @@ -152,7 +152,7 @@ class CollisionDetectionScene : public SceneDemo { std::vector mAllShapes; - uint mSelectedShapeIndex; + unsigned int mSelectedShapeIndex; /// Select the next shape void selectNextShape(); diff --git a/testbed/scenes/collisionshapes/CollisionShapesScene.cpp b/testbed/scenes/collisionshapes/CollisionShapesScene.cpp index a6fd6662..8efc13de 100644 --- a/testbed/scenes/collisionshapes/CollisionShapesScene.cpp +++ b/testbed/scenes/collisionshapes/CollisionShapesScene.cpp @@ -46,7 +46,14 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name, EngineSettin rp3d::Vector3 gravity(0, -9.81f, 0); // Create the dynamics world for the physics simulation - mPhysicsWorld = new rp3d::DynamicsWorld(gravity); + mPhysicsWorld = new rp3d::DynamicsWorld(gravity); + +#ifdef IS_PROFILING_ACTIVE + + mPhysicsWorld->setProfilerName(name + "_profiler"); + +#endif + for (int i=0; isetProfilerName(name + "_profiler"); + +#endif + + // ---------- Create the boxes ----------- // for (int i = 0; isetProfilerName(name + "_profiler"); + +#endif + // Create all the cubes of the scene for (int i=0; isetProfilerName(name + "_profiler"); + +#endif + for (int i = 0; isetProfilerName(name + "_profiler"); + +#endif + // Create the Ball-and-Socket joint createBallAndSocketJoints(); diff --git a/testbed/scenes/raycast/RaycastScene.cpp b/testbed/scenes/raycast/RaycastScene.cpp index bf806183..5705627d 100644 --- a/testbed/scenes/raycast/RaycastScene.cpp +++ b/testbed/scenes/raycast/RaycastScene.cpp @@ -47,6 +47,12 @@ RaycastScene::RaycastScene(const std::string& name, EngineSettings& settings) // Create the dynamics world for the physics simulation mPhysicsWorld = new rp3d::CollisionWorld(); +#ifdef IS_PROFILING_ACTIVE + + mPhysicsWorld->setProfilerName(name + "_profiler"); + +#endif + // ---------- Dumbbell ---------- // // Create a convex mesh and a corresponding collision body in the dynamics world diff --git a/testbed/src/Scene.h b/testbed/src/Scene.h index e33e9da9..89a9afdd 100644 --- a/testbed/src/Scene.h +++ b/testbed/src/Scene.h @@ -53,8 +53,8 @@ struct EngineSettings { long double elapsedTime; // Elapsed time (in seconds) float timeStep; // Current time step (in seconds) - uint nbVelocitySolverIterations; // Nb of velocity solver iterations - uint nbPositionSolverIterations; // Nb of position solver iterations + unsigned int nbVelocitySolverIterations; // Nb of velocity solver iterations + unsigned int nbPositionSolverIterations; // Nb of position solver iterations bool isSleepingEnabled; // True if sleeping technique is enabled float timeBeforeSleep; // Time of inactivity before a body sleep float sleepLinearVelocity; // Sleep linear velocity From 38bd462b91843834a529527b96cad3f1f7ff2ee6 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 13 Nov 2017 18:42:39 +0100 Subject: [PATCH 134/248] Fix issue in SAT algorithm, use the correct penetration depth for each contact point --- src/collision/narrowphase/SAT/SATAlgorithm.cpp | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 47953f1a..327f4465 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -871,8 +871,12 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene bool contactPointsFound = false; for (itPoints = clipPolygonVertices.begin(); itPoints != clipPolygonVertices.end(); ++itPoints) { + // Compute the penetration depth of this contact point (can be different from the minPenetration depth which is + // the maximal penetration depth of any contact point for this separating axis + decimal penetrationDepth = (referenceFaceVertex - (*itPoints)).dot(axisReferenceSpace); + // If the clip point is bellow the reference face - if (((*itPoints) - referenceFaceVertex).dot(axisReferenceSpace) < decimal(0.0)) { + if (penetrationDepth > decimal(0.0)) { contactPointsFound = true; @@ -889,10 +893,10 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene isMinPenetrationFaceNormalPolyhedron1 ? contactPointReferencePolyhedron : contactPointIncidentPolyhedron, isMinPenetrationFaceNormalPolyhedron1 ? contactPointIncidentPolyhedron : contactPointReferencePolyhedron, narrowPhaseInfo->shape1ToWorldTransform, narrowPhaseInfo->shape2ToWorldTransform, - minPenetrationDepth, outWorldNormal); + penetrationDepth, outWorldNormal); // Create a new contact point - narrowPhaseInfo->addContactPoint(outWorldNormal, minPenetrationDepth, + narrowPhaseInfo->addContactPoint(outWorldNormal, penetrationDepth, isMinPenetrationFaceNormalPolyhedron1 ? contactPointReferencePolyhedron : contactPointIncidentPolyhedron, isMinPenetrationFaceNormalPolyhedron1 ? contactPointIncidentPolyhedron : contactPointReferencePolyhedron); } From f403a6e8040832a222ff17ad648889b802aacef5 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 22 Nov 2017 22:43:27 +0100 Subject: [PATCH 135/248] Add temporal coherence for convex vs triangle collision detection --- src/collision/CollisionCallback.h | 2 + src/collision/CollisionDetection.cpp | 18 +- src/collision/ContactManifold.h | 1 + src/collision/ContactManifoldInfo.cpp | 3 + src/collision/MiddlePhaseTriangleCallback.cpp | 6 +- src/collision/MiddlePhaseTriangleCallback.h | 3 +- src/collision/NarrowPhaseInfo.cpp | 7 +- src/collision/NarrowPhaseInfo.h | 17 +- .../CapsuleVsConvexPolyhedronAlgorithm.cpp | 15 +- ...xPolyhedronVsConvexPolyhedronAlgorithm.cpp | 7 +- .../narrowphase/GJK/GJKAlgorithm.cpp | 10 +- .../narrowphase/SAT/SATAlgorithm.cpp | 300 +++++++++--------- .../SphereVsConvexPolyhedronAlgorithm.cpp | 11 +- src/collision/shapes/CollisionShape.cpp | 2 +- src/collision/shapes/CollisionShape.h | 11 + src/collision/shapes/ConcaveMeshShape.cpp | 21 +- src/collision/shapes/ConcaveMeshShape.h | 5 +- src/collision/shapes/ConcaveShape.h | 3 +- src/collision/shapes/HeightFieldShape.cpp | 10 +- src/collision/shapes/HeightFieldShape.h | 12 +- src/collision/shapes/SphereShape.cpp | 3 +- src/collision/shapes/TriangleShape.cpp | 15 +- src/collision/shapes/TriangleShape.h | 28 +- src/constraint/ContactPoint.h | 3 +- src/engine/CollisionWorld.h | 2 +- src/engine/OverlappingPair.cpp | 73 ++++- src/engine/OverlappingPair.h | 50 ++- test/tests/collision/TestRaycast.h | 9 +- 28 files changed, 400 insertions(+), 247 deletions(-) diff --git a/src/collision/CollisionCallback.h b/src/collision/CollisionCallback.h index f860b42d..54208fe4 100644 --- a/src/collision/CollisionCallback.h +++ b/src/collision/CollisionCallback.h @@ -32,6 +32,8 @@ /// ReactPhysics3D namespace namespace reactphysics3d { +class OverlappingPair; + // Class CollisionCallback /** * This class can be used to register a callback for collision test queries. diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 7cb865f9..4808ea65 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -113,6 +113,9 @@ void CollisionDetection::computeMiddlePhase() { // Make all the contact manifolds and contact points of the pair obsolete pair->makeContactsObsolete(); + // Make all the last frame collision info obsolete + pair->makeLastFrameCollisionInfosObsolete(); + ProxyShape* shape1 = pair->getShape1(); ProxyShape* shape2 = pair->getShape2(); @@ -192,6 +195,9 @@ void CollisionDetection::computeMiddlePhase() { // Not handled continue; } + + // Remove the obsolete last frame collision infos + pair->clearObsoleteLastFrameCollisionInfos(); } } } @@ -263,6 +269,8 @@ void CollisionDetection::computeNarrowPhase() { // If there is no collision algorithm between those two kinds of shapes, skip it if (narrowPhaseAlgorithm != nullptr) { + LastFrameCollisionInfo* lastCollisionFrameInfo = currentNarrowPhaseInfo->getLastFrameCollisionInfo(); + // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. @@ -271,14 +279,14 @@ void CollisionDetection::computeNarrowPhase() { // Add the contact points as a potential contact manifold into the pair currentNarrowPhaseInfo->addContactPointsAsPotentialContactManifold(); - currentNarrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasColliding = true; + lastCollisionFrameInfo->wasColliding = true; } else { - currentNarrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasColliding = false; + lastCollisionFrameInfo->wasColliding = false; } // The previous frame collision info is now valid - currentNarrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().isValid = true; + lastCollisionFrameInfo->isValid = true; } currentNarrowPhaseInfo = currentNarrowPhaseInfo->next; @@ -471,6 +479,8 @@ NarrowPhaseInfo* CollisionDetection::computeMiddlePhaseForProxyShapes(Overlappin NarrowPhaseInfo* narrowPhaseInfo = nullptr; + pair->makeLastFrameCollisionInfosObsolete(); + // If both shapes are convex if ((isShape1Convex && isShape2Convex)) { @@ -490,6 +500,8 @@ NarrowPhaseInfo* CollisionDetection::computeMiddlePhaseForProxyShapes(Overlappin computeConvexVsConcaveMiddlePhase(pair, mPoolAllocator, &narrowPhaseInfo); } + pair->clearObsoleteLastFrameCollisionInfos(); + return narrowPhaseInfo; } diff --git a/src/collision/ContactManifold.h b/src/collision/ContactManifold.h index 80a9f456..8303f35c 100644 --- a/src/collision/ContactManifold.h +++ b/src/collision/ContactManifold.h @@ -410,5 +410,6 @@ inline void ContactManifold::setIsObsolete(bool isObsolete, bool setContactPoint } } + #endif diff --git a/src/collision/ContactManifoldInfo.cpp b/src/collision/ContactManifoldInfo.cpp index f22593ac..6740fe4f 100644 --- a/src/collision/ContactManifoldInfo.cpp +++ b/src/collision/ContactManifoldInfo.cpp @@ -62,6 +62,9 @@ void ContactManifoldInfo::reset() { ContactPointInfo* elementToDelete = element; element = element->next; + // Call the constructor + elementToDelete->~ContactPointInfo(); + // Delete the current element mAllocator.release(elementToDelete, sizeof(ContactPointInfo)); } diff --git a/src/collision/MiddlePhaseTriangleCallback.cpp b/src/collision/MiddlePhaseTriangleCallback.cpp index 0bda49d4..58604087 100644 --- a/src/collision/MiddlePhaseTriangleCallback.cpp +++ b/src/collision/MiddlePhaseTriangleCallback.cpp @@ -29,14 +29,12 @@ using namespace reactphysics3d; // Report collision between a triangle of a concave shape and the convex mesh shape (for middle-phase) -void MiddlePhaseTriangleCallback::testTriangle(uint meshSubPart, uint triangleIndex, const Vector3* trianglePoints, - const Vector3* verticesNormals) { +void MiddlePhaseTriangleCallback::testTriangle(const Vector3* trianglePoints, const Vector3* verticesNormals, uint shapeId) { // 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[0], trianglePoints[1], trianglePoints[2], - verticesNormals, meshSubPart, triangleIndex); + TriangleShape(trianglePoints, verticesNormals, shapeId); #ifdef IS_PROFILING_ACTIVE diff --git a/src/collision/MiddlePhaseTriangleCallback.h b/src/collision/MiddlePhaseTriangleCallback.h index 4927c6e0..e04d7a9c 100644 --- a/src/collision/MiddlePhaseTriangleCallback.h +++ b/src/collision/MiddlePhaseTriangleCallback.h @@ -82,8 +82,7 @@ class MiddlePhaseTriangleCallback : public TriangleCallback { } /// Test collision between a triangle and the convex mesh shape - virtual void testTriangle(uint meshSubpart, uint triangleIndex, const Vector3* trianglePoints, - const Vector3* verticesNormals) override; + virtual void testTriangle(const Vector3* trianglePoints, const Vector3* verticesNormals, uint shapeId) override; #ifdef IS_PROFILING_ACTIVE diff --git a/src/collision/NarrowPhaseInfo.cpp b/src/collision/NarrowPhaseInfo.cpp index b4a92a38..660f6704 100644 --- a/src/collision/NarrowPhaseInfo.cpp +++ b/src/collision/NarrowPhaseInfo.cpp @@ -35,12 +35,15 @@ using namespace reactphysics3d; // Constructor NarrowPhaseInfo::NarrowPhaseInfo(OverlappingPair* pair, CollisionShape* shape1, CollisionShape* shape2, const Transform& shape1Transform, - const Transform& shape2Transform, void** cachedData1, void** cachedData2, Allocator& shapeAllocator) + const Transform& shape2Transform, void** cachedData1, void** cachedData2, + Allocator& shapeAllocator) : overlappingPair(pair), collisionShape1(shape1), collisionShape2(shape2), shape1ToWorldTransform(shape1Transform), shape2ToWorldTransform(shape2Transform), contactPoints(nullptr), cachedCollisionData1(cachedData1), - cachedCollisionData2(cachedData2), collisionShapeAllocator(shapeAllocator), next(nullptr) { + cachedCollisionData2(cachedData2), next(nullptr), collisionShapeAllocator(shapeAllocator) { + // Add a collision info for the two collision shapes into the overlapping pair (if not present yet) + overlappingPair->addLastFrameInfoIfNecessary(shape1->getId(), shape2->getId()); } // Destructor diff --git a/src/collision/NarrowPhaseInfo.h b/src/collision/NarrowPhaseInfo.h index c9b18094..b100939f 100644 --- a/src/collision/NarrowPhaseInfo.h +++ b/src/collision/NarrowPhaseInfo.h @@ -29,11 +29,12 @@ // Libraries #include "shapes/CollisionShape.h" #include "collision/ContactManifoldInfo.h" +#include "engine/OverlappingPair.h" /// Namespace ReactPhysics3D namespace reactphysics3d { -class OverlappingPair; +struct LastFrameCollisionInfo; // Class NarrowPhaseInfo /** @@ -70,12 +71,12 @@ struct NarrowPhaseInfo { // TODO : Check if we can use separating axis in OverlappingPair instead of cachedCollisionData1 and cachedCollisionData2 void** cachedCollisionData2; - /// Memory allocator for the collision shape (Used to release TriangleShape memory in destructor) - Allocator& collisionShapeAllocator; - /// Pointer to the next element in the linked list NarrowPhaseInfo* next; + /// Memory allocator for the collision shape (Used to release TriangleShape memory in destructor) + Allocator& collisionShapeAllocator; + /// Constructor NarrowPhaseInfo(OverlappingPair* pair, CollisionShape* shape1, CollisionShape* shape2, const Transform& shape1Transform, @@ -93,8 +94,16 @@ struct NarrowPhaseInfo { /// Reset the remaining contact points void resetContactPoints(); + + /// Get the last collision frame info for temporal coherence + LastFrameCollisionInfo* getLastFrameCollisionInfo() const; }; +// Get the last collision frame info for temporal coherence +inline LastFrameCollisionInfo* NarrowPhaseInfo::getLastFrameCollisionInfo() const { + return overlappingPair->getLastFrameCollisionInfo(collisionShape1->getId(), collisionShape2->getId()); +} + } #endif diff --git a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp index 315dcf7a..300ba5f2 100644 --- a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp @@ -50,10 +50,13 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPh #endif + // Get the last frame collision info + LastFrameCollisionInfo* lastFrameCollisionInfo = narrowPhaseInfo->getLastFrameCollisionInfo(); + GJKAlgorithm::GJKResult result = gjkAlgorithm.testCollision(narrowPhaseInfo, reportContacts); - narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = true; - narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = false; + lastFrameCollisionInfo->wasUsingGJK = true; + lastFrameCollisionInfo->wasUsingSAT = false; assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON || narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); @@ -140,8 +143,8 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPh } } - narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = false; - narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = false; + lastFrameCollisionInfo->wasUsingSAT = false; + lastFrameCollisionInfo->wasUsingGJK = false; // Return true return true; @@ -153,8 +156,8 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPh // Run the SAT algorithm to find the separating axis and compute contact point bool isColliding = satAlgorithm.testCollisionCapsuleVsConvexPolyhedron(narrowPhaseInfo, reportContacts); - narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = false; - narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = true; + lastFrameCollisionInfo->wasUsingGJK = false; + lastFrameCollisionInfo->wasUsingSAT = true; return isColliding; } diff --git a/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp index 9f2bb47e..507f6043 100644 --- a/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp @@ -45,10 +45,13 @@ bool ConvexPolyhedronVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* #endif + // Get the last frame collision info + LastFrameCollisionInfo* lastFrameCollisionInfo = narrowPhaseInfo->getLastFrameCollisionInfo(); + bool isColliding = satAlgorithm.testCollisionConvexPolyhedronVsConvexPolyhedron(narrowPhaseInfo, reportContacts); - narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = true; - narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = false; + lastFrameCollisionInfo->wasUsingSAT = true; + lastFrameCollisionInfo->wasUsingGJK = false; return isColliding; } diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp index c0f436a6..dcfff45e 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp @@ -88,11 +88,13 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhase // Create a simplex set VoronoiSimplex simplex; + // Get the last collision frame info + LastFrameCollisionInfo* lastFrameCollisionInfo = narrowPhaseInfo->getLastFrameCollisionInfo(); + // Get the previous point V (last cached separating axis) Vector3 v; - LastFrameCollisionInfo& lastFrameInfo = narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo(); - if (lastFrameInfo.isValid && lastFrameInfo.wasUsingGJK) { - v = lastFrameInfo.gjkSeparatingAxis; + if (lastFrameCollisionInfo->isValid && lastFrameCollisionInfo->wasUsingGJK) { + v = lastFrameCollisionInfo->gjkSeparatingAxis; assert(v.lengthSquare() > decimal(0.000001)); } else { @@ -117,7 +119,7 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhase if (vDotw > decimal(0.0) && vDotw * vDotw > distSquare * marginSquare) { // Cache the current separating axis for frame coherence - narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().gjkSeparatingAxis = v; + lastFrameCollisionInfo->gjkSeparatingAxis = v; // No intersection, we return return GJKResult::SEPARATED; diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 327f4465..761bd5ec 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -74,7 +74,6 @@ bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfo* narrow decimal minPenetrationDepth = DECIMAL_LARGEST; uint minFaceIndex = 0; - // For each face of the convex mesh for (uint f = 0; f < polyhedron->getNbFaces(); f++) { @@ -110,7 +109,6 @@ bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfo* narrow narrowPhaseInfo->shape1ToWorldTransform, narrowPhaseInfo->shape2ToWorldTransform, minPenetrationDepth, normalWorld); - // Create the contact info object narrowPhaseInfo->addContactPoint(normalWorld, minPenetrationDepth, isSphereShape1 ? contactPointSphereLocal : contactPointPolyhedronLocal, @@ -468,156 +466,152 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn Vector3 separatingEdge2A, separatingEdge2B; Vector3 minEdgeVsEdgeSeparatingAxisPolyhedron2Space; - LastFrameCollisionInfo& lastFrameInfo = narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo(); - // True if the shapes were overlapping in the previous frame and are // still overlapping on the same axis in this frame bool isTemporalCoherenceValid = false; - // If the shapes are not triangles (no temporal coherence for triangle collision because we do not store previous - // frame collision data per triangle) - if (polyhedron1->getName() != CollisionShapeName::TRIANGLE && polyhedron2->getName() != CollisionShapeName::TRIANGLE) { + LastFrameCollisionInfo* lastFrameCollisionInfo = narrowPhaseInfo->getLastFrameCollisionInfo(); - // If the last frame collision info is valid and was also using SAT algorithm - if (lastFrameInfo.isValid && lastFrameInfo.wasUsingSAT) { + // If the last frame collision info is valid and was also using SAT algorithm + if (lastFrameCollisionInfo->isValid && lastFrameCollisionInfo->wasUsingSAT) { - // We perform temporal coherence, we check if there is still an overlapping along the previous minimum separating - // axis. If it is the case, we directly report the collision without executing the whole SAT algorithm again. If - // the shapes are still separated along this axis, we directly exit with no collision. + // We perform temporal coherence, we check if there is still an overlapping along the previous minimum separating + // axis. If it is the case, we directly report the collision without executing the whole SAT algorithm again. If + // the shapes are still separated along this axis, we directly exit with no collision. - // If the previous separating axis (or axis with minimum penetration depth) - // was a face normal of polyhedron 1 - if (lastFrameInfo.satIsAxisFacePolyhedron1) { + // If the previous separating axis (or axis with minimum penetration depth) + // was a face normal of polyhedron 1 + if (lastFrameCollisionInfo->satIsAxisFacePolyhedron1) { - decimal penetrationDepth = testSingleFaceDirectionPolyhedronVsPolyhedron(polyhedron1, polyhedron2, polyhedron1ToPolyhedron2, - lastFrameInfo.satMinAxisFaceIndex); - // If the previous axis is a separating axis - if (penetrationDepth <= decimal(0.0)) { + decimal penetrationDepth = testSingleFaceDirectionPolyhedronVsPolyhedron(polyhedron1, polyhedron2, polyhedron1ToPolyhedron2, + lastFrameCollisionInfo->satMinAxisFaceIndex); + // If the previous axis is a separating axis + if (penetrationDepth <= decimal(0.0)) { - // Return no collision - return false; - } - - // The two shapes are overlapping as in the previous frame and on the same axis, therefore - // we will skip the entire SAT algorithm because the minimum separating axis did not change - isTemporalCoherenceValid = lastFrameInfo.wasColliding; - - if (isTemporalCoherenceValid) { - - minPenetrationDepth = penetrationDepth; - minFaceIndex = lastFrameInfo.satMinAxisFaceIndex; - isMinPenetrationFaceNormal = true; - isMinPenetrationFaceNormalPolyhedron1 = true; - - // Compute the contact points between two faces of two convex polyhedra. - // If contact points have been found, we report them without running the whole SAT algorithm - if(computePolyhedronVsPolyhedronFaceContactPoints(isMinPenetrationFaceNormalPolyhedron1, polyhedron1, polyhedron2, - polyhedron1ToPolyhedron2, polyhedron2ToPolyhedron1, minFaceIndex, - narrowPhaseInfo, minPenetrationDepth)) { - - lastFrameInfo.satIsAxisFacePolyhedron1 = isMinPenetrationFaceNormalPolyhedron1; - lastFrameInfo.satIsAxisFacePolyhedron2 = !isMinPenetrationFaceNormalPolyhedron1; - lastFrameInfo.satMinAxisFaceIndex = minFaceIndex; - - return true; - } - else { // Contact points have not been found (the set of clipped points was empty) - - // Therefore, we need to run the whole SAT algorithm again - isTemporalCoherenceValid = false; - } - } + // Return no collision + return false; } - else if (lastFrameInfo.satIsAxisFacePolyhedron2) { // If the previous separating axis (or axis with minimum penetration depth) - // was a face normal of polyhedron 2 - decimal penetrationDepth = testSingleFaceDirectionPolyhedronVsPolyhedron(polyhedron2, polyhedron1, polyhedron2ToPolyhedron1, - lastFrameInfo.satMinAxisFaceIndex); - // If the previous axis is a separating axis - if (penetrationDepth <= decimal(0.0)) { + // The two shapes are overlapping as in the previous frame and on the same axis, therefore + // we will skip the entire SAT algorithm because the minimum separating axis did not change + isTemporalCoherenceValid = lastFrameCollisionInfo->wasColliding; - // Return no collision - return false; + if (isTemporalCoherenceValid) { + + minPenetrationDepth = penetrationDepth; + minFaceIndex = lastFrameCollisionInfo->satMinAxisFaceIndex; + isMinPenetrationFaceNormal = true; + isMinPenetrationFaceNormalPolyhedron1 = true; + + // Compute the contact points between two faces of two convex polyhedra. + // If contact points have been found, we report them without running the whole SAT algorithm + if(computePolyhedronVsPolyhedronFaceContactPoints(isMinPenetrationFaceNormalPolyhedron1, polyhedron1, polyhedron2, + polyhedron1ToPolyhedron2, polyhedron2ToPolyhedron1, minFaceIndex, + narrowPhaseInfo, minPenetrationDepth)) { + + lastFrameCollisionInfo->satIsAxisFacePolyhedron1 = isMinPenetrationFaceNormalPolyhedron1; + lastFrameCollisionInfo->satIsAxisFacePolyhedron2 = !isMinPenetrationFaceNormalPolyhedron1; + lastFrameCollisionInfo->satMinAxisFaceIndex = minFaceIndex; + + return true; } + else { // Contact points have not been found (the set of clipped points was empty) - // The two shapes are overlapping as in the previous frame and on the same axis, therefore - // we will skip the entire SAT algorithm because the minimum separating axis did not change - isTemporalCoherenceValid = lastFrameInfo.wasColliding; - - if (isTemporalCoherenceValid) { - - minPenetrationDepth = penetrationDepth; - minFaceIndex = lastFrameInfo.satMinAxisFaceIndex; - isMinPenetrationFaceNormal = true; - isMinPenetrationFaceNormalPolyhedron1 = false; - - // Compute the contact points between two faces of two convex polyhedra. - // If contact points have been found, we report them without running the whole SAT algorithm - if(computePolyhedronVsPolyhedronFaceContactPoints(isMinPenetrationFaceNormalPolyhedron1, polyhedron1, polyhedron2, - polyhedron1ToPolyhedron2, polyhedron2ToPolyhedron1, minFaceIndex, - narrowPhaseInfo, minPenetrationDepth)) { - - lastFrameInfo.satIsAxisFacePolyhedron1 = isMinPenetrationFaceNormalPolyhedron1; - lastFrameInfo.satIsAxisFacePolyhedron2 = !isMinPenetrationFaceNormalPolyhedron1; - lastFrameInfo.satMinAxisFaceIndex = minFaceIndex; - - return true; - } - else { // Contact points have not been found (the set of clipped points was empty) - - // Therefore, we need to run the whole SAT algorithm again - isTemporalCoherenceValid = false; - } - } - } - else { // If the previous separating axis (or axis with minimum penetration depth) was the cross product of two edges - - HalfEdgeStructure::Edge edge1 = polyhedron1->getHalfEdge(lastFrameInfo.satMinEdge1Index); - HalfEdgeStructure::Edge edge2 = polyhedron2->getHalfEdge(lastFrameInfo.satMinEdge2Index); - - Vector3 separatingAxisPolyhedron2Space; - - const Vector3 edge1A = polyhedron1ToPolyhedron2 * polyhedron1->getVertexPosition(edge1.vertexIndex); - const Vector3 edge1B = polyhedron1ToPolyhedron2 * polyhedron1->getVertexPosition(polyhedron1->getHalfEdge(edge1.nextEdgeIndex).vertexIndex); - const Vector3 edge1Direction = edge1B - edge1A; - const Vector3 edge2A = polyhedron2->getVertexPosition(edge2.vertexIndex); - const Vector3 edge2B = polyhedron2->getVertexPosition(polyhedron2->getHalfEdge(edge2.nextEdgeIndex).vertexIndex); - const Vector3 edge2Direction = edge2B - edge2A; - - // Compute the penetration depth - decimal penetrationDepth = computeDistanceBetweenEdges(edge1A, edge2A, polyhedron2->getCentroid(), - edge1Direction, edge2Direction, separatingAxisPolyhedron2Space); - - // If the previous axis is a separating axis - if (penetrationDepth <= decimal(0.0)) { - - // Return no collision - return false; - } - - // The two shapes are overlapping as in the previous frame and on the same axis, therefore - // we will skip the entire SAT algorithm because the minimum separating axis did not change - isTemporalCoherenceValid = lastFrameInfo.wasColliding; - - // Temporal coherence is valid only if the two edges build a minkowski - // face (and the cross product is therefore a candidate for separating axis - if (isTemporalCoherenceValid && !testEdgesBuildMinkowskiFace(polyhedron1, edge1, polyhedron2, edge2, polyhedron1ToPolyhedron2)) { + // Therefore, we need to run the whole SAT algorithm again isTemporalCoherenceValid = false; } + } + } + else if (lastFrameCollisionInfo->satIsAxisFacePolyhedron2) { // If the previous separating axis (or axis with minimum penetration depth) + // was a face normal of polyhedron 2 - if (isTemporalCoherenceValid) { + decimal penetrationDepth = testSingleFaceDirectionPolyhedronVsPolyhedron(polyhedron2, polyhedron1, polyhedron2ToPolyhedron1, + lastFrameCollisionInfo->satMinAxisFaceIndex); - minPenetrationDepth = penetrationDepth; - isMinPenetrationFaceNormal = false; - isMinPenetrationFaceNormalPolyhedron1 = false; - minSeparatingEdge1Index = lastFrameInfo.satMinEdge1Index; - minSeparatingEdge2Index = lastFrameInfo.satMinEdge2Index; - separatingEdge1A = edge1A; - separatingEdge1B = edge1B; - separatingEdge2A = edge2A; - separatingEdge2B = edge2B; - minEdgeVsEdgeSeparatingAxisPolyhedron2Space = separatingAxisPolyhedron2Space; + // If the previous axis is a separating axis + if (penetrationDepth <= decimal(0.0)) { + + // Return no collision + return false; + } + + // The two shapes are overlapping as in the previous frame and on the same axis, therefore + // we will skip the entire SAT algorithm because the minimum separating axis did not change + isTemporalCoherenceValid = lastFrameCollisionInfo->wasColliding; + + if (isTemporalCoherenceValid) { + + minPenetrationDepth = penetrationDepth; + minFaceIndex = lastFrameCollisionInfo->satMinAxisFaceIndex; + isMinPenetrationFaceNormal = true; + isMinPenetrationFaceNormalPolyhedron1 = false; + + // Compute the contact points between two faces of two convex polyhedra. + // If contact points have been found, we report them without running the whole SAT algorithm + if(computePolyhedronVsPolyhedronFaceContactPoints(isMinPenetrationFaceNormalPolyhedron1, polyhedron1, polyhedron2, + polyhedron1ToPolyhedron2, polyhedron2ToPolyhedron1, minFaceIndex, + narrowPhaseInfo, minPenetrationDepth)) { + + lastFrameCollisionInfo->satIsAxisFacePolyhedron1 = isMinPenetrationFaceNormalPolyhedron1; + lastFrameCollisionInfo->satIsAxisFacePolyhedron2 = !isMinPenetrationFaceNormalPolyhedron1; + lastFrameCollisionInfo->satMinAxisFaceIndex = minFaceIndex; + + return true; } + else { // Contact points have not been found (the set of clipped points was empty) + + // Therefore, we need to run the whole SAT algorithm again + isTemporalCoherenceValid = false; + } + } + } + else { // If the previous separating axis (or axis with minimum penetration depth) was the cross product of two edges + + HalfEdgeStructure::Edge edge1 = polyhedron1->getHalfEdge(lastFrameCollisionInfo->satMinEdge1Index); + HalfEdgeStructure::Edge edge2 = polyhedron2->getHalfEdge(lastFrameCollisionInfo->satMinEdge2Index); + + Vector3 separatingAxisPolyhedron2Space; + + const Vector3 edge1A = polyhedron1ToPolyhedron2 * polyhedron1->getVertexPosition(edge1.vertexIndex); + const Vector3 edge1B = polyhedron1ToPolyhedron2 * polyhedron1->getVertexPosition(polyhedron1->getHalfEdge(edge1.nextEdgeIndex).vertexIndex); + const Vector3 edge1Direction = edge1B - edge1A; + const Vector3 edge2A = polyhedron2->getVertexPosition(edge2.vertexIndex); + const Vector3 edge2B = polyhedron2->getVertexPosition(polyhedron2->getHalfEdge(edge2.nextEdgeIndex).vertexIndex); + const Vector3 edge2Direction = edge2B - edge2A; + + // Compute the penetration depth + decimal penetrationDepth = computeDistanceBetweenEdges(edge1A, edge2A, polyhedron2->getCentroid(), + edge1Direction, edge2Direction, separatingAxisPolyhedron2Space); + + // If the previous axis is a separating axis + if (penetrationDepth <= decimal(0.0)) { + + // Return no collision + return false; + } + + // The two shapes are overlapping as in the previous frame and on the same axis, therefore + // we will skip the entire SAT algorithm because the minimum separating axis did not change + isTemporalCoherenceValid = lastFrameCollisionInfo->wasColliding; + + // Temporal coherence is valid only if the two edges build a minkowski + // face (and the cross product is therefore a candidate for separating axis + if (isTemporalCoherenceValid && !testEdgesBuildMinkowskiFace(polyhedron1, edge1, polyhedron2, edge2, polyhedron1ToPolyhedron2)) { + isTemporalCoherenceValid = false; + } + + if (isTemporalCoherenceValid) { + + minPenetrationDepth = penetrationDepth; + isMinPenetrationFaceNormal = false; + isMinPenetrationFaceNormalPolyhedron1 = false; + minSeparatingEdge1Index = lastFrameCollisionInfo->satMinEdge1Index; + minSeparatingEdge2Index = lastFrameCollisionInfo->satMinEdge2Index; + separatingEdge1A = edge1A; + separatingEdge1B = edge1B; + separatingEdge2A = edge2A; + separatingEdge2B = edge2B; + minEdgeVsEdgeSeparatingAxisPolyhedron2Space = separatingAxisPolyhedron2Space; } } } @@ -631,9 +625,9 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn decimal penetrationDepth = testFacesDirectionPolyhedronVsPolyhedron(polyhedron1, polyhedron2, polyhedron1ToPolyhedron2, faceIndex); if (penetrationDepth <= decimal(0.0)) { - lastFrameInfo.satIsAxisFacePolyhedron1 = true; - lastFrameInfo.satIsAxisFacePolyhedron2 = false; - lastFrameInfo.satMinAxisFaceIndex = faceIndex; + lastFrameCollisionInfo->satIsAxisFacePolyhedron1 = true; + lastFrameCollisionInfo->satIsAxisFacePolyhedron2 = false; + lastFrameCollisionInfo->satMinAxisFaceIndex = faceIndex; // We have found a separating axis return false; @@ -649,9 +643,9 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn penetrationDepth = testFacesDirectionPolyhedronVsPolyhedron(polyhedron2, polyhedron1, polyhedron2ToPolyhedron1, faceIndex); if (penetrationDepth <= decimal(0.0)) { - lastFrameInfo.satIsAxisFacePolyhedron1 = false; - lastFrameInfo.satIsAxisFacePolyhedron2 = true; - lastFrameInfo.satMinAxisFaceIndex = faceIndex; + lastFrameCollisionInfo->satIsAxisFacePolyhedron1 = false; + lastFrameCollisionInfo->satIsAxisFacePolyhedron2 = true; + lastFrameCollisionInfo->satMinAxisFaceIndex = faceIndex; // We have found a separating axis return false; @@ -694,10 +688,10 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn if (penetrationDepth <= decimal(0.0)) { - lastFrameInfo.satIsAxisFacePolyhedron1 = false; - lastFrameInfo.satIsAxisFacePolyhedron2 = false; - lastFrameInfo.satMinEdge1Index = i; - lastFrameInfo.satMinEdge2Index = j; + lastFrameCollisionInfo->satIsAxisFacePolyhedron1 = false; + lastFrameCollisionInfo->satIsAxisFacePolyhedron2 = false; + lastFrameCollisionInfo->satMinEdge1Index = i; + lastFrameCollisionInfo->satMinEdge2Index = j; // We have found a separating axis return false; @@ -742,18 +736,18 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn // because of a numerical issue if (!contactsFound) { - lastFrameInfo.satIsAxisFacePolyhedron1 = isMinPenetrationFaceNormalPolyhedron1; - lastFrameInfo.satIsAxisFacePolyhedron2 = !isMinPenetrationFaceNormalPolyhedron1; - lastFrameInfo.satMinAxisFaceIndex = minFaceIndex; + lastFrameCollisionInfo->satIsAxisFacePolyhedron1 = isMinPenetrationFaceNormalPolyhedron1; + lastFrameCollisionInfo->satIsAxisFacePolyhedron2 = !isMinPenetrationFaceNormalPolyhedron1; + lastFrameCollisionInfo->satMinAxisFaceIndex = minFaceIndex; // Return no collision return false; } } - lastFrameInfo.satIsAxisFacePolyhedron1 = isMinPenetrationFaceNormalPolyhedron1; - lastFrameInfo.satIsAxisFacePolyhedron2 = !isMinPenetrationFaceNormalPolyhedron1; - lastFrameInfo.satMinAxisFaceIndex = minFaceIndex; + lastFrameCollisionInfo->satIsAxisFacePolyhedron1 = isMinPenetrationFaceNormalPolyhedron1; + lastFrameCollisionInfo->satIsAxisFacePolyhedron2 = !isMinPenetrationFaceNormalPolyhedron1; + lastFrameCollisionInfo->satMinAxisFaceIndex = minFaceIndex; } else { // If we have an edge vs edge contact @@ -781,10 +775,10 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn closestPointPolyhedron1EdgeLocalSpace, closestPointPolyhedron2Edge); } - lastFrameInfo.satIsAxisFacePolyhedron1 = false; - lastFrameInfo.satIsAxisFacePolyhedron2 = false; - lastFrameInfo.satMinEdge1Index = minSeparatingEdge1Index; - lastFrameInfo.satMinEdge2Index = minSeparatingEdge2Index; + lastFrameCollisionInfo->satIsAxisFacePolyhedron1 = false; + lastFrameCollisionInfo->satIsAxisFacePolyhedron2 = false; + lastFrameCollisionInfo->satMinEdge1Index = minSeparatingEdge1Index; + lastFrameCollisionInfo->satMinEdge2Index = minSeparatingEdge2Index; } return true; diff --git a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp index ae3764ab..28a565c1 100644 --- a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp @@ -41,6 +41,9 @@ bool SphereVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPha assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE || narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::SPHERE); + // Get the last frame collision info + LastFrameCollisionInfo* lastFrameCollisionInfo = narrowPhaseInfo->getLastFrameCollisionInfo(); + // First, we run the GJK algorithm GJKAlgorithm gjkAlgorithm; @@ -52,8 +55,8 @@ bool SphereVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPha GJKAlgorithm::GJKResult result = gjkAlgorithm.testCollision(narrowPhaseInfo, reportContacts); - narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = true; - narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = false; + lastFrameCollisionInfo->wasUsingGJK = true; + lastFrameCollisionInfo->wasUsingSAT = false; // If we have found a contact point inside the margins (shallow penetration) if (result == GJKAlgorithm::GJKResult::COLLIDE_IN_MARGIN) { @@ -76,8 +79,8 @@ bool SphereVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPha bool isColliding = satAlgorithm.testCollisionSphereVsConvexPolyhedron(narrowPhaseInfo, reportContacts); - narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingGJK = false; - narrowPhaseInfo->overlappingPair->getLastFrameCollisionInfo().wasUsingSAT = true; + lastFrameCollisionInfo->wasUsingGJK = false; + lastFrameCollisionInfo->wasUsingSAT = true; return isColliding; } diff --git a/src/collision/shapes/CollisionShape.cpp b/src/collision/shapes/CollisionShape.cpp index a89747c9..0b64190e 100644 --- a/src/collision/shapes/CollisionShape.cpp +++ b/src/collision/shapes/CollisionShape.cpp @@ -33,7 +33,7 @@ using namespace reactphysics3d; // Constructor CollisionShape::CollisionShape(CollisionShapeName name, CollisionShapeType type) - : mType(type), mName(name), mScaling(1.0, 1.0, 1.0) { + : mType(type), mName(name), mScaling(1.0, 1.0, 1.0), mId(0) { } diff --git a/src/collision/shapes/CollisionShape.h b/src/collision/shapes/CollisionShape.h index feb4c502..6792cc09 100644 --- a/src/collision/shapes/CollisionShape.h +++ b/src/collision/shapes/CollisionShape.h @@ -71,6 +71,9 @@ class CollisionShape { /// Scaling vector of the collision shape Vector3 mScaling; + /// Unique identifier of the shape inside an overlapping pair + uint mId; + #ifdef IS_PROFILING_ACTIVE /// Pointer to the profiler @@ -126,6 +129,9 @@ class CollisionShape { /// Set the local scaling vector of the collision shape virtual void setLocalScaling(const Vector3& scaling); + /// Return the id of the shape + uint getId() const; + /// Return the local inertia tensor of the collision shapes virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const=0; @@ -171,6 +177,11 @@ inline void CollisionShape::setLocalScaling(const Vector3& scaling) { mScaling = scaling; } +// Return the id of the shape +inline uint CollisionShape::getId() const { + return mId; +} + #ifdef IS_PROFILING_ACTIVE // Set the profiler diff --git a/src/collision/shapes/ConcaveMeshShape.cpp b/src/collision/shapes/ConcaveMeshShape.cpp index 646638dd..ee90ce46 100644 --- a/src/collision/shapes/ConcaveMeshShape.cpp +++ b/src/collision/shapes/ConcaveMeshShape.cpp @@ -135,6 +135,22 @@ bool ConcaveMeshShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxySh return raycastCallback.getIsHit(); } +// Compute the shape Id for a given triangle of the mesh +uint ConcaveMeshShape::computeTriangleShapeId(uint subPart, uint triangleIndex) const { + + uint shapeId = 0; + + uint i=0; + while (i < subPart) { + + shapeId += mTriangleMesh->getSubpart(i)->getNbTriangles(); + + i++; + } + + return shapeId + triangleIndex; +} + // Collect all the AABB nodes that are hit by the ray in the Dynamic AABB Tree decimal ConcaveMeshRaycastCallback::raycastBroadPhaseShape(int32 nodeId, const Ray& ray) { @@ -162,9 +178,9 @@ void ConcaveMeshRaycastCallback::raycastTriangles() { // Get the vertices normals of the triangle Vector3 verticesNormals[3]; mConcaveMeshShape.getTriangleVerticesNormals(data[0], data[1], verticesNormals); + // Create a triangle collision shape - TriangleShape triangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], - verticesNormals, data[0], data[1]); + TriangleShape triangleShape(trianglePoints, verticesNormals, mConcaveMeshShape.computeTriangleShapeId(data[0], data[1])); triangleShape.setRaycastTestType(mConcaveMeshShape.getRaycastTestType()); #ifdef IS_PROFILING_ACTIVE @@ -194,5 +210,6 @@ void ConcaveMeshRaycastCallback::raycastTriangles() { smallestHitFraction = raycastInfo.hitFraction; mIsHit = true; } + } } diff --git a/src/collision/shapes/ConcaveMeshShape.h b/src/collision/shapes/ConcaveMeshShape.h index 678d5325..2d0a3e9c 100644 --- a/src/collision/shapes/ConcaveMeshShape.h +++ b/src/collision/shapes/ConcaveMeshShape.h @@ -155,6 +155,9 @@ class ConcaveMeshShape : public ConcaveShape { /// Return the three vertex normals (in the array outVerticesNormals) of a triangle void getTriangleVerticesNormals(uint subPart, uint triangleIndex, Vector3* outVerticesNormals) const; + /// Compute the shape Id for a given triangle of the mesh + uint computeTriangleShapeId(uint subPart, uint triangleIndex) const; + public: /// Constructor @@ -259,7 +262,7 @@ inline void ConvexTriangleAABBOverlapCallback::notifyOverlappingNode(int nodeId) mConcaveMeshShape.getTriangleVerticesNormals(data[0], data[1], verticesNormals); // Call the callback to test narrow-phase collision with this triangle - mTriangleTestCallback.testTriangle(data[0], data[1], trianglePoints, verticesNormals); + mTriangleTestCallback.testTriangle(trianglePoints, verticesNormals, mConcaveMeshShape.computeTriangleShapeId(data[0], data[1])); } #ifdef IS_PROFILING_ACTIVE diff --git a/src/collision/shapes/ConcaveShape.h b/src/collision/shapes/ConcaveShape.h index abc3759b..eb00d8f0 100644 --- a/src/collision/shapes/ConcaveShape.h +++ b/src/collision/shapes/ConcaveShape.h @@ -46,8 +46,7 @@ class TriangleCallback { virtual ~TriangleCallback() = default; /// Report a triangle - virtual void testTriangle(uint meshSubPart, uint triangleIndex, - const Vector3* trianglePoints, const Vector3* verticesNormals)=0; + virtual void testTriangle(const Vector3* trianglePoints, const Vector3* verticesNormals, uint shapeId)=0; }; diff --git a/src/collision/shapes/HeightFieldShape.cpp b/src/collision/shapes/HeightFieldShape.cpp index 08ec19a4..74276a75 100644 --- a/src/collision/shapes/HeightFieldShape.cpp +++ b/src/collision/shapes/HeightFieldShape.cpp @@ -154,7 +154,7 @@ void HeightFieldShape::testAllTriangles(TriangleCallback& callback, const AABB& Vector3 verticesNormals1[3] = {triangle1Normal, triangle1Normal, triangle1Normal}; // Test collision against the first triangle - callback.testTriangle(0, 0, trianglePoints, verticesNormals1); + callback.testTriangle(trianglePoints, verticesNormals1, computeTriangleShapeId(i, j, 0)); // Generate the second triangle for the current grid rectangle trianglePoints[0] = p3; @@ -174,7 +174,7 @@ void HeightFieldShape::testAllTriangles(TriangleCallback& callback, const AABB& Vector3 verticesNormals2[3] = {triangle2Normal, triangle2Normal, triangle2Normal}; // Test collision against the second triangle - callback.testTriangle(0, 0, trianglePoints, verticesNormals2); + callback.testTriangle(trianglePoints, verticesNormals2, computeTriangleShapeId(i, j, 1)); } } } @@ -263,12 +263,10 @@ Vector3 HeightFieldShape::getVertexAt(int x, int y) const { } // Raycast test between a ray and a triangle of the heightfield -void TriangleOverlapCallback::testTriangle(uint meshSubPart, uint triangleIndex, const Vector3* trianglePoints, - const Vector3* verticesNormals) { +void TriangleOverlapCallback::testTriangle(const Vector3* trianglePoints, const Vector3* verticesNormals, uint shapeId) { // Create a triangle collision shape - TriangleShape triangleShape(trianglePoints[0], trianglePoints[1], trianglePoints[2], - verticesNormals, meshSubPart, triangleIndex); + TriangleShape triangleShape(trianglePoints, verticesNormals, shapeId); triangleShape.setRaycastTestType(mHeightFieldShape.getRaycastTestType()); #ifdef IS_PROFILING_ACTIVE diff --git a/src/collision/shapes/HeightFieldShape.h b/src/collision/shapes/HeightFieldShape.h index 80c18d9c..f8b498d5 100644 --- a/src/collision/shapes/HeightFieldShape.h +++ b/src/collision/shapes/HeightFieldShape.h @@ -71,8 +71,7 @@ class TriangleOverlapCallback : public TriangleCallback { bool getIsHit() const {return mIsHit;} /// Raycast test between a ray and a triangle of the heightfield - virtual void testTriangle(uint meshSubPart, uint triangleIndex, - const Vector3* trianglePoints, const Vector3* verticesNormals) override; + virtual void testTriangle(const Vector3* trianglePoints, const Vector3* verticesNormals, uint shapeId) override; #ifdef IS_PROFILING_ACTIVE @@ -169,6 +168,9 @@ class HeightFieldShape : public ConcaveShape { /// Compute the min/max grid coords corresponding to the intersection of the AABB of the height field and the AABB to collide 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; + public: /// Constructor @@ -270,6 +272,12 @@ inline void HeightFieldShape::computeLocalInertiaTensor(Matrix3x3& tensor, decim 0, 0, mass); } +// Compute the shape Id for a given triangle +inline uint HeightFieldShape::computeTriangleShapeId(uint iIndex, uint jIndex, uint secondTriangleIncrement) const { + + return (jIndex * (mNbColumns - 1) + iIndex) * 2 + secondTriangleIncrement; +} + } #endif diff --git a/src/collision/shapes/SphereShape.cpp b/src/collision/shapes/SphereShape.cpp index 8583e80d..fa6b4f6a 100644 --- a/src/collision/shapes/SphereShape.cpp +++ b/src/collision/shapes/SphereShape.cpp @@ -35,7 +35,8 @@ using namespace reactphysics3d; /** * @param radius Radius of the sphere (in meters) */ -SphereShape::SphereShape(decimal radius) : ConvexShape(CollisionShapeName::SPHERE, CollisionShapeType::SPHERE, radius) { +SphereShape::SphereShape(decimal radius) + : ConvexShape(CollisionShapeName::SPHERE, CollisionShapeType::SPHERE, radius) { assert(radius > decimal(0.0)); } diff --git a/src/collision/shapes/TriangleShape.cpp b/src/collision/shapes/TriangleShape.cpp index 020053b6..77d0929c 100644 --- a/src/collision/shapes/TriangleShape.cpp +++ b/src/collision/shapes/TriangleShape.cpp @@ -43,16 +43,15 @@ 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& point1, const Vector3& point2, const Vector3& point3, - const Vector3* verticesNormals, uint meshSubPart, uint triangleIndex) - : ConvexPolyhedronShape(CollisionShapeName::TRIANGLE), mMeshSubPart(meshSubPart), mTriangleIndex(triangleIndex) { +TriangleShape::TriangleShape(const Vector3* vertices, const Vector3* verticesNormals, uint shapeId) + : ConvexPolyhedronShape(CollisionShapeName::TRIANGLE) { - mPoints[0] = point1; - mPoints[1] = point2; - mPoints[2] = point3; + mPoints[0] = vertices[0]; + mPoints[1] = vertices[1]; + mPoints[2] = vertices[2]; // Compute the triangle normal - mNormal = (point2 - point1).cross(point3 - point1); + mNormal = (vertices[1] - vertices[0]).cross(vertices[2] - vertices[0]); mNormal.normalize(); mVerticesNormals[0] = verticesNormals[0]; @@ -60,6 +59,8 @@ TriangleShape::TriangleShape(const Vector3& point1, const Vector3& point2, const mVerticesNormals[2] = verticesNormals[2]; mRaycastTestType = TriangleRaycastSide::FRONT; + + mId = shapeId; } // This method compute the smooth mesh contact with a triangle in case one of the two collision diff --git a/src/collision/shapes/TriangleShape.h b/src/collision/shapes/TriangleShape.h index 8360c32b..60ec216b 100644 --- a/src/collision/shapes/TriangleShape.h +++ b/src/collision/shapes/TriangleShape.h @@ -72,12 +72,6 @@ class TriangleShape : public ConvexPolyhedronShape { /// Raycast test type for the triangle (front, back, front-back) TriangleRaycastSide mRaycastTestType; - /// Index of the mesh sub part in the original mesh - uint mMeshSubPart; - - /// Triangle index of the triangle in the sub mesh - uint mTriangleIndex; - // -------------------- Methods -------------------- // /// Return a local support point in a given direction without the object margin @@ -95,6 +89,9 @@ class TriangleShape : public ConvexPolyhedronShape { /// Return the number of bytes used by the collision shape virtual size_t getSizeInBytes() const override; + /// Generate the id of the shape (used for temporal coherence) + void generateId(); + // -------------------- Methods -------------------- // /// This method implements the technique described in Game Physics Pearl book @@ -107,8 +104,7 @@ class TriangleShape : public ConvexPolyhedronShape { // -------------------- Methods -------------------- // /// Constructor - TriangleShape(const Vector3& point1, const Vector3& point2, const Vector3& point3, - const Vector3* verticesNormals, uint meshSubPart, uint triangleIndex); + TriangleShape(const Vector3* vertices, const Vector3* verticesNormals, uint shapeId); /// Destructor virtual ~TriangleShape() override = default; @@ -164,12 +160,6 @@ class TriangleShape : public ConvexPolyhedronShape { /// Return the centroid of the polyhedron virtual Vector3 getCentroid() const override; - /// Return the index of the sub part mesh of the original mesh - uint getMeshSubPart() const; - - /// Return the triangle index in the original mesh - uint getTriangleIndex() const; - /// This method compute the smooth mesh contact with a triangle in case one of the two collision shapes is a triangle. The idea in this case is to use a smooth vertex normal of the triangle mesh static void computeSmoothTriangleMeshContact(const CollisionShape* shape1, const CollisionShape* shape2, Vector3& localContactPointShape1, Vector3& localContactPointShape2, @@ -319,16 +309,6 @@ inline Vector3 TriangleShape::getCentroid() const { return (mPoints[0] + mPoints[1] + mPoints[2]) / decimal(3.0); } -// Return the index of the sub part mesh of the original mesh -inline uint TriangleShape::getMeshSubPart() const { - return mMeshSubPart; -} - -// Return the triangle index in the original mesh -inline uint TriangleShape::getTriangleIndex() const { - return mTriangleIndex; -} - // Return the number of half-edges of the polyhedron inline uint TriangleShape::getNbHalfEdges() const { return 6; diff --git a/src/constraint/ContactPoint.h b/src/constraint/ContactPoint.h index e2a9a5e5..739a9efb 100644 --- a/src/constraint/ContactPoint.h +++ b/src/constraint/ContactPoint.h @@ -28,7 +28,6 @@ // Libraries #include "body/CollisionBody.h" -#include "collision/NarrowPhaseInfo.h" #include "collision/ContactPointInfo.h" #include "configuration.h" #include "mathematics/mathematics.h" @@ -36,6 +35,8 @@ /// ReactPhysics3D namespace namespace reactphysics3d { +struct NarrowPhaseInfo; + // Class ContactPoint /** * This class represents a collision contact point between two diff --git a/src/engine/CollisionWorld.h b/src/engine/CollisionWorld.h index f523d169..6c558d6d 100644 --- a/src/engine/CollisionWorld.h +++ b/src/engine/CollisionWorld.h @@ -259,4 +259,4 @@ inline void CollisionWorld::setProfilerName(std::string name) { } - #endif +#endif diff --git a/src/engine/OverlappingPair.cpp b/src/engine/OverlappingPair.cpp index 0055e683..eba2fb80 100644 --- a/src/engine/OverlappingPair.cpp +++ b/src/engine/OverlappingPair.cpp @@ -27,20 +27,31 @@ #include #include "OverlappingPair.h" #include "collision/ContactManifoldInfo.h" +#include "collision/NarrowPhaseInfo.h" using namespace reactphysics3d; // Constructor OverlappingPair::OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, - Allocator& manifoldsAllocator, Allocator& temporaryMemoryAllocator) - : mContactManifoldSet(shape1, shape2, manifoldsAllocator), mPotentialContactManifolds(nullptr), - mTempMemoryAllocator(temporaryMemoryAllocator) { + Allocator& persistentMemoryAllocator, Allocator& temporaryMemoryAllocator) + : mContactManifoldSet(shape1, shape2, persistentMemoryAllocator), mPotentialContactManifolds(nullptr), + mPersistentAllocator(persistentMemoryAllocator), mTempMemoryAllocator(temporaryMemoryAllocator) { } // Destructor OverlappingPair::~OverlappingPair() { assert(mPotentialContactManifolds == nullptr); + + // Remove all the remaining last frame collision info + for (auto it = mLastFrameCollisionInfos.begin(); it != mLastFrameCollisionInfos.end(); ++it) { + + // Call the constructor + it->second->~LastFrameCollisionInfo(); + + // Release memory + mPersistentAllocator.release(it->second, sizeof(LastFrameCollisionInfo)); + } } // Create a new potential contact manifold using contact-points from narrow-phase @@ -137,3 +148,59 @@ void OverlappingPair::reducePotentialContactManifolds() { manifold = manifold->getNext(); } } + + +// Add a new last frame collision info if it does not exist for the given shapes already +void OverlappingPair::addLastFrameInfoIfNecessary(uint shapeId1, uint shapeId2) { + + // Try to get the corresponding last frame collision info + auto it = mLastFrameCollisionInfos.find(std::make_pair(shapeId1, shapeId2)); + + // If there is no collision info for those two shapes already + if (it == mLastFrameCollisionInfos.end()) { + + // Create a new collision info + LastFrameCollisionInfo* collisionInfo = new (mPersistentAllocator.allocate(sizeof(LastFrameCollisionInfo))) + LastFrameCollisionInfo(); + + // Add it into the map of collision infos + std::map, LastFrameCollisionInfo*>::iterator it; + auto ret = mLastFrameCollisionInfos.insert(std::make_pair(std::make_pair(shapeId1, shapeId2), collisionInfo)); + assert(ret.second); + } + else { + + // The existing collision info is not obsolete + it->second->isObsolete = false; + } +} + + +// Delete all the obsolete last frame collision info +void OverlappingPair::clearObsoleteLastFrameCollisionInfos() { + + // For each collision info + for (auto it = mLastFrameCollisionInfos.begin(); it != mLastFrameCollisionInfos.end(); ) { + + // If the collision info is obsolete + if (it->second->isObsolete) { + + // Delete it + it->second->~LastFrameCollisionInfo(); + mPersistentAllocator.release(it->second, sizeof(LastFrameCollisionInfo)); + + mLastFrameCollisionInfos.erase(it++); + } + else { + ++it; + } + } +} + +// Make all the last frame collision infos obsolete +void OverlappingPair::makeLastFrameCollisionInfosObsolete() { + + for (auto it = mLastFrameCollisionInfos.begin(); it != mLastFrameCollisionInfos.end(); ++it) { + it->second->isObsolete = true; + } +} diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index ce22bb7e..8c65e633 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -30,6 +30,7 @@ #include "collision/ContactManifoldSet.h" #include "collision/ProxyShape.h" #include "collision/shapes/CollisionShape.h" +#include /// ReactPhysics3D namespace namespace reactphysics3d { @@ -47,6 +48,9 @@ struct LastFrameCollisionInfo { /// True if we have information about the previous frame bool isValid; + /// True if the frame info is obsolete (the collision shape are not overlapping in middle phase) + bool isObsolete; + /// True if the two shapes were colliding in the previous frame bool wasColliding; @@ -72,6 +76,7 @@ struct LastFrameCollisionInfo { LastFrameCollisionInfo() { isValid = false; + isObsolete = false; wasColliding = false; wasUsingSAT = false; wasUsingGJK = false; @@ -97,12 +102,19 @@ class OverlappingPair { /// Set of persistent contact manifolds ContactManifoldSet mContactManifoldSet; - /// Collision information about the last frame (for temporal coherence) - LastFrameCollisionInfo mLastFrameCollisionInfo; + /// Temporal coherence collision data for each overlapping collision shapes of this pair. + /// Temporal coherence data store collision information about the last frame. + /// If two convex shapes overlap, we have a single collision data but if one shape is concave, + /// we might have collision data for several overlapping triangles. The key in the map is the + /// shape Ids of the two collision shapes. + std::map, LastFrameCollisionInfo*> mLastFrameCollisionInfos; /// Linked-list of potential contact manifold ContactManifoldInfo* mPotentialContactManifolds; + /// Persistent memory allocator + Allocator& mPersistentAllocator; + /// Memory allocator used to allocated memory for the ContactManifoldInfo and ContactPointInfo Allocator& mTempMemoryAllocator; @@ -111,8 +123,8 @@ class OverlappingPair { // -------------------- Methods -------------------- // /// Constructor - OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, - Allocator& memoryAllocator, Allocator& temporaryMemoryAllocator); + OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, Allocator& persistentMemoryAllocator, + Allocator& temporaryMemoryAllocator); /// Destructor ~OverlappingPair(); @@ -130,7 +142,7 @@ class OverlappingPair { ProxyShape* getShape2() const; /// Return the last frame collision info - LastFrameCollisionInfo& getLastFrameCollisionInfo(); + LastFrameCollisionInfo* getLastFrameCollisionInfo(std::pair shapeIds); /// Return the a reference to the contact manifold set const ContactManifoldSet& getContactManifoldSet(); @@ -168,6 +180,18 @@ class OverlappingPair { /// Reduce the contact manifolds that have too many contact points void reduceContactManifolds(); + /// Add a new last frame collision info if it does not exist for the given shapes already + void addLastFrameInfoIfNecessary(uint shapeId1, uint shapeId2); + + /// Return the last frame collision info for a given pair of shape ids + LastFrameCollisionInfo* getLastFrameCollisionInfo(uint shapeId1, uint shapeId2) const; + + /// Delete all the obsolete last frame collision info + void clearObsoleteLastFrameCollisionInfos(); + + /// Make all the last frame collision infos obsolete + void makeLastFrameCollisionInfosObsolete(); + /// Return the pair of bodies index static overlappingpairid computeID(ProxyShape* shape1, ProxyShape* shape2); @@ -194,9 +218,14 @@ inline void OverlappingPair::addContactManifold(const ContactManifoldInfo* conta mContactManifoldSet.addContactManifold(contactManifoldInfo); } -// Return the last frame collision info -inline LastFrameCollisionInfo& OverlappingPair::getLastFrameCollisionInfo() { - return mLastFrameCollisionInfo; +// Return the last frame collision info for a given shape id or nullptr if none is found +inline LastFrameCollisionInfo* OverlappingPair::getLastFrameCollisionInfo(std::pair shapeIds) { + std::map, LastFrameCollisionInfo*>::iterator it = mLastFrameCollisionInfos.find(shapeIds); + if (it != mLastFrameCollisionInfos.end()) { + return it->second; + } + + return nullptr; } // Return the contact manifold @@ -265,6 +294,11 @@ inline void OverlappingPair::reduceContactManifolds() { mContactManifoldSet.reduce(); } +// Return the last frame collision info for a given pair of shape ids +inline LastFrameCollisionInfo* OverlappingPair::getLastFrameCollisionInfo(uint shapeId1, uint shapeId2) const { + return mLastFrameCollisionInfos.at(std::make_pair(shapeId1, shapeId2)); +} + } #endif diff --git a/test/tests/collision/TestRaycast.h b/test/tests/collision/TestRaycast.h index f2ae3d6b..c62ca179 100644 --- a/test/tests/collision/TestRaycast.h +++ b/test/tests/collision/TestRaycast.h @@ -198,11 +198,12 @@ class TestRaycast : public Test { mSphereShape = new SphereShape(3); mSphereProxyShape = mSphereBody->addCollisionShape(mSphereShape, mShapeTransform); - const Vector3 triangleVertex1(100, 100, 0); - const Vector3 triangleVertex2(105, 100, 0); - const Vector3 triangleVertex3(100, 103, 0); + Vector3 triangleVertices[3]; + triangleVertices[0] = Vector3(100, 100, 0); + 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(triangleVertex1, triangleVertex2, triangleVertex3, triangleVerticesNormals, 0, 0); + mTriangleShape = new TriangleShape(triangleVertices, triangleVerticesNormals, 0); mTriangleProxyShape = mTriangleBody->addCollisionShape(mTriangleShape, mShapeTransform); mCapsuleShape = new CapsuleShape(2, 5); From f09331c185ddc81a3415ed26e565fd94ae2e71fa Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 22 Nov 2017 22:58:31 +0100 Subject: [PATCH 136/248] Remove unused cachedCollisionData variable --- src/collision/CollisionDetection.cpp | 6 ++---- src/collision/MiddlePhaseTriangleCallback.cpp | 3 +-- src/collision/NarrowPhaseInfo.cpp | 6 ++---- src/collision/NarrowPhaseInfo.h | 10 +--------- src/collision/ProxyShape.cpp | 7 +------ src/collision/ProxyShape.h | 11 ----------- 6 files changed, 7 insertions(+), 36 deletions(-) diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 4808ea65..f1a7b80a 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -169,8 +169,7 @@ void CollisionDetection::computeMiddlePhase() { mNarrowPhaseInfoList = new (mSingleFrameAllocator.allocate(sizeof(NarrowPhaseInfo))) NarrowPhaseInfo(pair, shape1->getCollisionShape(), shape2->getCollisionShape(), shape1->getLocalToWorldTransform(), - shape2->getLocalToWorldTransform(), shape1->getCachedCollisionData(), - shape2->getCachedCollisionData(), mSingleFrameAllocator); + shape2->getLocalToWorldTransform(), mSingleFrameAllocator); mNarrowPhaseInfoList->next = firstNarrowPhaseInfo; } @@ -488,8 +487,7 @@ NarrowPhaseInfo* CollisionDetection::computeMiddlePhaseForProxyShapes(Overlappin // for the narrow-phase collision detection narrowPhaseInfo = new (mPoolAllocator.allocate(sizeof(NarrowPhaseInfo))) NarrowPhaseInfo(pair, shape1->getCollisionShape(), shape2->getCollisionShape(), shape1->getLocalToWorldTransform(), - shape2->getLocalToWorldTransform(), shape1->getCachedCollisionData(), - shape2->getCachedCollisionData(), mPoolAllocator); + shape2->getLocalToWorldTransform(), mPoolAllocator); } // Concave vs Convex algorithm diff --git a/src/collision/MiddlePhaseTriangleCallback.cpp b/src/collision/MiddlePhaseTriangleCallback.cpp index 58604087..f8736a0b 100644 --- a/src/collision/MiddlePhaseTriangleCallback.cpp +++ b/src/collision/MiddlePhaseTriangleCallback.cpp @@ -55,7 +55,6 @@ void MiddlePhaseTriangleCallback::testTriangle(const Vector3* trianglePoints, co isShape1Convex ? triangleShape : mConvexProxyShape->getCollisionShape(), shape1->getLocalToWorldTransform(), shape2->getLocalToWorldTransform(), - shape1->getCachedCollisionData(), - shape2->getCachedCollisionData(), mAllocator); + mAllocator); narrowPhaseInfoList->next = firstNarrowPhaseInfo; } diff --git a/src/collision/NarrowPhaseInfo.cpp b/src/collision/NarrowPhaseInfo.cpp index 660f6704..a6440367 100644 --- a/src/collision/NarrowPhaseInfo.cpp +++ b/src/collision/NarrowPhaseInfo.cpp @@ -35,12 +35,10 @@ using namespace reactphysics3d; // Constructor NarrowPhaseInfo::NarrowPhaseInfo(OverlappingPair* pair, CollisionShape* shape1, CollisionShape* shape2, const Transform& shape1Transform, - const Transform& shape2Transform, void** cachedData1, void** cachedData2, - Allocator& shapeAllocator) + const Transform& shape2Transform, Allocator& shapeAllocator) : overlappingPair(pair), collisionShape1(shape1), collisionShape2(shape2), shape1ToWorldTransform(shape1Transform), shape2ToWorldTransform(shape2Transform), - contactPoints(nullptr), cachedCollisionData1(cachedData1), - cachedCollisionData2(cachedData2), next(nullptr), collisionShapeAllocator(shapeAllocator) { + contactPoints(nullptr), next(nullptr), collisionShapeAllocator(shapeAllocator) { // Add a collision info for the two collision shapes into the overlapping pair (if not present yet) overlappingPair->addLastFrameInfoIfNecessary(shape1->getId(), shape2->getId()); diff --git a/src/collision/NarrowPhaseInfo.h b/src/collision/NarrowPhaseInfo.h index b100939f..b732480c 100644 --- a/src/collision/NarrowPhaseInfo.h +++ b/src/collision/NarrowPhaseInfo.h @@ -63,14 +63,6 @@ struct NarrowPhaseInfo { /// Linked-list of contact points created during the narrow-phase ContactPointInfo* contactPoints; - /// Cached collision data of the proxy shape - // TODO : Check if we can use separating axis in OverlappingPair instead of cachedCollisionData1 and cachedCollisionData2 - void** cachedCollisionData1; - - /// Cached collision data of the proxy shape - // TODO : Check if we can use separating axis in OverlappingPair instead of cachedCollisionData1 and cachedCollisionData2 - void** cachedCollisionData2; - /// Pointer to the next element in the linked list NarrowPhaseInfo* next; @@ -80,7 +72,7 @@ struct NarrowPhaseInfo { /// Constructor NarrowPhaseInfo(OverlappingPair* pair, CollisionShape* shape1, CollisionShape* shape2, const Transform& shape1Transform, - const Transform& shape2Transform, void** cachedData1, void** cachedData2, Allocator& shapeAllocator); + const Transform& shape2Transform, Allocator& shapeAllocator); /// Destructor ~NarrowPhaseInfo(); diff --git a/src/collision/ProxyShape.cpp b/src/collision/ProxyShape.cpp index 50418011..6e6eefbd 100644 --- a/src/collision/ProxyShape.cpp +++ b/src/collision/ProxyShape.cpp @@ -37,18 +37,13 @@ using namespace reactphysics3d; */ ProxyShape::ProxyShape(CollisionBody* body, CollisionShape* shape, const Transform& transform, decimal mass) :mBody(body), mCollisionShape(shape), mLocalToBodyTransform(transform), mMass(mass), - mNext(nullptr), mBroadPhaseID(-1), mCachedCollisionData(nullptr), mUserData(nullptr), - mCollisionCategoryBits(0x0001), mCollideWithMaskBits(0xFFFF) { + mNext(nullptr), mBroadPhaseID(-1), mCollisionCategoryBits(0x0001), mCollideWithMaskBits(0xFFFF) { } // Destructor ProxyShape::~ProxyShape() { - // Release the cached collision data memory - if (mCachedCollisionData != nullptr) { - free(mCachedCollisionData); - } } // Return true if a point is inside the collision shape diff --git a/src/collision/ProxyShape.h b/src/collision/ProxyShape.h index 574758d4..8e9a9e9f 100644 --- a/src/collision/ProxyShape.h +++ b/src/collision/ProxyShape.h @@ -66,9 +66,6 @@ class ProxyShape { /// Broad-phase ID (node ID in the dynamic AABB tree) int mBroadPhaseID; - /// Cached collision data - void* mCachedCollisionData; - /// Pointer to user data void* mUserData; @@ -168,9 +165,6 @@ class ProxyShape { /// Return the next proxy shape in the linked list of proxy shapes const ProxyShape* getNext() const; - /// Return the pointer to the cached collision data - void** getCachedCollisionData(); - /// Return the local scaling vector of the collision shape Vector3 getLocalScaling() const; @@ -201,11 +195,6 @@ class ProxyShape { }; -// Return the pointer to the cached collision data -inline void** ProxyShape::getCachedCollisionData() { - return &mCachedCollisionData; -} - // Return the collision shape /** * @return Pointer to the internal collision shape From fea467f112e29f53dad44e8ada4077f8c4450505 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sat, 25 Nov 2017 17:51:14 +0100 Subject: [PATCH 137/248] Add profiling in SAT algorithm methods --- src/collision/CollisionDetection.cpp | 6 +++++ .../narrowphase/SAT/SATAlgorithm.cpp | 22 +++++++++++++++++++ 2 files changed, 28 insertions(+) diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index f1a7b80a..a2c3344d 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -366,6 +366,8 @@ void CollisionDetection::removeProxyCollisionShape(ProxyShape* proxyShape) { void CollisionDetection::addAllContactManifoldsToBodies() { + PROFILE("CollisionDetection::addAllContactManifoldsToBodies()", mProfiler); + // For each overlapping pairs in contact during the narrow-phase std::map::iterator it; for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ++it) { @@ -413,6 +415,8 @@ void CollisionDetection::addContactManifoldToBody(OverlappingPair* pair) { /// Convert the potential contact into actual contacts void CollisionDetection::processAllPotentialContacts() { + PROFILE("CollisionDetection::processAllPotentialContacts()", mProfiler); + // For each overlapping pairs in contact during the narrow-phase std::map::iterator it; for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ++it) { @@ -450,6 +454,8 @@ void CollisionDetection::processPotentialContacts(OverlappingPair* pair) { // Report contacts for all the colliding overlapping pairs void CollisionDetection::reportAllContacts() { + PROFILE("CollisionDetection::reportAllContacts()", mProfiler); + // For each overlapping pairs in contact during the narrow-phase std::map::iterator it; for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ++it) { diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 761bd5ec..f12964cf 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -122,6 +122,8 @@ bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfo* narrow decimal SATAlgorithm::computePolyhedronFaceVsSpherePenetrationDepth(uint faceIndex, const ConvexPolyhedronShape* polyhedron, const SphereShape* sphere, const Vector3& sphereCenter) const { + PROFILE("SATAlgorithm::computePolyhedronFaceVsSpherePenetrationDepth)", mProfiler); + // Get the face HalfEdgeStructure::Face face = polyhedron->getFace(faceIndex); @@ -297,6 +299,8 @@ decimal SATAlgorithm::computeEdgeVsCapsuleInnerSegmentPenetrationDepth(const Con const Vector3& edgeDirectionCapsuleSpace, const Transform& polyhedronToCapsuleTransform, Vector3& outAxis) const { + PROFILE("SATAlgorithm::computeEdgeVsCapsuleInnerSegmentPenetrationDepth)", mProfiler); + decimal penetrationDepth = DECIMAL_LARGEST; // Compute the axis to test (cross product between capsule inner segment and polyhedron edge) @@ -329,6 +333,8 @@ decimal SATAlgorithm::computePolyhedronFaceVsCapsulePenetrationDepth(uint polyhe const CapsuleShape* capsule, const Transform& polyhedronToCapsuleTransform, Vector3& outFaceNormalCapsuleSpace) const { + PROFILE("SATAlgorithm::computePolyhedronFaceVsCapsulePenetrationDepth", mProfiler); + // Get the face HalfEdgeStructure::Face face = polyhedron->getFace(polyhedronFaceIndex); @@ -353,6 +359,8 @@ bool SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceI const Vector3& capsuleSegAPolyhedronSpace, const Vector3& capsuleSegBPolyhedronSpace, NarrowPhaseInfo* narrowPhaseInfo, bool isCapsuleShape1) const { + PROFILE("SATAlgorithm::computeCapsulePolyhedronFaceContactPoints", mProfiler); + HalfEdgeStructure::Face face = polyhedron->getFace(referenceFaceIndex); // Get the face normal @@ -791,6 +799,8 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene const Transform& polyhedron1ToPolyhedron2, const Transform& polyhedron2ToPolyhedron1, uint minFaceIndex, NarrowPhaseInfo* narrowPhaseInfo, decimal minPenetrationDepth) const { + PROFILE("SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints", mProfiler); + const ConvexPolyhedronShape* referencePolyhedron = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron1 : polyhedron2; const ConvexPolyhedronShape* incidentPolyhedron = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron2 : polyhedron1; const Transform& referenceToIncidentTransform = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron1ToPolyhedron2 : polyhedron2ToPolyhedron1; @@ -903,6 +913,8 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene // This is used to find the incident face on a polyhedron of a given reference face of another polyhedron uint SATAlgorithm::findMostAntiParallelFaceOnPolyhedron(const ConvexPolyhedronShape* polyhedron, const Vector3& direction) const { + PROFILE("SATAlgorithm::findMostAntiParallelFaceOnPolyhedron", mProfiler); + decimal minDotProduct = DECIMAL_LARGEST; uint mostAntiParallelFace = 0; @@ -925,6 +937,8 @@ decimal SATAlgorithm::computeDistanceBetweenEdges(const Vector3& edge1A, const V const Vector3& edge1Direction, const Vector3& edge2Direction, Vector3& outSeparatingAxisPolyhedron2Space) const { + PROFILE("SATAlgorithm::computeDistanceBetweenEdges", mProfiler); + // If the two edges are parallel if (areParallelVectors(edge1Direction, edge2Direction)) { @@ -952,6 +966,8 @@ decimal SATAlgorithm::testSingleFaceDirectionPolyhedronVsPolyhedron(const Convex const Transform& polyhedron1ToPolyhedron2, uint faceIndex) const { + PROFILE("SATAlgorithm::testSingleFaceDirectionPolyhedronVsPolyhedron", mProfiler); + HalfEdgeStructure::Face face = polyhedron1->getFace(faceIndex); // Get the face normal @@ -976,6 +992,8 @@ decimal SATAlgorithm::testFacesDirectionPolyhedronVsPolyhedron(const ConvexPolyh const Transform& polyhedron1ToPolyhedron2, uint& minFaceIndex) const { + PROFILE("SATAlgorithm::testFacesDirectionPolyhedronVsPolyhedron", mProfiler); + decimal minPenetrationDepth = DECIMAL_LARGEST; // For each face of the first polyhedron @@ -1006,6 +1024,8 @@ bool SATAlgorithm::testEdgesBuildMinkowskiFace(const ConvexPolyhedronShape* poly const ConvexPolyhedronShape* polyhedron2, const HalfEdgeStructure::Edge& edge2, const Transform& polyhedron1ToPolyhedron2) const { + PROFILE("SATAlgorithm::testEdgesBuildMinkowskiFace", mProfiler); + const Vector3 a = polyhedron1ToPolyhedron2.getOrientation() * polyhedron1->getFaceNormal(edge1.faceIndex); const Vector3 b = polyhedron1ToPolyhedron2.getOrientation() * polyhedron1->getFaceNormal(polyhedron1->getHalfEdge(edge1.twinEdgeIndex).faceIndex); @@ -1037,6 +1057,8 @@ bool SATAlgorithm::testEdgesBuildMinkowskiFace(const ConvexPolyhedronShape* poly bool SATAlgorithm::testGaussMapArcsIntersect(const Vector3& a, const Vector3& b, const Vector3& c, const Vector3& d, const Vector3& bCrossA, const Vector3& dCrossC) const { + PROFILE("SATAlgorithm::testGaussMapArcsIntersect", mProfiler); + const decimal cba = c.dot(bCrossA); const decimal dba = d.dot(bCrossA); const decimal adc = a.dot(dCrossC); From c8e9cca9123295e2994a3530a1114917aaf4dc8a Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 26 Nov 2017 12:07:58 +0100 Subject: [PATCH 138/248] Compute the inverse quaternion using its conjugate --- src/mathematics/Quaternion.h | 24 +++++++----------------- 1 file changed, 7 insertions(+), 17 deletions(-) diff --git a/src/mathematics/Quaternion.h b/src/mathematics/Quaternion.h index 28f7b636..b8e75306 100644 --- a/src/mathematics/Quaternion.h +++ b/src/mathematics/Quaternion.h @@ -224,16 +224,11 @@ inline void Quaternion::normalize() { // Inverse the quaternion inline void Quaternion::inverse() { - // Get the square length of the quaternion - decimal lengthSquareQuaternion = lengthSquare(); - - assert (lengthSquareQuaternion > MACHINE_EPSILON); - - // Compute and return the inverse quaternion - x /= -lengthSquareQuaternion; - y /= -lengthSquareQuaternion; - z /= -lengthSquareQuaternion; - w /= lengthSquareQuaternion; + // Use the conjugate of the current quaternion + x = -x; + y = -y; + z = -z; + w = w; } // Return the unit quaternion @@ -261,13 +256,8 @@ inline Quaternion Quaternion::getConjugate() const { // Return the inverse of the quaternion (inline) inline Quaternion Quaternion::getInverse() const { - decimal lengthSquareQuaternion = lengthSquare(); - - assert (lengthSquareQuaternion > MACHINE_EPSILON); - - // Compute and return the inverse quaternion - return Quaternion(-x / lengthSquareQuaternion, -y / lengthSquareQuaternion, - -z / lengthSquareQuaternion, w / lengthSquareQuaternion); + // Return the conjugate quaternion + return Quaternion(-x, -y, -z, w); } // Scalar product between two quaternions From 317dea90bd5287085f3b4cd34718c06682db260f Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 28 Nov 2017 17:26:13 +0100 Subject: [PATCH 139/248] Remove Quaternion constructor with Euler angles and replace it by static fromEulerAngles() method --- src/mathematics/Quaternion.cpp | 66 ++++++++++--------- src/mathematics/Quaternion.h | 14 ++-- test/tests/collision/TestPointInside.h | 6 +- test/tests/collision/TestRaycast.h | 6 +- test/tests/mathematics/TestQuaternion.h | 8 +-- .../CollisionDetectionScene.cpp | 12 ++-- 6 files changed, 59 insertions(+), 53 deletions(-) diff --git a/src/mathematics/Quaternion.cpp b/src/mathematics/Quaternion.cpp index 0b2587f5..d0e1ae61 100644 --- a/src/mathematics/Quaternion.cpp +++ b/src/mathematics/Quaternion.cpp @@ -47,14 +47,28 @@ Quaternion::Quaternion(decimal newW, const Vector3& v) : x(v.x), y(v.y), z(v.z), } -// Constructor which convert Euler angles (in radians) to a quaternion -Quaternion::Quaternion(decimal angleX, decimal angleY, decimal angleZ) { - initWithEulerAngles(angleX, angleY, angleZ); +// Constructor with the component w and the vector v=(x y z) +Quaternion::Quaternion(const Vector3& v, decimal newW) : x(v.x), y(v.y), z(v.z), w(newW) { + } -// Constructor which convert Euler angles (in radians) to a quaternion -Quaternion::Quaternion(const Vector3& eulerAngles) { - initWithEulerAngles(eulerAngles.x, eulerAngles.y, eulerAngles.z); +// Return a quaternion constructed from Euler angles (in radians) +Quaternion Quaternion::fromEulerAngles(decimal angleX, decimal angleY, decimal angleZ) { + + Quaternion quaternion; + quaternion.initWithEulerAngles(angleX, angleY, angleZ); + + return quaternion; +} + + +// Return a quaternion constructed from Euler angles (in radians) +Quaternion Quaternion::fromEulerAngles(const Vector3& eulerAngles) { + + Quaternion quaternion; + quaternion.initWithEulerAngles(eulerAngles.x, eulerAngles.y, eulerAngles.z); + + return quaternion; } // Copy-constructor @@ -72,10 +86,10 @@ Quaternion::Quaternion(const Matrix3x3& matrix) { decimal r; decimal s; - if (trace < 0.0) { + if (trace < decimal(0.0)) { if (matrix[1][1] > matrix[0][0]) { if(matrix[2][2] > matrix[1][1]) { - r = sqrt(matrix[2][2] - matrix[0][0] - matrix[1][1] + decimal(1.0)); + r = std::sqrt(matrix[2][2] - matrix[0][0] - matrix[1][1] + decimal(1.0)); s = decimal(0.5) / r; // Compute the quaternion @@ -85,7 +99,7 @@ Quaternion::Quaternion(const Matrix3x3& matrix) { w = (matrix[1][0] - matrix[0][1]) * s; } else { - r = sqrt(matrix[1][1] - matrix[2][2] - matrix[0][0] + decimal(1.0)); + r = std::sqrt(matrix[1][1] - matrix[2][2] - matrix[0][0] + decimal(1.0)); s = decimal(0.5) / r; // Compute the quaternion @@ -96,7 +110,7 @@ Quaternion::Quaternion(const Matrix3x3& matrix) { } } else if (matrix[2][2] > matrix[0][0]) { - r = sqrt(matrix[2][2] - matrix[0][0] - matrix[1][1] + decimal(1.0)); + r = std::sqrt(matrix[2][2] - matrix[0][0] - matrix[1][1] + decimal(1.0)); s = decimal(0.5) / r; // Compute the quaternion @@ -106,7 +120,7 @@ Quaternion::Quaternion(const Matrix3x3& matrix) { w = (matrix[1][0] - matrix[0][1]) * s; } else { - r = sqrt(matrix[0][0] - matrix[1][1] - matrix[2][2] + decimal(1.0)); + r = std::sqrt(matrix[0][0] - matrix[1][1] - matrix[2][2] + decimal(1.0)); s = decimal(0.5) / r; // Compute the quaternion @@ -117,7 +131,7 @@ Quaternion::Quaternion(const Matrix3x3& matrix) { } } else { - r = sqrt(trace + decimal(1.0)); + r = std::sqrt(trace + decimal(1.0)); s = decimal(0.5) / r; // Compute the quaternion @@ -132,22 +146,12 @@ Quaternion::Quaternion(const Matrix3x3& matrix) { /// This method is used to get the rotation angle (in radian) and the unit /// rotation axis of an orientation quaternion. void Quaternion::getRotationAngleAxis(decimal& angle, Vector3& axis) const { - Quaternion quaternion; - - // If the quaternion is unit - if (length() == 1.0) { - quaternion = *this; - } - else { - // We compute the unit quaternion - quaternion = getUnit(); - } // Compute the roation angle - angle = acos(quaternion.w) * decimal(2.0); + angle = std::acos(w) * decimal(2.0); // Compute the 3D rotation axis - Vector3 rotationAxis(quaternion.x, quaternion.y, quaternion.z); + Vector3 rotationAxis(x, y, z); // Normalize the rotation axis rotationAxis = rotationAxis.getUnit(); @@ -162,7 +166,7 @@ Matrix3x3 Quaternion::getMatrix() const { decimal nQ = x*x + y*y + z*z + w*w; decimal s = 0.0; - if (nQ > 0.0) { + if (nQ > decimal(0.0)) { s = decimal(2.0) / nQ; } @@ -190,7 +194,7 @@ Matrix3x3 Quaternion::getMatrix() const { /// The t argument has to be such that 0 <= t <= 1. This method is static. Quaternion Quaternion::slerp(const Quaternion& quaternion1, const Quaternion& quaternion2, decimal t) { - assert(t >= 0.0 && t <= 1.0); + assert(t >= decimal(0.0) && t <= decimal(1.0)); decimal invert = 1.0; @@ -198,7 +202,7 @@ Quaternion Quaternion::slerp(const Quaternion& quaternion1, decimal cosineTheta = quaternion1.dot(quaternion2); // Take care of the sign of cosineTheta - if (cosineTheta < 0.0) { + if (cosineTheta < decimal(0.0)) { cosineTheta = -cosineTheta; invert = -1.0; } @@ -212,14 +216,14 @@ Quaternion Quaternion::slerp(const Quaternion& quaternion1, } // Compute the theta angle - decimal theta = acos(cosineTheta); + decimal theta = std::acos(cosineTheta); // Compute sin(theta) - decimal sineTheta = sin(theta); + decimal sineTheta = std::sin(theta); // Compute the two coefficients that are in the spherical linear interpolation formula - decimal coeff1 = sin((decimal(1.0)-t)*theta) / sineTheta; - decimal coeff2 = sin(t*theta) / sineTheta * invert; + decimal coeff1 = std::sin((decimal(1.0)-t)*theta) / sineTheta; + decimal coeff2 = std::sin(t*theta) / sineTheta * invert; // Compute and return the interpolated quaternion return quaternion1 * coeff1 + quaternion2 * coeff2; diff --git a/src/mathematics/Quaternion.h b/src/mathematics/Quaternion.h index b8e75306..74415eb8 100644 --- a/src/mathematics/Quaternion.h +++ b/src/mathematics/Quaternion.h @@ -69,11 +69,8 @@ struct Quaternion { /// Constructor with the component w and the vector v=(x y z) Quaternion(decimal newW, const Vector3& v); - /// Constructor which convert Euler angles (in radians) to a quaternion - Quaternion(decimal angleX, decimal angleY, decimal angleZ); - - /// Constructor which convert Euler angles (in radians) to a quaternion - Quaternion(const Vector3& eulerAngles); + /// Constructor with the component w and the vector v=(x y z) + Quaternion(const Vector3& v, decimal newW); /// Copy-constructor Quaternion(const Quaternion& quaternion); @@ -123,6 +120,12 @@ struct Quaternion { /// Return the identity quaternion static Quaternion identity(); + /// Return a quaternion constructed from Euler angles (in radians) + static Quaternion fromEulerAngles(decimal angleX, decimal angleY, decimal angleZ); + + /// Return a quaternion constructed from Euler angles (in radians) + static Quaternion fromEulerAngles(const Vector3& eulerAngles); + /// Dot product between two quaternions decimal dot(const Quaternion& quaternion) const; @@ -228,7 +231,6 @@ inline void Quaternion::inverse() { x = -x; y = -y; z = -z; - w = w; } // Return the unit quaternion diff --git a/test/tests/collision/TestPointInside.h b/test/tests/collision/TestPointInside.h index 608b439b..afdb415c 100644 --- a/test/tests/collision/TestPointInside.h +++ b/test/tests/collision/TestPointInside.h @@ -93,7 +93,7 @@ class TestPointInside : public Test { // Body transform Vector3 position(-3, 2, 7); - Quaternion orientation(PI / 5, PI / 6, PI / 7); + Quaternion orientation = Quaternion::fromEulerAngles(PI / 5, PI / 6, PI / 7); mBodyTransform = Transform(position, orientation); // Create the bodies @@ -108,7 +108,7 @@ class TestPointInside : public Test { // Collision shape transform Vector3 shapePosition(1, -4, -3); - Quaternion shapeOrientation(3 * PI / 6 , -PI / 8, PI / 3); + Quaternion shapeOrientation = Quaternion::fromEulerAngles(3 * PI / 6 , -PI / 8, PI / 3); mShapeTransform = Transform(shapePosition, shapeOrientation); // Compute the the transform from a local shape point to world-space @@ -165,7 +165,7 @@ class TestPointInside : public Test { // Compound shape is a capsule and a sphere Vector3 positionShape2(Vector3(4, 2, -3)); - Quaternion orientationShape2(-3 *PI / 8, 1.5 * PI/ 3, PI / 13); + Quaternion orientationShape2 = Quaternion::fromEulerAngles(-3 *PI / 8, 1.5 * PI/ 3, PI / 13); Transform shapeTransform2(positionShape2, orientationShape2); mLocalShape2ToWorld = mBodyTransform * shapeTransform2; mCompoundBody->addCollisionShape(mCapsuleShape, mShapeTransform); diff --git a/test/tests/collision/TestRaycast.h b/test/tests/collision/TestRaycast.h index c62ca179..97dd002a 100644 --- a/test/tests/collision/TestRaycast.h +++ b/test/tests/collision/TestRaycast.h @@ -169,7 +169,7 @@ class TestRaycast : public Test { // Body transform Vector3 position(-3, 2, 7); - Quaternion orientation(PI / 5, PI / 6, PI / 7); + Quaternion orientation = Quaternion::fromEulerAngles(PI / 5, PI / 6, PI / 7); mBodyTransform = Transform(position, orientation); // Create the bodies @@ -185,7 +185,7 @@ class TestRaycast : public Test { // Collision shape transform Vector3 shapePosition(1, -4, -3); - Quaternion shapeOrientation(3 * PI / 6 , -PI / 8, PI / 3); + Quaternion shapeOrientation = Quaternion::fromEulerAngles(3 * PI / 6 , -PI / 8, PI / 3); mShapeTransform = Transform(shapePosition, shapeOrientation); // Compute the the transform from a local shape point to world-space @@ -246,7 +246,7 @@ class TestRaycast : public Test { // Compound shape is a cylinder and a sphere Vector3 positionShape2(Vector3(4, 2, -3)); - Quaternion orientationShape2(-3 *PI / 8, 1.5 * PI/ 3, PI / 13); + Quaternion orientationShape2 = Quaternion::fromEulerAngles(-3 *PI / 8, 1.5 * PI/ 3, PI / 13); Transform shapeTransform2(positionShape2, orientationShape2); mLocalShape2ToWorld = mBodyTransform * shapeTransform2; mCompoundCapsuleProxyShape = mCompoundBody->addCollisionShape(mCapsuleShape, mShapeTransform); diff --git a/test/tests/mathematics/TestQuaternion.h b/test/tests/mathematics/TestQuaternion.h index 5fe0ccd0..dfc65955 100644 --- a/test/tests/mathematics/TestQuaternion.h +++ b/test/tests/mathematics/TestQuaternion.h @@ -94,7 +94,7 @@ class TestQuaternion : public Test { const decimal PI_OVER_2 = PI * decimal(0.5); const decimal PI_OVER_4 = PI_OVER_2 * decimal(0.5); - Quaternion quaternion5(PI_OVER_2, 0, 0); + Quaternion quaternion5 = Quaternion::fromEulerAngles(PI_OVER_2, 0, 0); Quaternion quaternionTest5(std::sin(PI_OVER_4), 0, 0, std::cos(PI_OVER_4)); quaternionTest5.normalize(); test(approxEqual(quaternion5.x, quaternionTest5.x)); @@ -102,7 +102,7 @@ class TestQuaternion : public Test { test(approxEqual(quaternion5.z, quaternionTest5.z)); test(approxEqual(quaternion5.w, quaternionTest5.w)); - Quaternion quaternion6(0, PI_OVER_2, 0); + Quaternion quaternion6 = Quaternion::fromEulerAngles(0, PI_OVER_2, 0); Quaternion quaternionTest6(0, std::sin(PI_OVER_4), 0, std::cos(PI_OVER_4)); quaternionTest6.normalize(); test(approxEqual(quaternion6.x, quaternionTest6.x)); @@ -110,7 +110,7 @@ class TestQuaternion : public Test { test(approxEqual(quaternion6.z, quaternionTest6.z)); test(approxEqual(quaternion6.w, quaternionTest6.w)); - Quaternion quaternion7(Vector3(0, 0, PI_OVER_2)); + Quaternion quaternion7 = Quaternion::fromEulerAngles(Vector3(0, 0, PI_OVER_2)); Quaternion quaternionTest7(0, 0, std::sin(PI_OVER_4), std::cos(PI_OVER_4)); quaternionTest7.normalize(); test(approxEqual(quaternion7.x, quaternionTest7.x)); @@ -124,7 +124,7 @@ class TestQuaternion : public Test { // Test method that returns the length Quaternion quaternion(2, 3, -4, 5); - test(approxEqual(quaternion.length(), sqrt(decimal(54.0)))); + test(approxEqual(quaternion.length(), std::sqrt(decimal(54.0)))); // Test method that returns a unit quaternion test(approxEqual(quaternion.getUnit().length(), 1.0)); diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp index 1241b701..6f2c65ae 100755 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp @@ -282,32 +282,32 @@ bool CollisionDetectionScene::keyboardEvent(int key, int scancode, int action, i } else if (key == GLFW_KEY_A && action == GLFW_PRESS) { rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); - transform.setOrientation(rp3d::Quaternion(0, stepAngle, 0) * transform.getOrientation()); + transform.setOrientation(rp3d::Quaternion::fromEulerAngles(0, stepAngle, 0) * transform.getOrientation()); mAllShapes[mSelectedShapeIndex]->setTransform(transform); } else if (key == GLFW_KEY_D && action == GLFW_PRESS) { rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); - transform.setOrientation(rp3d::Quaternion(0, -stepAngle, 0) * transform.getOrientation()); + transform.setOrientation(rp3d::Quaternion::fromEulerAngles(0, -stepAngle, 0) * transform.getOrientation()); mAllShapes[mSelectedShapeIndex]->setTransform(transform); } else if (key == GLFW_KEY_W && action == GLFW_PRESS) { rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); - transform.setOrientation(rp3d::Quaternion(stepAngle, 0, 0) * transform.getOrientation()); + transform.setOrientation(rp3d::Quaternion::fromEulerAngles(stepAngle, 0, 0) * transform.getOrientation()); mAllShapes[mSelectedShapeIndex]->setTransform(transform); } else if (key == GLFW_KEY_S && action == GLFW_PRESS) { rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); - transform.setOrientation(rp3d::Quaternion(-stepAngle, 0, 0) * transform.getOrientation()); + transform.setOrientation(rp3d::Quaternion::fromEulerAngles(-stepAngle, 0, 0) * transform.getOrientation()); mAllShapes[mSelectedShapeIndex]->setTransform(transform); } else if (key == GLFW_KEY_F && action == GLFW_PRESS) { rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); - transform.setOrientation(rp3d::Quaternion(0, 0, stepAngle) * transform.getOrientation()); + transform.setOrientation(rp3d::Quaternion::fromEulerAngles(0, 0, stepAngle) * transform.getOrientation()); mAllShapes[mSelectedShapeIndex]->setTransform(transform); } else if (key == GLFW_KEY_G && action == GLFW_PRESS) { rp3d::Transform transform = mAllShapes[mSelectedShapeIndex]->getTransform(); - transform.setOrientation(rp3d::Quaternion(0, 0, -stepAngle) * transform.getOrientation()); + transform.setOrientation(rp3d::Quaternion::fromEulerAngles(0, 0, -stepAngle) * transform.getOrientation()); mAllShapes[mSelectedShapeIndex]->setTransform(transform); } From e754711a84264c6f0db646d1bff620c5918ea2ec Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 28 Nov 2017 17:46:45 +0100 Subject: [PATCH 140/248] Remove unnecessary calls to Quaternion.getMatrix() --- src/collision/narrowphase/GJK/GJKAlgorithm.cpp | 5 ++--- src/mathematics/Transform.h | 5 ++--- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp index dcfff45e..62685867 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp @@ -75,10 +75,9 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhase Transform transform1Inverse = transform1.getInverse(); Transform body2Tobody1 = transform1Inverse * transform2; - // Matrix that transform a direction from local + // Quaternion that transform a direction from local // space of body 1 into local space of body 2 - Matrix3x3 rotateToBody2 = transform2.getOrientation().getMatrix().getTranspose() * - transform1.getOrientation().getMatrix(); + Quaternion rotateToBody2 = transform2.getOrientation().getInverse() * transform1.getOrientation(); // Initialize the margin (sum of margins of both objects) decimal margin = shape1->getMargin() + shape2->getMargin(); diff --git a/src/mathematics/Transform.h b/src/mathematics/Transform.h index a93734cd..ab17a620 100644 --- a/src/mathematics/Transform.h +++ b/src/mathematics/Transform.h @@ -169,8 +169,7 @@ inline void Transform::getOpenGLMatrix(decimal* openglMatrix) const { // Return the inverse of the transform inline Transform Transform::getInverse() const { const Quaternion& invQuaternion = mOrientation.getInverse(); - Matrix3x3 invMatrix = invQuaternion.getMatrix(); - return Transform(invMatrix * (-mPosition), invQuaternion); + return Transform(invQuaternion * (-mPosition), invQuaternion); } // Return an interpolated transform @@ -200,7 +199,7 @@ inline Vector3 Transform::operator*(const Vector3& vector) const { // Operator of multiplication of a transform with another one inline Transform Transform::operator*(const Transform& transform2) const { - return Transform(mPosition + mOrientation.getMatrix() * transform2.mPosition, + return Transform(mPosition + mOrientation * transform2.mPosition, mOrientation * transform2.mOrientation); } From ebd715d2e080a7547641a1065677e64256ec2f03 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 28 Nov 2017 17:53:50 +0100 Subject: [PATCH 141/248] Add data types --- src/configuration.h | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/src/configuration.h b/src/configuration.h index 779b45e2..a25c1502 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -54,9 +54,12 @@ using luint = long unsigned int; using bodyindex = luint; using bodyindexpair = std::pair; -using int8 = int8_t; -using int16 = int16_t; -using int32 = int32_t; +using int8 = std::int8_t; +using uint8 = std::uint8_t; +using int16 = std::int16_t; +using uint16 = std::uint16_t; +using int32 = std::int32_t; +using uint32 = std::uint32_t; // ------------------- Enumerations ------------------- // From 4cc024b85e9d384f423ec4632975292ac45bdada Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 29 Nov 2017 23:43:55 +0100 Subject: [PATCH 142/248] Rename fields and methods in ContactPoint class --- src/constraint/ContactPoint.cpp | 8 ++--- src/constraint/ContactPoint.h | 30 +++++++++---------- src/engine/ContactSolver.cpp | 4 +-- .../CollisionDetectionScene.h | 4 +-- testbed/src/SceneDemo.cpp | 2 +- 5 files changed, 24 insertions(+), 24 deletions(-) diff --git a/src/constraint/ContactPoint.cpp b/src/constraint/ContactPoint.cpp index b99d52f1..37dc34a3 100644 --- a/src/constraint/ContactPoint.cpp +++ b/src/constraint/ContactPoint.cpp @@ -34,8 +34,8 @@ using namespace std; ContactPoint::ContactPoint(const ContactPointInfo* contactInfo) : mNormal(contactInfo->normal), mPenetrationDepth(contactInfo->penetrationDepth), - mLocalPointOnBody1(contactInfo->localPoint1), - mLocalPointOnBody2(contactInfo->localPoint2), + mLocalPointOnShape1(contactInfo->localPoint1), + mLocalPointOnShape2(contactInfo->localPoint2), mIsRestingContact(false), mIsObsolete(false), mNext(nullptr), mPrevious(nullptr) { assert(mPenetrationDepth > decimal(0.0)); @@ -53,8 +53,8 @@ void ContactPoint::update(const ContactPointInfo* contactInfo) { mNormal = contactInfo->normal; mPenetrationDepth = contactInfo->penetrationDepth; - mLocalPointOnBody1 = contactInfo->localPoint1; - mLocalPointOnBody2 = contactInfo->localPoint2; + mLocalPointOnShape1 = contactInfo->localPoint1; + mLocalPointOnShape2 = contactInfo->localPoint2; mIsObsolete = false; } diff --git a/src/constraint/ContactPoint.h b/src/constraint/ContactPoint.h index 739a9efb..40a3d13c 100644 --- a/src/constraint/ContactPoint.h +++ b/src/constraint/ContactPoint.h @@ -54,11 +54,11 @@ class ContactPoint { /// Penetration depth decimal mPenetrationDepth; - /// Contact point on body 1 in local space of body 1 - Vector3 mLocalPointOnBody1; + /// Contact point on proxy shape 1 in local-space of proxy shape 1 + Vector3 mLocalPointOnShape1; - /// Contact point on body 2 in local space of body 2 - Vector3 mLocalPointOnBody2; + /// Contact point on proxy shape 2 in local-space of proxy shape 2 + Vector3 mLocalPointOnShape2; /// True if the contact is a resting contact (exists for more than one time step) bool mIsRestingContact; @@ -121,11 +121,11 @@ class ContactPoint { /// Return the normal vector of the contact Vector3 getNormal() const; - /// Return the contact local point on body 1 - Vector3 getLocalPointOnBody1() const; + /// Return the contact point on the first proxy shape in the local-space of the proxy shape + Vector3 getLocalPointOnShape1() const; - /// Return the contact local point on body 2 - Vector3 getLocalPointOnBody2() const; + /// Return the contact point on the second proxy shape in the local-space of the proxy shape + Vector3 getLocalPointOnShape2() const; /// Return the cached penetration impulse decimal getPenetrationImpulse() const; @@ -156,14 +156,14 @@ inline Vector3 ContactPoint::getNormal() const { return mNormal; } -// Return the contact point on body 1 -inline Vector3 ContactPoint::getLocalPointOnBody1() const { - return mLocalPointOnBody1; +// Return the contact point on the first proxy shape in the local-space of the proxy shape +inline Vector3 ContactPoint::getLocalPointOnShape1() const { + return mLocalPointOnShape1; } -// Return the contact point on body 2 -inline Vector3 ContactPoint::getLocalPointOnBody2() const { - return mLocalPointOnBody2; +// Return the contact point on the second proxy shape in the local-space of the proxy shape +inline Vector3 ContactPoint::getLocalPointOnShape2() const { + return mLocalPointOnShape2; } // Return the cached penetration impulse @@ -173,7 +173,7 @@ inline decimal ContactPoint::getPenetrationImpulse() const { // Return true if the contact point is similar (close enougth) to another given contact point inline bool ContactPoint::isSimilarWithContactPoint(const ContactPointInfo* localContactPointBody1) const { - return (localContactPointBody1->localPoint1 - mLocalPointOnBody1).lengthSquare() <= (PERSISTENT_CONTACT_DIST_THRESHOLD * + return (localContactPointBody1->localPoint1 - mLocalPointOnShape1).lengthSquare() <= (PERSISTENT_CONTACT_DIST_THRESHOLD * PERSISTENT_CONTACT_DIST_THRESHOLD); } diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index 1e5b5401..167d37b8 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -157,8 +157,8 @@ void ContactSolver::initializeForIsland(Island* island) { while (externalContact != nullptr) { // Get the contact point on the two bodies - Vector3 p1 = shape1->getLocalToWorldTransform() * externalContact->getLocalPointOnBody1(); - Vector3 p2 = shape2->getLocalToWorldTransform() * externalContact->getLocalPointOnBody2(); + Vector3 p1 = shape1->getLocalToWorldTransform() * externalContact->getLocalPointOnShape1(); + Vector3 p2 = shape2->getLocalToWorldTransform() * externalContact->getLocalPointOnShape2(); new (mContactPoints + mNbContactPoints) ContactPointSolver(); mContactPoints[mNbContactPoints].externalContact = externalContact; diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.h b/testbed/scenes/collisiondetection/CollisionDetectionScene.h index e5bd8db9..9a90f25c 100644 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.h +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.h @@ -94,13 +94,13 @@ class ContactManager : public rp3d::CollisionCallback { rp3d::Vector3 normal = contactPoint->getNormal(); openglframework::Vector3 contactNormal(normal.x, normal.y, normal.z); - rp3d::Vector3 point1 = contactPoint->getLocalPointOnBody1(); + rp3d::Vector3 point1 = contactPoint->getLocalPointOnShape1(); point1 = collisionCallbackInfo.proxyShape1->getLocalToWorldTransform() * point1; openglframework::Vector3 position1(point1.x, point1.y, point1.z); mContactPoints.push_back(ContactPoint(position1, contactNormal, openglframework::Color::red())); - rp3d::Vector3 point2 = contactPoint->getLocalPointOnBody2(); + rp3d::Vector3 point2 = contactPoint->getLocalPointOnShape2(); point2 = collisionCallbackInfo.proxyShape2->getLocalToWorldTransform() * point2; openglframework::Vector3 position2(point2.x, point2.y, point2.z); mContactPoints.push_back(ContactPoint(position2, contactNormal, openglframework::Color::blue())); diff --git a/testbed/src/SceneDemo.cpp b/testbed/src/SceneDemo.cpp index db5d030e..5ef6fb95 100644 --- a/testbed/src/SceneDemo.cpp +++ b/testbed/src/SceneDemo.cpp @@ -435,7 +435,7 @@ std::vector SceneDemo::computeContactPointsOfWorld(const rp3d::Dyn rp3d::ContactPoint* contactPoint = manifold->getContactPoints(); while (contactPoint != nullptr) { - rp3d::Vector3 point = manifold->getShape1()->getLocalToWorldTransform() * contactPoint->getLocalPointOnBody1(); + rp3d::Vector3 point = manifold->getShape1()->getLocalToWorldTransform() * contactPoint->getLocalPointOnShape1(); rp3d::Vector3 normalWorld = contactPoint->getNormal(); openglframework::Vector3 normal = openglframework::Vector3(normalWorld.x, normalWorld.y, normalWorld.z); ContactPoint contact(openglframework::Vector3(point.x, point.y, point.z), normal, openglframework::Color::red()); From 4f76553c59ae7410afa89f649a7aa089bb34a302 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 4 Dec 2017 22:14:52 +0100 Subject: [PATCH 143/248] Many small optimizations --- src/collision/CollisionDetection.cpp | 12 +-- src/collision/CollisionDetection.h | 1 - src/collision/HalfEdgeStructure.h | 18 ++-- src/collision/PolyhedronMesh.cpp | 2 +- .../narrowphase/CapsuleVsCapsuleAlgorithm.cpp | 3 +- .../narrowphase/CapsuleVsCapsuleAlgorithm.h | 2 +- .../CapsuleVsConvexPolyhedronAlgorithm.cpp | 8 +- .../CapsuleVsConvexPolyhedronAlgorithm.h | 2 +- ...xPolyhedronVsConvexPolyhedronAlgorithm.cpp | 5 +- ...vexPolyhedronVsConvexPolyhedronAlgorithm.h | 2 +- .../narrowphase/NarrowPhaseAlgorithm.h | 5 +- .../narrowphase/SAT/SATAlgorithm.cpp | 61 ++++++------ src/collision/narrowphase/SAT/SATAlgorithm.h | 5 +- .../narrowphase/SphereVsCapsuleAlgorithm.cpp | 3 +- .../narrowphase/SphereVsCapsuleAlgorithm.h | 2 +- .../SphereVsConvexPolyhedronAlgorithm.cpp | 5 +- .../SphereVsConvexPolyhedronAlgorithm.h | 2 +- .../narrowphase/SphereVsSphereAlgorithm.cpp | 3 +- .../narrowphase/SphereVsSphereAlgorithm.h | 2 +- src/collision/shapes/BoxShape.cpp | 7 +- src/collision/shapes/BoxShape.h | 14 +-- src/collision/shapes/ConvexMeshShape.h | 8 +- src/collision/shapes/ConvexPolyhedronShape.h | 4 +- src/collision/shapes/TriangleShape.cpp | 99 ++++++++++--------- src/collision/shapes/TriangleShape.h | 37 +++---- src/mathematics/Quaternion.h | 27 ++++- src/mathematics/Transform.h | 2 +- src/mathematics/mathematics_functions.cpp | 31 +++--- src/mathematics/mathematics_functions.h | 5 +- .../mathematics/TestMathematicsFunctions.h | 62 ++++++------ 30 files changed, 235 insertions(+), 204 deletions(-) diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index a2c3344d..c0b4d4e9 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -273,7 +273,7 @@ void CollisionDetection::computeNarrowPhase() { // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - if (narrowPhaseAlgorithm->testCollision(currentNarrowPhaseInfo, true)) { + if (narrowPhaseAlgorithm->testCollision(currentNarrowPhaseInfo, true, mSingleFrameAllocator)) { // Add the contact points as a potential contact manifold into the pair currentNarrowPhaseInfo->addContactPointsAsPotentialContactManifold(); @@ -593,7 +593,7 @@ bool CollisionDetection::testOverlap(CollisionBody* body1, CollisionBody* body2) // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - isColliding |= narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, false); + isColliding |= narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, false, mPoolAllocator); } } @@ -688,7 +688,7 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - isColliding |= narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, false); + isColliding |= narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, false, mPoolAllocator); } } @@ -767,7 +767,7 @@ void CollisionDetection::testCollision(CollisionBody* body1, CollisionBody* body // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, true)) { + if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, true, mPoolAllocator)) { // Add the contact points as a potential contact manifold into the pair narrowPhaseInfo->addContactPointsAsPotentialContactManifold(); @@ -859,7 +859,7 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, true)) { + if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, true, mPoolAllocator)) { // Add the contact points as a potential contact manifold into the pair narrowPhaseInfo->addContactPointsAsPotentialContactManifold(); @@ -943,7 +943,7 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, true)) { + if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, true, mPoolAllocator)) { // Add the contact points as a potential contact manifold into the pair narrowPhaseInfo->addContactPointsAsPotentialContactManifold(); diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index fc33c00f..d728a95f 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -150,7 +150,6 @@ class CollisionDetection { /// Process the potential contacts where one collion is a concave shape void processSmoothMeshContacts(OverlappingPair* pair); - public : diff --git a/src/collision/HalfEdgeStructure.h b/src/collision/HalfEdgeStructure.h index 6b4e3aa1..ec4fff35 100644 --- a/src/collision/HalfEdgeStructure.h +++ b/src/collision/HalfEdgeStructure.h @@ -106,13 +106,13 @@ class HalfEdgeStructure { uint getNbVertices() const; /// Return a given face - Face getFace(uint index) const; + const Face& getFace(uint index) const; /// Return a given edge - Edge getHalfEdge(uint index) const; + const Edge& getHalfEdge(uint index) const; /// Return a given vertex - Vertex getVertex(uint index) const; + const Vertex& getVertex(uint index) const; }; @@ -133,33 +133,33 @@ inline void HalfEdgeStructure::addFace(std::vector faceVertices) { // Return the number of faces inline uint HalfEdgeStructure::getNbFaces() const { - return mFaces.size(); + return static_cast(mFaces.size()); } // Return the number of edges inline uint HalfEdgeStructure::getNbHalfEdges() const { - return mEdges.size(); + return static_cast(mEdges.size()); } // Return the number of vertices inline uint HalfEdgeStructure::getNbVertices() const { - return mVertices.size(); + return static_cast(mVertices.size()); } // Return a given face -inline HalfEdgeStructure::Face HalfEdgeStructure::getFace(uint index) const { +inline const HalfEdgeStructure::Face& HalfEdgeStructure::getFace(uint index) const { assert(index < mFaces.size()); return mFaces[index]; } // Return a given edge -inline HalfEdgeStructure::Edge HalfEdgeStructure::getHalfEdge(uint index) const { +inline const HalfEdgeStructure::Edge& HalfEdgeStructure::getHalfEdge(uint index) const { assert(index < mEdges.size()); return mEdges[index]; } // Return a given vertex -inline HalfEdgeStructure::Vertex HalfEdgeStructure::getVertex(uint index) const { +inline const HalfEdgeStructure::Vertex& HalfEdgeStructure::getVertex(uint index) const { assert(index < mVertices.size()); return mVertices[index]; } diff --git a/src/collision/PolyhedronMesh.cpp b/src/collision/PolyhedronMesh.cpp index b4f82fad..ec8b661d 100644 --- a/src/collision/PolyhedronMesh.cpp +++ b/src/collision/PolyhedronMesh.cpp @@ -123,7 +123,7 @@ void PolyhedronMesh::computeFacesNormals() { // For each face for (uint f=0; f < mHalfEdgeStructure.getNbFaces(); f++) { - HalfEdgeStructure::Face face = mHalfEdgeStructure.getFace(f); + const HalfEdgeStructure::Face& face = mHalfEdgeStructure.getFace(f); assert(face.faceVertices.size() >= 3); diff --git a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp index b15cb186..bf9eefc2 100755 --- a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp @@ -33,7 +33,8 @@ using namespace reactphysics3d; // Compute the narrow-phase collision detection between two capsules // This technique is based on the "Robust Contact Creation for Physics Simulations" presentation // by Dirk Gregorius. -bool CapsuleVsCapsuleAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) { +bool CapsuleVsCapsuleAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, + Allocator& memoryAllocator) { assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE); assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CAPSULE); diff --git a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h index 0b19338f..df9a8854 100644 --- a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h +++ b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h @@ -61,7 +61,7 @@ class CapsuleVsCapsuleAlgorithm : public NarrowPhaseAlgorithm { CapsuleVsCapsuleAlgorithm& operator=(const CapsuleVsCapsuleAlgorithm& algorithm) = delete; /// Compute the narrow-phase collision detection between two capsules - virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) override; + virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, Allocator& memoryAllocator) override; }; } diff --git a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp index 300ba5f2..f943312b 100644 --- a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp @@ -37,11 +37,12 @@ using namespace reactphysics3d; // Compute the narrow-phase collision detection between a capsule and a polyhedron // This technique is based on the "Robust Contact Creation for Physics Simulations" presentation // by Dirk Gregorius. -bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) { +bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, + Allocator& memoryAllocator) { // First, we run the GJK algorithm GJKAlgorithm gjkAlgorithm; - SATAlgorithm satAlgorithm; + SATAlgorithm satAlgorithm(memoryAllocator); #ifdef IS_PROFILING_ACTIVE @@ -85,9 +86,6 @@ bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPh // For each face of the polyhedron for (uint f = 0; f < polyhedron->getNbFaces(); f++) { - // Get the face - HalfEdgeStructure::Face face = polyhedron->getFace(f); - const Transform polyhedronToWorld = isCapsuleShape1 ? narrowPhaseInfo->shape2ToWorldTransform : narrowPhaseInfo->shape1ToWorldTransform; const Transform capsuleToWorld = isCapsuleShape1 ? narrowPhaseInfo->shape1ToWorldTransform : narrowPhaseInfo->shape2ToWorldTransform; diff --git a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h index c0dd46d5..d7f96d63 100644 --- a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h +++ b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h @@ -61,7 +61,7 @@ class CapsuleVsConvexPolyhedronAlgorithm : public NarrowPhaseAlgorithm { CapsuleVsConvexPolyhedronAlgorithm& operator=(const CapsuleVsConvexPolyhedronAlgorithm& algorithm) = delete; /// Compute the narrow-phase collision detection between a capsule and a polyhedron - virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) override; + virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, Allocator& memoryAllocator) override; }; } diff --git a/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp index 507f6043..5cf10b17 100644 --- a/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp @@ -34,10 +34,11 @@ using namespace reactphysics3d; // Compute the narrow-phase collision detection between two convex polyhedra // This technique is based on the "Robust Contact Creation for Physics Simulations" presentation // by Dirk Gregorius. -bool ConvexPolyhedronVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) { +bool ConvexPolyhedronVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, + Allocator& memoryAllocator) { // Run the SAT algorithm to find the separating axis and compute contact point - SATAlgorithm satAlgorithm; + SATAlgorithm satAlgorithm(memoryAllocator); #ifdef IS_PROFILING_ACTIVE diff --git a/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.h b/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.h index 1e0c9748..204bc269 100644 --- a/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.h +++ b/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.h @@ -61,7 +61,7 @@ class ConvexPolyhedronVsConvexPolyhedronAlgorithm : public NarrowPhaseAlgorithm ConvexPolyhedronVsConvexPolyhedronAlgorithm& operator=(const ConvexPolyhedronVsConvexPolyhedronAlgorithm& algorithm) = delete; /// Compute the narrow-phase collision detection between two convex polyhedra - virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) override; + virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, Allocator& memoryAllocator) override; }; } diff --git a/src/collision/narrowphase/NarrowPhaseAlgorithm.h b/src/collision/narrowphase/NarrowPhaseAlgorithm.h index 34fa5962..40d3fbc6 100644 --- a/src/collision/narrowphase/NarrowPhaseAlgorithm.h +++ b/src/collision/narrowphase/NarrowPhaseAlgorithm.h @@ -90,8 +90,9 @@ class NarrowPhaseAlgorithm { /// Deleted assignment operator NarrowPhaseAlgorithm& operator=(const NarrowPhaseAlgorithm& algorithm) = delete; - /// Compute a contact info if the two bounding volume collide - virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts)=0; + /// Compute a contact info if the two bounding volumes collide + virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, + Allocator& memoryAllocator)=0; #ifdef IS_PROFILING_ACTIVE diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index f12964cf..7ef99e1f 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -44,6 +44,11 @@ using namespace reactphysics3d; // Static variables initialization const decimal SATAlgorithm::SAME_SEPARATING_AXIS_BIAS = decimal(0.001); +// Constructor +SATAlgorithm::SATAlgorithm(Allocator& memoryAllocator) : mMemoryAllocator(memoryAllocator) { + +} + // Test collision between a sphere and a convex mesh bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) const { @@ -125,7 +130,7 @@ decimal SATAlgorithm::computePolyhedronFaceVsSpherePenetrationDepth(uint faceInd PROFILE("SATAlgorithm::computePolyhedronFaceVsSpherePenetrationDepth)", mProfiler); // Get the face - HalfEdgeStructure::Face face = polyhedron->getFace(faceIndex); + const HalfEdgeStructure::Face& face = polyhedron->getFace(faceIndex); // Get the face normal const Vector3 faceNormal = polyhedron->getFaceNormal(faceIndex); @@ -200,12 +205,12 @@ bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfo* narro for (uint e = 0; e < polyhedron->getNbHalfEdges(); e += 2) { // Get an edge from the polyhedron (convert it into the capsule local-space) - HalfEdgeStructure::Edge edge = polyhedron->getHalfEdge(e); + const HalfEdgeStructure::Edge& edge = polyhedron->getHalfEdge(e); const Vector3 edgeVertex1 = polyhedron->getVertexPosition(edge.vertexIndex); const Vector3 edgeVertex2 = polyhedron->getVertexPosition(polyhedron->getHalfEdge(edge.nextEdgeIndex).vertexIndex); const Vector3 edgeDirectionCapsuleSpace = polyhedronToCapsuleTransform.getOrientation() * (edgeVertex2 - edgeVertex1); - HalfEdgeStructure::Edge twinEdge = polyhedron->getHalfEdge(edge.twinEdgeIndex); + const HalfEdgeStructure::Edge& twinEdge = polyhedron->getHalfEdge(edge.twinEdgeIndex); const Vector3 adjacentFace1Normal = polyhedronToCapsuleTransform.getOrientation() * polyhedron->getFaceNormal(edge.faceIndex); const Vector3 adjacentFace2Normal = polyhedronToCapsuleTransform.getOrientation() * polyhedron->getFaceNormal(twinEdge.faceIndex); @@ -336,7 +341,7 @@ decimal SATAlgorithm::computePolyhedronFaceVsCapsulePenetrationDepth(uint polyhe PROFILE("SATAlgorithm::computePolyhedronFaceVsCapsulePenetrationDepth", mProfiler); // Get the face - HalfEdgeStructure::Face face = polyhedron->getFace(polyhedronFaceIndex); + const HalfEdgeStructure::Face& face = polyhedron->getFace(polyhedronFaceIndex); // Get the face normal const Vector3 faceNormal = polyhedron->getFaceNormal(polyhedronFaceIndex); @@ -361,7 +366,7 @@ bool SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceI PROFILE("SATAlgorithm::computeCapsulePolyhedronFaceContactPoints", mProfiler); - HalfEdgeStructure::Face face = polyhedron->getFace(referenceFaceIndex); + const HalfEdgeStructure::Face& face = polyhedron->getFace(referenceFaceIndex); // Get the face normal Vector3 faceNormal = polyhedron->getFaceNormal(referenceFaceIndex); @@ -375,8 +380,8 @@ bool SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceI // For each adjacent edge of the separating face of the polyhedron do { - HalfEdgeStructure::Edge edge = polyhedron->getHalfEdge(edgeIndex); - HalfEdgeStructure::Edge twinEdge = polyhedron->getHalfEdge(edge.twinEdgeIndex); + const HalfEdgeStructure::Edge& edge = polyhedron->getHalfEdge(edgeIndex); + const HalfEdgeStructure::Edge& twinEdge = polyhedron->getHalfEdge(edge.twinEdgeIndex); // Compute the edge vertices and edge direction Vector3 edgeV1 = polyhedron->getVertexPosition(edge.vertexIndex); @@ -575,8 +580,8 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn } else { // If the previous separating axis (or axis with minimum penetration depth) was the cross product of two edges - HalfEdgeStructure::Edge edge1 = polyhedron1->getHalfEdge(lastFrameCollisionInfo->satMinEdge1Index); - HalfEdgeStructure::Edge edge2 = polyhedron2->getHalfEdge(lastFrameCollisionInfo->satMinEdge2Index); + const HalfEdgeStructure::Edge& edge1 = polyhedron1->getHalfEdge(lastFrameCollisionInfo->satMinEdge1Index); + const HalfEdgeStructure::Edge& edge2 = polyhedron2->getHalfEdge(lastFrameCollisionInfo->satMinEdge2Index); Vector3 separatingAxisPolyhedron2Space; @@ -669,7 +674,7 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn for (uint i=0; i < polyhedron1->getNbHalfEdges(); i += 2) { // Get an edge of polyhedron 1 - HalfEdgeStructure::Edge edge1 = polyhedron1->getHalfEdge(i); + const HalfEdgeStructure::Edge& edge1 = polyhedron1->getHalfEdge(i); const Vector3 edge1A = polyhedron1ToPolyhedron2 * polyhedron1->getVertexPosition(edge1.vertexIndex); const Vector3 edge1B = polyhedron1ToPolyhedron2 * polyhedron1->getVertexPosition(polyhedron1->getHalfEdge(edge1.nextEdgeIndex).vertexIndex); @@ -678,7 +683,7 @@ bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseIn for (uint j=0; j < polyhedron2->getNbHalfEdges(); j += 2) { // Get an edge of polyhedron 2 - HalfEdgeStructure::Edge edge2 = polyhedron2->getHalfEdge(j); + const HalfEdgeStructure::Edge& edge2 = polyhedron2->getHalfEdge(j); const Vector3 edge2A = polyhedron2->getVertexPosition(edge2.vertexIndex); const Vector3 edge2B = polyhedron2->getVertexPosition(polyhedron2->getHalfEdge(edge2.nextEdgeIndex).vertexIndex); @@ -816,23 +821,24 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene -(narrowPhaseInfo->shape2ToWorldTransform.getOrientation() * axisReferenceSpace); // Get the reference face - HalfEdgeStructure::Face referenceFace = referencePolyhedron->getFace(minFaceIndex); + const HalfEdgeStructure::Face& referenceFace = referencePolyhedron->getFace(minFaceIndex); // Find the incident face on the other polyhedron (most anti-parallel face) uint incidentFaceIndex = findMostAntiParallelFaceOnPolyhedron(incidentPolyhedron, axisIncidentSpace); // Get the incident face - HalfEdgeStructure::Face incidentFace = incidentPolyhedron->getFace(incidentFaceIndex); + const HalfEdgeStructure::Face& incidentFace = incidentPolyhedron->getFace(incidentFaceIndex); - std::vector polygonVertices; // Vertices to clip of the incident face - std::vector planesNormals; // Normals of the clipping planes - std::vector planesPoints; // Points on the clipping planes + uint nbIncidentFaceVertices = static_cast(incidentFace.faceVertices.size()); + List polygonVertices(mMemoryAllocator, nbIncidentFaceVertices); // Vertices to clip of the incident face + List planesNormals(mMemoryAllocator, nbIncidentFaceVertices); // Normals of the clipping planes + List planesPoints(mMemoryAllocator, nbIncidentFaceVertices); // Points on the clipping planes // Get all the vertices of the incident face (in the reference local-space) std::vector::const_iterator it; for (it = incidentFace.faceVertices.begin(); it != incidentFace.faceVertices.end(); ++it) { const Vector3 faceVertexIncidentSpace = incidentPolyhedron->getVertexPosition(*it); - polygonVertices.push_back(incidentToReferenceTransform * faceVertexIncidentSpace); + polygonVertices.add(incidentToReferenceTransform * faceVertexIncidentSpace); } // Get the reference face clipping planes @@ -841,10 +847,10 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene do { // Get the adjacent edge - HalfEdgeStructure::Edge edge = referencePolyhedron->getHalfEdge(currentEdgeIndex); + const HalfEdgeStructure::Edge& edge = referencePolyhedron->getHalfEdge(currentEdgeIndex); // Get the twin edge - HalfEdgeStructure::Edge twinEdge = referencePolyhedron->getHalfEdge(edge.twinEdgeIndex); + const HalfEdgeStructure::Edge& twinEdge = referencePolyhedron->getHalfEdge(edge.twinEdgeIndex); // Compute the edge vertices and edge direction Vector3 edgeV1 = referencePolyhedron->getVertexPosition(edge.vertexIndex); @@ -855,8 +861,8 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene // The clipping plane is perpendicular to the edge direction and the reference face normal Vector3 clipPlaneNormal = axisReferenceSpace.cross(edgeDirection); - planesNormals.push_back(clipPlaneNormal); - planesPoints.push_back(edgeV1); + planesNormals.add(clipPlaneNormal); + planesPoints.add(edgeV1); // Go to the next adjacent edge of the reference face currentEdgeIndex = edge.nextEdgeIndex; @@ -867,17 +873,16 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene assert(planesNormals.size() == planesPoints.size()); // Clip the reference faces with the adjacent planes of the reference face - std::vector clipPolygonVertices = clipPolygonWithPlanes(polygonVertices, planesPoints, planesNormals); + List clipPolygonVertices = clipPolygonWithPlanes(polygonVertices, planesPoints, planesNormals, mMemoryAllocator); // We only keep the clipped points that are below the reference face const Vector3 referenceFaceVertex = referencePolyhedron->getVertexPosition(referencePolyhedron->getHalfEdge(firstEdgeIndex).vertexIndex); - std::vector::const_iterator itPoints; bool contactPointsFound = false; - for (itPoints = clipPolygonVertices.begin(); itPoints != clipPolygonVertices.end(); ++itPoints) { + for (uint i=0; i decimal(0.0)) { @@ -887,10 +892,10 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene Vector3 outWorldNormal = normalWorld; // Convert the clip incident polyhedron vertex into the incident polyhedron local-space - Vector3 contactPointIncidentPolyhedron = referenceToIncidentTransform * (*itPoints); + Vector3 contactPointIncidentPolyhedron = referenceToIncidentTransform * clipPolygonVertices[i]; // Project the contact point onto the reference face - Vector3 contactPointReferencePolyhedron = projectPointOntoPlane(*itPoints, axisReferenceSpace, referenceFaceVertex); + Vector3 contactPointReferencePolyhedron = projectPointOntoPlane(clipPolygonVertices[i], axisReferenceSpace, referenceFaceVertex); // Compute smooth triangle mesh contact if one of the two collision shapes is a triangle TriangleShape::computeSmoothTriangleMeshContact(narrowPhaseInfo->collisionShape1, narrowPhaseInfo->collisionShape2, @@ -968,7 +973,7 @@ decimal SATAlgorithm::testSingleFaceDirectionPolyhedronVsPolyhedron(const Convex PROFILE("SATAlgorithm::testSingleFaceDirectionPolyhedronVsPolyhedron", mProfiler); - HalfEdgeStructure::Face face = polyhedron1->getFace(faceIndex); + const HalfEdgeStructure::Face& face = polyhedron1->getFace(faceIndex); // Get the face normal const Vector3 faceNormal = polyhedron1->getFaceNormal(faceIndex); diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.h b/src/collision/narrowphase/SAT/SATAlgorithm.h index 60f7a091..af49ca09 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.h +++ b/src/collision/narrowphase/SAT/SATAlgorithm.h @@ -50,6 +50,9 @@ class SATAlgorithm { /// make sure the contact manifold does not change too much between frames. static const decimal SAME_SEPARATING_AXIS_BIAS; + /// Memory allocator + Allocator& mMemoryAllocator; + #ifdef IS_PROFILING_ACTIVE /// Pointer to the profiler @@ -115,7 +118,7 @@ class SATAlgorithm { // -------------------- Methods -------------------- // /// Constructor - SATAlgorithm() = default; + SATAlgorithm(Allocator& memoryAllocator); /// Destructor ~SATAlgorithm() = default; diff --git a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp index a5d7a6ac..f5bfc11d 100755 --- a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp @@ -34,7 +34,8 @@ using namespace reactphysics3d; // Compute the narrow-phase collision detection between a sphere and a capsule // This technique is based on the "Robust Contact Creation for Physics Simulations" presentation // by Dirk Gregorius. -bool SphereVsCapsuleAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) { +bool SphereVsCapsuleAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, + Allocator& memoryAllocator) { bool isSphereShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE; diff --git a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h index bb9e9866..b51bba57 100644 --- a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h +++ b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h @@ -61,7 +61,7 @@ class SphereVsCapsuleAlgorithm : public NarrowPhaseAlgorithm { SphereVsCapsuleAlgorithm& operator=(const SphereVsCapsuleAlgorithm& algorithm) = delete; /// Compute the narrow-phase collision detection between a sphere and a capsule - virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) override; + virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, Allocator& memoryAllocator) override; }; } diff --git a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp index 28a565c1..6cc3e578 100644 --- a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp @@ -34,7 +34,8 @@ using namespace reactphysics3d; // Compute the narrow-phase collision detection between a sphere and a convex polyhedron // This technique is based on the "Robust Contact Creation for Physics Simulations" presentation // by Dirk Gregorius. -bool SphereVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) { +bool SphereVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, + Allocator& memoryAllocator) { assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON || narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); @@ -69,7 +70,7 @@ bool SphereVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPha if (result == GJKAlgorithm::GJKResult::INTERPENETRATE) { // Run the SAT algorithm to find the separating axis and compute contact point - SATAlgorithm satAlgorithm; + SATAlgorithm satAlgorithm(memoryAllocator); #ifdef IS_PROFILING_ACTIVE diff --git a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h index 2d9fa801..17055431 100644 --- a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h +++ b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h @@ -61,7 +61,7 @@ class SphereVsConvexPolyhedronAlgorithm : public NarrowPhaseAlgorithm { SphereVsConvexPolyhedronAlgorithm& operator=(const SphereVsConvexPolyhedronAlgorithm& algorithm) = delete; /// Compute the narrow-phase collision detection between a sphere and a convex polyhedron - virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) override; + virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, Allocator& memoryAllocator) override; }; } diff --git a/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp b/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp index 0b520213..f8820106 100755 --- a/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp @@ -30,7 +30,8 @@ // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; -bool SphereVsSphereAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) { +bool SphereVsSphereAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, + Allocator& memoryAllocator) { assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE); assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::SPHERE); diff --git a/src/collision/narrowphase/SphereVsSphereAlgorithm.h b/src/collision/narrowphase/SphereVsSphereAlgorithm.h index 1fd885a5..e0741ab8 100644 --- a/src/collision/narrowphase/SphereVsSphereAlgorithm.h +++ b/src/collision/narrowphase/SphereVsSphereAlgorithm.h @@ -61,7 +61,7 @@ class SphereVsSphereAlgorithm : public NarrowPhaseAlgorithm { SphereVsSphereAlgorithm& operator=(const SphereVsSphereAlgorithm& algorithm) = delete; /// Compute a contact info if the two bounding volume collide - virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) override; + virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, Allocator& memoryAllocator) override; }; } diff --git a/src/collision/shapes/BoxShape.cpp b/src/collision/shapes/BoxShape.cpp index 6b8c8d6b..37667958 100644 --- a/src/collision/shapes/BoxShape.cpp +++ b/src/collision/shapes/BoxShape.cpp @@ -84,10 +84,9 @@ BoxShape::BoxShape(const Vector3& extent) */ void BoxShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const { decimal factor = (decimal(1.0) / decimal(3.0)) * mass; - Vector3 realExtent = mExtent + Vector3(mMargin, mMargin, mMargin); - decimal xSquare = realExtent.x * realExtent.x; - decimal ySquare = realExtent.y * realExtent.y; - decimal zSquare = realExtent.z * realExtent.z; + decimal xSquare = mExtent.x * mExtent.x; + decimal ySquare = mExtent.y * mExtent.y; + decimal zSquare = mExtent.z * mExtent.z; tensor.setAllValues(factor * (ySquare + zSquare), 0.0, 0.0, 0.0, factor * (xSquare + zSquare), 0.0, 0.0, 0.0, factor * (xSquare + ySquare)); diff --git a/src/collision/shapes/BoxShape.h b/src/collision/shapes/BoxShape.h index 5643a5c8..d1aa9810 100644 --- a/src/collision/shapes/BoxShape.h +++ b/src/collision/shapes/BoxShape.h @@ -101,7 +101,7 @@ class BoxShape : public ConvexPolyhedronShape { virtual uint getNbFaces() const override; /// Return a given face of the polyhedron - virtual HalfEdgeStructure::Face getFace(uint faceIndex) const override; + virtual const HalfEdgeStructure::Face& getFace(uint faceIndex) const override; /// Return the number of vertices of the polyhedron virtual uint getNbVertices() const override; @@ -113,7 +113,7 @@ class BoxShape : public ConvexPolyhedronShape { virtual uint getNbHalfEdges() const override; /// Return a given half-edge of the polyhedron - virtual HalfEdgeStructure::Edge getHalfEdge(uint edgeIndex) const override; + virtual const HalfEdgeStructure::Edge& getHalfEdge(uint edgeIndex) const override; /// Return the position of a given vertex virtual Vector3 getVertexPosition(uint vertexIndex) const override; @@ -130,7 +130,7 @@ class BoxShape : public ConvexPolyhedronShape { * @return The vector with the three extents of the box shape (in meters) */ inline Vector3 BoxShape::getExtent() const { - return mExtent + Vector3(mMargin, mMargin, mMargin); + return mExtent; } // Set the scaling vector of the collision shape @@ -150,7 +150,7 @@ inline void BoxShape::setLocalScaling(const Vector3& scaling) { inline void BoxShape::getLocalBounds(Vector3& min, Vector3& max) const { // Maximum bounds - max = mExtent + Vector3(mMargin, mMargin, mMargin); + max = mExtent; // Minimum bounds min = -max; @@ -161,7 +161,7 @@ inline size_t BoxShape::getSizeInBytes() const { return sizeof(BoxShape); } -// Return a local support point in a given direction without the objec margin +// Return a local support point in a given direction without the object margin inline Vector3 BoxShape::getLocalSupportPointWithoutMargin(const Vector3& direction) const { return Vector3(direction.x < decimal(0.0) ? -mExtent.x : mExtent.x, @@ -182,7 +182,7 @@ inline uint BoxShape::getNbFaces() const { } // Return a given face of the polyhedron -inline HalfEdgeStructure::Face BoxShape::getFace(uint faceIndex) const { +inline const HalfEdgeStructure::Face& BoxShape::getFace(uint faceIndex) const { assert(faceIndex < mHalfEdgeStructure.getNbFaces()); return mHalfEdgeStructure.getFace(faceIndex); } @@ -243,7 +243,7 @@ inline uint BoxShape::getNbHalfEdges() const { } // Return a given half-edge of the polyhedron -inline HalfEdgeStructure::Edge BoxShape::getHalfEdge(uint edgeIndex) const { +inline const HalfEdgeStructure::Edge& BoxShape::getHalfEdge(uint edgeIndex) const { assert(edgeIndex < getNbHalfEdges()); return mHalfEdgeStructure.getHalfEdge(edgeIndex); } diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index 71077af2..0ce696af 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -111,7 +111,7 @@ class ConvexMeshShape : public ConvexPolyhedronShape { virtual uint getNbFaces() const override; /// Return a given face of the polyhedron - virtual HalfEdgeStructure::Face getFace(uint faceIndex) const override; + virtual const HalfEdgeStructure::Face& getFace(uint faceIndex) const override; /// Return the number of vertices of the polyhedron virtual uint getNbVertices() const override; @@ -123,7 +123,7 @@ class ConvexMeshShape : public ConvexPolyhedronShape { virtual uint getNbHalfEdges() const override; /// Return a given half-edge of the polyhedron - virtual HalfEdgeStructure::Edge getHalfEdge(uint edgeIndex) const override; + virtual const HalfEdgeStructure::Edge& getHalfEdge(uint edgeIndex) const override; /// Return the position of a given vertex virtual Vector3 getVertexPosition(uint vertexIndex) const override; @@ -191,7 +191,7 @@ inline uint ConvexMeshShape::getNbFaces() const { } // Return a given face of the polyhedron -inline HalfEdgeStructure::Face ConvexMeshShape::getFace(uint faceIndex) const { +inline const HalfEdgeStructure::Face& ConvexMeshShape::getFace(uint faceIndex) const { assert(faceIndex < getNbFaces()); return mPolyhedronMesh->getHalfEdgeStructure().getFace(faceIndex); } @@ -213,7 +213,7 @@ inline uint ConvexMeshShape::getNbHalfEdges() const { } // Return a given half-edge of the polyhedron -inline HalfEdgeStructure::Edge ConvexMeshShape::getHalfEdge(uint edgeIndex) const { +inline const HalfEdgeStructure::Edge& ConvexMeshShape::getHalfEdge(uint edgeIndex) const { assert(edgeIndex < getNbHalfEdges()); return mPolyhedronMesh->getHalfEdgeStructure().getHalfEdge(edgeIndex); } diff --git a/src/collision/shapes/ConvexPolyhedronShape.h b/src/collision/shapes/ConvexPolyhedronShape.h index 96707d69..1d944cb8 100644 --- a/src/collision/shapes/ConvexPolyhedronShape.h +++ b/src/collision/shapes/ConvexPolyhedronShape.h @@ -62,7 +62,7 @@ class ConvexPolyhedronShape : public ConvexShape { virtual uint getNbFaces() const=0; /// Return a given face of the polyhedron - virtual HalfEdgeStructure::Face getFace(uint faceIndex) const=0; + virtual const HalfEdgeStructure::Face& getFace(uint faceIndex) const=0; /// Return the number of vertices of the polyhedron virtual uint getNbVertices() const=0; @@ -80,7 +80,7 @@ class ConvexPolyhedronShape : public ConvexShape { virtual uint getNbHalfEdges() const=0; /// Return a given half-edge of the polyhedron - virtual HalfEdgeStructure::Edge getHalfEdge(uint edgeIndex) const=0; + virtual const HalfEdgeStructure::Edge& getHalfEdge(uint edgeIndex) const=0; /// Return true if the collision shape is a polyhedron virtual bool isPolyhedron() const override; diff --git a/src/collision/shapes/TriangleShape.cpp b/src/collision/shapes/TriangleShape.cpp index 77d0929c..e43cc674 100644 --- a/src/collision/shapes/TriangleShape.cpp +++ b/src/collision/shapes/TriangleShape.cpp @@ -58,6 +58,57 @@ TriangleShape::TriangleShape(const Vector3* vertices, const Vector3* verticesNor mVerticesNormals[1] = verticesNormals[1]; mVerticesNormals[2] = verticesNormals[2]; + // 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].edgeIndex = i; + } + + // Edges + for (uint i=0; i<6; i++) { + switch(i) { + case 0: + mEdges[0].vertexIndex = 0; + mEdges[0].twinEdgeIndex = 1; + mEdges[0].faceIndex = 0; + mEdges[0].nextEdgeIndex = 2; + break; + case 1: + mEdges[1].vertexIndex = 1; + mEdges[1].twinEdgeIndex = 0; + mEdges[1].faceIndex = 1; + mEdges[1].nextEdgeIndex = 5; + break; + case 2: + mEdges[2].vertexIndex = 1; + mEdges[2].twinEdgeIndex = 3; + mEdges[2].faceIndex = 0; + mEdges[2].nextEdgeIndex = 4; + break; + case 3: + mEdges[3].vertexIndex = 2; + mEdges[3].twinEdgeIndex = 2; + mEdges[3].faceIndex = 1; + mEdges[3].nextEdgeIndex = 1; + break; + case 4: + mEdges[4].vertexIndex = 2; + mEdges[4].twinEdgeIndex = 5; + mEdges[4].faceIndex = 0; + mEdges[4].nextEdgeIndex = 0; + break; + case 5: + mEdges[5].vertexIndex = 0; + mEdges[5].twinEdgeIndex = 4; + mEdges[5].faceIndex = 1; + mEdges[5].nextEdgeIndex = 3; + break; + } + } + + mRaycastTestType = TriangleRaycastSide::FRONT; mId = shapeId; @@ -227,51 +278,3 @@ bool TriangleShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape return true; } -// Return a given half-edge of the polyhedron -HalfEdgeStructure::Edge TriangleShape::getHalfEdge(uint edgeIndex) const { - assert(edgeIndex < getNbHalfEdges()); - - HalfEdgeStructure::Edge edge; - - switch(edgeIndex) { - case 0: - edge.vertexIndex = 0; - edge.twinEdgeIndex = 1; - edge.faceIndex = 0; - edge.nextEdgeIndex = 2; - break; - case 1: - edge.vertexIndex = 1; - edge.twinEdgeIndex = 0; - edge.faceIndex = 1; - edge.nextEdgeIndex = 5; - break; - case 2: - edge.vertexIndex = 1; - edge.twinEdgeIndex = 3; - edge.faceIndex = 0; - edge.nextEdgeIndex = 4; - break; - case 3: - edge.vertexIndex = 2; - edge.twinEdgeIndex = 2; - edge.faceIndex = 1; - edge.nextEdgeIndex = 1; - break; - case 4: - edge.vertexIndex = 2; - edge.twinEdgeIndex = 5; - edge.faceIndex = 0; - edge.nextEdgeIndex = 0; - break; - case 5: - edge.vertexIndex = 0; - edge.twinEdgeIndex = 4; - edge.faceIndex = 1; - edge.nextEdgeIndex = 3; - break; - } - - return edge; - -} diff --git a/src/collision/shapes/TriangleShape.h b/src/collision/shapes/TriangleShape.h index 60ec216b..a4ce7726 100644 --- a/src/collision/shapes/TriangleShape.h +++ b/src/collision/shapes/TriangleShape.h @@ -72,6 +72,12 @@ class TriangleShape : public ConvexPolyhedronShape { /// Raycast test type for the triangle (front, back, front-back) TriangleRaycastSide mRaycastTestType; + /// Faces information for the two faces of the triangle + HalfEdgeStructure::Face mFaces[2]; + + /// Edges information for the six edges of the triangle + HalfEdgeStructure::Edge mEdges[6]; + // -------------------- Methods -------------------- // /// Return a local support point in a given direction without the object margin @@ -137,7 +143,7 @@ class TriangleShape : public ConvexPolyhedronShape { virtual uint getNbFaces() const override; /// Return a given face of the polyhedron - virtual HalfEdgeStructure::Face getFace(uint faceIndex) const override; + virtual const HalfEdgeStructure::Face& getFace(uint faceIndex) const override; /// Return the number of vertices of the polyhedron virtual uint getNbVertices() const override; @@ -155,7 +161,7 @@ class TriangleShape : public ConvexPolyhedronShape { virtual uint getNbHalfEdges() const override; /// Return a given half-edge of the polyhedron - virtual HalfEdgeStructure::Edge getHalfEdge(uint edgeIndex) const override; + virtual const HalfEdgeStructure::Edge& getHalfEdge(uint edgeIndex) const override; /// Return the centroid of the polyhedron virtual Vector3 getCentroid() const override; @@ -252,26 +258,9 @@ inline uint TriangleShape::getNbFaces() const { } // Return a given face of the polyhedron -inline HalfEdgeStructure::Face TriangleShape::getFace(uint faceIndex) const { +inline const HalfEdgeStructure::Face& TriangleShape::getFace(uint faceIndex) const { assert(faceIndex < 2); - - HalfEdgeStructure::Face face; - - if (faceIndex == 0) { - face.faceVertices.push_back(0); - face.faceVertices.push_back(1); - face.faceVertices.push_back(2); - face.edgeIndex = 0; - - } - else { - face.faceVertices.push_back(0); - face.faceVertices.push_back(2); - face.faceVertices.push_back(1); - face.edgeIndex = 1; - } - - return face; + return mFaces[faceIndex]; } // Return the number of vertices of the polyhedron @@ -292,6 +281,12 @@ inline HalfEdgeStructure::Vertex TriangleShape::getVertex(uint vertexIndex) cons return vertex; } +// Return a given half-edge of the polyhedron +inline const HalfEdgeStructure::Edge& TriangleShape::getHalfEdge(uint edgeIndex) const { + assert(edgeIndex < getNbHalfEdges()); + return mEdges[edgeIndex]; +} + // Return the position of a given vertex inline Vector3 TriangleShape::getVertexPosition(uint vertexIndex) const { assert(vertexIndex < 3); diff --git a/src/mathematics/Quaternion.h b/src/mathematics/Quaternion.h index 74415eb8..d5e771e2 100644 --- a/src/mathematics/Quaternion.h +++ b/src/mathematics/Quaternion.h @@ -306,16 +306,35 @@ inline Quaternion Quaternion::operator*(decimal nb) const { // Overloaded operator for the multiplication of two quaternions inline Quaternion Quaternion::operator*(const Quaternion& quaternion) const { + + /* The followin code is equivalent to this return Quaternion(w * quaternion.w - getVectorV().dot(quaternion.getVectorV()), - w * quaternion.getVectorV() + quaternion.w * getVectorV() + - getVectorV().cross(quaternion.getVectorV())); + w * quaternion.getVectorV() + quaternion.w * getVectorV() + + getVectorV().cross(quaternion.getVectorV())); + */ + + return Quaternion(w * quaternion.x + quaternion.w * x + y * quaternion.z - z * quaternion.y, + w * quaternion.y + quaternion.w * y + z * quaternion.x - x * quaternion.z, + w * quaternion.z + quaternion.w * z + x * quaternion.y - y * quaternion.x, + w * quaternion.w - x * quaternion.x - y * quaternion.y - z * quaternion.z); } // Overloaded operator for the multiplication with a vector. /// This methods rotates a point given the rotation of a quaternion. inline Vector3 Quaternion::operator*(const Vector3& point) const { - Quaternion p(point.x, point.y, point.z, 0.0); - return (((*this) * p) * getConjugate()).getVectorV(); + + /* The following code is equivalent to this + * Quaternion p(point.x, point.y, point.z, 0.0); + * return (((*this) * p) * getConjugate()).getVectorV(); + */ + + const decimal prodX = w * point.x + y * point.z - z * point.y; + const decimal prodY = w * point.y + z * point.x - x * point.z; + const decimal prodZ = w * point.z + x * point.y - y * point.x; + const decimal prodW = -x * point.x - y * point.y - z * point.z; + return Vector3(w * prodX - prodY * z + prodZ * y - prodW * x, + w * prodY - prodZ * x + prodX * z - prodW * y, + w * prodZ - prodX * y + prodY * x - prodW * z); } // Overloaded operator for the assignment diff --git a/src/mathematics/Transform.h b/src/mathematics/Transform.h index ab17a620..52ee663e 100644 --- a/src/mathematics/Transform.h +++ b/src/mathematics/Transform.h @@ -194,7 +194,7 @@ inline Transform Transform::identity() { // Return the transformed vector inline Vector3 Transform::operator*(const Vector3& vector) const { - return (mOrientation.getMatrix() * vector) + mPosition; + return (mOrientation * vector) + mPosition; } // Operator of multiplication of a transform with another one diff --git a/src/mathematics/mathematics_functions.cpp b/src/mathematics/mathematics_functions.cpp index 37335abe..e7c9f371 100755 --- a/src/mathematics/mathematics_functions.cpp +++ b/src/mathematics/mathematics_functions.cpp @@ -198,10 +198,7 @@ decimal reactphysics3d::computePlaneSegmentIntersection(const Vector3& segA, con const decimal parallelEpsilon = decimal(0.0001); decimal t = decimal(-1); - // Segment AB - const Vector3 ab = segB - segA; - - decimal nDotAB = planeNormal.dot(ab); + decimal nDotAB = planeNormal.dot(segB - segA); // If the segment is not parallel to the plane if (std::abs(nDotAB) > parallelEpsilon) { @@ -297,23 +294,27 @@ std::vector reactphysics3d::clipSegmentWithPlanes(const Vector3& segA, // Clip a polygon against multiple planes and return the clipped polygon vertices // This method implements the Sutherland–Hodgman clipping algorithm -std::vector reactphysics3d::clipPolygonWithPlanes(const std::vector& polygonVertices, const std::vector& planesPoints, - const std::vector& planesNormals) { +List reactphysics3d::clipPolygonWithPlanes(const List& polygonVertices, const List& planesPoints, + const List& planesNormals, Allocator& allocator) { assert(planesPoints.size() == planesNormals.size()); - std::vector inputVertices(polygonVertices); - std::vector outputVertices; + uint nbMaxElements = polygonVertices.size() + planesPoints.size(); + List inputVertices(allocator, nbMaxElements); + List outputVertices(allocator, nbMaxElements); + + inputVertices.addRange(polygonVertices); // For each clipping plane for (uint p=0; p reactphysics3d::clipPolygonWithPlanes(const std::vector= decimal(0) && t <= decimal(1.0)) { - outputVertices.push_back(v1 + t * (v2 - v1)); + outputVertices.add(v1 + t * (v2 - v1)); } else { - outputVertices.push_back(v2); + outputVertices.add(v2); } } // Add the second vertex - outputVertices.push_back(v2); + outputVertices.add(v2); } else { // If the second vertex is behind the clipping plane @@ -350,10 +351,10 @@ std::vector reactphysics3d::clipPolygonWithPlanes(const std::vector= decimal(0.0) && t <= decimal(1.0)) { - outputVertices.push_back(v1 + t * (v2 - v1)); + outputVertices.add(v1 + t * (v2 - v1)); } else { - outputVertices.push_back(v1); + outputVertices.add(v1); } } } diff --git a/src/mathematics/mathematics_functions.h b/src/mathematics/mathematics_functions.h index 9f062826..ff6ac6f4 100755 --- a/src/mathematics/mathematics_functions.h +++ b/src/mathematics/mathematics_functions.h @@ -33,6 +33,7 @@ #include #include #include +#include "containers/List.h" /// ReactPhysics3D namespace namespace reactphysics3d { @@ -116,8 +117,8 @@ std::vector clipSegmentWithPlanes(const Vector3& segA, const Vector3& s const std::vector& planesNormals); /// Clip a polygon against multiple planes and return the clipped polygon vertices -std::vector clipPolygonWithPlanes(const std::vector& polygonVertices, const std::vector& planesPoints, - const std::vector& planesNormals); +List clipPolygonWithPlanes(const List& polygonVertices, const List& planesPoints, + const List& planesNormals, Allocator& allocator); /// Project a point onto a plane that is given by a point and its unit length normal Vector3 projectPointOntoPlane(const Vector3& point, const Vector3& planeNormal, const Vector3& planePoint); diff --git a/test/tests/mathematics/TestMathematicsFunctions.h b/test/tests/mathematics/TestMathematicsFunctions.h index b45415ee..793a79fb 100644 --- a/test/tests/mathematics/TestMathematicsFunctions.h +++ b/test/tests/mathematics/TestMathematicsFunctions.h @@ -27,6 +27,8 @@ #define TEST_MATHEMATICS_FUNCTIONS_H // Libraries +#include "containers/List.h" +#include "memory/DefaultAllocator.h" /// Reactphysics3D namespace namespace reactphysics3d { @@ -41,7 +43,7 @@ class TestMathematicsFunctions : public Test { // ---------- Atributes ---------- // - + DefaultAllocator mAllocator; public : @@ -223,37 +225,37 @@ class TestMathematicsFunctions : public Test { test(clipSegmentVertices.size() == 0); // Test clipPolygonWithPlanes() - std::vector polygonVertices; - polygonVertices.push_back(Vector3(-4, 2, 0)); - polygonVertices.push_back(Vector3(7, 2, 0)); - polygonVertices.push_back(Vector3(7, 4, 0)); - polygonVertices.push_back(Vector3(-4, 4, 0)); + List polygonVertices(mAllocator); + polygonVertices.add(Vector3(-4, 2, 0)); + polygonVertices.add(Vector3(7, 2, 0)); + polygonVertices.add(Vector3(7, 4, 0)); + polygonVertices.add(Vector3(-4, 4, 0)); - planesNormals.clear(); - planesPoints.clear(); - planesNormals.push_back(Vector3(1, 0, 0)); - planesPoints.push_back(Vector3(0, 0, 0)); - planesNormals.push_back(Vector3(0, 1, 0)); - planesPoints.push_back(Vector3(0, 0, 0)); - planesNormals.push_back(Vector3(-1, 0, 0)); - planesPoints.push_back(Vector3(10, 0, 0)); - planesNormals.push_back(Vector3(0, -1, 0)); - planesPoints.push_back(Vector3(10, 5, 0)); + List polygonPlanesNormals(mAllocator); + List polygonPlanesPoints(mAllocator); + polygonPlanesNormals.add(Vector3(1, 0, 0)); + polygonPlanesPoints.add(Vector3(0, 0, 0)); + polygonPlanesNormals.add(Vector3(0, 1, 0)); + polygonPlanesPoints.add(Vector3(0, 0, 0)); + polygonPlanesNormals.add(Vector3(-1, 0, 0)); + polygonPlanesPoints.add(Vector3(10, 0, 0)); + polygonPlanesNormals.add(Vector3(0, -1, 0)); + polygonPlanesPoints.add(Vector3(10, 5, 0)); - clipSegmentVertices = clipPolygonWithPlanes(polygonVertices, planesPoints, planesNormals); - test(clipSegmentVertices.size() == 4); - test(approxEqual(clipSegmentVertices[0].x, 0, 0.000001)); - test(approxEqual(clipSegmentVertices[0].y, 2, 0.000001)); - test(approxEqual(clipSegmentVertices[0].z, 0, 0.000001)); - test(approxEqual(clipSegmentVertices[1].x, 7, 0.000001)); - test(approxEqual(clipSegmentVertices[1].y, 2, 0.000001)); - test(approxEqual(clipSegmentVertices[1].z, 0, 0.000001)); - test(approxEqual(clipSegmentVertices[2].x, 7, 0.000001)); - test(approxEqual(clipSegmentVertices[2].y, 4, 0.000001)); - test(approxEqual(clipSegmentVertices[2].z, 0, 0.000001)); - test(approxEqual(clipSegmentVertices[3].x, 0, 0.000001)); - test(approxEqual(clipSegmentVertices[3].y, 4, 0.000001)); - test(approxEqual(clipSegmentVertices[3].z, 0, 0.000001)); + List clipPolygonVertices = clipPolygonWithPlanes(polygonVertices, polygonPlanesPoints, polygonPlanesNormals, mAllocator); + test(clipPolygonVertices.size() == 4); + test(approxEqual(clipPolygonVertices[0].x, 0, 0.000001)); + test(approxEqual(clipPolygonVertices[0].y, 2, 0.000001)); + test(approxEqual(clipPolygonVertices[0].z, 0, 0.000001)); + test(approxEqual(clipPolygonVertices[1].x, 7, 0.000001)); + test(approxEqual(clipPolygonVertices[1].y, 2, 0.000001)); + test(approxEqual(clipPolygonVertices[1].z, 0, 0.000001)); + test(approxEqual(clipPolygonVertices[2].x, 7, 0.000001)); + test(approxEqual(clipPolygonVertices[2].y, 4, 0.000001)); + test(approxEqual(clipPolygonVertices[2].z, 0, 0.000001)); + test(approxEqual(clipPolygonVertices[3].x, 0, 0.000001)); + test(approxEqual(clipPolygonVertices[3].y, 4, 0.000001)); + test(approxEqual(clipPolygonVertices[3].z, 0, 0.000001)); } From 9d761291d620efdf23749d0ed2d82daee054c45a Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 6 Dec 2017 21:55:50 +0100 Subject: [PATCH 144/248] Small optimizations --- CMakeLists.txt | 2 ++ .../narrowphase/SAT/SATAlgorithm.cpp | 24 +-------------- src/collision/narrowphase/SAT/SATAlgorithm.h | 3 -- .../shapes/ConvexPolyhedronShape.cpp | 22 ++++++++++++++ src/collision/shapes/ConvexPolyhedronShape.h | 5 ++++ src/constraint/ContactPoint.h | 8 ++--- src/mathematics/mathematics_functions.cpp | 29 ++++++++++--------- 7 files changed, 50 insertions(+), 43 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index c4cfde6e..e7e2df87 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -192,8 +192,10 @@ SET (REACTPHYSICS3D_SOURCES "src/memory/PoolAllocator.cpp" "src/memory/SingleFrameAllocator.h" "src/memory/SingleFrameAllocator.cpp" + "src/memory/DefaultAllocator.h" "src/containers/Stack.h" "src/containers/LinkedList.h" + "src/containers/List.h" ) # Create the library diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 7ef99e1f..5e40f45f 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -824,7 +824,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 = findMostAntiParallelFaceOnPolyhedron(incidentPolyhedron, axisIncidentSpace); + uint incidentFaceIndex = incidentPolyhedron->findMostAntiParallelFace(axisIncidentSpace); // Get the incident face const HalfEdgeStructure::Face& incidentFace = incidentPolyhedron->getFace(incidentFaceIndex); @@ -914,28 +914,6 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene return contactPointsFound; } -// Find and return the index of the polyhedron face with the most anti-parallel face normal given a direction vector -// This is used to find the incident face on a polyhedron of a given reference face of another polyhedron -uint SATAlgorithm::findMostAntiParallelFaceOnPolyhedron(const ConvexPolyhedronShape* polyhedron, const Vector3& direction) const { - - PROFILE("SATAlgorithm::findMostAntiParallelFaceOnPolyhedron", mProfiler); - - decimal minDotProduct = DECIMAL_LARGEST; - uint mostAntiParallelFace = 0; - - // For each face of the polyhedron - for (uint i=0; i < polyhedron->getNbFaces(); i++) { - - // Get the face normal - decimal dotProduct = polyhedron->getFaceNormal(i).dot(direction); - if (dotProduct < minDotProduct) { - minDotProduct = dotProduct; - mostAntiParallelFace = i; - } - } - - return mostAntiParallelFace; -} // Compute and return the distance between the two edges in the direction of the candidate separating axis decimal SATAlgorithm::computeDistanceBetweenEdges(const Vector3& edge1A, const Vector3& edge2A, const Vector3& polyhedron2Centroid, diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.h b/src/collision/narrowphase/SAT/SATAlgorithm.h index af49ca09..52884f8e 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.h +++ b/src/collision/narrowphase/SAT/SATAlgorithm.h @@ -72,9 +72,6 @@ class SATAlgorithm { const Vector3& c, const Vector3& d, const Vector3& bCrossA, const Vector3& dCrossC) const; - // Find and return the index of the polyhedron face with the most anti-parallel face normal given a direction vector - uint findMostAntiParallelFaceOnPolyhedron(const ConvexPolyhedronShape* polyhedron, const Vector3& direction) const; - /// Compute and return the distance between the two edges in the direction of the candidate separating axis decimal computeDistanceBetweenEdges(const Vector3& edge1A, const Vector3& edge2A, const Vector3& polyhedron2Centroid, const Vector3& edge1Direction, const Vector3& edge2Direction, diff --git a/src/collision/shapes/ConvexPolyhedronShape.cpp b/src/collision/shapes/ConvexPolyhedronShape.cpp index ab93584d..24f80de6 100644 --- a/src/collision/shapes/ConvexPolyhedronShape.cpp +++ b/src/collision/shapes/ConvexPolyhedronShape.cpp @@ -35,3 +35,25 @@ ConvexPolyhedronShape::ConvexPolyhedronShape(CollisionShapeName name) : ConvexShape(name, CollisionShapeType::CONVEX_POLYHEDRON) { } + +// Find and return the index of the polyhedron face with the most anti-parallel face +// normal given a direction vector. This is used to find the incident face on +// a polyhedron of a given reference face of another polyhedron +uint ConvexPolyhedronShape::findMostAntiParallelFace(const Vector3& direction) const { + + decimal minDotProduct = DECIMAL_LARGEST; + uint mostAntiParallelFace = 0; + + // For each face of the polyhedron + for (uint i=0; i < getNbFaces(); i++) { + + // Get the face normal + decimal dotProduct = getFaceNormal(i).dot(direction); + if (dotProduct < minDotProduct) { + minDotProduct = dotProduct; + mostAntiParallelFace = i; + } + } + + return mostAntiParallelFace; +} diff --git a/src/collision/shapes/ConvexPolyhedronShape.h b/src/collision/shapes/ConvexPolyhedronShape.h index 1d944cb8..50c6df89 100644 --- a/src/collision/shapes/ConvexPolyhedronShape.h +++ b/src/collision/shapes/ConvexPolyhedronShape.h @@ -87,6 +87,10 @@ class ConvexPolyhedronShape : public ConvexShape { /// Return the centroid of the polyhedron virtual Vector3 getCentroid() const=0; + + /// Find and return the index of the polyhedron face with the most anti-parallel face + /// normal given a direction vector + uint findMostAntiParallelFace(const Vector3& direction) const; }; // Return true if the collision shape is a polyhedron @@ -94,6 +98,7 @@ inline bool ConvexPolyhedronShape::isPolyhedron() const { return true; } + } #endif diff --git a/src/constraint/ContactPoint.h b/src/constraint/ContactPoint.h index 40a3d13c..d78659f8 100644 --- a/src/constraint/ContactPoint.h +++ b/src/constraint/ContactPoint.h @@ -122,10 +122,10 @@ class ContactPoint { Vector3 getNormal() const; /// Return the contact point on the first proxy shape in the local-space of the proxy shape - Vector3 getLocalPointOnShape1() const; + const Vector3& getLocalPointOnShape1() const; /// Return the contact point on the second proxy shape in the local-space of the proxy shape - Vector3 getLocalPointOnShape2() const; + const Vector3& getLocalPointOnShape2() const; /// Return the cached penetration impulse decimal getPenetrationImpulse() const; @@ -157,12 +157,12 @@ inline Vector3 ContactPoint::getNormal() const { } // Return the contact point on the first proxy shape in the local-space of the proxy shape -inline Vector3 ContactPoint::getLocalPointOnShape1() const { +inline const Vector3& ContactPoint::getLocalPointOnShape1() const { return mLocalPointOnShape1; } // Return the contact point on the second proxy shape in the local-space of the proxy shape -inline Vector3 ContactPoint::getLocalPointOnShape2() const { +inline const Vector3& ContactPoint::getLocalPointOnShape2() const { return mLocalPointOnShape2; } diff --git a/src/mathematics/mathematics_functions.cpp b/src/mathematics/mathematics_functions.cpp index e7c9f371..b82c9fbd 100755 --- a/src/mathematics/mathematics_functions.cpp +++ b/src/mathematics/mathematics_functions.cpp @@ -300,24 +300,26 @@ List reactphysics3d::clipPolygonWithPlanes(const List& polygon assert(planesPoints.size() == planesNormals.size()); uint nbMaxElements = polygonVertices.size() + planesPoints.size(); - List inputVertices(allocator, nbMaxElements); - List outputVertices(allocator, nbMaxElements); + List list1(allocator, nbMaxElements); + List list2(allocator, nbMaxElements); + List dotProducts(allocator, nbMaxElements * 2); - inputVertices.addRange(polygonVertices); + const List* inputVertices = &polygonVertices; + List* outputVertices = &list2; // For each clipping plane for (uint p=0; pclear(); - uint nbInputVertices = inputVertices.size(); + uint nbInputVertices = inputVertices->size(); uint vStart = nbInputVertices - 1; // For each edge of the polygon for (uint vEnd = 0; vEnd reactphysics3d::clipPolygonWithPlanes(const List& polygon decimal t = computePlaneSegmentIntersection(v1, v2, planesNormals[p].dot(planesPoints[p]), planesNormals[p]); if (t >= decimal(0) && t <= decimal(1.0)) { - outputVertices.add(v1 + t * (v2 - v1)); + outputVertices->add(v1 + t * (v2 - v1)); } else { - outputVertices.add(v2); + outputVertices->add(v2); } } // Add the second vertex - outputVertices.add(v2); + outputVertices->add(v2); } else { // If the second vertex is behind the clipping plane @@ -351,10 +353,10 @@ List reactphysics3d::clipPolygonWithPlanes(const List& polygon decimal t = computePlaneSegmentIntersection(v1, v2, -planesNormals[p].dot(planesPoints[p]), -planesNormals[p]); if (t >= decimal(0.0) && t <= decimal(1.0)) { - outputVertices.add(v1 + t * (v2 - v1)); + outputVertices->add(v1 + t * (v2 - v1)); } else { - outputVertices.add(v1); + outputVertices->add(v1); } } } @@ -363,9 +365,10 @@ List reactphysics3d::clipPolygonWithPlanes(const List& polygon } inputVertices = outputVertices; + outputVertices = p % 2 == 0 ? &list1 : &list2; } - return outputVertices; + return *outputVertices; } // Project a point onto a plane that is given by a point and its unit length normal From cf42e9f04c35cdacb3b7ae54881812d8bd187d7d Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 12 Dec 2017 07:29:29 +0100 Subject: [PATCH 145/248] Optimizations in contact solver --- src/engine/ContactSolver.cpp | 300 +++++++++++++++++++++++++++-------- 1 file changed, 233 insertions(+), 67 deletions(-) diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index 167d37b8..7bd74e8a 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -163,22 +163,48 @@ void ContactSolver::initializeForIsland(Island* island) { new (mContactPoints + mNbContactPoints) ContactPointSolver(); mContactPoints[mNbContactPoints].externalContact = externalContact; mContactPoints[mNbContactPoints].normal = externalContact->getNormal(); - mContactPoints[mNbContactPoints].r1 = p1 - x1; - mContactPoints[mNbContactPoints].r2 = p2 - x2; + mContactPoints[mNbContactPoints].r1.x = p1.x - x1.x; + mContactPoints[mNbContactPoints].r1.y = p1.y - x1.y; + mContactPoints[mNbContactPoints].r1.z = p1.z - x1.z; + mContactPoints[mNbContactPoints].r2.x = p2.x - x2.x; + mContactPoints[mNbContactPoints].r2.y = p2.y - x2.y; + mContactPoints[mNbContactPoints].r2.z = p2.z - x2.z; mContactPoints[mNbContactPoints].penetrationDepth = externalContact->getPenetrationDepth(); mContactPoints[mNbContactPoints].isRestingContact = externalContact->getIsRestingContact(); externalContact->setIsRestingContact(true); mContactPoints[mNbContactPoints].penetrationImpulse = externalContact->getPenetrationImpulse(); mContactPoints[mNbContactPoints].penetrationSplitImpulse = 0.0; - mContactConstraints[mNbContactManifolds].frictionPointBody1 += p1; - mContactConstraints[mNbContactManifolds].frictionPointBody2 += p2; + mContactConstraints[mNbContactManifolds].frictionPointBody1.x += p1.x; + mContactConstraints[mNbContactManifolds].frictionPointBody1.y += p1.y; + mContactConstraints[mNbContactManifolds].frictionPointBody1.z += p1.z; + mContactConstraints[mNbContactManifolds].frictionPointBody2.x += p2.x; + mContactConstraints[mNbContactManifolds].frictionPointBody2.y += p2.y; + mContactConstraints[mNbContactManifolds].frictionPointBody2.z += p2.z; // Compute the velocity difference - Vector3 deltaV = v2 + w2.cross(mContactPoints[mNbContactPoints].r2) - v1 - w1.cross(mContactPoints[mNbContactPoints].r1); + //deltaV = v2 + w2.cross(mContactPoints[mNbContactPoints].r2) - v1 - w1.cross(mContactPoints[mNbContactPoints].r1); + Vector3 deltaV(v2.x + w2.y * mContactPoints[mNbContactPoints].r2.z - w2.z * mContactPoints[mNbContactPoints].r2.y + - v1.x - w1.y * mContactPoints[mNbContactPoints].r1.z - w1.z * mContactPoints[mNbContactPoints].r1.y, + v2.y + w2.z * mContactPoints[mNbContactPoints].r2.x - w2.x * mContactPoints[mNbContactPoints].r2.z + - v1.y - w1.z * mContactPoints[mNbContactPoints].r1.x - w1.x * mContactPoints[mNbContactPoints].r1.z, + v2.z + w2.x * mContactPoints[mNbContactPoints].r2.y - w2.y * mContactPoints[mNbContactPoints].r2.x + - v1.z - w1.x * mContactPoints[mNbContactPoints].r1.y - w1.y * mContactPoints[mNbContactPoints].r1.x); - Vector3 r1CrossN = mContactPoints[mNbContactPoints].r1.cross(mContactPoints[mNbContactPoints].normal); - Vector3 r2CrossN = mContactPoints[mNbContactPoints].r2.cross(mContactPoints[mNbContactPoints].normal); + // r1CrossN = mContactPoints[mNbContactPoints].r1.cross(mContactPoints[mNbContactPoints].normal); + Vector3 r1CrossN(mContactPoints[mNbContactPoints].r1.y * mContactPoints[mNbContactPoints].normal.z - + mContactPoints[mNbContactPoints].r1.z * mContactPoints[mNbContactPoints].normal.y, + mContactPoints[mNbContactPoints].r1.z * mContactPoints[mNbContactPoints].normal.x - + mContactPoints[mNbContactPoints].r1.x * mContactPoints[mNbContactPoints].normal.z, + mContactPoints[mNbContactPoints].r1.x * mContactPoints[mNbContactPoints].normal.y - + mContactPoints[mNbContactPoints].r1.y * mContactPoints[mNbContactPoints].normal.x); + // r2CrossN = mContactPoints[mNbContactPoints].r2.cross(mContactPoints[mNbContactPoints].normal); + Vector3 r2CrossN(mContactPoints[mNbContactPoints].r2.y * mContactPoints[mNbContactPoints].normal.z - + mContactPoints[mNbContactPoints].r2.z * mContactPoints[mNbContactPoints].normal.y, + mContactPoints[mNbContactPoints].r2.z * mContactPoints[mNbContactPoints].normal.x - + mContactPoints[mNbContactPoints].r2.x * mContactPoints[mNbContactPoints].normal.z, + mContactPoints[mNbContactPoints].r2.x * mContactPoints[mNbContactPoints].normal.y - + mContactPoints[mNbContactPoints].r2.y * mContactPoints[mNbContactPoints].normal.x); mContactPoints[mNbContactPoints].i1TimesR1CrossN = mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody1 * r1CrossN; mContactPoints[mNbContactPoints].i2TimesR2CrossN = mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody2 * r2CrossN; @@ -194,13 +220,18 @@ void ContactSolver::initializeForIsland(Island* island) { // at the beginning of the contact. Note that if it is a resting contact (normal // velocity bellow a given threshold), we do not add a restitution velocity bias mContactPoints[mNbContactPoints].restitutionBias = 0.0; - decimal deltaVDotN = deltaV.dot(mContactPoints[mNbContactPoints].normal); + // deltaVDotN = deltaV.dot(mContactPoints[mNbContactPoints].normal); + decimal deltaVDotN = deltaV.x * mContactPoints[mNbContactPoints].normal.x + + deltaV.y * mContactPoints[mNbContactPoints].normal.y + + deltaV.z * mContactPoints[mNbContactPoints].normal.z; const decimal restitutionFactor = computeMixedRestitutionFactor(body1, body2); if (deltaVDotN < -RESTITUTION_VELOCITY_THRESHOLD) { mContactPoints[mNbContactPoints].restitutionBias = restitutionFactor * deltaVDotN; } - mContactConstraints[mNbContactManifolds].normal += mContactPoints[mNbContactPoints].normal; + mContactConstraints[mNbContactManifolds].normal.x += mContactPoints[mNbContactPoints].normal.x; + mContactConstraints[mNbContactManifolds].normal.y += mContactPoints[mNbContactPoints].normal.y; + mContactConstraints[mNbContactManifolds].normal.z += mContactPoints[mNbContactPoints].normal.z; mNbContactPoints++; @@ -209,8 +240,12 @@ void ContactSolver::initializeForIsland(Island* island) { mContactConstraints[mNbContactManifolds].frictionPointBody1 /=static_cast(mContactConstraints[mNbContactManifolds].nbContacts); mContactConstraints[mNbContactManifolds].frictionPointBody2 /=static_cast(mContactConstraints[mNbContactManifolds].nbContacts); - mContactConstraints[mNbContactManifolds].r1Friction = mContactConstraints[mNbContactManifolds].frictionPointBody1 - x1; - mContactConstraints[mNbContactManifolds].r2Friction = mContactConstraints[mNbContactManifolds].frictionPointBody2 - x2; + mContactConstraints[mNbContactManifolds].r1Friction.x = mContactConstraints[mNbContactManifolds].frictionPointBody1.x - x1.x; + mContactConstraints[mNbContactManifolds].r1Friction.y = mContactConstraints[mNbContactManifolds].frictionPointBody1.y - x1.y; + mContactConstraints[mNbContactManifolds].r1Friction.z = mContactConstraints[mNbContactManifolds].frictionPointBody1.z - x1.z; + mContactConstraints[mNbContactManifolds].r2Friction.x = mContactConstraints[mNbContactManifolds].frictionPointBody2.x - x2.x; + mContactConstraints[mNbContactManifolds].r2Friction.y = mContactConstraints[mNbContactManifolds].frictionPointBody2.y - x2.y; + mContactConstraints[mNbContactManifolds].r2Friction.z = mContactConstraints[mNbContactManifolds].frictionPointBody2.z - x2.z; mContactConstraints[mNbContactManifolds].oldFrictionVector1 = externalManifold->getFrictionVector1(); mContactConstraints[mNbContactManifolds].oldFrictionVector2 = externalManifold->getFrictionVector2(); @@ -230,8 +265,20 @@ void ContactSolver::initializeForIsland(Island* island) { mContactConstraints[mNbContactManifolds].normal.normalize(); - Vector3 deltaVFrictionPoint = v2 + w2.cross(mContactConstraints[mNbContactManifolds].r2Friction) - - v1 - w1.cross(mContactConstraints[mNbContactManifolds].r1Friction); + // deltaVFrictionPoint = v2 + w2.cross(mContactConstraints[mNbContactManifolds].r2Friction) - + // v1 - w1.cross(mContactConstraints[mNbContactManifolds].r1Friction); + Vector3 deltaVFrictionPoint(v2.x + w2.y * mContactConstraints[mNbContactManifolds].r2Friction.z - + w2.z * mContactConstraints[mNbContactManifolds].r2Friction.y - + v1.x - w1.y * mContactConstraints[mNbContactManifolds].r1Friction.z - + w1.z * mContactConstraints[mNbContactManifolds].r1Friction.y, + v2.y + w2.z * mContactConstraints[mNbContactManifolds].r2Friction.x - + w2.x * mContactConstraints[mNbContactManifolds].r2Friction.z - + v1.y - w1.z * mContactConstraints[mNbContactManifolds].r1Friction.x - + w1.x * mContactConstraints[mNbContactManifolds].r1Friction.z, + v2.z + w2.x * mContactConstraints[mNbContactManifolds].r2Friction.y - + w2.y * mContactConstraints[mNbContactManifolds].r2Friction.x - + v1.z - w1.x * mContactConstraints[mNbContactManifolds].r1Friction.y - + w1.y * mContactConstraints[mNbContactManifolds].r1Friction.x); // Compute the friction vectors computeFrictionVectors(deltaVFrictionPoint, mContactConstraints[mNbContactManifolds]); @@ -289,13 +336,25 @@ void ContactSolver::warmStart() { // --------- Penetration --------- // // Update the velocities of the body 1 by applying the impulse P - Vector3 impulsePenetration = mContactPoints[contactPointIndex].normal * mContactPoints[contactPointIndex].penetrationImpulse; - mLinearVelocities[mContactConstraints[c].indexBody1] -= mContactConstraints[c].massInverseBody1 * impulsePenetration; - mAngularVelocities[mContactConstraints[c].indexBody1] -= mContactPoints[contactPointIndex].i1TimesR1CrossN * mContactPoints[contactPointIndex].penetrationImpulse; + Vector3 impulsePenetration(mContactPoints[contactPointIndex].normal.x * mContactPoints[contactPointIndex].penetrationImpulse, + mContactPoints[contactPointIndex].normal.y * mContactPoints[contactPointIndex].penetrationImpulse, + mContactPoints[contactPointIndex].normal.z * mContactPoints[contactPointIndex].penetrationImpulse); + mLinearVelocities[mContactConstraints[c].indexBody1].x -= mContactConstraints[c].massInverseBody1 * impulsePenetration.x; + mLinearVelocities[mContactConstraints[c].indexBody1].y -= mContactConstraints[c].massInverseBody1 * impulsePenetration.y; + mLinearVelocities[mContactConstraints[c].indexBody1].z -= mContactConstraints[c].massInverseBody1 * impulsePenetration.z; + + mAngularVelocities[mContactConstraints[c].indexBody1].x -= mContactPoints[contactPointIndex].i1TimesR1CrossN.x * mContactPoints[contactPointIndex].penetrationImpulse; + mAngularVelocities[mContactConstraints[c].indexBody1].y -= mContactPoints[contactPointIndex].i1TimesR1CrossN.y * mContactPoints[contactPointIndex].penetrationImpulse; + mAngularVelocities[mContactConstraints[c].indexBody1].z -= mContactPoints[contactPointIndex].i1TimesR1CrossN.z * mContactPoints[contactPointIndex].penetrationImpulse; // Update the velocities of the body 2 by applying the impulse P - mLinearVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].massInverseBody2 * impulsePenetration; - mAngularVelocities[mContactConstraints[c].indexBody2] += mContactPoints[contactPointIndex].i2TimesR2CrossN * mContactPoints[contactPointIndex].penetrationImpulse; + mLinearVelocities[mContactConstraints[c].indexBody2].x += mContactConstraints[c].massInverseBody2 * impulsePenetration.x; + mLinearVelocities[mContactConstraints[c].indexBody2].y += mContactConstraints[c].massInverseBody2 * impulsePenetration.y; + mLinearVelocities[mContactConstraints[c].indexBody2].z += mContactConstraints[c].massInverseBody2 * impulsePenetration.z; + + mAngularVelocities[mContactConstraints[c].indexBody2].x += mContactPoints[contactPointIndex].i2TimesR2CrossN.x * mContactPoints[contactPointIndex].penetrationImpulse; + mAngularVelocities[mContactConstraints[c].indexBody2].y += mContactPoints[contactPointIndex].i2TimesR2CrossN.y * mContactPoints[contactPointIndex].penetrationImpulse; + mAngularVelocities[mContactConstraints[c].indexBody2].z += mContactPoints[contactPointIndex].i2TimesR2CrossN.z * mContactPoints[contactPointIndex].penetrationImpulse; } else { // If it is a new contact point @@ -312,20 +371,27 @@ void ContactSolver::warmStart() { // Project the old friction impulses (with old friction vectors) into the new friction // vectors to get the new friction impulses - Vector3 oldFrictionImpulse = mContactConstraints[c].friction1Impulse * mContactConstraints[c].oldFrictionVector1 + - mContactConstraints[c].friction2Impulse * mContactConstraints[c].oldFrictionVector2; + Vector3 oldFrictionImpulse(mContactConstraints[c].friction1Impulse * mContactConstraints[c].oldFrictionVector1.x + + mContactConstraints[c].friction2Impulse * mContactConstraints[c].oldFrictionVector2.x, + mContactConstraints[c].friction1Impulse * mContactConstraints[c].oldFrictionVector1.y + + mContactConstraints[c].friction2Impulse * mContactConstraints[c].oldFrictionVector2.y, + mContactConstraints[c].friction1Impulse * mContactConstraints[c].oldFrictionVector1.z + + mContactConstraints[c].friction2Impulse * mContactConstraints[c].oldFrictionVector2.z); mContactConstraints[c].friction1Impulse = oldFrictionImpulse.dot(mContactConstraints[c].frictionVector1); mContactConstraints[c].friction2Impulse = oldFrictionImpulse.dot(mContactConstraints[c].frictionVector2); // ------ First friction constraint at the center of the contact manifold ------ // // Compute the impulse P = J^T * lambda - Vector3 angularImpulseBody1 = -mContactConstraints[c].r1CrossT1 * - mContactConstraints[c].friction1Impulse; - Vector3 linearImpulseBody2 = mContactConstraints[c].frictionVector1 * - mContactConstraints[c].friction1Impulse; - Vector3 angularImpulseBody2 = mContactConstraints[c].r2CrossT1 * - mContactConstraints[c].friction1Impulse; + Vector3 angularImpulseBody1(-mContactConstraints[c].r1CrossT1.x * mContactConstraints[c].friction1Impulse, + -mContactConstraints[c].r1CrossT1.y * mContactConstraints[c].friction1Impulse, + -mContactConstraints[c].r1CrossT1.z * mContactConstraints[c].friction1Impulse); + Vector3 linearImpulseBody2(mContactConstraints[c].frictionVector1.x * mContactConstraints[c].friction1Impulse, + mContactConstraints[c].frictionVector1.y * mContactConstraints[c].friction1Impulse, + mContactConstraints[c].frictionVector1.z * mContactConstraints[c].friction1Impulse); + Vector3 angularImpulseBody2(mContactConstraints[c].r2CrossT1.x * mContactConstraints[c].friction1Impulse, + mContactConstraints[c].r2CrossT1.y * mContactConstraints[c].friction1Impulse, + mContactConstraints[c].r2CrossT1.z * mContactConstraints[c].friction1Impulse); // Update the velocities of the body 1 by applying the impulse P mLinearVelocities[mContactConstraints[c].indexBody1] -= mContactConstraints[c].massInverseBody1 * linearImpulseBody2; @@ -338,23 +404,40 @@ void ContactSolver::warmStart() { // ------ Second friction constraint at the center of the contact manifold ----- // // Compute the impulse P = J^T * lambda - angularImpulseBody1 = -mContactConstraints[c].r1CrossT2 * mContactConstraints[c].friction2Impulse; - linearImpulseBody2 = mContactConstraints[c].frictionVector2 * mContactConstraints[c].friction2Impulse; - angularImpulseBody2 = mContactConstraints[c].r2CrossT2 * mContactConstraints[c].friction2Impulse; + angularImpulseBody1.x = -mContactConstraints[c].r1CrossT2.x * mContactConstraints[c].friction2Impulse; + angularImpulseBody1.y = -mContactConstraints[c].r1CrossT2.y * mContactConstraints[c].friction2Impulse; + angularImpulseBody1.z = -mContactConstraints[c].r1CrossT2.z * mContactConstraints[c].friction2Impulse; + linearImpulseBody2.x = mContactConstraints[c].frictionVector2.x * mContactConstraints[c].friction2Impulse; + linearImpulseBody2.y = mContactConstraints[c].frictionVector2.y * mContactConstraints[c].friction2Impulse; + linearImpulseBody2.z = mContactConstraints[c].frictionVector2.z * mContactConstraints[c].friction2Impulse; + angularImpulseBody2.x = mContactConstraints[c].r2CrossT2.x * mContactConstraints[c].friction2Impulse; + angularImpulseBody2.y = mContactConstraints[c].r2CrossT2.y * mContactConstraints[c].friction2Impulse; + angularImpulseBody2.z = mContactConstraints[c].r2CrossT2.z * mContactConstraints[c].friction2Impulse; // Update the velocities of the body 1 by applying the impulse P - mLinearVelocities[mContactConstraints[c].indexBody1] -= mContactConstraints[c].massInverseBody1 * linearImpulseBody2; + mLinearVelocities[mContactConstraints[c].indexBody1].x -= mContactConstraints[c].massInverseBody1 * linearImpulseBody2.x; + mLinearVelocities[mContactConstraints[c].indexBody1].y -= mContactConstraints[c].massInverseBody1 * linearImpulseBody2.y; + mLinearVelocities[mContactConstraints[c].indexBody1].z -= mContactConstraints[c].massInverseBody1 * linearImpulseBody2.z; + mAngularVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].inverseInertiaTensorBody1 * angularImpulseBody1; // Update the velocities of the body 2 by applying the impulse P - mLinearVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].massInverseBody2 * linearImpulseBody2; + mLinearVelocities[mContactConstraints[c].indexBody2].x += mContactConstraints[c].massInverseBody2 * linearImpulseBody2.x; + mLinearVelocities[mContactConstraints[c].indexBody2].y += mContactConstraints[c].massInverseBody2 * linearImpulseBody2.y; + mLinearVelocities[mContactConstraints[c].indexBody2].z += mContactConstraints[c].massInverseBody2 * linearImpulseBody2.z; + mAngularVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].inverseInertiaTensorBody2 * angularImpulseBody2; // ------ Twist friction constraint at the center of the contact manifold ------ // // Compute the impulse P = J^T * lambda - angularImpulseBody1 = -mContactConstraints[c].normal * mContactConstraints[c].frictionTwistImpulse; - angularImpulseBody2 = mContactConstraints[c].normal * mContactConstraints[c].frictionTwistImpulse; + angularImpulseBody1.x = -mContactConstraints[c].normal.x * mContactConstraints[c].frictionTwistImpulse; + angularImpulseBody1.y = -mContactConstraints[c].normal.y * mContactConstraints[c].frictionTwistImpulse; + angularImpulseBody1.z = -mContactConstraints[c].normal.z * mContactConstraints[c].frictionTwistImpulse; + + angularImpulseBody2.x = mContactConstraints[c].normal.x * mContactConstraints[c].frictionTwistImpulse; + angularImpulseBody2.y = mContactConstraints[c].normal.y * mContactConstraints[c].frictionTwistImpulse; + angularImpulseBody2.z = mContactConstraints[c].normal.z * mContactConstraints[c].frictionTwistImpulse; // Update the velocities of the body 1 by applying the impulse P mAngularVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].inverseInertiaTensorBody1 * angularImpulseBody1; @@ -409,8 +492,15 @@ void ContactSolver::solve() { // --------- Penetration --------- // // Compute J*v - Vector3 deltaV = v2 + w2.cross(mContactPoints[contactPointIndex].r2) - v1 - w1.cross(mContactPoints[contactPointIndex].r1); - decimal deltaVDotN = deltaV.dot(mContactPoints[contactPointIndex].normal); + //Vector3 deltaV = v2 + w2.cross(mContactPoints[contactPointIndex].r2) - v1 - w1.cross(mContactPoints[contactPointIndex].r1); + Vector3 deltaV(v2.x + w2.y * mContactPoints[contactPointIndex].r2.z - w2.z * mContactPoints[contactPointIndex].r2.y - v1.x - + w1.y * mContactPoints[contactPointIndex].r1.z + w1.z * mContactPoints[contactPointIndex].r1.y, + v2.y + w2.z * mContactPoints[contactPointIndex].r2.x - w2.x * mContactPoints[contactPointIndex].r2.z - v1.y - + w1.z * mContactPoints[contactPointIndex].r1.x + w1.x * mContactPoints[contactPointIndex].r1.z, + v2.z + w2.x * mContactPoints[contactPointIndex].r2.y - w2.y * mContactPoints[contactPointIndex].r2.x - v1.z - + w1.x * mContactPoints[contactPointIndex].r1.y + w1.y * mContactPoints[contactPointIndex].r1.x); + decimal deltaVDotN = deltaV.x * mContactPoints[contactPointIndex].normal.x + deltaV.y * mContactPoints[contactPointIndex].normal.y + + deltaV.z * mContactPoints[contactPointIndex].normal.z; decimal Jv = deltaVDotN; // Compute the bias "b" of the constraint @@ -433,15 +523,27 @@ void ContactSolver::solve() { deltaLambda, decimal(0.0)); deltaLambda = mContactPoints[contactPointIndex].penetrationImpulse - lambdaTemp; - Vector3 linearImpulse = mContactPoints[contactPointIndex].normal * deltaLambda; + Vector3 linearImpulse(mContactPoints[contactPointIndex].normal.x * deltaLambda, + mContactPoints[contactPointIndex].normal.y * deltaLambda, + mContactPoints[contactPointIndex].normal.z * deltaLambda); // Update the velocities of the body 1 by applying the impulse P - mLinearVelocities[mContactConstraints[c].indexBody1] -= mContactConstraints[c].massInverseBody1 * linearImpulse; - mAngularVelocities[mContactConstraints[c].indexBody1] -= mContactPoints[contactPointIndex].i1TimesR1CrossN * deltaLambda; + mLinearVelocities[mContactConstraints[c].indexBody1].x -= mContactConstraints[c].massInverseBody1 * linearImpulse.x; + mLinearVelocities[mContactConstraints[c].indexBody1].y -= mContactConstraints[c].massInverseBody1 * linearImpulse.y; + mLinearVelocities[mContactConstraints[c].indexBody1].z -= mContactConstraints[c].massInverseBody1 * linearImpulse.z; + + mAngularVelocities[mContactConstraints[c].indexBody1].x -= mContactPoints[contactPointIndex].i1TimesR1CrossN.x * deltaLambda; + mAngularVelocities[mContactConstraints[c].indexBody1].y -= mContactPoints[contactPointIndex].i1TimesR1CrossN.y * deltaLambda; + mAngularVelocities[mContactConstraints[c].indexBody1].z -= mContactPoints[contactPointIndex].i1TimesR1CrossN.z * deltaLambda; // Update the velocities of the body 2 by applying the impulse P - mLinearVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].massInverseBody2 * linearImpulse; - mAngularVelocities[mContactConstraints[c].indexBody2] += mContactPoints[contactPointIndex].i2TimesR2CrossN * deltaLambda; + mLinearVelocities[mContactConstraints[c].indexBody2].x += mContactConstraints[c].massInverseBody2 * linearImpulse.x; + mLinearVelocities[mContactConstraints[c].indexBody2].y += mContactConstraints[c].massInverseBody2 * linearImpulse.y; + mLinearVelocities[mContactConstraints[c].indexBody2].z += mContactConstraints[c].massInverseBody2 * linearImpulse.z; + + mAngularVelocities[mContactConstraints[c].indexBody2].x += mContactPoints[contactPointIndex].i2TimesR2CrossN.x * deltaLambda; + mAngularVelocities[mContactConstraints[c].indexBody2].y += mContactPoints[contactPointIndex].i2TimesR2CrossN.y * deltaLambda; + mAngularVelocities[mContactConstraints[c].indexBody2].z += mContactPoints[contactPointIndex].i2TimesR2CrossN.z * deltaLambda; sumPenetrationImpulse += mContactPoints[contactPointIndex].penetrationImpulse; @@ -453,9 +555,17 @@ void ContactSolver::solve() { const Vector3& w1Split = mSplitAngularVelocities[mContactConstraints[c].indexBody1]; const Vector3& v2Split = mSplitLinearVelocities[mContactConstraints[c].indexBody2]; const Vector3& w2Split = mSplitAngularVelocities[mContactConstraints[c].indexBody2]; - Vector3 deltaVSplit = v2Split + w2Split.cross(mContactPoints[contactPointIndex].r2) - - v1Split - w1Split.cross(mContactPoints[contactPointIndex].r1); - decimal JvSplit = deltaVSplit.dot(mContactPoints[contactPointIndex].normal); + + //Vector3 deltaVSplit = v2Split + w2Split.cross(mContactPoints[contactPointIndex].r2) - v1Split - w1Split.cross(mContactPoints[contactPointIndex].r1); + Vector3 deltaVSplit(v2Split.x + w2Split.y * mContactPoints[contactPointIndex].r2.z - w2Split.z * mContactPoints[contactPointIndex].r2.y - v1Split.x - + w1Split.y * mContactPoints[contactPointIndex].r1.z + w1Split.z * mContactPoints[contactPointIndex].r1.y, + v2Split.y + w2Split.z * mContactPoints[contactPointIndex].r2.x - w2Split.x * mContactPoints[contactPointIndex].r2.z - v1Split.y - + w1Split.z * mContactPoints[contactPointIndex].r1.x + w1Split.x * mContactPoints[contactPointIndex].r1.z, + v2Split.z + w2Split.x * mContactPoints[contactPointIndex].r2.y - w2Split.y * mContactPoints[contactPointIndex].r2.x - v1Split.z - + w1Split.x * mContactPoints[contactPointIndex].r1.y + w1Split.y * mContactPoints[contactPointIndex].r1.x); + decimal JvSplit = deltaVSplit.x * mContactPoints[contactPointIndex].normal.x + + deltaVSplit.y * mContactPoints[contactPointIndex].normal.y + + deltaVSplit.z * mContactPoints[contactPointIndex].normal.z; decimal deltaLambdaSplit = - (JvSplit + biasPenetrationDepth) * mContactPoints[contactPointIndex].inversePenetrationMass; decimal lambdaTempSplit = mContactPoints[contactPointIndex].penetrationSplitImpulse; @@ -464,15 +574,27 @@ void ContactSolver::solve() { deltaLambdaSplit, decimal(0.0)); deltaLambdaSplit = mContactPoints[contactPointIndex].penetrationSplitImpulse - lambdaTempSplit; - Vector3 linearImpulse = mContactPoints[contactPointIndex].normal * deltaLambdaSplit; + Vector3 linearImpulse(mContactPoints[contactPointIndex].normal.x * deltaLambdaSplit, + mContactPoints[contactPointIndex].normal.y * deltaLambdaSplit, + mContactPoints[contactPointIndex].normal.z * deltaLambdaSplit); // Update the velocities of the body 1 by applying the impulse P - mSplitLinearVelocities[mContactConstraints[c].indexBody1] -= mContactConstraints[c].massInverseBody1 * linearImpulse; - mSplitAngularVelocities[mContactConstraints[c].indexBody1] -= mContactPoints[contactPointIndex].i1TimesR1CrossN * deltaLambdaSplit; + mSplitLinearVelocities[mContactConstraints[c].indexBody1].x -= mContactConstraints[c].massInverseBody1 * linearImpulse.x; + mSplitLinearVelocities[mContactConstraints[c].indexBody1].y -= mContactConstraints[c].massInverseBody1 * linearImpulse.y; + mSplitLinearVelocities[mContactConstraints[c].indexBody1].z -= mContactConstraints[c].massInverseBody1 * linearImpulse.z; + + mSplitAngularVelocities[mContactConstraints[c].indexBody1].x -= mContactPoints[contactPointIndex].i1TimesR1CrossN.x * deltaLambdaSplit; + mSplitAngularVelocities[mContactConstraints[c].indexBody1].y -= mContactPoints[contactPointIndex].i1TimesR1CrossN.y * deltaLambdaSplit; + mSplitAngularVelocities[mContactConstraints[c].indexBody1].z -= mContactPoints[contactPointIndex].i1TimesR1CrossN.z * deltaLambdaSplit; // Update the velocities of the body 1 by applying the impulse P - mSplitLinearVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].massInverseBody2 * linearImpulse; - mSplitAngularVelocities[mContactConstraints[c].indexBody2] += mContactPoints[contactPointIndex].i2TimesR2CrossN * deltaLambdaSplit; + mSplitLinearVelocities[mContactConstraints[c].indexBody2].x += mContactConstraints[c].massInverseBody2 * linearImpulse.x; + mSplitLinearVelocities[mContactConstraints[c].indexBody2].y += mContactConstraints[c].massInverseBody2 * linearImpulse.y; + mSplitLinearVelocities[mContactConstraints[c].indexBody2].z += mContactConstraints[c].massInverseBody2 * linearImpulse.z; + + mSplitAngularVelocities[mContactConstraints[c].indexBody2].x += mContactPoints[contactPointIndex].i2TimesR2CrossN.x * deltaLambdaSplit; + mSplitAngularVelocities[mContactConstraints[c].indexBody2].y += mContactPoints[contactPointIndex].i2TimesR2CrossN.y * deltaLambdaSplit; + mSplitAngularVelocities[mContactConstraints[c].indexBody2].z += mContactPoints[contactPointIndex].i2TimesR2CrossN.z * deltaLambdaSplit; } contactPointIndex++; @@ -481,9 +603,16 @@ void ContactSolver::solve() { // ------ First friction constraint at the center of the contact manifol ------ // // Compute J*v - Vector3 deltaV = v2 + w2.cross(mContactConstraints[c].r2Friction) - - v1 - w1.cross(mContactConstraints[c].r1Friction); - decimal Jv = deltaV.dot(mContactConstraints[c].frictionVector1); + // deltaV = v2 + w2.cross(mContactConstraints[c].r2Friction) - v1 - w1.cross(mContactConstraints[c].r1Friction); + Vector3 deltaV(v2.x + w2.y * mContactConstraints[c].r2Friction.z - w2.z * mContactConstraints[c].r2Friction.y - v1.x - + w1.y * mContactConstraints[c].r1Friction.z + w1.z * mContactConstraints[c].r1Friction.y, + v2.y + w2.z * mContactConstraints[c].r2Friction.x - w2.x * mContactConstraints[c].r2Friction.z - v1.y - + w1.z * mContactConstraints[c].r1Friction.x + w1.x * mContactConstraints[c].r1Friction.z, + v2.z + w2.x * mContactConstraints[c].r2Friction.y - w2.y * mContactConstraints[c].r2Friction.x - v1.z - + w1.x * mContactConstraints[c].r1Friction.y + w1.y * mContactConstraints[c].r1Friction.x); + decimal Jv = deltaV.x * mContactConstraints[c].frictionVector1.x + + deltaV.y * mContactConstraints[c].frictionVector1.y + + deltaV.z * mContactConstraints[c].frictionVector1.z; // Compute the Lagrange multiplier lambda decimal deltaLambda = -Jv * mContactConstraints[c].inverseFriction1Mass; @@ -495,23 +624,42 @@ void ContactSolver::solve() { deltaLambda = mContactConstraints[c].friction1Impulse - lambdaTemp; // Compute the impulse P=J^T * lambda - Vector3 angularImpulseBody1 = -mContactConstraints[c].r1CrossT1 * deltaLambda; - Vector3 linearImpulseBody2 = mContactConstraints[c].frictionVector1 * deltaLambda; - Vector3 angularImpulseBody2 = mContactConstraints[c].r2CrossT1 * deltaLambda; + Vector3 angularImpulseBody1(-mContactConstraints[c].r1CrossT1.x * deltaLambda, + -mContactConstraints[c].r1CrossT1.y * deltaLambda, + -mContactConstraints[c].r1CrossT1.z * deltaLambda); + Vector3 linearImpulseBody2(mContactConstraints[c].frictionVector1.x * deltaLambda, + mContactConstraints[c].frictionVector1.y * deltaLambda, + mContactConstraints[c].frictionVector1.z * deltaLambda); + Vector3 angularImpulseBody2(mContactConstraints[c].r2CrossT1.x * deltaLambda, + mContactConstraints[c].r2CrossT1.y * deltaLambda, + mContactConstraints[c].r2CrossT1.z * deltaLambda); // Update the velocities of the body 1 by applying the impulse P - mLinearVelocities[mContactConstraints[c].indexBody1] -= mContactConstraints[c].massInverseBody1 * linearImpulseBody2; + mLinearVelocities[mContactConstraints[c].indexBody1].x -= mContactConstraints[c].massInverseBody1 * linearImpulseBody2.x; + mLinearVelocities[mContactConstraints[c].indexBody1].y -= mContactConstraints[c].massInverseBody1 * linearImpulseBody2.y; + mLinearVelocities[mContactConstraints[c].indexBody1].z -= mContactConstraints[c].massInverseBody1 * linearImpulseBody2.z; + mAngularVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].inverseInertiaTensorBody1 * angularImpulseBody1; // Update the velocities of the body 2 by applying the impulse P - mLinearVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].massInverseBody2 * linearImpulseBody2; + mLinearVelocities[mContactConstraints[c].indexBody2].x += mContactConstraints[c].massInverseBody2 * linearImpulseBody2.x; + mLinearVelocities[mContactConstraints[c].indexBody2].y += mContactConstraints[c].massInverseBody2 * linearImpulseBody2.y; + mLinearVelocities[mContactConstraints[c].indexBody2].z += mContactConstraints[c].massInverseBody2 * linearImpulseBody2.z; + mAngularVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].inverseInertiaTensorBody2 * angularImpulseBody2; // ------ Second friction constraint at the center of the contact manifol ----- // // Compute J*v - deltaV = v2 + w2.cross(mContactConstraints[c].r2Friction) - v1 - w1.cross(mContactConstraints[c].r1Friction); - Jv = deltaV.dot(mContactConstraints[c].frictionVector2); + //deltaV = v2 + w2.cross(mContactConstraints[c].r2Friction) - v1 - w1.cross(mContactConstraints[c].r1Friction); + deltaV.x = v2.x + w2.y * mContactConstraints[c].r2Friction.z - v2.z * mContactConstraints[c].r2Friction.y - v1.x - + w1.y * mContactConstraints[c].r1Friction.z + w1.z * mContactConstraints[c].r1Friction.y; + deltaV.y = v2.y + w2.z * mContactConstraints[c].r2Friction.x - v2.x * mContactConstraints[c].r2Friction.z - v1.y - + w1.z * mContactConstraints[c].r1Friction.x + w1.x * mContactConstraints[c].r1Friction.z; + deltaV.z = v2.z + w2.x * mContactConstraints[c].r2Friction.y - v2.y * mContactConstraints[c].r2Friction.x - v1.z - + w1.x * mContactConstraints[c].r1Friction.y + w1.y * mContactConstraints[c].r1Friction.x; + Jv = deltaV.x * mContactConstraints[c].frictionVector2.x + deltaV.y * mContactConstraints[c].frictionVector2.y + + deltaV.z * mContactConstraints[c].frictionVector2.z; // Compute the Lagrange multiplier lambda deltaLambda = -Jv * mContactConstraints[c].inverseFriction2Mass; @@ -523,23 +671,36 @@ void ContactSolver::solve() { deltaLambda = mContactConstraints[c].friction2Impulse - lambdaTemp; // Compute the impulse P=J^T * lambda - angularImpulseBody1 = -mContactConstraints[c].r1CrossT2 * deltaLambda; - linearImpulseBody2 = mContactConstraints[c].frictionVector2 * deltaLambda; - angularImpulseBody2 = mContactConstraints[c].r2CrossT2 * deltaLambda; + angularImpulseBody1.x = -mContactConstraints[c].r1CrossT2.x * deltaLambda; + angularImpulseBody1.y = -mContactConstraints[c].r1CrossT2.y * deltaLambda; + angularImpulseBody1.z = -mContactConstraints[c].r1CrossT2.z * deltaLambda; + + linearImpulseBody2.x = mContactConstraints[c].frictionVector2.x * deltaLambda; + linearImpulseBody2.y = mContactConstraints[c].frictionVector2.y * deltaLambda; + linearImpulseBody2.z = mContactConstraints[c].frictionVector2.z * deltaLambda; + + angularImpulseBody2.x = mContactConstraints[c].r2CrossT2.x * deltaLambda; + angularImpulseBody2.y = mContactConstraints[c].r2CrossT2.y * deltaLambda; + angularImpulseBody2.z = mContactConstraints[c].r2CrossT2.z * deltaLambda; // Update the velocities of the body 1 by applying the impulse P - mLinearVelocities[mContactConstraints[c].indexBody1] -= mContactConstraints[c].massInverseBody1 * linearImpulseBody2; + mLinearVelocities[mContactConstraints[c].indexBody1].x -= mContactConstraints[c].massInverseBody1 * linearImpulseBody2.x; + mLinearVelocities[mContactConstraints[c].indexBody1].y -= mContactConstraints[c].massInverseBody1 * linearImpulseBody2.y; + mLinearVelocities[mContactConstraints[c].indexBody1].z -= mContactConstraints[c].massInverseBody1 * linearImpulseBody2.z; mAngularVelocities[mContactConstraints[c].indexBody1] += mContactConstraints[c].inverseInertiaTensorBody1 * angularImpulseBody1; // Update the velocities of the body 2 by applying the impulse P - mLinearVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].massInverseBody2 * linearImpulseBody2; + mLinearVelocities[mContactConstraints[c].indexBody2].x += mContactConstraints[c].massInverseBody2 * linearImpulseBody2.x; + mLinearVelocities[mContactConstraints[c].indexBody2].y += mContactConstraints[c].massInverseBody2 * linearImpulseBody2.y; + mLinearVelocities[mContactConstraints[c].indexBody2].z += mContactConstraints[c].massInverseBody2 * linearImpulseBody2.z; mAngularVelocities[mContactConstraints[c].indexBody2] += mContactConstraints[c].inverseInertiaTensorBody2 * angularImpulseBody2; // ------ Twist friction constraint at the center of the contact manifol ------ // // Compute J*v deltaV = w2 - w1; - Jv = deltaV.dot(mContactConstraints[c].normal); + Jv = deltaV.x * mContactConstraints[c].normal.x + deltaV.y * mContactConstraints[c].normal.y + + deltaV.z * mContactConstraints[c].normal.z; deltaLambda = -Jv * (mContactConstraints[c].inverseTwistFrictionMass); frictionLimit = mContactConstraints[c].frictionCoefficient * sumPenetrationImpulse; @@ -550,7 +711,9 @@ void ContactSolver::solve() { deltaLambda = mContactConstraints[c].frictionTwistImpulse - lambdaTemp; // Compute the impulse P=J^T * lambda - angularImpulseBody2 = mContactConstraints[c].normal * deltaLambda; + angularImpulseBody2.x = mContactConstraints[c].normal.x * deltaLambda; + angularImpulseBody2.y = mContactConstraints[c].normal.y * deltaLambda; + angularImpulseBody2.z = mContactConstraints[c].normal.z * deltaLambda; // Update the velocities of the body 1 by applying the impulse P mAngularVelocities[mContactConstraints[c].indexBody1] -= mContactConstraints[c].inverseInertiaTensorBody1 * angularImpulseBody2; @@ -619,8 +782,11 @@ void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, assert(contact.normal.length() > decimal(0.0)); // Compute the velocity difference vector in the tangential plane - Vector3 normalVelocity = deltaVelocity.dot(contact.normal) * contact.normal; - Vector3 tangentVelocity = deltaVelocity - normalVelocity; + Vector3 normalVelocity(deltaVelocity.x * contact.normal.x * contact.normal.x, + deltaVelocity.y * contact.normal.y * contact.normal.y, + deltaVelocity.z * contact.normal.z * contact.normal.z); + Vector3 tangentVelocity(deltaVelocity.x - normalVelocity.x, deltaVelocity.y - normalVelocity.y, + deltaVelocity.z - normalVelocity.z); // If the velocty difference in the tangential plane is not zero decimal lengthTangenVelocity = tangentVelocity.length(); From 9066264189e27c85bd7a16b04cd3bb32c6a8ef8c Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 12 Dec 2017 22:36:19 +0100 Subject: [PATCH 146/248] Remove commented code --- src/engine/DynamicsWorld.cpp | 23 ----------------------- 1 file changed, 23 deletions(-) diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index bb824228..66b13a8e 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -358,20 +358,6 @@ void DynamicsWorld::solveContactsAndConstraints() { // Check if there are contacts and constraints to solve bool isConstraintsToSolve = mIslands[islandIndex]->getNbJoints() > 0; - //bool isContactsToSolve = mIslands[islandIndex]->getNbContactManifolds() > 0; - //if (!isConstraintsToSolve && !isContactsToSolve) continue; - - // If there are contacts in the current island -// if (isContactsToSolve) { - -// // Initialize the solver -// mContactSolver.initializeForIsland(mTimeStep, mIslands[islandIndex]); - -// // Warm start the contact solver -// if (mContactSolver.IsWarmStartingActive()) { -// mContactSolver.warmStart(); -// } -// } // If there are constraints if (isConstraintsToSolve) { @@ -393,15 +379,6 @@ void DynamicsWorld::solveContactsAndConstraints() { } mContactSolver.solve(); - - // Solve the contacts -// if (isContactsToSolve) { - -// mContactSolver.resetTotalPenetrationImpulse(); - -// mContactSolver.solvePenetrationConstraints(); -// mContactSolver.solveFrictionConstraints(); -// } } mContactSolver.storeImpulses(); From 2d0cb2753832059abb460ebb317bbbfd9e8f0eab Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 12 Dec 2017 07:38:56 +0100 Subject: [PATCH 147/248] Add List and DefaultAllocator classes --- src/containers/List.h | 191 ++++++++++++++++++++++++++++++++++ src/memory/DefaultAllocator.h | 66 ++++++++++++ 2 files changed, 257 insertions(+) create mode 100644 src/containers/List.h create mode 100644 src/memory/DefaultAllocator.h diff --git a/src/containers/List.h b/src/containers/List.h new file mode 100644 index 00000000..4915f32d --- /dev/null +++ b/src/containers/List.h @@ -0,0 +1,191 @@ +/******************************************************************************** +* 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_LIST_H +#define REACTPHYSICS3D_LIST_H + +// Libraries +#include "configuration.h" +#include "memory/Allocator.h" +#include + +namespace reactphysics3d { + +// Class List +/** + * This class represents a simple generic list with custom memory allocator. + */ +template +class List { + + private: + + // -------------------- Attributes -------------------- // + + /// Pointer to the first element of the list + T* mElements; + + /// Number of elements in the list + uint mSize; + + /// Number of allocated elements in the list + uint 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(mElements), mSize * sizeof(T)); + + // Release the previously allocated memory + mAllocator.release(mElements, mCapacity * sizeof(T)); + } + + mElements = static_cast(newMemory); + + mCapacity = nbElementsToAllocate; + } + + public: + + // -------------------- Methods -------------------- // + + /// Constructor + List(Allocator& allocator, uint capacity = 0) + : mElements(nullptr), mSize(0), mCapacity(0), mAllocator(allocator) { + + if (capacity > 0) { + + // Allocate memory + allocateMemory(capacity); + } + } + + /// Copy constructor + List(const List& list) : mElements(nullptr), mSize(0), mCapacity(0), mAllocator(list.mAllocator) { + + // All all the elements of the list to the current one + addRange(list); + } + + /// Destructor + ~List() { + + // If elements have been allocated + if (mCapacity > 0) { + + // Clear the list + clear(); + + // Release the memory allocated on the heap + mAllocator.release(static_cast(mElements), mCapacity * sizeof(T)); + } + } + + /// 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); + } + + mElements[mSize] = element; + mSize++; + } + + /// Append another list to the current one + void addRange(const List& list) { + + // If we need to allocate more memory + if (mSize + list.size() > mCapacity) { + + // Allocate memory + allocateMemory(mSize + list.size()); + } + + // Add the elements of the list to the current one + for(uint i=0; i= 0 && index < mSize); + return mElements[index]; + } + + /// Overloaded const index operator + const T& operator[](const uint index) const { + assert(index >= 0 && index < mSize); + return mElements[index]; + } + + /// Overloaded assignment operator + List& operator=(const List& list) { + + // Clear all the elements + clear(); + + // Add all the elements of the list to the current one + addRange(list); + + return *this; + } +}; + +} + +#endif diff --git a/src/memory/DefaultAllocator.h b/src/memory/DefaultAllocator.h new file mode 100644 index 00000000..367171bd --- /dev/null +++ b/src/memory/DefaultAllocator.h @@ -0,0 +1,66 @@ +/******************************************************************************** +* 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_DEFAULT_ALLOCATOR_H +#define REACTPHYSICS3D_DEFAULT_ALLOCATOR_H + +// Libraries +#include "memory/Allocator.h" +#include + +/// ReactPhysics3D namespace +namespace reactphysics3d { + +// Class DefaultAllocator +/** + * This class represents a default memory allocator that uses default malloc/free methods + */ +class DefaultAllocator : public Allocator { + + public: + + /// Destructor + virtual ~DefaultAllocator() = default; + + /// Allocate memory of a given size (in bytes) and return a pointer to the + /// allocated memory. + virtual void* allocate(size_t size) override { + return malloc(size); + } + + /// Release previously allocated memory. + virtual void release(void* pointer, size_t size) override { + free(pointer); + } + + /// Return true if memory needs to be release with this allocator + virtual bool isReleaseNeeded() const override { + return true; + } +}; + +} + +#endif From 5392948518ef415991feb55e0595bc15b48d737c Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 13 Dec 2017 17:51:38 +0100 Subject: [PATCH 148/248] Use inline constructors for mathematics objects (vectors, quaternion, matrices, ...) --- src/mathematics/Matrix2x2.cpp | 25 ------------------ src/mathematics/Matrix2x2.h | 25 ++++++++++++++++++ src/mathematics/Matrix3x3.cpp | 26 ------------------- src/mathematics/Matrix3x3.h | 26 +++++++++++++++++++ src/mathematics/Quaternion.cpp | 21 ---------------- src/mathematics/Quaternion.h | 25 ++++++++++++++++-- src/mathematics/Transform.cpp | 22 ---------------- src/mathematics/Transform.h | 46 ++++++++++++++++++++++++++++++++-- src/mathematics/Vector2.cpp | 15 ----------- src/mathematics/Vector2.h | 16 ++++++++++++ src/mathematics/Vector3.cpp | 15 ----------- src/mathematics/Vector3.h | 15 +++++++++++ 12 files changed, 149 insertions(+), 128 deletions(-) diff --git a/src/mathematics/Matrix2x2.cpp b/src/mathematics/Matrix2x2.cpp index c501c1db..bf4adbe5 100644 --- a/src/mathematics/Matrix2x2.cpp +++ b/src/mathematics/Matrix2x2.cpp @@ -28,31 +28,6 @@ using namespace reactphysics3d; -// Constructor of the class Matrix2x2 -Matrix2x2::Matrix2x2() { - - // Initialize all values in the matrix to zero - setAllValues(0.0, 0.0, 0.0, 0.0); -} - -// Constructor -Matrix2x2::Matrix2x2(decimal value) { - setAllValues(value, value, value, value); -} - -// Constructor with arguments -Matrix2x2::Matrix2x2(decimal a1, decimal a2, decimal b1, decimal b2) { - - // Initialize the matrix with the values - setAllValues(a1, a2, b1, b2); -} - -// Copy-constructor -Matrix2x2::Matrix2x2(const Matrix2x2& matrix) { - setAllValues(matrix.mRows[0][0], matrix.mRows[0][1], - matrix.mRows[1][0], matrix.mRows[1][1]); -} - // Assignment operator Matrix2x2& Matrix2x2::operator=(const Matrix2x2& matrix) { diff --git a/src/mathematics/Matrix2x2.h b/src/mathematics/Matrix2x2.h index ee31b07a..8315eb99 100644 --- a/src/mathematics/Matrix2x2.h +++ b/src/mathematics/Matrix2x2.h @@ -147,6 +147,31 @@ class Matrix2x2 { Vector2& operator[](int row); }; +// Constructor of the class Matrix2x2 +inline Matrix2x2::Matrix2x2() { + + // Initialize all values in the matrix to zero + setAllValues(0.0, 0.0, 0.0, 0.0); +} + +// Constructor +inline Matrix2x2::Matrix2x2(decimal value) { + setAllValues(value, value, value, value); +} + +// Constructor with arguments +inline Matrix2x2::Matrix2x2(decimal a1, decimal a2, decimal b1, decimal b2) { + + // Initialize the matrix with the values + setAllValues(a1, a2, b1, b2); +} + +// Copy-constructor +inline Matrix2x2::Matrix2x2(const Matrix2x2& matrix) { + setAllValues(matrix.mRows[0][0], matrix.mRows[0][1], + matrix.mRows[1][0], matrix.mRows[1][1]); +} + // Method to set all the values in the matrix inline void Matrix2x2::setAllValues(decimal a1, decimal a2, decimal b1, decimal b2) { diff --git a/src/mathematics/Matrix3x3.cpp b/src/mathematics/Matrix3x3.cpp index a5491ed4..e86e63a1 100644 --- a/src/mathematics/Matrix3x3.cpp +++ b/src/mathematics/Matrix3x3.cpp @@ -30,32 +30,6 @@ // Namespaces using namespace reactphysics3d; -// Constructor of the class Matrix3x3 -Matrix3x3::Matrix3x3() { - // Initialize all values in the matrix to zero - setAllValues(0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0); -} - -// Constructor -Matrix3x3::Matrix3x3(decimal value) { - setAllValues(value, value, value, value, value, value, value, value, value); -} - -// Constructor with arguments -Matrix3x3::Matrix3x3(decimal a1, decimal a2, decimal a3, - decimal b1, decimal b2, decimal b3, - decimal c1, decimal c2, decimal c3) { - // Initialize the matrix with the values - setAllValues(a1, a2, a3, b1, b2, b3, c1, c2, c3); -} - -// Copy-constructor -Matrix3x3::Matrix3x3(const Matrix3x3& matrix) { - setAllValues(matrix.mRows[0][0], matrix.mRows[0][1], matrix.mRows[0][2], - matrix.mRows[1][0], matrix.mRows[1][1], matrix.mRows[1][2], - matrix.mRows[2][0], matrix.mRows[2][1], matrix.mRows[2][2]); -} - // Assignment operator Matrix3x3& Matrix3x3::operator=(const Matrix3x3& matrix) { diff --git a/src/mathematics/Matrix3x3.h b/src/mathematics/Matrix3x3.h index ebb8792d..6897a2cf 100644 --- a/src/mathematics/Matrix3x3.h +++ b/src/mathematics/Matrix3x3.h @@ -155,6 +155,32 @@ class Matrix3x3 { Vector3& operator[](int row); }; +// Constructor of the class Matrix3x3 +inline Matrix3x3::Matrix3x3() { + // Initialize all values in the matrix to zero + setAllValues(0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0); +} + +// Constructor +inline Matrix3x3::Matrix3x3(decimal value) { + setAllValues(value, value, value, value, value, value, value, value, value); +} + +// Constructor with arguments +inline Matrix3x3::Matrix3x3(decimal a1, decimal a2, decimal a3, + decimal b1, decimal b2, decimal b3, + decimal c1, decimal c2, decimal c3) { + // Initialize the matrix with the values + setAllValues(a1, a2, a3, b1, b2, b3, c1, c2, c3); +} + +// Copy-constructor +inline Matrix3x3::Matrix3x3(const Matrix3x3& matrix) { + setAllValues(matrix.mRows[0][0], matrix.mRows[0][1], matrix.mRows[0][2], + matrix.mRows[1][0], matrix.mRows[1][1], matrix.mRows[1][2], + matrix.mRows[2][0], matrix.mRows[2][1], matrix.mRows[2][2]); +} + // Method to set all the values in the matrix inline void Matrix3x3::setAllValues(decimal a1, decimal a2, decimal a3, decimal b1, decimal b2, decimal b3, diff --git a/src/mathematics/Quaternion.cpp b/src/mathematics/Quaternion.cpp index d0e1ae61..0e877612 100644 --- a/src/mathematics/Quaternion.cpp +++ b/src/mathematics/Quaternion.cpp @@ -31,27 +31,6 @@ // Namespace using namespace reactphysics3d; -// Constructor of the class -Quaternion::Quaternion() : x(0.0), y(0.0), z(0.0), w(0.0) { - -} - -// Constructor with arguments -Quaternion::Quaternion(decimal newX, decimal newY, decimal newZ, decimal newW) - :x(newX), y(newY), z(newZ), w(newW) { - -} - -// Constructor with the component w and the vector v=(x y z) -Quaternion::Quaternion(decimal newW, const Vector3& v) : x(v.x), y(v.y), z(v.z), w(newW) { - -} - -// Constructor with the component w and the vector v=(x y z) -Quaternion::Quaternion(const Vector3& v, decimal newW) : x(v.x), y(v.y), z(v.z), w(newW) { - -} - // Return a quaternion constructed from Euler angles (in radians) Quaternion Quaternion::fromEulerAngles(decimal angleX, decimal angleY, decimal angleZ) { diff --git a/src/mathematics/Quaternion.h b/src/mathematics/Quaternion.h index d5e771e2..dd0726dc 100644 --- a/src/mathematics/Quaternion.h +++ b/src/mathematics/Quaternion.h @@ -169,7 +169,28 @@ struct Quaternion { void initWithEulerAngles(decimal angleX, decimal angleY, decimal angleZ); }; -/// Set all the values +// Constructor of the class +inline Quaternion::Quaternion() : x(0.0), y(0.0), z(0.0), w(0.0) { + +} + +// Constructor with arguments +inline Quaternion::Quaternion(decimal newX, decimal newY, decimal newZ, decimal newW) + :x(newX), y(newY), z(newZ), w(newW) { + +} + +// Constructor with the component w and the vector v=(x y z) +inline Quaternion::Quaternion(decimal newW, const Vector3& v) : x(v.x), y(v.y), z(v.z), w(newW) { + +} + +// Constructor with the component w and the vector v=(x y z) +inline Quaternion::Quaternion(const Vector3& v, decimal newW) : x(v.x), y(v.y), z(v.z), w(newW) { + +} + +// Set all the values inline void Quaternion::setAllValues(decimal newX, decimal newY, decimal newZ, decimal newW) { x = newX; y = newY; @@ -177,7 +198,7 @@ inline void Quaternion::setAllValues(decimal newX, decimal newY, decimal newZ, d w = newW; } -/// Set the quaternion to zero +// Set the quaternion to zero inline void Quaternion::setToZero() { x = 0; y = 0; diff --git a/src/mathematics/Transform.cpp b/src/mathematics/Transform.cpp index 4bc91253..d5cf0399 100644 --- a/src/mathematics/Transform.cpp +++ b/src/mathematics/Transform.cpp @@ -29,25 +29,3 @@ // Namespaces using namespace reactphysics3d; -// Constructor -Transform::Transform() : mPosition(Vector3(0.0, 0.0, 0.0)), mOrientation(Quaternion::identity()) { - -} - -// Constructor -Transform::Transform(const Vector3& position, const Matrix3x3& orientation) - : mPosition(position), mOrientation(Quaternion(orientation)) { - -} - -// Constructor -Transform::Transform(const Vector3& position, const Quaternion& orientation) - : mPosition(position), mOrientation(orientation) { - -} - -// Copy-constructor -Transform::Transform(const Transform& transform) - : mPosition(transform.mPosition), mOrientation(transform.mOrientation) { - -} diff --git a/src/mathematics/Transform.h b/src/mathematics/Transform.h index 52ee663e..a5248fc2 100644 --- a/src/mathematics/Transform.h +++ b/src/mathematics/Transform.h @@ -118,6 +118,29 @@ class Transform { Transform& operator=(const Transform& transform); }; +// Constructor +inline Transform::Transform() : mPosition(Vector3(0.0, 0.0, 0.0)), mOrientation(Quaternion::identity()) { + +} + +// Constructor +inline Transform::Transform(const Vector3& position, const Matrix3x3& orientation) + : mPosition(position), mOrientation(Quaternion(orientation)) { + +} + +// Constructor +inline Transform::Transform(const Vector3& position, const Quaternion& orientation) + : mPosition(position), mOrientation(orientation) { + +} + +// Copy-constructor +inline Transform::Transform(const Transform& transform) + : mPosition(transform.mPosition), mOrientation(transform.mOrientation) { + +} + // Return the position of the transform inline const Vector3& Transform::getPosition() const { return mPosition; @@ -199,8 +222,27 @@ inline Vector3 Transform::operator*(const Vector3& vector) const { // Operator of multiplication of a transform with another one inline Transform Transform::operator*(const Transform& transform2) const { - return Transform(mPosition + mOrientation * transform2.mPosition, - mOrientation * transform2.mOrientation); + + const decimal prodX = mOrientation.w * transform2.mPosition.x + mOrientation.w * transform2.mPosition.z + - mOrientation.z * transform2.mPosition.y; + const decimal prodY = mOrientation.w * transform2.mPosition.y + mOrientation.z * transform2.mPosition.x + - mOrientation.x * transform2.mPosition.z; + const decimal prodZ = mOrientation.w * transform2.mPosition.z + mOrientation.x * transform2.mPosition.y + - mOrientation.y * transform2.mPosition.x; + const decimal prodW = -mOrientation.x * transform2.mPosition.x - mOrientation.y * transform2.mPosition.y + - mOrientation.z * transform2.mPosition.z; + + return Transform(Vector3(mPosition.x + mOrientation.w * prodX - prodY * mOrientation.z + prodZ * mOrientation.y - prodW * mOrientation.x, + mPosition.y + mOrientation.w * prodY - prodZ * mOrientation.x + prodX * mOrientation.z - prodW * mOrientation.y, + mPosition.z + mOrientation.w * prodZ - prodX * mOrientation.y + prodY * mOrientation.x - prodW * mOrientation.z), + Quaternion(mOrientation.w * transform2.mOrientation.x + transform2.mOrientation.w * mOrientation.x + + mOrientation.y * transform2.mOrientation.z - mOrientation.z * transform2.mOrientation.y, + mOrientation.w * transform2.mOrientation.y + transform2.mOrientation.w * mOrientation.y + + mOrientation.z * transform2.mOrientation.x - mOrientation.x * transform2.mOrientation.z, + mOrientation.w * transform2.mOrientation.z + transform2.mOrientation.w * mOrientation.z + + mOrientation.x * transform2.mOrientation.y - mOrientation.y * transform2.mOrientation.x, + mOrientation.w * transform2.mOrientation.w - mOrientation.x * transform2.mOrientation.x + - mOrientation.y * transform2.mOrientation.y - mOrientation.z * transform2.mOrientation.z)); } // Return true if the two transforms are equal diff --git a/src/mathematics/Vector2.cpp b/src/mathematics/Vector2.cpp index 2f225636..271fd82f 100644 --- a/src/mathematics/Vector2.cpp +++ b/src/mathematics/Vector2.cpp @@ -30,21 +30,6 @@ // Namespaces using namespace reactphysics3d; -// Constructor -Vector2::Vector2() : x(0.0), y(0.0) { - -} - -// Constructor with arguments -Vector2::Vector2(decimal newX, decimal newY) : x(newX), y(newY) { - -} - -// Copy-constructor -Vector2::Vector2(const Vector2& vector) : x(vector.x), y(vector.y) { - -} - // Return the corresponding unit vector Vector2 Vector2::getUnit() const { decimal lengthVector = length(); diff --git a/src/mathematics/Vector2.h b/src/mathematics/Vector2.h index 4b0e32f1..bc5f8872 100644 --- a/src/mathematics/Vector2.h +++ b/src/mathematics/Vector2.h @@ -156,6 +156,22 @@ struct Vector2 { friend Vector2 operator/(const Vector2& vector1, const Vector2& vector2); }; +// Constructor +inline Vector2::Vector2() : x(0.0), y(0.0) { + +} + +// Constructor with arguments +inline Vector2::Vector2(decimal newX, decimal newY) : x(newX), y(newY) { + +} + +// Copy-constructor +inline Vector2::Vector2(const Vector2& vector) : x(vector.x), y(vector.y) { + +} + + // Set the vector to zero inline void Vector2::setToZero() { x = 0; diff --git a/src/mathematics/Vector3.cpp b/src/mathematics/Vector3.cpp index ab2d126d..33b760ba 100644 --- a/src/mathematics/Vector3.cpp +++ b/src/mathematics/Vector3.cpp @@ -31,21 +31,6 @@ // Namespaces using namespace reactphysics3d; -// Constructor of the class Vector3D -Vector3::Vector3() : x(0.0), y(0.0), z(0.0) { - -} - -// Constructor with arguments -Vector3::Vector3(decimal newX, decimal newY, decimal newZ) : x(newX), y(newY), z(newZ) { - -} - -// Copy-constructor -Vector3::Vector3(const Vector3& vector) : x(vector.x), y(vector.y), z(vector.z) { - -} - // Return the corresponding unit vector Vector3 Vector3::getUnit() const { decimal lengthVector = length(); diff --git a/src/mathematics/Vector3.h b/src/mathematics/Vector3.h index 1ca1adfd..95255fdb 100644 --- a/src/mathematics/Vector3.h +++ b/src/mathematics/Vector3.h @@ -168,6 +168,21 @@ struct Vector3 { friend Vector3 operator/(const Vector3& vector1, const Vector3& vector2); }; +// Constructor of the class Vector3D +inline Vector3::Vector3() : x(0.0), y(0.0), z(0.0) { + +} + +// Constructor with arguments +inline Vector3::Vector3(decimal newX, decimal newY, decimal newZ) : x(newX), y(newY), z(newZ) { + +} + +// Copy-constructor +inline Vector3::Vector3(const Vector3& vector) : x(vector.x), y(vector.y), z(vector.z) { + +} + // Set the vector to zero inline void Vector3::setToZero() { x = 0; From 7d20a746e9a8822d4530e6b7b44ef3286d8aed68 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 14 Dec 2017 15:09:56 +0100 Subject: [PATCH 149/248] Do not std::map to store mapping from rigid body to index in array --- src/body/RigidBody.cpp | 2 +- src/body/RigidBody.h | 7 ++++++- src/constraint/BallAndSocketJoint.cpp | 4 ++-- src/constraint/FixedJoint.cpp | 4 ++-- src/constraint/HingeJoint.cpp | 4 ++-- src/constraint/SliderJoint.cpp | 4 ++-- src/engine/ConstraintSolver.cpp | 4 +--- src/engine/ConstraintSolver.h | 16 +++------------- src/engine/ContactSolver.cpp | 8 +++----- src/engine/ContactSolver.h | 6 +----- src/engine/DynamicsWorld.cpp | 26 +++++++++----------------- src/engine/DynamicsWorld.h | 3 --- 12 files changed, 32 insertions(+), 56 deletions(-) diff --git a/src/body/RigidBody.cpp b/src/body/RigidBody.cpp index d0f0c782..01e1694b 100644 --- a/src/body/RigidBody.cpp +++ b/src/body/RigidBody.cpp @@ -42,7 +42,7 @@ RigidBody::RigidBody(const Transform& transform, CollisionWorld& world, bodyinde : CollisionBody(transform, world, id), mInitMass(decimal(1.0)), mCenterOfMassLocal(0, 0, 0), mCenterOfMassWorld(transform.getPosition()), mIsGravityEnabled(true), mLinearDamping(decimal(0.0)), mAngularDamping(decimal(0.0)), - mJointsList(nullptr) { + mJointsList(nullptr), mArrayIndex(0) { // Compute the inverse mass mMassInverse = decimal(1.0) / mInitMass; diff --git a/src/body/RigidBody.h b/src/body/RigidBody.h index 6ba7a596..e12cab05 100644 --- a/src/body/RigidBody.h +++ b/src/body/RigidBody.h @@ -50,6 +50,11 @@ class DynamicsWorld; */ class RigidBody : public CollisionBody { + private : + + /// Index of the body in arrays for contact/constraint solver + uint mArrayIndex; + protected : // -------------------- Attributes -------------------- // @@ -102,7 +107,7 @@ class RigidBody : public CollisionBody { decimal mAngularDamping; /// First element of the linked list of joints involving this body - JointListElement* mJointsList; + JointListElement* mJointsList; // -------------------- Methods -------------------- // diff --git a/src/constraint/BallAndSocketJoint.cpp b/src/constraint/BallAndSocketJoint.cpp index 7a5fce1b..272d922e 100644 --- a/src/constraint/BallAndSocketJoint.cpp +++ b/src/constraint/BallAndSocketJoint.cpp @@ -45,8 +45,8 @@ BallAndSocketJoint::BallAndSocketJoint(const BallAndSocketJointInfo& jointInfo) void BallAndSocketJoint::initBeforeSolve(const ConstraintSolverData& constraintSolverData) { // Initialize the bodies index in the velocity array - mIndexBody1 = constraintSolverData.mapBodyToConstrainedVelocityIndex.find(mBody1)->second; - mIndexBody2 = constraintSolverData.mapBodyToConstrainedVelocityIndex.find(mBody2)->second; + mIndexBody1 = mBody1->mArrayIndex; + mIndexBody2 = mBody2->mArrayIndex; // Get the bodies center of mass and orientations const Vector3& x1 = mBody1->mCenterOfMassWorld; diff --git a/src/constraint/FixedJoint.cpp b/src/constraint/FixedJoint.cpp index 8f0b105c..01fe3957 100644 --- a/src/constraint/FixedJoint.cpp +++ b/src/constraint/FixedJoint.cpp @@ -53,8 +53,8 @@ FixedJoint::FixedJoint(const FixedJointInfo& jointInfo) void FixedJoint::initBeforeSolve(const ConstraintSolverData& constraintSolverData) { // Initialize the bodies index in the velocity array - mIndexBody1 = constraintSolverData.mapBodyToConstrainedVelocityIndex.find(mBody1)->second; - mIndexBody2 = constraintSolverData.mapBodyToConstrainedVelocityIndex.find(mBody2)->second; + mIndexBody1 = mBody1->mArrayIndex; + mIndexBody2 = mBody2->mArrayIndex; // Get the bodies positions and orientations const Vector3& x1 = mBody1->mCenterOfMassWorld; diff --git a/src/constraint/HingeJoint.cpp b/src/constraint/HingeJoint.cpp index 1634bf27..7b400a2a 100644 --- a/src/constraint/HingeJoint.cpp +++ b/src/constraint/HingeJoint.cpp @@ -68,8 +68,8 @@ HingeJoint::HingeJoint(const HingeJointInfo& jointInfo) void HingeJoint::initBeforeSolve(const ConstraintSolverData& constraintSolverData) { // Initialize the bodies index in the velocity array - mIndexBody1 = constraintSolverData.mapBodyToConstrainedVelocityIndex.find(mBody1)->second; - mIndexBody2 = constraintSolverData.mapBodyToConstrainedVelocityIndex.find(mBody2)->second; + mIndexBody1 = mBody1->mArrayIndex; + mIndexBody2 = mBody2->mArrayIndex; // Get the bodies positions and orientations const Vector3& x1 = mBody1->mCenterOfMassWorld; diff --git a/src/constraint/SliderJoint.cpp b/src/constraint/SliderJoint.cpp index 919d91c0..7697013d 100644 --- a/src/constraint/SliderJoint.cpp +++ b/src/constraint/SliderJoint.cpp @@ -67,8 +67,8 @@ SliderJoint::SliderJoint(const SliderJointInfo& jointInfo) void SliderJoint::initBeforeSolve(const ConstraintSolverData& constraintSolverData) { // Initialize the bodies index in the veloc ity array - mIndexBody1 = constraintSolverData.mapBodyToConstrainedVelocityIndex.find(mBody1)->second; - mIndexBody2 = constraintSolverData.mapBodyToConstrainedVelocityIndex.find(mBody2)->second; + mIndexBody1 = mBody1->mArrayIndex; + mIndexBody2 = mBody2->mArrayIndex; // Get the bodies positions and orientations const Vector3& x1 = mBody1->mCenterOfMassWorld; diff --git a/src/engine/ConstraintSolver.cpp b/src/engine/ConstraintSolver.cpp index 458c39a7..5345cbaf 100644 --- a/src/engine/ConstraintSolver.cpp +++ b/src/engine/ConstraintSolver.cpp @@ -30,9 +30,7 @@ using namespace reactphysics3d; // Constructor -ConstraintSolver::ConstraintSolver(const std::map& mapBodyToVelocityIndex) - : mMapBodyToConstrainedVelocityIndex(mapBodyToVelocityIndex), - mIsWarmStartingActive(true), mConstraintSolverData(mapBodyToVelocityIndex) { +ConstraintSolver::ConstraintSolver() : mIsWarmStartingActive(true) { #ifdef IS_PROFILING_ACTIVE diff --git a/src/engine/ConstraintSolver.h b/src/engine/ConstraintSolver.h index fbb54ed1..105045e0 100644 --- a/src/engine/ConstraintSolver.h +++ b/src/engine/ConstraintSolver.h @@ -60,18 +60,12 @@ struct ConstraintSolverData { /// Reference to the bodies orientations Quaternion* orientations; - /// Reference to the map that associates rigid body to their index - /// in the constrained velocities array - const std::map& mapBodyToConstrainedVelocityIndex; - /// True if warm starting of the solver is active bool isWarmStartingActive; /// Constructor - ConstraintSolverData(const std::map& refMapBodyToConstrainedVelocityIndex) - :linearVelocities(nullptr), angularVelocities(nullptr), - positions(nullptr), orientations(nullptr), - mapBodyToConstrainedVelocityIndex(refMapBodyToConstrainedVelocityIndex){ + ConstraintSolverData() :linearVelocities(nullptr), angularVelocities(nullptr), + positions(nullptr), orientations(nullptr) { } @@ -152,10 +146,6 @@ class ConstraintSolver { // -------------------- Attributes -------------------- // - /// Reference to the map that associates rigid body to their index in - /// the constrained velocities array - const std::map& mMapBodyToConstrainedVelocityIndex; - /// Current time step decimal mTimeStep; @@ -176,7 +166,7 @@ class ConstraintSolver { // -------------------- Methods -------------------- // /// Constructor - ConstraintSolver(const std::map& mapBodyToVelocityIndex); + ConstraintSolver(); /// Destructor ~ConstraintSolver() = default; diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index 7bd74e8a..6361badd 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -39,12 +39,10 @@ const decimal ContactSolver::BETA_SPLIT_IMPULSE = decimal(0.2); const decimal ContactSolver::SLOP = decimal(0.01); // Constructor -ContactSolver::ContactSolver(const std::map& mapBodyToVelocityIndex, - SingleFrameAllocator& allocator) +ContactSolver::ContactSolver(SingleFrameAllocator& allocator) :mSplitLinearVelocities(nullptr), mSplitAngularVelocities(nullptr), mContactConstraints(nullptr), mSingleFrameAllocator(allocator), mLinearVelocities(nullptr), mAngularVelocities(nullptr), - mMapBodyToConstrainedVelocityIndex(mapBodyToVelocityIndex), mIsSplitImpulseActive(true) { } @@ -131,8 +129,8 @@ void ContactSolver::initializeForIsland(Island* island) { // Initialize the internal contact manifold structure using the external // contact manifold new (mContactConstraints + mNbContactManifolds) ContactManifoldSolver(); - mContactConstraints[mNbContactManifolds].indexBody1 = mMapBodyToConstrainedVelocityIndex.find(body1)->second; - mContactConstraints[mNbContactManifolds].indexBody2 = mMapBodyToConstrainedVelocityIndex.find(body2)->second; + mContactConstraints[mNbContactManifolds].indexBody1 = body1->mArrayIndex; + mContactConstraints[mNbContactManifolds].indexBody2 = body2->mArrayIndex; mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody1 = body1->getInertiaTensorInverseWorld(); mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody2 = body2->getInertiaTensorInverseWorld(); mContactConstraints[mNbContactManifolds].massInverseBody1 = body1->mMassInverse; diff --git a/src/engine/ContactSolver.h b/src/engine/ContactSolver.h index 0a2850f5..05bd569c 100644 --- a/src/engine/ContactSolver.h +++ b/src/engine/ContactSolver.h @@ -302,9 +302,6 @@ class ContactSolver { /// Array of angular velocities Vector3* mAngularVelocities; - /// Reference to the map of rigid body to their index in the constrained velocities array - const std::map& mMapBodyToConstrainedVelocityIndex; - /// True if the split impulse position correction is active bool mIsSplitImpulseActive; @@ -342,8 +339,7 @@ class ContactSolver { // -------------------- Methods -------------------- // /// Constructor - ContactSolver(const std::map& mapBodyToVelocityIndex, - SingleFrameAllocator& allocator); + ContactSolver(SingleFrameAllocator& allocator); /// Destructor ~ContactSolver() = default; diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index 66b13a8e..054c4dc5 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -41,8 +41,7 @@ using namespace std; */ DynamicsWorld::DynamicsWorld(const Vector3 &gravity) : CollisionWorld(), - mContactSolver(mMapBodyToConstrainedVelocityIndex, mSingleFrameAllocator), - mConstraintSolver(mMapBodyToConstrainedVelocityIndex), + mContactSolver(mSingleFrameAllocator), mNbVelocitySolverIterations(DEFAULT_VELOCITY_SOLVER_NB_ITERATIONS), mNbPositionSolverIterations(DEFAULT_POSITION_SOLVER_NB_ITERATIONS), mIsSleepingEnabled(SLEEPING_ENABLED), mGravity(gravity), mTimeStep(decimal(1.0f / 60.0f)), @@ -167,7 +166,7 @@ void DynamicsWorld::integrateRigidBodiesPositions() { for (uint b=0; b < mIslands[i]->getNbBodies(); b++) { // Get the constrained velocity - uint indexArray = mMapBodyToConstrainedVelocityIndex.find(bodies[b])->second; + uint indexArray = bodies[b]->mArrayIndex; Vector3 newLinVelocity = mConstrainedLinearVelocities[indexArray]; Vector3 newAngVelocity = mConstrainedAngularVelocities[indexArray]; @@ -205,7 +204,7 @@ void DynamicsWorld::updateBodiesState() { for (uint b=0; b < mIslands[islandIndex]->getNbBodies(); b++) { - uint index = mMapBodyToConstrainedVelocityIndex.find(bodies[b])->second; + uint index = bodies[b]->mArrayIndex; // Update the linear and angular velocity of the body bodies[b]->mLinearVelocity = mConstrainedLinearVelocities[index]; @@ -250,21 +249,14 @@ void DynamicsWorld::initVelocityArrays() { assert(mConstrainedPositions != nullptr); assert(mConstrainedOrientations != nullptr); - // Reset the velocities arrays - for (uint i=0; i::iterator it = mRigidBodies.begin(); it != mRigidBodies.end(); ++it) { + mSplitLinearVelocities[i].setToZero(); mSplitAngularVelocities[i].setToZero(); - } - // Initialize the map of body indexes in the velocity arrays - mMapBodyToConstrainedVelocityIndex.clear(); - std::set::const_iterator it; - uint indexBody = 0; - for (it = mRigidBodies.begin(); it != mRigidBodies.end(); ++it) { - - // Add the body into the map - mMapBodyToConstrainedVelocityIndex.insert(std::make_pair(*it, indexBody)); - indexBody++; + (*it)->mArrayIndex = i++; } } @@ -289,7 +281,7 @@ void DynamicsWorld::integrateRigidBodiesVelocities() { for (uint b=0; b < mIslands[i]->getNbBodies(); b++) { // Insert the body into the map of constrained velocities - uint indexBody = mMapBodyToConstrainedVelocityIndex.find(bodies[b])->second; + uint indexBody = bodies[b]->mArrayIndex; assert(mSplitLinearVelocities[indexBody] == Vector3(0, 0, 0)); assert(mSplitAngularVelocities[indexBody] == Vector3(0, 0, 0)); diff --git a/src/engine/DynamicsWorld.h b/src/engine/DynamicsWorld.h index 366b2770..0c614b65 100644 --- a/src/engine/DynamicsWorld.h +++ b/src/engine/DynamicsWorld.h @@ -100,9 +100,6 @@ class DynamicsWorld : public CollisionWorld { /// Array of constrained rigid bodies orientation (for position error correction) Quaternion* mConstrainedOrientations; - /// Map body to their index in the constrained velocities array - std::map mMapBodyToConstrainedVelocityIndex; - /// Number of islands in the world uint mNbIslands; From 47869627d13d71f3997adea53731890e55a10de4 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 14 Dec 2017 20:24:19 +0100 Subject: [PATCH 150/248] Fix issue in Transform --- src/mathematics/Transform.h | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/mathematics/Transform.h b/src/mathematics/Transform.h index a5248fc2..aeaf4234 100644 --- a/src/mathematics/Transform.h +++ b/src/mathematics/Transform.h @@ -223,7 +223,11 @@ inline Vector3 Transform::operator*(const Vector3& vector) const { // Operator of multiplication of a transform with another one inline Transform Transform::operator*(const Transform& transform2) const { - const decimal prodX = mOrientation.w * transform2.mPosition.x + mOrientation.w * transform2.mPosition.z + // The following code is equivalent to this + //return Transform(mPosition + mOrientation * transform2.mPosition, + // mOrientation * transform2.mOrientation); + + const decimal prodX = mOrientation.w * transform2.mPosition.x + mOrientation.y * transform2.mPosition.z - mOrientation.z * transform2.mPosition.y; const decimal prodY = mOrientation.w * transform2.mPosition.y + mOrientation.z * transform2.mPosition.x - mOrientation.x * transform2.mPosition.z; From f2ee00ca68b409234b84d134cdc9845c9c55e2c3 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 14 Dec 2017 22:25:52 +0100 Subject: [PATCH 151/248] Use List instead of std::vector compute segment clipping in SAT algorithm --- src/body/RigidBody.cpp | 4 +- .../narrowphase/SAT/SATAlgorithm.cpp | 10 ++--- src/mathematics/mathematics_functions.cpp | 43 +++++++++++-------- src/mathematics/mathematics_functions.h | 7 +-- 4 files changed, 36 insertions(+), 28 deletions(-) diff --git a/src/body/RigidBody.cpp b/src/body/RigidBody.cpp index 01e1694b..e4ce4458 100644 --- a/src/body/RigidBody.cpp +++ b/src/body/RigidBody.cpp @@ -39,10 +39,10 @@ using namespace reactphysics3d; * @param id The ID of the body */ RigidBody::RigidBody(const Transform& transform, CollisionWorld& world, bodyindex id) - : CollisionBody(transform, world, id), mInitMass(decimal(1.0)), + : CollisionBody(transform, world, id), mArrayIndex(0), mInitMass(decimal(1.0)), mCenterOfMassLocal(0, 0, 0), mCenterOfMassWorld(transform.getPosition()), mIsGravityEnabled(true), mLinearDamping(decimal(0.0)), mAngularDamping(decimal(0.0)), - mJointsList(nullptr), mArrayIndex(0) { + mJointsList(nullptr) { // Compute the inverse mass mMassInverse = decimal(1.0) / mInitMass; diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 5e40f45f..2605eaf9 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -374,8 +374,8 @@ bool SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceI uint firstEdgeIndex = face.edgeIndex; uint edgeIndex = firstEdgeIndex; - std::vector planesPoints; - std::vector planesNormals; + List planesPoints(mMemoryAllocator, 2); + List planesNormals(mMemoryAllocator, 2); // For each adjacent edge of the separating face of the polyhedron do { @@ -393,15 +393,15 @@ bool SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceI Vector3 clipPlaneNormal = faceNormal.cross(edgeDirection); // Construct a clipping plane for each adjacent edge of the separating face of the polyhedron - planesPoints.push_back(polyhedron->getVertexPosition(edge.vertexIndex)); - planesNormals.push_back(clipPlaneNormal); + planesPoints.add(polyhedron->getVertexPosition(edge.vertexIndex)); + planesNormals.add(clipPlaneNormal); edgeIndex = edge.nextEdgeIndex; } while(edgeIndex != firstEdgeIndex); // First we clip the inner segment of the capsule with the four planes of the adjacent faces - std::vector clipSegment = clipSegmentWithPlanes(capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, planesPoints, planesNormals); + List clipSegment = clipSegmentWithPlanes(capsuleSegAPolyhedronSpace, capsuleSegBPolyhedronSpace, planesPoints, planesNormals, mMemoryAllocator); // Project the two clipped points into the polyhedron face const Vector3 delta = faceNormal * (penetrationDepth - capsuleRadius); diff --git a/src/mathematics/mathematics_functions.cpp b/src/mathematics/mathematics_functions.cpp index b82c9fbd..0d8994f4 100755 --- a/src/mathematics/mathematics_functions.cpp +++ b/src/mathematics/mathematics_functions.cpp @@ -222,27 +222,34 @@ decimal reactphysics3d::computePointToLineDistance(const Vector3& linePointA, co // Clip a segment against multiple planes and return the clipped segment vertices // This method implements the Sutherland–Hodgman clipping algorithm -std::vector reactphysics3d::clipSegmentWithPlanes(const Vector3& segA, const Vector3& segB, - const std::vector& planesPoints, - const std::vector& planesNormals) { +List reactphysics3d::clipSegmentWithPlanes(const Vector3& segA, const Vector3& segB, + const List& planesPoints, + const List& planesNormals, + Allocator& allocator) { assert(planesPoints.size() == planesNormals.size()); - std::vector inputVertices = {segA, segB}; - std::vector outputVertices; + List list1(allocator, 2); + List list2(allocator, 2); + + List* inputVertices = &list1; + List* outputVertices = &list2; + + inputVertices->add(segA); + inputVertices->add(segB); // For each clipping plane for (uint p=0; psize() == 0) return *inputVertices; - assert(inputVertices.size() == 2); + assert(inputVertices->size() == 2); - outputVertices.clear(); + outputVertices->clear(); - Vector3& v1 = inputVertices[0]; - Vector3& v2 = inputVertices[1]; + Vector3& v1 = (*inputVertices)[0]; + Vector3& v2 = (*inputVertices)[1]; decimal v1DotN = (v1 - planesPoints[p]).dot(planesNormals[p]); decimal v2DotN = (v2 - planesPoints[p]).dot(planesNormals[p]); @@ -257,39 +264,40 @@ std::vector reactphysics3d::clipSegmentWithPlanes(const Vector3& segA, decimal t = computePlaneSegmentIntersection(v1, v2, planesNormals[p].dot(planesPoints[p]), planesNormals[p]); if (t >= decimal(0) && t <= decimal(1.0)) { - outputVertices.push_back(v1 + t * (v2 - v1)); + outputVertices->add(v1 + t * (v2 - v1)); } else { - outputVertices.push_back(v2); + outputVertices->add(v2); } } else { - outputVertices.push_back(v1); + outputVertices->add(v1); } // Add the second vertex - outputVertices.push_back(v2); + outputVertices->add(v2); } else { // If the second vertex is behind the clipping plane // If the first vertex is in front of the clippling plane if (v1DotN >= decimal(0.0)) { - outputVertices.push_back(v1); + outputVertices->add(v1); // The first point we keep is the intersection between the segment v1, v2 and the clipping plane decimal t = computePlaneSegmentIntersection(v1, v2, -planesNormals[p].dot(planesPoints[p]), -planesNormals[p]); if (t >= decimal(0.0) && t <= decimal(1.0)) { - outputVertices.push_back(v1 + t * (v2 - v1)); + outputVertices->add(v1 + t * (v2 - v1)); } } } inputVertices = outputVertices; + outputVertices = p % 2 == 0 ? &list1 : &list2; } - return outputVertices; + return *outputVertices; } // Clip a polygon against multiple planes and return the clipped polygon vertices @@ -302,7 +310,6 @@ List reactphysics3d::clipPolygonWithPlanes(const List& polygon uint nbMaxElements = polygonVertices.size() + planesPoints.size(); List list1(allocator, nbMaxElements); List list2(allocator, nbMaxElements); - List dotProducts(allocator, nbMaxElements * 2); const List* inputVertices = &polygonVertices; List* outputVertices = &list2; diff --git a/src/mathematics/mathematics_functions.h b/src/mathematics/mathematics_functions.h index ff6ac6f4..5081d741 100755 --- a/src/mathematics/mathematics_functions.h +++ b/src/mathematics/mathematics_functions.h @@ -112,9 +112,10 @@ decimal computePlaneSegmentIntersection(const Vector3& segA, const Vector3& segB decimal computePointToLineDistance(const Vector3& linePointA, const Vector3& linePointB, const Vector3& point); /// Clip a segment against multiple planes and return the clipped segment vertices -std::vector clipSegmentWithPlanes(const Vector3& segA, const Vector3& segB, - const std::vector& planesPoints, - const std::vector& planesNormals); +List clipSegmentWithPlanes(const Vector3& segA, const Vector3& segB, + const List& planesPoints, + const List& planesNormals, + Allocator& allocator); /// Clip a polygon against multiple planes and return the clipped polygon vertices List clipPolygonWithPlanes(const List& polygonVertices, const List& planesPoints, From 8f126a75d6d38dd4152739fab4257bd0f427e514 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 27 Dec 2017 20:53:09 +0100 Subject: [PATCH 152/248] Use List in HalfEdgeStructure with some changes in memory allocation --- CMakeLists.txt | 2 + src/body/CollisionBody.cpp | 2 +- src/body/RigidBody.cpp | 2 +- src/collision/CollisionDetection.cpp | 7 + src/collision/ContactManifoldSet.cpp | 1 - src/collision/HalfEdgeStructure.cpp | 4 +- src/collision/HalfEdgeStructure.h | 29 +- src/collision/MiddlePhaseTriangleCallback.cpp | 2 +- src/collision/NarrowPhaseInfo.cpp | 6 +- src/collision/PolyhedronMesh.cpp | 11 +- src/collision/PolyhedronMesh.h | 1 + src/collision/ProxyShape.cpp | 6 +- src/collision/ProxyShape.h | 5 +- .../narrowphase/SAT/SATAlgorithm.cpp | 5 +- src/collision/shapes/BoxShape.cpp | 33 +- src/collision/shapes/BoxShape.h | 4 +- src/collision/shapes/CapsuleShape.cpp | 2 +- src/collision/shapes/CapsuleShape.h | 2 +- src/collision/shapes/CollisionShape.h | 2 +- src/collision/shapes/ConcaveMeshShape.cpp | 8 +- src/collision/shapes/ConcaveMeshShape.h | 7 +- src/collision/shapes/ConvexMeshShape.cpp | 2 +- src/collision/shapes/ConvexMeshShape.h | 2 +- src/collision/shapes/HeightFieldShape.cpp | 8 +- src/collision/shapes/HeightFieldShape.h | 7 +- src/collision/shapes/SphereShape.cpp | 2 +- src/collision/shapes/SphereShape.h | 2 +- src/collision/shapes/TriangleShape.cpp | 15 +- src/collision/shapes/TriangleShape.h | 7 +- src/containers/List.h | 105 ++-- src/engine/CollisionWorld.cpp | 1 - src/engine/CollisionWorld.h | 1 + src/engine/OverlappingPair.cpp | 20 +- src/memory/MemoryManager.cpp | 32 ++ src/memory/MemoryManager.h | 74 +++ src/memory/PoolAllocator.cpp | 2 +- src/memory/PoolAllocator.h | 2 +- test/tests/collision/TestCollisionWorld.h | 499 +++++++++++++----- test/tests/collision/TestDynamicAABBTree.h | 29 + test/tests/collision/TestHalfEdgeStructure.h | 47 +- test/tests/collision/TestRaycast.h | 4 +- .../mathematics/TestMathematicsFunctions.h | 18 +- 42 files changed, 730 insertions(+), 290 deletions(-) create mode 100644 src/memory/MemoryManager.cpp create mode 100644 src/memory/MemoryManager.h mode change 100644 => 100755 test/tests/collision/TestCollisionWorld.h mode change 100644 => 100755 test/tests/collision/TestDynamicAABBTree.h diff --git a/CMakeLists.txt b/CMakeLists.txt index e7e2df87..e585e0d1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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" diff --git a/src/body/CollisionBody.cpp b/src/body/CollisionBody.cpp index e588f93c..56493d28 100644 --- a/src/body/CollisionBody.cpp +++ b/src/body/CollisionBody.cpp @@ -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 diff --git a/src/body/RigidBody.cpp b/src/body/RigidBody.cpp index e4ce4458..7419fc4c 100644 --- a/src/body/RigidBody.cpp +++ b/src/body/RigidBody.cpp @@ -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 diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index c0b4d4e9..e57c5fd8 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -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 diff --git a/src/collision/ContactManifoldSet.cpp b/src/collision/ContactManifoldSet.cpp index ce3e4492..5f70bbc0 100644 --- a/src/collision/ContactManifoldSet.cpp +++ b/src/collision/ContactManifoldSet.cpp @@ -225,7 +225,6 @@ void ContactManifoldSet::removeManifold(ContactManifold* manifold) { // Delete the contact manifold manifold->~ContactManifold(); mMemoryAllocator.release(manifold, sizeof(ContactManifold)); - mNbManifolds--; } diff --git a/src/collision/HalfEdgeStructure.cpp b/src/collision/HalfEdgeStructure.cpp index 0f7b8f6e..70a731d5 100644 --- a/src/collision/HalfEdgeStructure.cpp +++ b/src/collision/HalfEdgeStructure.cpp @@ -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); diff --git a/src/collision/HalfEdgeStructure.h b/src/collision/HalfEdgeStructure.h index ec4fff35..e398913f 100644 --- a/src/collision/HalfEdgeStructure.h +++ b/src/collision/HalfEdgeStructure.h @@ -50,14 +50,14 @@ class HalfEdgeStructure { }; struct Face { - uint edgeIndex; // Index of an half-edge of the face - std::vector faceVertices; // Index of the vertices of the face + uint edgeIndex; // Index of an half-edge of the face + List faceVertices; // Index of the vertices of the face /// Constructor - Face() {} + Face(Allocator& allocator) : faceVertices(allocator) {} /// Constructor - Face(std::vector vertices) : faceVertices(vertices) {} + Face(List vertices) : faceVertices(vertices) {} }; struct Vertex { @@ -70,19 +70,24 @@ class HalfEdgeStructure { private: + /// Reference to a memory allocator + Allocator& mAllocator; + /// All the faces - std::vector mFaces; + List mFaces; /// All the vertices - std::vector mVertices; + List mVertices; /// All the half-edges - std::vector mEdges; + List 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 faceVertices); + void addFace(List 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 faceVertices) { +inline void HalfEdgeStructure::addFace(List faceVertices) { // Create a new face Face face(faceVertices); - mFaces.push_back(face); + mFaces.add(face); } // Return the number of faces diff --git a/src/collision/MiddlePhaseTriangleCallback.cpp b/src/collision/MiddlePhaseTriangleCallback.cpp index f8736a0b..a53271a4 100644 --- a/src/collision/MiddlePhaseTriangleCallback.cpp +++ b/src/collision/MiddlePhaseTriangleCallback.cpp @@ -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 diff --git a/src/collision/NarrowPhaseInfo.cpp b/src/collision/NarrowPhaseInfo.cpp index a6440367..0189db99 100644 --- a/src/collision/NarrowPhaseInfo.cpp +++ b/src/collision/NarrowPhaseInfo.cpp @@ -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 diff --git a/src/collision/PolyhedronMesh.cpp b/src/collision/PolyhedronMesh.cpp index ec8b661d..08a84e7d 100644 --- a/src/collision/PolyhedronMesh.cpp +++ b/src/collision/PolyhedronMesh.cpp @@ -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 faceVertices; + List 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); diff --git a/src/collision/PolyhedronMesh.h b/src/collision/PolyhedronMesh.h index a64db670..b459723a 100644 --- a/src/collision/PolyhedronMesh.h +++ b/src/collision/PolyhedronMesh.h @@ -30,6 +30,7 @@ #include "mathematics/mathematics.h" #include "HalfEdgeStructure.h" #include "collision/PolygonVertexArray.h" +#include "memory/DefaultAllocator.h" #include namespace reactphysics3d { diff --git a/src/collision/ProxyShape.cpp b/src/collision/ProxyShape.cpp index 6e6eefbd..f782b2a8 100644 --- a/src/collision/ProxyShape.cpp +++ b/src/collision/ProxyShape.cpp @@ -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; diff --git a/src/collision/ProxyShape.h b/src/collision/ProxyShape.h index 8e9a9e9f..0ba34698 100644 --- a/src/collision/ProxyShape.h +++ b/src/collision/ProxyShape.h @@ -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(); diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 2605eaf9..1992cbc7 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -835,9 +835,8 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene List planesPoints(mMemoryAllocator, nbIncidentFaceVertices); // Points on the clipping planes // Get all the vertices of the incident face (in the reference local-space) - std::vector::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); } diff --git a/src/collision/shapes/BoxShape.cpp b/src/collision/shapes/BoxShape.cpp index 37667958..079b15c5 100644 --- a/src/collision/shapes/BoxShape.cpp +++ b/src/collision/shapes/BoxShape.cpp @@ -27,6 +27,7 @@ #include "BoxShape.h" #include "collision/ProxyShape.h" #include "configuration.h" +#include "memory/MemoryManager.h" #include #include @@ -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 face0; - face0.push_back(0); face0.push_back(1); face0.push_back(2); face0.push_back(3); - std::vector face1; - face1.push_back(1); face1.push_back(5); face1.push_back(6); face1.push_back(2); - std::vector face2; - face2.push_back(4); face2.push_back(7); face2.push_back(6); face2.push_back(5); - std::vector face3; - face3.push_back(4); face3.push_back(0); face3.push_back(3); face3.push_back(7); - std::vector face4; - face4.push_back(4); face4.push_back(5); face4.push_back(1); face4.push_back(0); - std::vector face5; - face5.push_back(2); face5.push_back(6); face5.push_back(7); face5.push_back(3); + List face0(allocator, 4); + face0.add(0); face0.add(1); face0.add(2); face0.add(3); + List face1(allocator, 4); + face1.add(1); face1.add(5); face1.add(6); face1.add(2); + List face2(allocator, 4); + face2.add(4); face2.add(7); face2.add(6); face2.add(5); + List face3(allocator, 4); + face3.add(4); face3.add(0); face3.add(3); face3.add(7); + List face4(allocator, 4); + face4.add(4); face4.add(5); face4.add(1); face4.add(0); + List 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; diff --git a/src/collision/shapes/BoxShape.h b/src/collision/shapes/BoxShape.h index d1aa9810..b3e094bd 100644 --- a/src/collision/shapes/BoxShape.h +++ b/src/collision/shapes/BoxShape.h @@ -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; diff --git a/src/collision/shapes/CapsuleShape.cpp b/src/collision/shapes/CapsuleShape.cpp index 32ea146c..da29fede 100644 --- a/src/collision/shapes/CapsuleShape.cpp +++ b/src/collision/shapes/CapsuleShape.cpp @@ -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; diff --git a/src/collision/shapes/CapsuleShape.h b/src/collision/shapes/CapsuleShape.h index 8aebff58..0da2d1f4 100644 --- a/src/collision/shapes/CapsuleShape.h +++ b/src/collision/shapes/CapsuleShape.h @@ -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, diff --git a/src/collision/shapes/CollisionShape.h b/src/collision/shapes/CollisionShape.h index 6792cc09..4381b05c 100644 --- a/src/collision/shapes/CollisionShape.h +++ b/src/collision/shapes/CollisionShape.h @@ -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; diff --git a/src/collision/shapes/ConcaveMeshShape.cpp b/src/collision/shapes/ConcaveMeshShape.cpp index ee90ce46..0b49f20c 100644 --- a/src/collision/shapes/ConcaveMeshShape.cpp +++ b/src/collision/shapes/ConcaveMeshShape.cpp @@ -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) { diff --git a/src/collision/shapes/ConcaveMeshShape.h b/src/collision/shapes/ConcaveMeshShape.h index 2d0a3e9c..52d49a02 100644 --- a/src/collision/shapes/ConcaveMeshShape.h +++ b/src/collision/shapes/ConcaveMeshShape.h @@ -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; diff --git a/src/collision/shapes/ConvexMeshShape.cpp b/src/collision/shapes/ConvexMeshShape.cpp index f6011375..19ef5016 100644 --- a/src/collision/shapes/ConvexMeshShape.cpp +++ b/src/collision/shapes/ConvexMeshShape.cpp @@ -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); } diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index 0ce696af..1c33d919 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -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; diff --git a/src/collision/shapes/HeightFieldShape.cpp b/src/collision/shapes/HeightFieldShape.cpp index 74276a75..f067a827 100644 --- a/src/collision/shapes/HeightFieldShape.cpp +++ b/src/collision/shapes/HeightFieldShape.cpp @@ -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) { diff --git a/src/collision/shapes/HeightFieldShape.h b/src/collision/shapes/HeightFieldShape.h index f8b498d5..4190c3c7 100644 --- a/src/collision/shapes/HeightFieldShape.h +++ b/src/collision/shapes/HeightFieldShape.h @@ -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; diff --git a/src/collision/shapes/SphereShape.cpp b/src/collision/shapes/SphereShape.cpp index fa6b4f6a..7d155f97 100644 --- a/src/collision/shapes/SphereShape.cpp +++ b/src/collision/shapes/SphereShape.cpp @@ -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; diff --git a/src/collision/shapes/SphereShape.h b/src/collision/shapes/SphereShape.h index 70f651de..18883d79 100644 --- a/src/collision/shapes/SphereShape.h +++ b/src/collision/shapes/SphereShape.h @@ -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; diff --git a/src/collision/shapes/TriangleShape.cpp b/src/collision/shapes/TriangleShape.cpp index e43cc674..4a7eb013 100644 --- a/src/collision/shapes/TriangleShape.cpp +++ b/src/collision/shapes/TriangleShape.cpp @@ -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); diff --git a/src/collision/shapes/TriangleShape.h b/src/collision/shapes/TriangleShape.h index a4ce7726..9a2c756e 100644 --- a/src/collision/shapes/TriangleShape.h +++ b/src/collision/shapes/TriangleShape.h @@ -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; diff --git a/src/containers/List.h b/src/containers/List.h index 4915f32d..71ae7ef7 100644 --- a/src/containers/List.h +++ b/src/containers/List.h @@ -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(mElements), mSize * sizeof(T)); - - // Release the previously allocated memory - mAllocator.release(mElements, mCapacity * sizeof(T)); - } - - mElements = static_cast(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& list) : mElements(nullptr), mSize(0), mCapacity(0), mAllocator(list.mAllocator) { + List(const List& 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(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(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(mBuffer)[index]).~T(); + + mSize--; + + if (index != mSize) { + + // Move the elements to fill in the empty slot + char* dest = static_cast(mBuffer) + index * sizeof(T); + char* src = dest + sizeof(T); + std::memcpy(static_cast(dest), static_cast(src), (mSize - index) * sizeof(T)); + } + } + /// Append another list to the current one void addRange(const List& 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(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(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(mBuffer)[index]); } /// Overloaded const index operator const T& operator[](const uint index) const { assert(index >= 0 && index < mSize); - return mElements[index]; + return (static_cast(mBuffer)[index]); } /// Overloaded assignment operator diff --git a/src/engine/CollisionWorld.cpp b/src/engine/CollisionWorld.cpp index eeb06305..8b29e4a1 100644 --- a/src/engine/CollisionWorld.cpp +++ b/src/engine/CollisionWorld.cpp @@ -187,4 +187,3 @@ AABB CollisionWorld::getWorldAABB(const ProxyShape* proxyShape) const { return mCollisionDetection.getWorldAABB(proxyShape); } - diff --git a/src/engine/CollisionWorld.h b/src/engine/CollisionWorld.h index 6c558d6d..ead42710 100644 --- a/src/engine/CollisionWorld.h +++ b/src/engine/CollisionWorld.h @@ -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" diff --git a/src/engine/OverlappingPair.cpp b/src/engine/OverlappingPair.cpp index eba2fb80..431476ed 100644 --- a/src/engine/OverlappingPair.cpp +++ b/src/engine/OverlappingPair.cpp @@ -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; diff --git a/src/memory/MemoryManager.cpp b/src/memory/MemoryManager.cpp new file mode 100644 index 00000000..85832cb1 --- /dev/null +++ b/src/memory/MemoryManager.cpp @@ -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; diff --git a/src/memory/MemoryManager.h b/src/memory/MemoryManager.h new file mode 100644 index 00000000..922a5a17 --- /dev/null +++ b/src/memory/MemoryManager.h @@ -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 + diff --git a/src/memory/PoolAllocator.cpp b/src/memory/PoolAllocator.cpp index dc1306bc..53cee0a1 100644 --- a/src/memory/PoolAllocator.cpp +++ b/src/memory/PoolAllocator.cpp @@ -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 diff --git a/src/memory/PoolAllocator.h b/src/memory/PoolAllocator.h index 0664e559..b06778d5 100644 --- a/src/memory/PoolAllocator.h +++ b/src/memory/PoolAllocator.h @@ -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]; diff --git a/test/tests/collision/TestCollisionWorld.h b/test/tests/collision/TestCollisionWorld.h old mode 100644 new mode 100755 index 678b5f21..ad0c92cf --- a/test/tests/collision/TestCollisionWorld.h +++ b/test/tests/collision/TestCollisionWorld.h @@ -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 contactPoints; + + int getNbContactPoints() const { + return contactPoints.size(); + } + + bool hasContactPointSimilarTo(const Vector3& localPointBody1, const Vector3& localPointBody2, decimal penetrationDepth, decimal epsilon = 0.001) { + + std::vector::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 proxyShapes; + std::pair bodies; + std::vector contactManifolds; + + int getNbContactManifolds() const { + return contactManifolds.size(); + } + + int getTotalNbContactPoints() const { + + int nbPoints = 0; + + std::vector::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::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> mCollisionData; + + std::pair getCollisionKeyPair(std::pair 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); + } }; } diff --git a/test/tests/collision/TestDynamicAABBTree.h b/test/tests/collision/TestDynamicAABBTree.h old mode 100644 new mode 100755 index 7ab3202b..53f5e618 --- a/test/tests/collision/TestDynamicAABBTree.h +++ b/test/tests/collision/TestDynamicAABBTree.h @@ -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 } }; diff --git a/test/tests/collision/TestHalfEdgeStructure.h b/test/tests/collision/TestHalfEdgeStructure.h index 4c4a2b39..35f357b3 100644 --- a/test/tests/collision/TestHalfEdgeStructure.h +++ b/test/tests/collision/TestHalfEdgeStructure.h @@ -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 face0; - face0.push_back(0); face0.push_back(1); face0.push_back(2); face0.push_back(3); - std::vector face1; - face1.push_back(1); face1.push_back(5); face1.push_back(6); face1.push_back(2); - std::vector face2; - face2.push_back(5); face2.push_back(4); face2.push_back(7); face2.push_back(6); - std::vector face3; - face3.push_back(4); face3.push_back(0); face3.push_back(3); face3.push_back(7); - std::vector face4; - face4.push_back(0); face4.push_back(4); face4.push_back(5); face4.push_back(1); - std::vector face5; - face5.push_back(2); face5.push_back(6); face5.push_back(7); face5.push_back(3); + List face0(mAllocator, 4); + face0.add(0); face0.add(1); face0.add(2); face0.add(3); + List face1(mAllocator, 4); + face1.add(1); face1.add(5); face1.add(6); face1.add(2); + List face2(mAllocator, 4); + face2.add(5); face2.add(4); face2.add(7); face2.add(6); + List face3(mAllocator, 4); + face3.add(4); face3.add(0); face3.add(3); face3.add(7); + List face4(mAllocator, 4); + face4.add(0); face4.add(4); face4.add(5); face4.add(1); + List 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> 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 face0; - face0.push_back(0); face0.push_back(1); face0.push_back(2); - std::vector face1; - face1.push_back(0); face1.push_back(3); face1.push_back(1); - std::vector face2; - face2.push_back(1); face2.push_back(3); face2.push_back(2); - std::vector face3; - face3.push_back(0); face3.push_back(2); face3.push_back(3); + List face0(mAllocator, 3); + face0.add(0); face0.add(1); face0.add(2); + List face1(mAllocator, 3); + face1.add(0); face1.add(3); face1.add(1); + List face2(mAllocator, 3); + face2.add(1); face2.add(3); face2.add(2); + List face3(mAllocator, 3); + face3.add(0); face3.add(2); face3.add(3); tetrahedron.addFace(face0); tetrahedron.addFace(face1); diff --git a/test/tests/collision/TestRaycast.h b/test/tests/collision/TestRaycast.h index 97dd002a..d02ab847 100644 --- a/test/tests/collision/TestRaycast.h +++ b/test/tests/collision/TestRaycast.h @@ -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); diff --git a/test/tests/mathematics/TestMathematicsFunctions.h b/test/tests/mathematics/TestMathematicsFunctions.h index 793a79fb..b76cb78c 100644 --- a/test/tests/mathematics/TestMathematicsFunctions.h +++ b/test/tests/mathematics/TestMathematicsFunctions.h @@ -176,13 +176,13 @@ class TestMathematicsFunctions : public Test { segmentVertices.push_back(Vector3(-6, 3, 0)); segmentVertices.push_back(Vector3(8, 3, 0)); - std::vector planesNormals; - std::vector planesPoints; - planesNormals.push_back(Vector3(-1, 0, 0)); - planesPoints.push_back(Vector3(4, 0, 0)); + List planesNormals(mAllocator, 2); + List planesPoints(mAllocator, 2); + planesNormals.add(Vector3(-1, 0, 0)); + planesPoints.add(Vector3(4, 0, 0)); - std::vector clipSegmentVertices = clipSegmentWithPlanes(segmentVertices[0], segmentVertices[1], - planesPoints, planesNormals); + List 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() From 261ffef616b8d6af37eefd0beec52d2c3bb7a5ff Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 1 Jan 2018 18:35:57 +0100 Subject: [PATCH 153/248] Refactor memory allocation --- CMakeLists.txt | 2 +- src/body/CollisionBody.cpp | 12 +-- src/body/RigidBody.cpp | 12 ++- src/body/RigidBody.h | 4 +- src/collision/CollisionCallback.cpp | 12 ++- src/collision/CollisionCallback.h | 6 +- src/collision/CollisionDetection.cpp | 97 ++++++++++--------- src/collision/CollisionDetection.h | 19 ++-- src/collision/ContactManifold.cpp | 2 +- src/collision/ContactManifold.h | 4 +- src/collision/ContactManifoldInfo.cpp | 2 +- src/collision/ContactManifoldInfo.h | 6 +- src/collision/ContactManifoldSet.cpp | 2 +- src/collision/ContactManifoldSet.h | 4 +- src/collision/HalfEdgeStructure.h | 6 +- src/collision/MiddlePhaseTriangleCallback.h | 4 +- src/collision/NarrowPhaseInfo.cpp | 6 +- src/collision/NarrowPhaseInfo.h | 4 +- src/collision/PolyhedronMesh.cpp | 4 +- src/collision/ProxyShape.cpp | 8 +- src/collision/ProxyShape.h | 9 +- .../broadphase/BroadPhaseAlgorithm.cpp | 4 +- .../broadphase/BroadPhaseAlgorithm.h | 2 +- .../narrowphase/CapsuleVsCapsuleAlgorithm.cpp | 2 +- .../narrowphase/CapsuleVsCapsuleAlgorithm.h | 2 +- .../CapsuleVsConvexPolyhedronAlgorithm.cpp | 2 +- .../CapsuleVsConvexPolyhedronAlgorithm.h | 2 +- ...xPolyhedronVsConvexPolyhedronAlgorithm.cpp | 2 +- ...vexPolyhedronVsConvexPolyhedronAlgorithm.h | 2 +- .../narrowphase/NarrowPhaseAlgorithm.h | 2 +- .../narrowphase/SAT/SATAlgorithm.cpp | 2 +- src/collision/narrowphase/SAT/SATAlgorithm.h | 4 +- .../narrowphase/SphereVsCapsuleAlgorithm.cpp | 2 +- .../narrowphase/SphereVsCapsuleAlgorithm.h | 2 +- .../SphereVsConvexPolyhedronAlgorithm.cpp | 2 +- .../SphereVsConvexPolyhedronAlgorithm.h | 2 +- .../narrowphase/SphereVsSphereAlgorithm.cpp | 2 +- .../narrowphase/SphereVsSphereAlgorithm.h | 2 +- src/collision/shapes/BoxShape.cpp | 6 +- src/collision/shapes/BoxShape.h | 2 +- src/collision/shapes/CapsuleShape.cpp | 2 +- src/collision/shapes/CapsuleShape.h | 2 +- src/collision/shapes/CollisionShape.h | 2 +- src/collision/shapes/ConcaveMeshShape.cpp | 2 +- src/collision/shapes/ConcaveMeshShape.h | 6 +- src/collision/shapes/ConvexMeshShape.cpp | 2 +- src/collision/shapes/ConvexMeshShape.h | 2 +- src/collision/shapes/HeightFieldShape.cpp | 2 +- src/collision/shapes/HeightFieldShape.h | 6 +- src/collision/shapes/SphereShape.cpp | 2 +- src/collision/shapes/SphereShape.h | 2 +- src/collision/shapes/TriangleShape.cpp | 4 +- src/collision/shapes/TriangleShape.h | 4 +- src/configuration.h | 2 +- src/containers/LinkedList.h | 6 +- src/containers/List.h | 6 +- src/engine/CollisionWorld.cpp | 8 +- src/engine/CollisionWorld.h | 10 +- src/engine/ContactSolver.cpp | 12 ++- src/engine/ContactSolver.h | 9 +- src/engine/DynamicsWorld.cpp | 63 +++++++----- src/engine/Island.cpp | 11 ++- src/engine/Island.h | 2 +- src/engine/OverlappingPair.cpp | 2 +- src/engine/OverlappingPair.h | 12 +-- src/mathematics/mathematics_functions.cpp | 4 +- src/mathematics/mathematics_functions.h | 4 +- src/memory/DefaultAllocator.h | 12 +-- src/memory/{Allocator.h => MemoryAllocator.h} | 19 ++-- src/memory/MemoryManager.cpp | 2 + src/memory/MemoryManager.h | 92 +++++++++++++++--- src/memory/PoolAllocator.cpp | 35 ++++--- src/memory/PoolAllocator.h | 16 +-- src/memory/SingleFrameAllocator.cpp | 75 ++++++++++++-- src/memory/SingleFrameAllocator.h | 34 ++++--- 75 files changed, 449 insertions(+), 296 deletions(-) rename src/memory/{Allocator.h => MemoryAllocator.h} (87%) diff --git a/CMakeLists.txt b/CMakeLists.txt index e585e0d1..bc11aebd 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -187,7 +187,7 @@ SET (REACTPHYSICS3D_SOURCES "src/mathematics/Vector3.h" "src/mathematics/Ray.h" "src/mathematics/Vector3.cpp" - "src/memory/Allocator.h" + "src/memory/MemoryAllocator.h" "src/memory/PoolAllocator.h" "src/memory/PoolAllocator.cpp" "src/memory/SingleFrameAllocator.h" diff --git a/src/body/CollisionBody.cpp b/src/body/CollisionBody.cpp index 56493d28..bb8b0408 100644 --- a/src/body/CollisionBody.cpp +++ b/src/body/CollisionBody.cpp @@ -70,9 +70,9 @@ ProxyShape* CollisionBody::addCollisionShape(CollisionShape* collisionShape, const Transform& transform) { // Create a new proxy collision shape to attach the collision shape to the body - ProxyShape* proxyShape = new (mWorld.mPoolAllocator.allocate( + ProxyShape* proxyShape = new (mWorld.mMemoryManager.allocate(MemoryManager::AllocationType::Pool, sizeof(ProxyShape))) ProxyShape(this, collisionShape, - transform, decimal(1), mWorld.mPoolAllocator); + transform, decimal(1), mWorld.mMemoryManager); #ifdef IS_PROFILING_ACTIVE @@ -123,7 +123,7 @@ void CollisionBody::removeCollisionShape(const ProxyShape* proxyShape) { } current->~ProxyShape(); - mWorld.mPoolAllocator.release(current, sizeof(ProxyShape)); + mWorld.mMemoryManager.release(MemoryManager::AllocationType::Pool, current, sizeof(ProxyShape)); mNbCollisionShapes--; return; } @@ -143,7 +143,7 @@ void CollisionBody::removeCollisionShape(const ProxyShape* proxyShape) { } elementToRemove->~ProxyShape(); - mWorld.mPoolAllocator.release(elementToRemove, sizeof(ProxyShape)); + mWorld.mMemoryManager.release(MemoryManager::AllocationType::Pool, elementToRemove, sizeof(ProxyShape)); mNbCollisionShapes--; return; } @@ -169,7 +169,7 @@ void CollisionBody::removeAllCollisionShapes() { } current->~ProxyShape(); - mWorld.mPoolAllocator.release(current, sizeof(ProxyShape)); + mWorld.mMemoryManager.release(MemoryManager::AllocationType::Pool, current, sizeof(ProxyShape)); // Get the next element in the list current = nextElement; @@ -188,7 +188,7 @@ void CollisionBody::resetContactManifoldsList() { // Delete the current element currentElement->~ContactManifoldListElement(); - mWorld.mPoolAllocator.release(currentElement, sizeof(ContactManifoldListElement)); + mWorld.mMemoryManager.release(MemoryManager::AllocationType::Pool, currentElement, sizeof(ContactManifoldListElement)); currentElement = nextElement; } diff --git a/src/body/RigidBody.cpp b/src/body/RigidBody.cpp index 7419fc4c..36c362dc 100644 --- a/src/body/RigidBody.cpp +++ b/src/body/RigidBody.cpp @@ -176,7 +176,7 @@ void RigidBody::setMass(decimal mass) { } // Remove a joint from the joints list -void RigidBody::removeJointFromJointsList(PoolAllocator& memoryAllocator, const Joint* joint) { +void RigidBody::removeJointFromJointsList(MemoryManager& memoryManager, const Joint* joint) { assert(joint != nullptr); assert(mJointsList != nullptr); @@ -186,7 +186,8 @@ void RigidBody::removeJointFromJointsList(PoolAllocator& memoryAllocator, const JointListElement* elementToRemove = mJointsList; mJointsList = elementToRemove->next; elementToRemove->~JointListElement(); - memoryAllocator.release(elementToRemove, sizeof(JointListElement)); + memoryManager.release(MemoryManager::AllocationType::Pool, + elementToRemove, sizeof(JointListElement)); } else { // If the element to remove is not the first one in the list JointListElement* currentElement = mJointsList; @@ -195,7 +196,8 @@ void RigidBody::removeJointFromJointsList(PoolAllocator& memoryAllocator, const JointListElement* elementToRemove = currentElement->next; currentElement->next = elementToRemove->next; elementToRemove->~JointListElement(); - memoryAllocator.release(elementToRemove, sizeof(JointListElement)); + memoryManager.release(MemoryManager::AllocationType::Pool, + elementToRemove, sizeof(JointListElement)); break; } currentElement = currentElement->next; @@ -224,9 +226,9 @@ ProxyShape* RigidBody::addCollisionShape(CollisionShape* collisionShape, decimal mass) { // Create a new proxy collision shape to attach the collision shape to the body - ProxyShape* proxyShape = new (mWorld.mPoolAllocator.allocate( + ProxyShape* proxyShape = new (mWorld.mMemoryManager.allocate(MemoryManager::AllocationType::Pool, sizeof(ProxyShape))) ProxyShape(this, collisionShape, - transform, mass, mWorld.mPoolAllocator); + transform, mass, mWorld.mMemoryManager); #ifdef IS_PROFILING_ACTIVE diff --git a/src/body/RigidBody.h b/src/body/RigidBody.h index e12cab05..23603bda 100644 --- a/src/body/RigidBody.h +++ b/src/body/RigidBody.h @@ -31,7 +31,7 @@ #include "CollisionBody.h" #include "engine/Material.h" #include "mathematics/mathematics.h" -#include "memory/PoolAllocator.h" +#include "memory/MemoryManager.h" /// Namespace reactphysics3d namespace reactphysics3d { @@ -112,7 +112,7 @@ class RigidBody : public CollisionBody { // -------------------- Methods -------------------- // /// Remove a joint from the joints list - void removeJointFromJointsList(PoolAllocator& memoryAllocator, const Joint* joint); + void removeJointFromJointsList(reactphysics3d::MemoryManager& memoryManager, const Joint* joint); /// Update the transform of the body after a change of the center of mass void updateTransformWithCenterOfMass(); diff --git a/src/collision/CollisionCallback.cpp b/src/collision/CollisionCallback.cpp index db820db4..1702e40a 100644 --- a/src/collision/CollisionCallback.cpp +++ b/src/collision/CollisionCallback.cpp @@ -26,18 +26,18 @@ // Libraries #include "collision/CollisionCallback.h" #include "engine/OverlappingPair.h" -#include "memory/Allocator.h" +#include "memory/MemoryAllocator.h" #include "collision/ContactManifold.h" // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; // Constructor -CollisionCallback::CollisionCallbackInfo::CollisionCallbackInfo(OverlappingPair* pair, Allocator& allocator) : +CollisionCallback::CollisionCallbackInfo::CollisionCallbackInfo(OverlappingPair* pair, MemoryManager& memoryManager) : contactManifoldElements(nullptr), body1(pair->getShape1()->getBody()), body2(pair->getShape2()->getBody()), proxyShape1(pair->getShape1()), proxyShape2(pair->getShape2()), - mMemoryAllocator(allocator) { + mMemoryManager(memoryManager) { assert(pair != nullptr); @@ -52,7 +52,8 @@ CollisionCallback::CollisionCallbackInfo::CollisionCallbackInfo(OverlappingPair* // Add the contact manifold at the beginning of the linked // list of contact manifolds of the first body - ContactManifoldListElement* element = new (mMemoryAllocator.allocate(sizeof(ContactManifoldListElement))) + ContactManifoldListElement* element = new (mMemoryManager.allocate(MemoryManager::AllocationType::Pool, + sizeof(ContactManifoldListElement))) ContactManifoldListElement(contactManifold, contactManifoldElements); contactManifoldElements = element; @@ -72,7 +73,8 @@ CollisionCallback::CollisionCallbackInfo::~CollisionCallbackInfo() { // Delete and release memory element->~ContactManifoldListElement(); - mMemoryAllocator.release(element, sizeof(ContactManifoldListElement)); + mMemoryManager.release(MemoryManager::AllocationType::Pool, element, + sizeof(ContactManifoldListElement)); element = nextElement; } diff --git a/src/collision/CollisionCallback.h b/src/collision/CollisionCallback.h index 54208fe4..57ae0f04 100644 --- a/src/collision/CollisionCallback.h +++ b/src/collision/CollisionCallback.h @@ -69,11 +69,11 @@ class CollisionCallback { /// Pointer to the proxy shape of second body const ProxyShape* proxyShape2; - /// Memory allocator - Allocator& mMemoryAllocator; + /// Memory manager + MemoryManager& mMemoryManager; // Constructor - CollisionCallbackInfo(OverlappingPair* pair, Allocator& allocator); + CollisionCallbackInfo(OverlappingPair* pair, MemoryManager& memoryManager); // Destructor ~CollisionCallbackInfo(); diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index e57c5fd8..66cf1eb5 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -47,9 +47,8 @@ using namespace reactphysics3d; using namespace std; // Constructor -CollisionDetection::CollisionDetection(CollisionWorld* world, PoolAllocator& memoryAllocator, SingleFrameAllocator& singleFrameAllocator) - : mPoolAllocator(memoryAllocator), mSingleFrameAllocator(singleFrameAllocator), - mWorld(world), mNarrowPhaseInfoList(nullptr), mBroadPhaseAlgorithm(*this), +CollisionDetection::CollisionDetection(CollisionWorld* world, MemoryManager& memoryManager) + : mMemoryManager(memoryManager), mWorld(world), mNarrowPhaseInfoList(nullptr), mBroadPhaseAlgorithm(*this), mIsCollisionShapesAdded(false) { // Set the default collision dispatch configuration @@ -95,7 +94,7 @@ void CollisionDetection::computeBroadPhase() { // Ask the broad-phase to recompute the overlapping pairs of collision // shapes. This call can only add new overlapping pairs in the collision // detection. - mBroadPhaseAlgorithm.computeOverlappingPairs(mPoolAllocator); + mBroadPhaseAlgorithm.computeOverlappingPairs(mMemoryManager); } } @@ -133,7 +132,7 @@ void CollisionDetection::computeMiddlePhase() { // Destroy the overlapping pair itToRemove->second->~OverlappingPair(); - mWorld->mPoolAllocator.release(itToRemove->second, sizeof(OverlappingPair)); + mWorld->mMemoryManager.release(MemoryManager::AllocationType::Pool, itToRemove->second, sizeof(OverlappingPair)); mOverlappingPairs.erase(itToRemove); continue; } @@ -166,10 +165,10 @@ void CollisionDetection::computeMiddlePhase() { // No middle-phase is necessary, simply create a narrow phase info // for the narrow-phase collision detection NarrowPhaseInfo* firstNarrowPhaseInfo = mNarrowPhaseInfoList; - mNarrowPhaseInfoList = new (mSingleFrameAllocator.allocate(sizeof(NarrowPhaseInfo))) + mNarrowPhaseInfoList = new (mMemoryManager.allocate(MemoryManager::AllocationType::Frame, sizeof(NarrowPhaseInfo))) NarrowPhaseInfo(pair, shape1->getCollisionShape(), shape2->getCollisionShape(), shape1->getLocalToWorldTransform(), - shape2->getLocalToWorldTransform(), mSingleFrameAllocator); + shape2->getLocalToWorldTransform(), mMemoryManager.getSingleFrameAllocator()); mNarrowPhaseInfoList->next = firstNarrowPhaseInfo; } @@ -177,7 +176,7 @@ void CollisionDetection::computeMiddlePhase() { else if ((!isShape1Convex && isShape2Convex) || (!isShape2Convex && isShape1Convex)) { NarrowPhaseInfo* narrowPhaseInfo = nullptr; - computeConvexVsConcaveMiddlePhase(pair, mSingleFrameAllocator, &narrowPhaseInfo); + computeConvexVsConcaveMiddlePhase(pair, mMemoryManager.getSingleFrameAllocator(), &narrowPhaseInfo); // Add all the narrow-phase info object reported by the callback into the // list of all the narrow-phase info object @@ -202,7 +201,7 @@ void CollisionDetection::computeMiddlePhase() { } // Compute the concave vs convex middle-phase algorithm for a given pair of bodies -void CollisionDetection::computeConvexVsConcaveMiddlePhase(OverlappingPair* pair, Allocator& allocator, +void CollisionDetection::computeConvexVsConcaveMiddlePhase(OverlappingPair* pair, MemoryAllocator& allocator, NarrowPhaseInfo** firstNarrowPhaseInfo) { ProxyShape* shape1 = pair->getShape1(); @@ -273,7 +272,7 @@ void CollisionDetection::computeNarrowPhase() { // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - if (narrowPhaseAlgorithm->testCollision(currentNarrowPhaseInfo, true, mSingleFrameAllocator)) { + if (narrowPhaseAlgorithm->testCollision(currentNarrowPhaseInfo, true, mMemoryManager.getSingleFrameAllocator())) { // Add the contact points as a potential contact manifold into the pair currentNarrowPhaseInfo->addContactPointsAsPotentialContactManifold(); @@ -295,7 +294,7 @@ void CollisionDetection::computeNarrowPhase() { narrowPhaseInfoToDelete->~NarrowPhaseInfo(); // Release the allocated memory for the narrow phase info - mSingleFrameAllocator.release(narrowPhaseInfoToDelete, sizeof(NarrowPhaseInfo)); + mMemoryManager.release(MemoryManager::AllocationType::Frame, narrowPhaseInfoToDelete, sizeof(NarrowPhaseInfo)); } // Convert the potential contact into actual contacts @@ -327,8 +326,9 @@ void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, Pro if (mOverlappingPairs.find(pairID) != mOverlappingPairs.end()) return; // Create the overlapping pair and add it into the set of overlapping pairs - OverlappingPair* newPair = new (mPoolAllocator.allocate(sizeof(OverlappingPair))) - OverlappingPair(shape1, shape2, mPoolAllocator, mSingleFrameAllocator); + OverlappingPair* newPair = new (mMemoryManager.allocate(MemoryManager::AllocationType::Pool, sizeof(OverlappingPair))) + OverlappingPair(shape1, shape2, mMemoryManager.getPoolAllocator(), + mMemoryManager.getSingleFrameAllocator()); assert(newPair != nullptr); #ifndef NDEBUG @@ -359,7 +359,7 @@ void CollisionDetection::removeProxyCollisionShape(ProxyShape* proxyShape) { // Destroy the overlapping pair itToRemove->second->~OverlappingPair(); - mWorld->mPoolAllocator.release(itToRemove->second, sizeof(OverlappingPair)); + mWorld->mMemoryManager.release(MemoryManager::AllocationType::Pool, itToRemove->second, sizeof(OverlappingPair)); mOverlappingPairs.erase(itToRemove); } else { @@ -403,14 +403,16 @@ void CollisionDetection::addContactManifoldToBody(OverlappingPair* pair) { // Add the contact manifold at the beginning of the linked // list of contact manifolds of the first body - ContactManifoldListElement* listElement1 = new (mPoolAllocator.allocate(sizeof(ContactManifoldListElement))) + ContactManifoldListElement* listElement1 = new (mMemoryManager.allocate(MemoryManager::AllocationType::Pool, + sizeof(ContactManifoldListElement))) ContactManifoldListElement(contactManifold, body1->mContactManifoldsList); body1->mContactManifoldsList = listElement1; // Add the contact manifold at the beginning of the linked // list of the contact manifolds of the second body - ContactManifoldListElement* listElement2 = new (mPoolAllocator.allocate(sizeof(ContactManifoldListElement))) + ContactManifoldListElement* listElement2 = new (mMemoryManager.allocate(MemoryManager::AllocationType::Pool, + sizeof(ContactManifoldListElement))) ContactManifoldListElement(contactManifold, body2->mContactManifoldsList); body2->mContactManifoldsList = listElement2; @@ -470,7 +472,7 @@ void CollisionDetection::reportAllContacts() { // If there is a user callback if (mWorld->mEventListener != nullptr && it->second->hasContacts()) { - CollisionCallback::CollisionCallbackInfo collisionInfo(it->second, mPoolAllocator); + CollisionCallback::CollisionCallbackInfo collisionInfo(it->second, mMemoryManager); // Trigger a callback event to report the new contact to the user mWorld->mEventListener->newContact(collisionInfo); @@ -498,9 +500,10 @@ NarrowPhaseInfo* CollisionDetection::computeMiddlePhaseForProxyShapes(Overlappin // No middle-phase is necessary, simply create a narrow phase info // for the narrow-phase collision detection - narrowPhaseInfo = new (mPoolAllocator.allocate(sizeof(NarrowPhaseInfo))) NarrowPhaseInfo(pair, shape1->getCollisionShape(), + narrowPhaseInfo = new (mMemoryManager.allocate(MemoryManager::AllocationType::Pool, + sizeof(NarrowPhaseInfo))) NarrowPhaseInfo(pair, shape1->getCollisionShape(), shape2->getCollisionShape(), shape1->getLocalToWorldTransform(), - shape2->getLocalToWorldTransform(), mPoolAllocator); + shape2->getLocalToWorldTransform(), mMemoryManager.getPoolAllocator()); } // Concave vs Convex algorithm @@ -508,7 +511,7 @@ NarrowPhaseInfo* CollisionDetection::computeMiddlePhaseForProxyShapes(Overlappin // Run the middle-phase collision detection algorithm to find the triangles of the concave // shape we need to use during the narrow-phase collision detection - computeConvexVsConcaveMiddlePhase(pair, mPoolAllocator, &narrowPhaseInfo); + computeConvexVsConcaveMiddlePhase(pair, mMemoryManager.getPoolAllocator(), &narrowPhaseInfo); } pair->clearObsoleteLastFrameCollisionInfos(); @@ -524,7 +527,7 @@ void CollisionDetection::testAABBOverlap(const AABB& aabb, OverlapCallback* over std::unordered_set reportedBodies; // Ask the broad-phase to get all the overlapping shapes - LinkedList overlappingNodes(mPoolAllocator); + LinkedList overlappingNodes(mMemoryManager.getPoolAllocator()); mBroadPhaseAlgorithm.reportAllShapesOverlappingWithAABB(aabb, overlappingNodes); // For each overlaping proxy shape @@ -575,7 +578,8 @@ bool CollisionDetection::testOverlap(CollisionBody* body1, CollisionBody* body2) if (aabb1.testCollision(aabb2)) { // Create a temporary overlapping pair - OverlappingPair pair(body1ProxyShape, body2ProxyShape, mPoolAllocator, mPoolAllocator); + OverlappingPair pair(body1ProxyShape, body2ProxyShape, mMemoryManager.getPoolAllocator(), + mMemoryManager.getPoolAllocator()); // Compute the middle-phase collision detection between the two shapes NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); @@ -600,7 +604,7 @@ bool CollisionDetection::testOverlap(CollisionBody* body1, CollisionBody* body2) // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - isColliding |= narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, false, mPoolAllocator); + isColliding |= narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, false, mMemoryManager.getPoolAllocator()); } } @@ -611,7 +615,7 @@ bool CollisionDetection::testOverlap(CollisionBody* body1, CollisionBody* body2) currentNarrowPhaseInfo->~NarrowPhaseInfo(); // Release the allocated memory - mPoolAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); + mMemoryManager.release(MemoryManager::AllocationType::Pool, currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); } // Return if we have found a narrow-phase collision @@ -648,7 +652,7 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl const AABB& shapeAABB = mBroadPhaseAlgorithm.getFatAABB(bodyProxyShape->mBroadPhaseID); // Ask the broad-phase to get all the overlapping shapes - LinkedList overlappingNodes(mPoolAllocator); + LinkedList overlappingNodes(mMemoryManager.getPoolAllocator()); mBroadPhaseAlgorithm.reportAllShapesOverlappingWithAABB(shapeAABB, overlappingNodes); const bodyindex bodyId = body->getID(); @@ -670,7 +674,8 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl if ((proxyShape->getCollisionCategoryBits() & categoryMaskBits) != 0) { // Create a temporary overlapping pair - OverlappingPair pair(bodyProxyShape, proxyShape, mPoolAllocator, mPoolAllocator); + OverlappingPair pair(bodyProxyShape, proxyShape, mMemoryManager.getPoolAllocator(), + mMemoryManager.getPoolAllocator()); // Compute the middle-phase collision detection between the two shapes NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); @@ -695,7 +700,7 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - isColliding |= narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, false, mPoolAllocator); + isColliding |= narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, false, mMemoryManager.getPoolAllocator()); } } @@ -706,7 +711,7 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl currentNarrowPhaseInfo->~NarrowPhaseInfo(); // Release the allocated memory - mPoolAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); + mMemoryManager.release(MemoryManager::AllocationType::Pool, currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); } // Return if we have found a narrow-phase collision @@ -754,7 +759,8 @@ void CollisionDetection::testCollision(CollisionBody* body1, CollisionBody* body if (aabb1.testCollision(aabb2)) { // Create a temporary overlapping pair - OverlappingPair pair(body1ProxyShape, body2ProxyShape, mPoolAllocator, mPoolAllocator); + OverlappingPair pair(body1ProxyShape, body2ProxyShape, mMemoryManager.getPoolAllocator(), + mMemoryManager.getPoolAllocator()); // Compute the middle-phase collision detection between the two shapes NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); @@ -774,7 +780,7 @@ void CollisionDetection::testCollision(CollisionBody* body1, CollisionBody* body // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, true, mPoolAllocator)) { + if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, true, mMemoryManager.getPoolAllocator())) { // Add the contact points as a potential contact manifold into the pair narrowPhaseInfo->addContactPointsAsPotentialContactManifold(); @@ -788,7 +794,7 @@ void CollisionDetection::testCollision(CollisionBody* body1, CollisionBody* body currentNarrowPhaseInfo->~NarrowPhaseInfo(); // Release the allocated memory - mPoolAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); + mMemoryManager.release(MemoryManager::AllocationType::Pool, currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); } // Process the potential contacts @@ -797,7 +803,7 @@ void CollisionDetection::testCollision(CollisionBody* body1, CollisionBody* body if (pair.hasContacts()) { // Report the contacts to the user - CollisionCallback::CollisionCallbackInfo collisionInfo(&pair, mPoolAllocator); + CollisionCallback::CollisionCallbackInfo collisionInfo(&pair, mMemoryManager); collisionCallback->notifyContact(collisionInfo); } } @@ -826,7 +832,7 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c const AABB& shapeAABB = mBroadPhaseAlgorithm.getFatAABB(bodyProxyShape->mBroadPhaseID); // Ask the broad-phase to get all the overlapping shapes - LinkedList overlappingNodes(mPoolAllocator); + LinkedList overlappingNodes(mMemoryManager.getPoolAllocator()); mBroadPhaseAlgorithm.reportAllShapesOverlappingWithAABB(shapeAABB, overlappingNodes); const bodyindex bodyId = body->getID(); @@ -846,7 +852,8 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c if ((proxyShape->getCollisionCategoryBits() & categoryMaskBits) != 0) { // Create a temporary overlapping pair - OverlappingPair pair(bodyProxyShape, proxyShape, mPoolAllocator, mPoolAllocator); + OverlappingPair pair(bodyProxyShape, proxyShape, mMemoryManager.getPoolAllocator(), + mMemoryManager.getPoolAllocator()); // Compute the middle-phase collision detection between the two shapes NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); @@ -866,7 +873,7 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, true, mPoolAllocator)) { + if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, true, mMemoryManager.getPoolAllocator())) { // Add the contact points as a potential contact manifold into the pair narrowPhaseInfo->addContactPointsAsPotentialContactManifold(); @@ -880,7 +887,7 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c currentNarrowPhaseInfo->~NarrowPhaseInfo(); // Release the allocated memory - mPoolAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); + mMemoryManager.release(MemoryManager::AllocationType::Pool, currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); } // Process the potential contacts @@ -889,7 +896,7 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c if (pair.hasContacts()) { // Report the contacts to the user - CollisionCallback::CollisionCallbackInfo collisionInfo(&pair, mPoolAllocator); + CollisionCallback::CollisionCallbackInfo collisionInfo(&pair, mMemoryManager); callback->notifyContact(collisionInfo); } } @@ -920,8 +927,8 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { OverlappingPair* originalPair = it->second; // Create a new overlapping pair so that we do not work on the original one - OverlappingPair pair(originalPair->getShape1(), originalPair->getShape2(), mPoolAllocator, - mPoolAllocator); + OverlappingPair pair(originalPair->getShape1(), originalPair->getShape2(), mMemoryManager.getPoolAllocator(), + mMemoryManager.getPoolAllocator()); ProxyShape* shape1 = pair.getShape1(); ProxyShape* shape2 = pair.getShape2(); @@ -950,7 +957,7 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { // Use the narrow-phase collision detection algorithm to check // if there really is a collision. If a collision occurs, the // notifyContact() callback method will be called. - if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, true, mPoolAllocator)) { + if (narrowPhaseAlgorithm->testCollision(narrowPhaseInfo, true, mMemoryManager.getPoolAllocator())) { // Add the contact points as a potential contact manifold into the pair narrowPhaseInfo->addContactPointsAsPotentialContactManifold(); @@ -964,7 +971,7 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { currentNarrowPhaseInfo->~NarrowPhaseInfo(); // Release the allocated memory - mPoolAllocator.release(currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); + mMemoryManager.release(MemoryManager::AllocationType::Pool, currentNarrowPhaseInfo, sizeof(NarrowPhaseInfo)); } // Process the potential contacts @@ -973,7 +980,7 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { if (pair.hasContacts()) { // Report the contacts to the user - CollisionCallback::CollisionCallbackInfo collisionInfo(&pair, mPoolAllocator); + CollisionCallback::CollisionCallbackInfo collisionInfo(&pair, mMemoryManager); callback->notifyContact(collisionInfo); } } @@ -996,12 +1003,6 @@ EventListener* CollisionDetection::getWorldEventListener() { return mWorld->mEventListener; } -// Return a reference to the world memory allocator -PoolAllocator& CollisionDetection::getWorldMemoryAllocator() { - return mWorld->mPoolAllocator; -} - - // Return the world-space AABB of a given proxy shape const AABB CollisionDetection::getWorldAABB(const ProxyShape* proxyShape) const { assert(proxyShape->mBroadPhaseID > -1); diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index d728a95f..6aeac709 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -32,8 +32,7 @@ #include "engine/OverlappingPair.h" #include "engine/EventListener.h" #include "narrowphase/DefaultCollisionDispatch.h" -#include "memory/PoolAllocator.h" -#include "memory/SingleFrameAllocator.h" +#include "memory/MemoryManager.h" #include "constraint/ContactPoint.h" #include #include @@ -62,6 +61,9 @@ class CollisionDetection { // -------------------- Attributes -------------------- // + /// Memory manager + MemoryManager& mMemoryManager; + /// Collision Detection Dispatch configuration CollisionDispatch* mCollisionDispatch; @@ -71,12 +73,6 @@ class CollisionDetection { /// Collision detection matrix (algorithms to use) NarrowPhaseAlgorithm* mCollisionMatrix[NB_COLLISION_SHAPE_TYPES][NB_COLLISION_SHAPE_TYPES]; - /// Reference to the memory allocator - PoolAllocator& mPoolAllocator; - - /// Reference to the single frame memory allocator - SingleFrameAllocator& mSingleFrameAllocator; - /// Pointer to the physics world CollisionWorld* mWorld; @@ -133,7 +129,7 @@ class CollisionDetection { void addAllContactManifoldsToBodies(); /// Compute the concave vs convex middle-phase algorithm for a given pair of bodies - void computeConvexVsConcaveMiddlePhase(OverlappingPair* pair, Allocator& allocator, + void computeConvexVsConcaveMiddlePhase(OverlappingPair* pair, MemoryAllocator& allocator, NarrowPhaseInfo** firstNarrowPhaseInfo); /// Compute the middle-phase collision detection between two proxy shapes @@ -156,7 +152,7 @@ class CollisionDetection { // -------------------- Methods -------------------- // /// Constructor - CollisionDetection(CollisionWorld* world, PoolAllocator& memoryAllocator, SingleFrameAllocator& singleFrameAllocator); + CollisionDetection(CollisionWorld* world, MemoryManager& memoryManager); /// Destructor ~CollisionDetection() = default; @@ -223,9 +219,6 @@ class CollisionDetection { /// Return the world event listener EventListener* getWorldEventListener(); - /// Return a reference to the world memory allocator - PoolAllocator& getWorldMemoryAllocator(); - #ifdef IS_PROFILING_ACTIVE /// Set the profiler diff --git a/src/collision/ContactManifold.cpp b/src/collision/ContactManifold.cpp index c2d60422..ba1bcb1e 100644 --- a/src/collision/ContactManifold.cpp +++ b/src/collision/ContactManifold.cpp @@ -30,7 +30,7 @@ using namespace reactphysics3d; // Constructor -ContactManifold::ContactManifold(const ContactManifoldInfo* manifoldInfo, ProxyShape* shape1, ProxyShape* shape2, Allocator& memoryAllocator) +ContactManifold::ContactManifold(const ContactManifoldInfo* manifoldInfo, ProxyShape* shape1, ProxyShape* shape2, MemoryAllocator& memoryAllocator) : mShape1(shape1), mShape2(shape2), mContactPoints(nullptr), mNbContactPoints(0), mFrictionImpulse1(0.0), mFrictionImpulse2(0.0), mFrictionTwistImpulse(0.0), mIsAlreadyInIsland(false), diff --git a/src/collision/ContactManifold.h b/src/collision/ContactManifold.h index 8303f35c..f513ad82 100644 --- a/src/collision/ContactManifold.h +++ b/src/collision/ContactManifold.h @@ -129,7 +129,7 @@ class ContactManifold { bool mIsAlreadyInIsland; /// Reference to the memory allocator - Allocator& mMemoryAllocator; + MemoryAllocator& mMemoryAllocator; /// Pointer to the next contact manifold in the linked-list ContactManifold* mNext; @@ -217,7 +217,7 @@ class ContactManifold { /// Constructor ContactManifold(const ContactManifoldInfo* manifoldInfo, ProxyShape* shape1, ProxyShape* shape2, - Allocator& memoryAllocator); + MemoryAllocator& memoryAllocator); /// Destructor ~ContactManifold(); diff --git a/src/collision/ContactManifoldInfo.cpp b/src/collision/ContactManifoldInfo.cpp index 6740fe4f..a28e3817 100644 --- a/src/collision/ContactManifoldInfo.cpp +++ b/src/collision/ContactManifoldInfo.cpp @@ -29,7 +29,7 @@ using namespace reactphysics3d; // Constructor -ContactManifoldInfo::ContactManifoldInfo(Allocator& allocator) +ContactManifoldInfo::ContactManifoldInfo(MemoryAllocator& allocator) : mContactPointsList(nullptr), mNbContactPoints(0), mNext(nullptr), mAllocator(allocator) { } diff --git a/src/collision/ContactManifoldInfo.h b/src/collision/ContactManifoldInfo.h index 4126f4c8..b2687da5 100644 --- a/src/collision/ContactManifoldInfo.h +++ b/src/collision/ContactManifoldInfo.h @@ -28,7 +28,7 @@ // Libraries #include "collision/ContactPointInfo.h" -#include "memory/Allocator.h" +#include "memory/MemoryAllocator.h" /// ReactPhysics3D namespace namespace reactphysics3d { @@ -57,14 +57,14 @@ class ContactManifoldInfo { ContactManifoldInfo* mNext; /// Reference the the memory allocator where the contact point infos have been allocated - Allocator& mAllocator; + MemoryAllocator& mAllocator; public: // -------------------- Methods -------------------- // /// Constructor - ContactManifoldInfo(Allocator& allocator); + ContactManifoldInfo(MemoryAllocator& allocator); /// Destructor ~ContactManifoldInfo(); diff --git a/src/collision/ContactManifoldSet.cpp b/src/collision/ContactManifoldSet.cpp index 5f70bbc0..c63e6a11 100644 --- a/src/collision/ContactManifoldSet.cpp +++ b/src/collision/ContactManifoldSet.cpp @@ -30,7 +30,7 @@ using namespace reactphysics3d; // Constructor ContactManifoldSet::ContactManifoldSet(ProxyShape* shape1, ProxyShape* shape2, - Allocator& memoryAllocator) + MemoryAllocator& memoryAllocator) : mNbManifolds(0), mShape1(shape1), mShape2(shape2), mMemoryAllocator(memoryAllocator), mManifolds(nullptr) { diff --git a/src/collision/ContactManifoldSet.h b/src/collision/ContactManifoldSet.h index 13d27b70..56b09b04 100644 --- a/src/collision/ContactManifoldSet.h +++ b/src/collision/ContactManifoldSet.h @@ -61,7 +61,7 @@ class ContactManifoldSet { ProxyShape* mShape2; /// Reference to the memory allocator for the contact manifolds - Allocator& mMemoryAllocator; + MemoryAllocator& mMemoryAllocator; /// Contact manifolds of the set ContactManifold* mManifolds; @@ -95,7 +95,7 @@ class ContactManifoldSet { /// Constructor ContactManifoldSet(ProxyShape* shape1, ProxyShape* shape2, - Allocator& memoryAllocator); + MemoryAllocator& memoryAllocator); /// Destructor ~ContactManifoldSet(); diff --git a/src/collision/HalfEdgeStructure.h b/src/collision/HalfEdgeStructure.h index e398913f..15658a93 100644 --- a/src/collision/HalfEdgeStructure.h +++ b/src/collision/HalfEdgeStructure.h @@ -54,7 +54,7 @@ class HalfEdgeStructure { List faceVertices; // Index of the vertices of the face /// Constructor - Face(Allocator& allocator) : faceVertices(allocator) {} + Face(MemoryAllocator& allocator) : faceVertices(allocator) {} /// Constructor Face(List vertices) : faceVertices(vertices) {} @@ -71,7 +71,7 @@ class HalfEdgeStructure { private: /// Reference to a memory allocator - Allocator& mAllocator; + MemoryAllocator& mAllocator; /// All the faces List mFaces; @@ -85,7 +85,7 @@ class HalfEdgeStructure { public: /// Constructor - HalfEdgeStructure(Allocator& allocator, uint facesCapacity, uint verticesCapacity, + HalfEdgeStructure(MemoryAllocator& allocator, uint facesCapacity, uint verticesCapacity, uint edgesCapacity) :mAllocator(allocator), mFaces(allocator, facesCapacity), mVertices(allocator, verticesCapacity), mEdges(allocator, edgesCapacity) {} diff --git a/src/collision/MiddlePhaseTriangleCallback.h b/src/collision/MiddlePhaseTriangleCallback.h index e04d7a9c..b4798a2c 100644 --- a/src/collision/MiddlePhaseTriangleCallback.h +++ b/src/collision/MiddlePhaseTriangleCallback.h @@ -56,7 +56,7 @@ class MiddlePhaseTriangleCallback : public TriangleCallback { const ConcaveShape* mConcaveShape; /// Reference to the single-frame memory allocator - Allocator& mAllocator; + MemoryAllocator& mAllocator; #ifdef IS_PROFILING_ACTIVE @@ -74,7 +74,7 @@ class MiddlePhaseTriangleCallback : public TriangleCallback { MiddlePhaseTriangleCallback(OverlappingPair* overlappingPair, ProxyShape* concaveProxyShape, ProxyShape* convexProxyShape, const ConcaveShape* concaveShape, - Allocator& allocator) + MemoryAllocator& allocator) :mOverlappingPair(overlappingPair), mConcaveProxyShape(concaveProxyShape), mConvexProxyShape(convexProxyShape), mConcaveShape(concaveShape), mAllocator(allocator), narrowPhaseInfoList(nullptr) { diff --git a/src/collision/NarrowPhaseInfo.cpp b/src/collision/NarrowPhaseInfo.cpp index 0189db99..2c7a226c 100644 --- a/src/collision/NarrowPhaseInfo.cpp +++ b/src/collision/NarrowPhaseInfo.cpp @@ -35,7 +35,7 @@ using namespace reactphysics3d; // Constructor NarrowPhaseInfo::NarrowPhaseInfo(OverlappingPair* pair, CollisionShape* shape1, CollisionShape* shape2, const Transform& shape1Transform, - const Transform& shape2Transform, Allocator& shapeAllocator) + const Transform& shape2Transform, MemoryAllocator& shapeAllocator) : overlappingPair(pair), collisionShape1(shape1), collisionShape2(shape2), shape1ToWorldTransform(shape1Transform), shape2ToWorldTransform(shape2Transform), contactPoints(nullptr), next(nullptr), collisionShapeAllocator(shapeAllocator) { @@ -68,7 +68,7 @@ void NarrowPhaseInfo::addContactPoint(const Vector3& contactNormal, decimal penD assert(penDepth > decimal(0.0)); // Get the memory allocator - Allocator& allocator = overlappingPair->getTemporaryAllocator(); + MemoryAllocator& allocator = overlappingPair->getTemporaryAllocator(); // Create the contact point info ContactPointInfo* contactPointInfo = new (allocator.allocate(sizeof(ContactPointInfo))) @@ -89,7 +89,7 @@ void NarrowPhaseInfo::addContactPointsAsPotentialContactManifold() { void NarrowPhaseInfo::resetContactPoints() { // Get the memory allocator - Allocator& allocator = overlappingPair->getTemporaryAllocator(); + MemoryAllocator& allocator = overlappingPair->getTemporaryAllocator(); // For each remaining contact point info ContactPointInfo* element = contactPoints; diff --git a/src/collision/NarrowPhaseInfo.h b/src/collision/NarrowPhaseInfo.h index b732480c..f9ea1ac9 100644 --- a/src/collision/NarrowPhaseInfo.h +++ b/src/collision/NarrowPhaseInfo.h @@ -67,12 +67,12 @@ struct NarrowPhaseInfo { NarrowPhaseInfo* next; /// Memory allocator for the collision shape (Used to release TriangleShape memory in destructor) - Allocator& collisionShapeAllocator; + MemoryAllocator& collisionShapeAllocator; /// Constructor NarrowPhaseInfo(OverlappingPair* pair, CollisionShape* shape1, CollisionShape* shape2, const Transform& shape1Transform, - const Transform& shape2Transform, Allocator& shapeAllocator); + const Transform& shape2Transform, MemoryAllocator& shapeAllocator); /// Destructor ~NarrowPhaseInfo(); diff --git a/src/collision/PolyhedronMesh.cpp b/src/collision/PolyhedronMesh.cpp index 08a84e7d..64db474e 100644 --- a/src/collision/PolyhedronMesh.cpp +++ b/src/collision/PolyhedronMesh.cpp @@ -36,7 +36,7 @@ using namespace reactphysics3d; * @param polygonVertexArray Pointer to the array of polygons and their vertices */ PolyhedronMesh::PolyhedronMesh(PolygonVertexArray* polygonVertexArray) - : mHalfEdgeStructure(MemoryManager::getDefaultAllocator(), + : mHalfEdgeStructure(MemoryManager::getBaseAllocator(), polygonVertexArray->getNbFaces(), polygonVertexArray->getNbVertices(), (polygonVertexArray->getNbFaces() + polygonVertexArray->getNbVertices() - 2) * 2) { @@ -75,7 +75,7 @@ void PolyhedronMesh::createHalfEdgeStructure() { // Get the polygon face PolygonVertexArray::PolygonFace* face = mPolygonVertexArray->getPolygonFace(f); - List faceVertices(MemoryManager::getDefaultAllocator(), face->nbVertices); + List faceVertices(MemoryManager::getBaseAllocator(), face->nbVertices); // For each vertex of the face for (uint v=0; v < face->nbVertices; v++) { diff --git a/src/collision/ProxyShape.cpp b/src/collision/ProxyShape.cpp index f782b2a8..8847d094 100644 --- a/src/collision/ProxyShape.cpp +++ b/src/collision/ProxyShape.cpp @@ -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, Allocator& allocator) - :mBody(body), mCollisionShape(shape), mLocalToBodyTransform(transform), mMass(mass), - mNext(nullptr), mBroadPhaseID(-1), mCollisionCategoryBits(0x0001), mCollideWithMaskBits(0xFFFF), mAllocator(allocator) { +ProxyShape::ProxyShape(CollisionBody* body, CollisionShape* shape, const Transform& transform, decimal mass, MemoryManager& memoryManager) + :mMemoryManager(memoryManager), mBody(body), mCollisionShape(shape), mLocalToBodyTransform(transform), mMass(mass), + mNext(nullptr), mBroadPhaseID(-1), mCollisionCategoryBits(0x0001), mCollideWithMaskBits(0xFFFF) { } @@ -76,7 +76,7 @@ bool ProxyShape::raycast(const Ray& ray, RaycastInfo& raycastInfo) { worldToLocalTransform * ray.point2, ray.maxFraction); - bool isHit = mCollisionShape->raycast(rayLocal, raycastInfo, this, mAllocator); + bool isHit = mCollisionShape->raycast(rayLocal, raycastInfo, this, mMemoryManager.getPoolAllocator()); // Convert the raycast info into world-space raycastInfo.worldPoint = localToWorldTransform * raycastInfo.worldPoint; diff --git a/src/collision/ProxyShape.h b/src/collision/ProxyShape.h index 0ba34698..0da79e28 100644 --- a/src/collision/ProxyShape.h +++ b/src/collision/ProxyShape.h @@ -29,6 +29,7 @@ // Libraries #include "body/CollisionBody.h" #include "shapes/CollisionShape.h" +#include "memory/MemoryManager.h" namespace reactphysics3d { @@ -48,6 +49,9 @@ class ProxyShape { // -------------------- Attributes -------------------- // + /// Reference to the memory manager + MemoryManager& mMemoryManager; + /// Pointer to the parent body CollisionBody* mBody; @@ -82,9 +86,6 @@ 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 @@ -103,7 +104,7 @@ class ProxyShape { /// Constructor ProxyShape(CollisionBody* body, CollisionShape* shape, - const Transform& transform, decimal mass, Allocator& allocator); + const Transform& transform, decimal mass, MemoryManager& memoryManager); /// Destructor virtual ~ProxyShape(); diff --git a/src/collision/broadphase/BroadPhaseAlgorithm.cpp b/src/collision/broadphase/BroadPhaseAlgorithm.cpp index c1484434..8998859e 100644 --- a/src/collision/broadphase/BroadPhaseAlgorithm.cpp +++ b/src/collision/broadphase/BroadPhaseAlgorithm.cpp @@ -185,14 +185,14 @@ void BroadPhaseAlgorithm::reportAllShapesOverlappingWithAABB(const AABB& aabb, } // Compute all the overlapping pairs of collision shapes -void BroadPhaseAlgorithm::computeOverlappingPairs(Allocator& allocator) { +void BroadPhaseAlgorithm::computeOverlappingPairs(MemoryManager& memoryManager) { // TODO : Try to see if we can allocate potential pairs in single frame allocator // Reset the potential overlapping pairs mNbPotentialPairs = 0; - LinkedList overlappingNodes(allocator); + LinkedList overlappingNodes(memoryManager.getPoolAllocator()); // For all collision shapes that have moved (or have been created) during the // last simulation step diff --git a/src/collision/broadphase/BroadPhaseAlgorithm.h b/src/collision/broadphase/BroadPhaseAlgorithm.h index 7e1ff262..30a67920 100644 --- a/src/collision/broadphase/BroadPhaseAlgorithm.h +++ b/src/collision/broadphase/BroadPhaseAlgorithm.h @@ -210,7 +210,7 @@ class BroadPhaseAlgorithm { void reportAllShapesOverlappingWithAABB(const AABB& aabb, LinkedList& overlappingNodes) const; /// Compute all the overlapping pairs of collision shapes - void computeOverlappingPairs(Allocator& allocator); + void computeOverlappingPairs(MemoryManager& memoryManager); /// Return the proxy shape corresponding to the broad-phase node id in parameter ProxyShape* getProxyShapeForBroadPhaseId(int broadPhaseId) const; diff --git a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp index bf9eefc2..dce9b04b 100755 --- a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.cpp @@ -34,7 +34,7 @@ using namespace reactphysics3d; // This technique is based on the "Robust Contact Creation for Physics Simulations" presentation // by Dirk Gregorius. bool CapsuleVsCapsuleAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, - Allocator& memoryAllocator) { + MemoryAllocator& memoryAllocator) { assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE); assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CAPSULE); diff --git a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h index df9a8854..b122ca14 100644 --- a/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h +++ b/src/collision/narrowphase/CapsuleVsCapsuleAlgorithm.h @@ -61,7 +61,7 @@ class CapsuleVsCapsuleAlgorithm : public NarrowPhaseAlgorithm { CapsuleVsCapsuleAlgorithm& operator=(const CapsuleVsCapsuleAlgorithm& algorithm) = delete; /// Compute the narrow-phase collision detection between two capsules - virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, Allocator& memoryAllocator) override; + virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, MemoryAllocator& memoryAllocator) override; }; } diff --git a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp index f943312b..33a381f0 100644 --- a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.cpp @@ -38,7 +38,7 @@ using namespace reactphysics3d; // This technique is based on the "Robust Contact Creation for Physics Simulations" presentation // by Dirk Gregorius. bool CapsuleVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, - Allocator& memoryAllocator) { + MemoryAllocator& memoryAllocator) { // First, we run the GJK algorithm GJKAlgorithm gjkAlgorithm; diff --git a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h index d7f96d63..58bb14fb 100644 --- a/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h +++ b/src/collision/narrowphase/CapsuleVsConvexPolyhedronAlgorithm.h @@ -61,7 +61,7 @@ class CapsuleVsConvexPolyhedronAlgorithm : public NarrowPhaseAlgorithm { CapsuleVsConvexPolyhedronAlgorithm& operator=(const CapsuleVsConvexPolyhedronAlgorithm& algorithm) = delete; /// Compute the narrow-phase collision detection between a capsule and a polyhedron - virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, Allocator& memoryAllocator) override; + virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, MemoryAllocator& memoryAllocator) override; }; } diff --git a/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp index 5cf10b17..375814cd 100644 --- a/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp @@ -35,7 +35,7 @@ using namespace reactphysics3d; // This technique is based on the "Robust Contact Creation for Physics Simulations" presentation // by Dirk Gregorius. bool ConvexPolyhedronVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, - Allocator& memoryAllocator) { + MemoryAllocator& memoryAllocator) { // Run the SAT algorithm to find the separating axis and compute contact point SATAlgorithm satAlgorithm(memoryAllocator); diff --git a/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.h b/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.h index 204bc269..ddd10585 100644 --- a/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.h +++ b/src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.h @@ -61,7 +61,7 @@ class ConvexPolyhedronVsConvexPolyhedronAlgorithm : public NarrowPhaseAlgorithm ConvexPolyhedronVsConvexPolyhedronAlgorithm& operator=(const ConvexPolyhedronVsConvexPolyhedronAlgorithm& algorithm) = delete; /// Compute the narrow-phase collision detection between two convex polyhedra - virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, Allocator& memoryAllocator) override; + virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, MemoryAllocator& memoryAllocator) override; }; } diff --git a/src/collision/narrowphase/NarrowPhaseAlgorithm.h b/src/collision/narrowphase/NarrowPhaseAlgorithm.h index 40d3fbc6..3088d874 100644 --- a/src/collision/narrowphase/NarrowPhaseAlgorithm.h +++ b/src/collision/narrowphase/NarrowPhaseAlgorithm.h @@ -92,7 +92,7 @@ class NarrowPhaseAlgorithm { /// Compute a contact info if the two bounding volumes collide virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, - Allocator& memoryAllocator)=0; + MemoryAllocator& memoryAllocator)=0; #ifdef IS_PROFILING_ACTIVE diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 1992cbc7..66be7d06 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -45,7 +45,7 @@ using namespace reactphysics3d; const decimal SATAlgorithm::SAME_SEPARATING_AXIS_BIAS = decimal(0.001); // Constructor -SATAlgorithm::SATAlgorithm(Allocator& memoryAllocator) : mMemoryAllocator(memoryAllocator) { +SATAlgorithm::SATAlgorithm(MemoryAllocator& memoryAllocator) : mMemoryAllocator(memoryAllocator) { } diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.h b/src/collision/narrowphase/SAT/SATAlgorithm.h index 52884f8e..0402067f 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.h +++ b/src/collision/narrowphase/SAT/SATAlgorithm.h @@ -51,7 +51,7 @@ class SATAlgorithm { static const decimal SAME_SEPARATING_AXIS_BIAS; /// Memory allocator - Allocator& mMemoryAllocator; + MemoryAllocator& mMemoryAllocator; #ifdef IS_PROFILING_ACTIVE @@ -115,7 +115,7 @@ class SATAlgorithm { // -------------------- Methods -------------------- // /// Constructor - SATAlgorithm(Allocator& memoryAllocator); + SATAlgorithm(MemoryAllocator& memoryAllocator); /// Destructor ~SATAlgorithm() = default; diff --git a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp index f5bfc11d..2e86dfe3 100755 --- a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp @@ -35,7 +35,7 @@ using namespace reactphysics3d; // This technique is based on the "Robust Contact Creation for Physics Simulations" presentation // by Dirk Gregorius. bool SphereVsCapsuleAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, - Allocator& memoryAllocator) { + MemoryAllocator& memoryAllocator) { bool isSphereShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE; diff --git a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h index b51bba57..c7c4b39e 100644 --- a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h +++ b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.h @@ -61,7 +61,7 @@ class SphereVsCapsuleAlgorithm : public NarrowPhaseAlgorithm { SphereVsCapsuleAlgorithm& operator=(const SphereVsCapsuleAlgorithm& algorithm) = delete; /// Compute the narrow-phase collision detection between a sphere and a capsule - virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, Allocator& memoryAllocator) override; + virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, MemoryAllocator& memoryAllocator) override; }; } diff --git a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp index 6cc3e578..8d4f562c 100644 --- a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.cpp @@ -35,7 +35,7 @@ using namespace reactphysics3d; // This technique is based on the "Robust Contact Creation for Physics Simulations" presentation // by Dirk Gregorius. bool SphereVsConvexPolyhedronAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, - Allocator& memoryAllocator) { + MemoryAllocator& memoryAllocator) { assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON || narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); diff --git a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h index 17055431..1929f43c 100644 --- a/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h +++ b/src/collision/narrowphase/SphereVsConvexPolyhedronAlgorithm.h @@ -61,7 +61,7 @@ class SphereVsConvexPolyhedronAlgorithm : public NarrowPhaseAlgorithm { SphereVsConvexPolyhedronAlgorithm& operator=(const SphereVsConvexPolyhedronAlgorithm& algorithm) = delete; /// Compute the narrow-phase collision detection between a sphere and a convex polyhedron - virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, Allocator& memoryAllocator) override; + virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, MemoryAllocator& memoryAllocator) override; }; } diff --git a/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp b/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp index f8820106..8103380e 100755 --- a/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsSphereAlgorithm.cpp @@ -31,7 +31,7 @@ using namespace reactphysics3d; bool SphereVsSphereAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, - Allocator& memoryAllocator) { + MemoryAllocator& memoryAllocator) { assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE); assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::SPHERE); diff --git a/src/collision/narrowphase/SphereVsSphereAlgorithm.h b/src/collision/narrowphase/SphereVsSphereAlgorithm.h index e0741ab8..142053c4 100644 --- a/src/collision/narrowphase/SphereVsSphereAlgorithm.h +++ b/src/collision/narrowphase/SphereVsSphereAlgorithm.h @@ -61,7 +61,7 @@ class SphereVsSphereAlgorithm : public NarrowPhaseAlgorithm { SphereVsSphereAlgorithm& operator=(const SphereVsSphereAlgorithm& algorithm) = delete; /// Compute a contact info if the two bounding volume collide - virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, Allocator& memoryAllocator) override; + virtual bool testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts, MemoryAllocator& memoryAllocator) override; }; } diff --git a/src/collision/shapes/BoxShape.cpp b/src/collision/shapes/BoxShape.cpp index 079b15c5..c13e32f4 100644 --- a/src/collision/shapes/BoxShape.cpp +++ b/src/collision/shapes/BoxShape.cpp @@ -39,7 +39,7 @@ using namespace reactphysics3d; */ BoxShape::BoxShape(const Vector3& extent) : ConvexPolyhedronShape(CollisionShapeName::BOX), mExtent(extent), - mHalfEdgeStructure(MemoryManager::getDefaultAllocator(), 6, 8, 24) { + mHalfEdgeStructure(MemoryManager::getBaseAllocator(), 6, 8, 24) { assert(extent.x > decimal(0.0)); assert(extent.y > decimal(0.0)); @@ -55,7 +55,7 @@ BoxShape::BoxShape(const Vector3& extent) mHalfEdgeStructure.addVertex(6); mHalfEdgeStructure.addVertex(7); - DefaultAllocator& allocator = MemoryManager::getDefaultAllocator(); + MemoryAllocator& allocator = MemoryManager::getBaseAllocator(); // Faces List face0(allocator, 4); @@ -98,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, Allocator& allocator) const { +bool BoxShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, MemoryAllocator& allocator) const { Vector3 rayDirection = ray.point2 - ray.point1; decimal tMin = DECIMAL_SMALLEST; diff --git a/src/collision/shapes/BoxShape.h b/src/collision/shapes/BoxShape.h index b3e094bd..2ebcdce1 100644 --- a/src/collision/shapes/BoxShape.h +++ b/src/collision/shapes/BoxShape.h @@ -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, Allocator& allocator) const override; + virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, MemoryAllocator& allocator) const override; /// Return the number of bytes used by the collision shape virtual size_t getSizeInBytes() const override; diff --git a/src/collision/shapes/CapsuleShape.cpp b/src/collision/shapes/CapsuleShape.cpp index da29fede..3f89d090 100644 --- a/src/collision/shapes/CapsuleShape.cpp +++ b/src/collision/shapes/CapsuleShape.cpp @@ -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, Allocator& allocator) const { +bool CapsuleShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, MemoryAllocator& allocator) const { const Vector3 n = ray.point2 - ray.point1; diff --git a/src/collision/shapes/CapsuleShape.h b/src/collision/shapes/CapsuleShape.h index 0da2d1f4..7843f139 100644 --- a/src/collision/shapes/CapsuleShape.h +++ b/src/collision/shapes/CapsuleShape.h @@ -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, Allocator& allocator) const override; + virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, MemoryAllocator& 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, diff --git a/src/collision/shapes/CollisionShape.h b/src/collision/shapes/CollisionShape.h index 4381b05c..8d84ab55 100644 --- a/src/collision/shapes/CollisionShape.h +++ b/src/collision/shapes/CollisionShape.h @@ -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, Allocator& allocator) const=0; + virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, MemoryAllocator& allocator) const=0; /// Return the number of bytes used by the collision shape virtual size_t getSizeInBytes() const = 0; diff --git a/src/collision/shapes/ConcaveMeshShape.cpp b/src/collision/shapes/ConcaveMeshShape.cpp index 0b49f20c..8f215fc2 100644 --- a/src/collision/shapes/ConcaveMeshShape.cpp +++ b/src/collision/shapes/ConcaveMeshShape.cpp @@ -111,7 +111,7 @@ 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, Allocator& allocator) const { +bool ConcaveMeshShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, MemoryAllocator& allocator) const { PROFILE("ConcaveMeshShape::raycast()", mProfiler); diff --git a/src/collision/shapes/ConcaveMeshShape.h b/src/collision/shapes/ConcaveMeshShape.h index 52d49a02..c8c91972 100644 --- a/src/collision/shapes/ConcaveMeshShape.h +++ b/src/collision/shapes/ConcaveMeshShape.h @@ -77,7 +77,7 @@ class ConcaveMeshRaycastCallback : public DynamicAABBTreeRaycastCallback { RaycastInfo& mRaycastInfo; const Ray& mRay; bool mIsHit; - Allocator& mAllocator; + MemoryAllocator& mAllocator; #ifdef IS_PROFILING_ACTIVE @@ -90,7 +90,7 @@ class ConcaveMeshRaycastCallback : public DynamicAABBTreeRaycastCallback { // Constructor ConcaveMeshRaycastCallback(const DynamicAABBTree& dynamicAABBTree, const ConcaveMeshShape& concaveMeshShape, - ProxyShape* proxyShape, RaycastInfo& raycastInfo, const Ray& ray, Allocator& allocator) + ProxyShape* proxyShape, RaycastInfo& raycastInfo, const Ray& ray, MemoryAllocator& allocator) : mDynamicAABBTree(dynamicAABBTree), mConcaveMeshShape(concaveMeshShape), mProxyShape(proxyShape), mRaycastInfo(raycastInfo), mRay(ray), mIsHit(false), mAllocator(allocator) { @@ -142,7 +142,7 @@ class ConcaveMeshShape : public ConcaveShape { // -------------------- Methods -------------------- // /// Raycast method with feedback information - virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, Allocator& allocator) const override; + virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, MemoryAllocator& allocator) const override; /// Return the number of bytes used by the collision shape virtual size_t getSizeInBytes() const override; diff --git a/src/collision/shapes/ConvexMeshShape.cpp b/src/collision/shapes/ConvexMeshShape.cpp index 19ef5016..5b6c70d6 100644 --- a/src/collision/shapes/ConvexMeshShape.cpp +++ b/src/collision/shapes/ConvexMeshShape.cpp @@ -112,7 +112,7 @@ void ConvexMeshShape::recalculateBounds() { } // Raycast method with feedback information -bool ConvexMeshShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, Allocator& allocator) const { +bool ConvexMeshShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, MemoryAllocator& allocator) const { return proxyShape->mBody->mWorld.mCollisionDetection.mNarrowPhaseGJKAlgorithm.raycast( ray, proxyShape, raycastInfo); } diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index 1c33d919..44d01df4 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -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, Allocator& allocator) const override; + virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, MemoryAllocator& allocator) const override; /// Return the number of bytes used by the collision shape virtual size_t getSizeInBytes() const override; diff --git a/src/collision/shapes/HeightFieldShape.cpp b/src/collision/shapes/HeightFieldShape.cpp index f067a827..badfb68d 100644 --- a/src/collision/shapes/HeightFieldShape.cpp +++ b/src/collision/shapes/HeightFieldShape.cpp @@ -212,7 +212,7 @@ 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, Allocator& allocator) const { +bool HeightFieldShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, MemoryAllocator& allocator) const { // TODO : Implement raycasting without using an AABB for the ray // but using a dynamic AABB tree or octree instead diff --git a/src/collision/shapes/HeightFieldShape.h b/src/collision/shapes/HeightFieldShape.h index 4190c3c7..fc587d4c 100644 --- a/src/collision/shapes/HeightFieldShape.h +++ b/src/collision/shapes/HeightFieldShape.h @@ -49,7 +49,7 @@ class TriangleOverlapCallback : public TriangleCallback { bool mIsHit; decimal mSmallestHitFraction; const HeightFieldShape& mHeightFieldShape; - Allocator& mAllocator; + MemoryAllocator& mAllocator; #ifdef IS_PROFILING_ACTIVE @@ -62,7 +62,7 @@ class TriangleOverlapCallback : public TriangleCallback { // Constructor TriangleOverlapCallback(const Ray& ray, ProxyShape* proxyShape, RaycastInfo& raycastInfo, - const HeightFieldShape& heightFieldShape, Allocator& allocator) + const HeightFieldShape& heightFieldShape, MemoryAllocator& allocator) : mRay(ray), mProxyShape(proxyShape), mRaycastInfo(raycastInfo), mHeightFieldShape (heightFieldShape), mAllocator(allocator) { mIsHit = false; @@ -144,7 +144,7 @@ class HeightFieldShape : public ConcaveShape { // -------------------- Methods -------------------- // /// Raycast method with feedback information - virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, Allocator& allocator) const override; + virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, MemoryAllocator& allocator) const override; /// Return the number of bytes used by the collision shape virtual size_t getSizeInBytes() const override; diff --git a/src/collision/shapes/SphereShape.cpp b/src/collision/shapes/SphereShape.cpp index 7d155f97..3ad7afe7 100644 --- a/src/collision/shapes/SphereShape.cpp +++ b/src/collision/shapes/SphereShape.cpp @@ -41,7 +41,7 @@ SphereShape::SphereShape(decimal radius) } // Raycast method with feedback information -bool SphereShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, Allocator& allocator) const { +bool SphereShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, MemoryAllocator& allocator) const { const Vector3 m = ray.point1; decimal c = m.dot(m) - mMargin * mMargin; diff --git a/src/collision/shapes/SphereShape.h b/src/collision/shapes/SphereShape.h index 18883d79..90b20d2d 100644 --- a/src/collision/shapes/SphereShape.h +++ b/src/collision/shapes/SphereShape.h @@ -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, Allocator& allocator) const override; + virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, MemoryAllocator& allocator) const override; /// Return the number of bytes used by the collision shape virtual size_t getSizeInBytes() const override; diff --git a/src/collision/shapes/TriangleShape.cpp b/src/collision/shapes/TriangleShape.cpp index 4a7eb013..2257c0e6 100644 --- a/src/collision/shapes/TriangleShape.cpp +++ b/src/collision/shapes/TriangleShape.cpp @@ -45,7 +45,7 @@ using namespace reactphysics3d; * @param margin The collision margin (in meters) around the collision shape */ TriangleShape::TriangleShape(const Vector3* vertices, const Vector3* verticesNormals, uint shapeId, - Allocator& allocator) + MemoryAllocator& allocator) : ConvexPolyhedronShape(CollisionShapeName::TRIANGLE), mFaces{HalfEdgeStructure::Face(allocator), HalfEdgeStructure::Face(allocator)} { mPoints[0] = vertices[0]; @@ -211,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, Allocator& allocator) const { +bool TriangleShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, MemoryAllocator& allocator) const { PROFILE("TriangleShape::raycast()", mProfiler); diff --git a/src/collision/shapes/TriangleShape.h b/src/collision/shapes/TriangleShape.h index 9a2c756e..23f26adc 100644 --- a/src/collision/shapes/TriangleShape.h +++ b/src/collision/shapes/TriangleShape.h @@ -92,7 +92,7 @@ class TriangleShape : public ConvexPolyhedronShape { /// Raycast method with feedback information virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, - Allocator& allocator) const override; + MemoryAllocator& allocator) const override; /// Return the number of bytes used by the collision shape virtual size_t getSizeInBytes() const override; @@ -113,7 +113,7 @@ class TriangleShape : public ConvexPolyhedronShape { /// Constructor TriangleShape(const Vector3* vertices, const Vector3* verticesNormals, - uint shapeId, Allocator& allocator); + uint shapeId, MemoryAllocator& allocator); /// Destructor virtual ~TriangleShape() override = default; diff --git a/src/configuration.h b/src/configuration.h index a25c1502..96391e76 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -152,7 +152,7 @@ constexpr int NB_MAX_CONTACT_MANIFOLDS_CONCAVE_SHAPE = 3; constexpr decimal COS_ANGLE_SIMILAR_CONTACT_MANIFOLD = decimal(0.95); /// Size (in bytes) of the single frame allocator -constexpr size_t SIZE_SINGLE_FRAME_ALLOCATOR_BYTES = 15728640; // 15 Mb +constexpr size_t INIT_SINGLE_FRAME_ALLOCATOR_BYTES = 1048576; // 1Mb } diff --git a/src/containers/LinkedList.h b/src/containers/LinkedList.h index 281c134c..997035b7 100644 --- a/src/containers/LinkedList.h +++ b/src/containers/LinkedList.h @@ -27,7 +27,7 @@ #define REACTPHYSICS3D_LINKED_LIST_H // Libraries -#include "memory/Allocator.h" +#include "memory/MemoryAllocator.h" namespace reactphysics3d { @@ -64,14 +64,14 @@ class LinkedList { ListElement* mListHead; /// Memory allocator used to allocate the list elements - Allocator& mAllocator; + MemoryAllocator& mAllocator; public: // -------------------- Methods -------------------- // /// Constructor - LinkedList(Allocator& allocator) : mListHead(nullptr), mAllocator(allocator) { + LinkedList(MemoryAllocator& allocator) : mListHead(nullptr), mAllocator(allocator) { } diff --git a/src/containers/List.h b/src/containers/List.h index 71ae7ef7..176766a5 100644 --- a/src/containers/List.h +++ b/src/containers/List.h @@ -28,7 +28,7 @@ // Libraries #include "configuration.h" -#include "memory/Allocator.h" +#include "memory/MemoryAllocator.h" #include namespace reactphysics3d { @@ -54,7 +54,7 @@ class List { size_t mCapacity; /// Memory allocator - Allocator& mAllocator; + MemoryAllocator& mAllocator; // -------------------- Methods -------------------- // @@ -64,7 +64,7 @@ class List { // -------------------- Methods -------------------- // /// Constructor - List(Allocator& allocator, size_t capacity = 0) + List(MemoryAllocator& allocator, size_t capacity = 0) : mBuffer(nullptr), mSize(0), mCapacity(0), mAllocator(allocator) { if (capacity > 0) { diff --git a/src/engine/CollisionWorld.cpp b/src/engine/CollisionWorld.cpp index 8b29e4a1..da5bf609 100644 --- a/src/engine/CollisionWorld.cpp +++ b/src/engine/CollisionWorld.cpp @@ -33,8 +33,7 @@ using namespace std; // Constructor CollisionWorld::CollisionWorld() - : mSingleFrameAllocator(SIZE_SINGLE_FRAME_ALLOCATOR_BYTES), - mCollisionDetection(this, mPoolAllocator, mSingleFrameAllocator), mCurrentBodyID(0), + : mCollisionDetection(this, mMemoryManager), mCurrentBodyID(0), mEventListener(nullptr) { #ifdef IS_PROFILING_ACTIVE @@ -74,7 +73,8 @@ CollisionBody* CollisionWorld::createCollisionBody(const Transform& transform) { assert(bodyID < std::numeric_limits::max()); // Create the collision body - CollisionBody* collisionBody = new (mPoolAllocator.allocate(sizeof(CollisionBody))) + CollisionBody* collisionBody = new (mMemoryManager.allocate(MemoryManager::AllocationType::Pool, + sizeof(CollisionBody))) CollisionBody(transform, *this, bodyID); assert(collisionBody != nullptr); @@ -111,7 +111,7 @@ void CollisionWorld::destroyCollisionBody(CollisionBody* collisionBody) { mBodies.erase(collisionBody); // Free the object from the memory allocator - mPoolAllocator.release(collisionBody, sizeof(CollisionBody)); + mMemoryManager.release(MemoryManager::AllocationType::Pool, collisionBody, sizeof(CollisionBody)); } // Return the next available body ID diff --git a/src/engine/CollisionWorld.h b/src/engine/CollisionWorld.h index ead42710..9f1fea58 100644 --- a/src/engine/CollisionWorld.h +++ b/src/engine/CollisionWorld.h @@ -39,8 +39,7 @@ #include "collision/CollisionDetection.h" #include "constraint/Joint.h" #include "constraint/ContactPoint.h" -#include "memory/DefaultAllocator.h" -#include "memory/PoolAllocator.h" +#include "memory/MemoryManager.h" #include "EventListener.h" /// Namespace reactphysics3d @@ -62,11 +61,8 @@ class CollisionWorld { // -------------------- Attributes -------------------- // - /// Pool Memory allocator - PoolAllocator mPoolAllocator; - - /// Single frame Memory allocator - SingleFrameAllocator mSingleFrameAllocator; + /// Memory manager + MemoryManager mMemoryManager; /// Reference to the collision detection CollisionDetection mCollisionDetection; diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index 6361badd..f4762c49 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -39,9 +39,9 @@ const decimal ContactSolver::BETA_SPLIT_IMPULSE = decimal(0.2); const decimal ContactSolver::SLOP = decimal(0.01); // Constructor -ContactSolver::ContactSolver(SingleFrameAllocator& allocator) - :mSplitLinearVelocities(nullptr), mSplitAngularVelocities(nullptr), - mContactConstraints(nullptr), mSingleFrameAllocator(allocator), +ContactSolver::ContactSolver(MemoryManager& memoryManager) + :mMemoryManager(memoryManager), mSplitLinearVelocities(nullptr), + mSplitAngularVelocities(nullptr), mContactConstraints(nullptr), mLinearVelocities(nullptr), mAngularVelocities(nullptr), mIsSplitImpulseActive(true) { @@ -75,10 +75,12 @@ void ContactSolver::init(Island** islands, uint nbIslands, decimal timeStep) { if (nbContactManifolds == 0 || nbContactPoints == 0) return; // TODO : Count exactly the number of constraints to allocate here - mContactPoints = static_cast(mSingleFrameAllocator.allocate(sizeof(ContactPointSolver) * nbContactPoints)); + mContactPoints = static_cast(mMemoryManager.allocate(MemoryManager::AllocationType::Frame, + sizeof(ContactPointSolver) * nbContactPoints)); assert(mContactPoints != nullptr); - mContactConstraints = static_cast(mSingleFrameAllocator.allocate(sizeof(ContactManifoldSolver) * nbContactManifolds)); + mContactConstraints = static_cast(mMemoryManager.allocate(MemoryManager::AllocationType::Frame, + sizeof(ContactManifoldSolver) * nbContactManifolds)); assert(mContactConstraints != nullptr); // For each island of the world diff --git a/src/engine/ContactSolver.h b/src/engine/ContactSolver.h index 05bd569c..8799a1ad 100644 --- a/src/engine/ContactSolver.h +++ b/src/engine/ContactSolver.h @@ -272,6 +272,10 @@ class ContactSolver { // -------------------- Attributes -------------------- // + /// Memory manager + MemoryManager& mMemoryManager; + + /// Split linear velocities for the position contact solver (split impulse) Vector3* mSplitLinearVelocities; @@ -293,9 +297,6 @@ class ContactSolver { /// Number of contact constraints uint mNbContactManifolds; - /// Single frame memory allocator - SingleFrameAllocator& mSingleFrameAllocator; - /// Array of linear velocities Vector3* mLinearVelocities; @@ -339,7 +340,7 @@ class ContactSolver { // -------------------- Methods -------------------- // /// Constructor - ContactSolver(SingleFrameAllocator& allocator); + ContactSolver(MemoryManager& memoryManager); /// Destructor ~ContactSolver() = default; diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index 054c4dc5..35b1ba04 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -41,7 +41,7 @@ using namespace std; */ DynamicsWorld::DynamicsWorld(const Vector3 &gravity) : CollisionWorld(), - mContactSolver(mSingleFrameAllocator), + mContactSolver(mMemoryManager), mNbVelocitySolverIterations(DEFAULT_VELOCITY_SOLVER_NB_ITERATIONS), mNbPositionSolverIterations(DEFAULT_POSITION_SOLVER_NB_ITERATIONS), mIsSleepingEnabled(SLEEPING_ENABLED), mGravity(gravity), mTimeStep(decimal(1.0f / 60.0f)), @@ -147,7 +147,7 @@ void DynamicsWorld::update(decimal timeStep) { resetBodiesForceAndTorque(); // Reset the single frame memory allocator - mSingleFrameAllocator.reset(); + mMemoryManager.resetFrameAllocator(); } // Integrate position and orientation of the rigid bodies. @@ -236,12 +236,18 @@ void DynamicsWorld::initVelocityArrays() { // Allocate memory for the bodies velocity arrays uint nbBodies = mRigidBodies.size(); - mSplitLinearVelocities = static_cast(mSingleFrameAllocator.allocate(nbBodies * sizeof(Vector3))); - mSplitAngularVelocities = static_cast(mSingleFrameAllocator.allocate(nbBodies * sizeof(Vector3))); - mConstrainedLinearVelocities = static_cast(mSingleFrameAllocator.allocate(nbBodies * sizeof(Vector3))); - mConstrainedAngularVelocities = static_cast(mSingleFrameAllocator.allocate(nbBodies * sizeof(Vector3))); - mConstrainedPositions = static_cast(mSingleFrameAllocator.allocate(nbBodies * sizeof(Vector3))); - mConstrainedOrientations = static_cast(mSingleFrameAllocator.allocate(nbBodies * sizeof(Quaternion))); + mSplitLinearVelocities = static_cast(mMemoryManager.allocate(MemoryManager::AllocationType::Frame, + nbBodies * sizeof(Vector3))); + mSplitAngularVelocities = static_cast(mMemoryManager.allocate(MemoryManager::AllocationType::Frame, + nbBodies * sizeof(Vector3))); + mConstrainedLinearVelocities = static_cast(mMemoryManager.allocate(MemoryManager::AllocationType::Frame, + nbBodies * sizeof(Vector3))); + mConstrainedAngularVelocities = static_cast(mMemoryManager.allocate(MemoryManager::AllocationType::Frame, + nbBodies * sizeof(Vector3))); + mConstrainedPositions = static_cast(mMemoryManager.allocate(MemoryManager::AllocationType::Frame, + nbBodies * sizeof(Vector3))); + mConstrainedOrientations = static_cast(mMemoryManager.allocate(MemoryManager::AllocationType::Frame, + nbBodies * sizeof(Quaternion))); assert(mSplitLinearVelocities != nullptr); assert(mSplitAngularVelocities != nullptr); assert(mConstrainedLinearVelocities != nullptr); @@ -412,8 +418,8 @@ RigidBody* DynamicsWorld::createRigidBody(const Transform& transform) { assert(bodyID < std::numeric_limits::max()); // Create the rigid body - RigidBody* rigidBody = new (mPoolAllocator.allocate(sizeof(RigidBody))) RigidBody(transform, - *this, bodyID); + RigidBody* rigidBody = new (mMemoryManager.allocate(MemoryManager::AllocationType::Pool, + sizeof(RigidBody))) RigidBody(transform, *this, bodyID); assert(rigidBody != nullptr); // Add the rigid body to the physics world @@ -459,7 +465,7 @@ void DynamicsWorld::destroyRigidBody(RigidBody* rigidBody) { mRigidBodies.erase(rigidBody); // Free the object from the memory allocator - mPoolAllocator.release(rigidBody, sizeof(RigidBody)); + mMemoryManager.release(MemoryManager::AllocationType::Pool, rigidBody, sizeof(RigidBody)); } // Create a joint between two bodies in the world and return a pointer to the new joint @@ -477,7 +483,8 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { // Ball-and-Socket joint case JointType::BALLSOCKETJOINT: { - void* allocatedMemory = mPoolAllocator.allocate(sizeof(BallAndSocketJoint)); + void* allocatedMemory = mMemoryManager.allocate(MemoryManager::AllocationType::Pool, + sizeof(BallAndSocketJoint)); const BallAndSocketJointInfo& info = static_cast( jointInfo); newJoint = new (allocatedMemory) BallAndSocketJoint(info); @@ -487,7 +494,8 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { // Slider joint case JointType::SLIDERJOINT: { - void* allocatedMemory = mPoolAllocator.allocate(sizeof(SliderJoint)); + void* allocatedMemory = mMemoryManager.allocate(MemoryManager::AllocationType::Pool, + sizeof(SliderJoint)); const SliderJointInfo& info = static_cast(jointInfo); newJoint = new (allocatedMemory) SliderJoint(info); break; @@ -496,7 +504,8 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { // Hinge joint case JointType::HINGEJOINT: { - void* allocatedMemory = mPoolAllocator.allocate(sizeof(HingeJoint)); + void* allocatedMemory = mMemoryManager.allocate(MemoryManager::AllocationType::Pool, + sizeof(HingeJoint)); const HingeJointInfo& info = static_cast(jointInfo); newJoint = new (allocatedMemory) HingeJoint(info); break; @@ -505,7 +514,8 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { // Fixed joint case JointType::FIXEDJOINT: { - void* allocatedMemory = mPoolAllocator.allocate(sizeof(FixedJoint)); + void* allocatedMemory = mMemoryManager.allocate(MemoryManager::AllocationType::Pool, + sizeof(FixedJoint)); const FixedJointInfo& info = static_cast(jointInfo); newJoint = new (allocatedMemory) FixedJoint(info); break; @@ -558,8 +568,8 @@ void DynamicsWorld::destroyJoint(Joint* joint) { mJoints.erase(joint); // Remove the joint from the joint list of the bodies involved in the joint - joint->mBody1->removeJointFromJointsList(mPoolAllocator, joint); - joint->mBody2->removeJointFromJointsList(mPoolAllocator, joint); + joint->mBody1->removeJointFromJointsList(mMemoryManager, joint); + joint->mBody2->removeJointFromJointsList(mMemoryManager, joint); size_t nbBytes = joint->getSizeInBytes(); @@ -567,7 +577,7 @@ void DynamicsWorld::destroyJoint(Joint* joint) { joint->~Joint(); // Release the allocated memory - mPoolAllocator.release(joint, nbBytes); + mMemoryManager.release(MemoryManager::AllocationType::Pool, joint, nbBytes); } // Add the joint to the list of joints of the two bodies involved in the joint @@ -576,13 +586,15 @@ void DynamicsWorld::addJointToBody(Joint* joint) { assert(joint != nullptr); // Add the joint at the beginning of the linked list of joints of the first body - void* allocatedMemory1 = mPoolAllocator.allocate(sizeof(JointListElement)); + void* allocatedMemory1 = mMemoryManager.allocate(MemoryManager::AllocationType::Pool, + sizeof(JointListElement)); JointListElement* jointListElement1 = new (allocatedMemory1) JointListElement(joint, joint->mBody1->mJointsList); joint->mBody1->mJointsList = jointListElement1; // Add the joint at the beginning of the linked list of joints of the second body - void* allocatedMemory2 = mPoolAllocator.allocate(sizeof(JointListElement)); + void* allocatedMemory2 = mMemoryManager.allocate(MemoryManager::AllocationType::Pool, + sizeof(JointListElement)); JointListElement* jointListElement2 = new (allocatedMemory2) JointListElement(joint, joint->mBody2->mJointsList); joint->mBody2->mJointsList = jointListElement2; @@ -603,7 +615,8 @@ void DynamicsWorld::computeIslands() { // Allocate and create the array of islands pointer. This memory is allocated // in the single frame allocator - mIslands = static_cast(mSingleFrameAllocator.allocate(sizeof(Island*) * nbBodies)); + mIslands = static_cast(mMemoryManager.allocate(MemoryManager::AllocationType::Frame, + sizeof(Island*) * nbBodies)); mNbIslands = 0; int nbContactManifolds = 0; @@ -619,7 +632,8 @@ void DynamicsWorld::computeIslands() { // Create a stack (using an array) for the rigid bodies to visit during the Depth First Search size_t nbBytesStack = sizeof(RigidBody*) * nbBodies; - RigidBody** stackBodiesToVisit = static_cast(mSingleFrameAllocator.allocate(nbBytesStack)); + RigidBody** stackBodiesToVisit = static_cast(mMemoryManager.allocate(MemoryManager::AllocationType::Frame, + nbBytesStack)); // For each rigid body of the world for (std::set::iterator it = mRigidBodies.begin(); it != mRigidBodies.end(); ++it) { @@ -642,9 +656,10 @@ void DynamicsWorld::computeIslands() { body->mIsAlreadyInIsland = true; // Create the new island - void* allocatedMemoryIsland = mSingleFrameAllocator.allocate(sizeof(Island)); + void* allocatedMemoryIsland = mMemoryManager.allocate(MemoryManager::AllocationType::Frame, + sizeof(Island)); mIslands[mNbIslands] = new (allocatedMemoryIsland) Island(nbBodies, nbContactManifolds, mJoints.size(), - mSingleFrameAllocator); + mMemoryManager); // While there are still some bodies to visit in the stack while (stackIndex > 0) { diff --git a/src/engine/Island.cpp b/src/engine/Island.cpp index 19eef304..34b65540 100644 --- a/src/engine/Island.cpp +++ b/src/engine/Island.cpp @@ -29,14 +29,17 @@ using namespace reactphysics3d; // Constructor -Island::Island(uint nbMaxBodies, uint nbMaxContactManifolds, uint nbMaxJoints, SingleFrameAllocator& allocator) +Island::Island(uint nbMaxBodies, uint nbMaxContactManifolds, uint nbMaxJoints, MemoryManager& memoryManager) : mBodies(nullptr), mContactManifolds(nullptr), mJoints(nullptr), mNbBodies(0), mNbContactManifolds(0), mNbJoints(0) { // Allocate memory for the arrays on the single frame allocator - mBodies = static_cast(allocator.allocate(sizeof(RigidBody*) * nbMaxBodies)); - mContactManifolds = static_cast(allocator.allocate(sizeof(ContactManifold*) * nbMaxContactManifolds)); - mJoints = static_cast(allocator.allocate(sizeof(Joint*) * nbMaxJoints)); + mBodies = static_cast(memoryManager.allocate(MemoryManager::AllocationType::Frame, + sizeof(RigidBody*) * nbMaxBodies)); + mContactManifolds = static_cast(memoryManager.allocate(MemoryManager::AllocationType::Frame, + sizeof(ContactManifold*) * nbMaxContactManifolds)); + mJoints = static_cast(memoryManager.allocate(MemoryManager::AllocationType::Frame, + sizeof(Joint*) * nbMaxJoints)); } // Destructor diff --git a/src/engine/Island.h b/src/engine/Island.h index 5f370004..ca1e6fdd 100644 --- a/src/engine/Island.h +++ b/src/engine/Island.h @@ -69,7 +69,7 @@ class Island { /// Constructor Island(uint nbMaxBodies, uint nbMaxContactManifolds, uint nbMaxJoints, - SingleFrameAllocator& allocator); + MemoryManager& memoryManager); /// Destructor ~Island(); diff --git a/src/engine/OverlappingPair.cpp b/src/engine/OverlappingPair.cpp index 431476ed..7a95be95 100644 --- a/src/engine/OverlappingPair.cpp +++ b/src/engine/OverlappingPair.cpp @@ -33,7 +33,7 @@ using namespace reactphysics3d; // Constructor OverlappingPair::OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, - Allocator& persistentMemoryAllocator, Allocator& temporaryMemoryAllocator) + MemoryAllocator& persistentMemoryAllocator, MemoryAllocator& temporaryMemoryAllocator) : mContactManifoldSet(shape1, shape2, persistentMemoryAllocator), mPotentialContactManifolds(nullptr), mPersistentAllocator(persistentMemoryAllocator), mTempMemoryAllocator(temporaryMemoryAllocator) { diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index 8c65e633..f3631775 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -113,18 +113,18 @@ class OverlappingPair { ContactManifoldInfo* mPotentialContactManifolds; /// Persistent memory allocator - Allocator& mPersistentAllocator; + MemoryAllocator& mPersistentAllocator; /// Memory allocator used to allocated memory for the ContactManifoldInfo and ContactPointInfo - Allocator& mTempMemoryAllocator; + MemoryAllocator& mTempMemoryAllocator; public: // -------------------- Methods -------------------- // /// Constructor - OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, Allocator& persistentMemoryAllocator, - Allocator& temporaryMemoryAllocator); + OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, MemoryAllocator& persistentMemoryAllocator, + MemoryAllocator& temporaryMemoryAllocator); /// Destructor ~OverlappingPair(); @@ -157,7 +157,7 @@ class OverlappingPair { void addContactManifold(const ContactManifoldInfo* contactManifoldInfo); /// Return a reference to the temporary memory allocator - Allocator& getTemporaryAllocator(); + MemoryAllocator& getTemporaryAllocator(); /// Return true if one of the shapes of the pair is a concave shape bool hasConcaveShape() const; @@ -264,7 +264,7 @@ inline bodyindexpair OverlappingPair::computeBodiesIndexPair(CollisionBody* body } // Return a reference to the temporary memory allocator -inline Allocator& OverlappingPair::getTemporaryAllocator() { +inline MemoryAllocator& OverlappingPair::getTemporaryAllocator() { return mTempMemoryAllocator; } diff --git a/src/mathematics/mathematics_functions.cpp b/src/mathematics/mathematics_functions.cpp index 0d8994f4..9fa13083 100755 --- a/src/mathematics/mathematics_functions.cpp +++ b/src/mathematics/mathematics_functions.cpp @@ -225,7 +225,7 @@ decimal reactphysics3d::computePointToLineDistance(const Vector3& linePointA, co List reactphysics3d::clipSegmentWithPlanes(const Vector3& segA, const Vector3& segB, const List& planesPoints, const List& planesNormals, - Allocator& allocator) { + MemoryAllocator& allocator) { assert(planesPoints.size() == planesNormals.size()); @@ -303,7 +303,7 @@ List reactphysics3d::clipSegmentWithPlanes(const Vector3& segA, const V // Clip a polygon against multiple planes and return the clipped polygon vertices // This method implements the Sutherland–Hodgman clipping algorithm List reactphysics3d::clipPolygonWithPlanes(const List& polygonVertices, const List& planesPoints, - const List& planesNormals, Allocator& allocator) { + const List& planesNormals, MemoryAllocator& allocator) { assert(planesPoints.size() == planesNormals.size()); diff --git a/src/mathematics/mathematics_functions.h b/src/mathematics/mathematics_functions.h index 5081d741..eda0fdd3 100755 --- a/src/mathematics/mathematics_functions.h +++ b/src/mathematics/mathematics_functions.h @@ -115,11 +115,11 @@ decimal computePointToLineDistance(const Vector3& linePointA, const Vector3& lin List clipSegmentWithPlanes(const Vector3& segA, const Vector3& segB, const List& planesPoints, const List& planesNormals, - Allocator& allocator); + MemoryAllocator& allocator); /// Clip a polygon against multiple planes and return the clipped polygon vertices List clipPolygonWithPlanes(const List& polygonVertices, const List& planesPoints, - const List& planesNormals, Allocator& allocator); + const List& planesNormals, MemoryAllocator& allocator); /// Project a point onto a plane that is given by a point and its unit length normal Vector3 projectPointOntoPlane(const Vector3& point, const Vector3& planeNormal, const Vector3& planePoint); diff --git a/src/memory/DefaultAllocator.h b/src/memory/DefaultAllocator.h index 367171bd..ac4ddd04 100644 --- a/src/memory/DefaultAllocator.h +++ b/src/memory/DefaultAllocator.h @@ -27,7 +27,7 @@ #define REACTPHYSICS3D_DEFAULT_ALLOCATOR_H // Libraries -#include "memory/Allocator.h" +#include "memory/MemoryAllocator.h" #include /// ReactPhysics3D namespace @@ -37,13 +37,16 @@ namespace reactphysics3d { /** * This class represents a default memory allocator that uses default malloc/free methods */ -class DefaultAllocator : public Allocator { +class DefaultAllocator : public MemoryAllocator { public: /// Destructor virtual ~DefaultAllocator() = default; + /// Assignment operator + DefaultAllocator& operator=(DefaultAllocator& allocator) = default; + /// Allocate memory of a given size (in bytes) and return a pointer to the /// allocated memory. virtual void* allocate(size_t size) override { @@ -54,11 +57,6 @@ class DefaultAllocator : public Allocator { virtual void release(void* pointer, size_t size) override { free(pointer); } - - /// Return true if memory needs to be release with this allocator - virtual bool isReleaseNeeded() const override { - return true; - } }; } diff --git a/src/memory/Allocator.h b/src/memory/MemoryAllocator.h similarity index 87% rename from src/memory/Allocator.h rename to src/memory/MemoryAllocator.h index 0440a5c9..c0d86a33 100644 --- a/src/memory/Allocator.h +++ b/src/memory/MemoryAllocator.h @@ -23,8 +23,8 @@ * * ********************************************************************************/ -#ifndef REACTPHYSICS3D_ALLOCATOR_H -#define REACTPHYSICS3D_ALLOCATOR_H +#ifndef REACTPHYSICS3D_MEMORY_ALLOCATOR_H +#define REACTPHYSICS3D_MEMORY_ALLOCATOR_H // Libraries #include @@ -32,16 +32,22 @@ /// ReactPhysics3D namespace namespace reactphysics3d { -// Class Allocator +// Class MemoryAllocator /** * Abstract class with the basic interface of all the derived memory allocators */ -class Allocator { +class MemoryAllocator { public: + /// Constructor + MemoryAllocator() = default; + /// Destructor - virtual ~Allocator() = default; + virtual ~MemoryAllocator() = default; + + /// Assignment operator + MemoryAllocator& operator=(MemoryAllocator& allocator) = default; /// Allocate memory of a given size (in bytes) and return a pointer to the /// allocated memory. @@ -49,9 +55,6 @@ class Allocator { /// Release previously allocated memory. virtual void release(void* pointer, size_t size)=0; - - /// Return true if memory needs to be release with this allocator - virtual bool isReleaseNeeded() const=0; }; } diff --git a/src/memory/MemoryManager.cpp b/src/memory/MemoryManager.cpp index 85832cb1..99a32655 100644 --- a/src/memory/MemoryManager.cpp +++ b/src/memory/MemoryManager.cpp @@ -30,3 +30,5 @@ using namespace reactphysics3d; // Static variables DefaultAllocator MemoryManager::mDefaultAllocator; +MemoryAllocator* MemoryManager::mBaseAllocator = &mDefaultAllocator; + diff --git a/src/memory/MemoryManager.h b/src/memory/MemoryManager.h index 922a5a17..8d986a31 100644 --- a/src/memory/MemoryManager.h +++ b/src/memory/MemoryManager.h @@ -27,7 +27,10 @@ #define REACTPHYSICS3D_MEMORY_MANAGER_H // Libraries +#include "memory/MemoryAllocator.h" #include "memory/DefaultAllocator.h" +#include "memory/PoolAllocator.h" +#include "memory/SingleFrameAllocator.h" /// Namespace ReactPhysics3D namespace reactphysics3d { @@ -41,31 +44,98 @@ class MemoryManager { private: - /// Default memory allocator + /// Default malloc/free memory allocator static DefaultAllocator mDefaultAllocator; + /// Pointer to the base memory allocator to use + static MemoryAllocator* mBaseAllocator; + + /// Memory pool allocator + PoolAllocator mPoolAllocator; + + /// Single frame stack allocator + SingleFrameAllocator mSingleFrameAllocator; + public: /// Memory allocation types enum class AllocationType { - Default, // Default memory allocator + Base, // Base memory allocator Pool, // Memory pool allocator Frame, // Single frame memory allocator }; - /// Constructor - MemoryManager(); + /// Constructor + MemoryManager() = default; - /// Destructor - ~MemoryManager(); + /// Destructor + ~MemoryManager() = default; - /// Return the default memory allocator - static DefaultAllocator& getDefaultAllocator(); + /// Allocate memory of a given type + void* allocate(AllocationType allocationType, size_t size); + + /// Release previously allocated memory. + void release(AllocationType allocationType, void* pointer, size_t size); + + /// Return the pool allocator + PoolAllocator& getPoolAllocator(); + + /// Return the single frame stack allocator + SingleFrameAllocator& getSingleFrameAllocator(); + + /// Return the base memory allocator + static MemoryAllocator& getBaseAllocator(); + + /// Set the base memory allocator + static void setBaseAllocator(MemoryAllocator* memoryAllocator); + + /// Reset the single frame allocator + void resetFrameAllocator(); }; -// Return the default memory allocator -inline DefaultAllocator& MemoryManager::getDefaultAllocator() { - return mDefaultAllocator; +// Allocate memory of a given type +inline void* MemoryManager::allocate(AllocationType allocationType, size_t size) { + + switch (allocationType) { + case AllocationType::Base: return mBaseAllocator->allocate(size); break; + case AllocationType::Pool: return mPoolAllocator.allocate(size); break; + case AllocationType::Frame: return mSingleFrameAllocator.allocate(size); break; + } +} + +// Release previously allocated memory. +inline void MemoryManager::release(AllocationType allocationType, void* pointer, size_t size) { + + switch (allocationType) { + case AllocationType::Base: mBaseAllocator->release(pointer, size); break; + case AllocationType::Pool: mPoolAllocator.release(pointer, size); break; + case AllocationType::Frame: mSingleFrameAllocator.release(pointer, size); break; + } +} + +// Return the pool allocator +inline PoolAllocator& MemoryManager::getPoolAllocator() { + return mPoolAllocator; +} + +// Return the single frame stack allocator +inline SingleFrameAllocator& MemoryManager::getSingleFrameAllocator() { + return mSingleFrameAllocator; +} + +// Return the base memory allocator +inline MemoryAllocator& MemoryManager::getBaseAllocator() { + return *mBaseAllocator; +} + +// Set the base memory allocator +inline void MemoryManager::setBaseAllocator(MemoryAllocator* baseAllocator) { + mBaseAllocator = baseAllocator; +} + +// Reset the single frame allocator +inline void MemoryManager::resetFrameAllocator() { + mSingleFrameAllocator.reset(); } } diff --git a/src/memory/PoolAllocator.cpp b/src/memory/PoolAllocator.cpp index 53cee0a1..2a9507c4 100644 --- a/src/memory/PoolAllocator.cpp +++ b/src/memory/PoolAllocator.cpp @@ -25,6 +25,7 @@ // Libraries #include "PoolAllocator.h" +#include "MemoryManager.h" #include #include @@ -42,7 +43,7 @@ PoolAllocator::PoolAllocator() { mNbAllocatedMemoryBlocks = 64; mNbCurrentMemoryBlocks = 0; const size_t sizeToAllocate = mNbAllocatedMemoryBlocks * sizeof(MemoryBlock); - mMemoryBlocks = (MemoryBlock*) malloc(sizeToAllocate); + mMemoryBlocks = static_cast(MemoryManager::getBaseAllocator().allocate(sizeToAllocate)); memset(mMemoryBlocks, 0, sizeToAllocate); memset(mFreeMemoryUnits, 0, sizeof(mFreeMemoryUnits)); @@ -55,7 +56,7 @@ PoolAllocator::PoolAllocator() { // Initialize the array that contains the sizes the memory units that will // be allocated in each different heap - for (int i=0; i < NB_HEAPS; i++) { + for (uint i=0; i < NB_HEAPS; i++) { mUnitSizes[i] = (i+1) * 8; } @@ -82,16 +83,17 @@ PoolAllocator::~PoolAllocator() { // Release the memory allocated for each block for (uint i=0; i MAX_UNIT_SIZE) { - // Allocate memory using standard malloc() function - return malloc(size); + // Allocate memory using default allocation + return MemoryManager::getBaseAllocator().allocate(size); } // Get the index of the heap that will take care of the allocation request @@ -132,7 +134,7 @@ void* PoolAllocator::allocate(size_t size) { // Allocate more memory to contain the blocks MemoryBlock* currentMemoryBlocks = mMemoryBlocks; mNbAllocatedMemoryBlocks += 64; - mMemoryBlocks = (MemoryBlock*) malloc(mNbAllocatedMemoryBlocks * sizeof(MemoryBlock)); + mMemoryBlocks = static_cast(MemoryManager::getBaseAllocator().allocate(mNbAllocatedMemoryBlocks * sizeof(MemoryBlock))); memcpy(mMemoryBlocks, currentMemoryBlocks,mNbCurrentMemoryBlocks * sizeof(MemoryBlock)); memset(mMemoryBlocks + mNbCurrentMemoryBlocks, 0, 64 * sizeof(MemoryBlock)); free(currentMemoryBlocks); @@ -141,17 +143,22 @@ void* PoolAllocator::allocate(size_t size) { // Allocate a new memory blocks for the corresponding heap and divide it in many // memory units MemoryBlock* newBlock = mMemoryBlocks + mNbCurrentMemoryBlocks; - newBlock->memoryUnits = (MemoryUnit*) malloc(BLOCK_SIZE); + newBlock->memoryUnits = static_cast(MemoryManager::getBaseAllocator().allocate(BLOCK_SIZE)); assert(newBlock->memoryUnits != nullptr); size_t unitSize = mUnitSizes[indexHeap]; uint nbUnits = BLOCK_SIZE / unitSize; assert(nbUnits * unitSize <= BLOCK_SIZE); + void* memoryUnitsStart = static_cast(newBlock->memoryUnits); + char* memoryUnitsStartChar = static_cast(memoryUnitsStart); for (size_t i=0; i < nbUnits - 1; i++) { - MemoryUnit* unit = (MemoryUnit*) ((size_t)newBlock->memoryUnits + unitSize * i); - MemoryUnit* nextUnit = (MemoryUnit*) ((size_t)newBlock->memoryUnits + unitSize * (i+1)); + void* unitPointer = static_cast(memoryUnitsStartChar + unitSize * i); + void* nextUnitPointer = static_cast(memoryUnitsStartChar + unitSize * (i+1)); + MemoryUnit* unit = static_cast(unitPointer); + MemoryUnit* nextUnit = static_cast(nextUnitPointer); unit->nextUnit = nextUnit; } - MemoryUnit* lastUnit = (MemoryUnit*) ((size_t)newBlock->memoryUnits + unitSize*(nbUnits-1)); + void* lastUnitPointer = static_cast(memoryUnitsStartChar + unitSize*(nbUnits-1)); + MemoryUnit* lastUnit = static_cast(lastUnitPointer); lastUnit->nextUnit = nullptr; // Add the new allocated block into the list of free memory units in the heap @@ -176,8 +183,8 @@ void PoolAllocator::release(void* pointer, size_t size) { // If the size is larger than the maximum memory unit size if (size > MAX_UNIT_SIZE) { - // Release the memory using the standard free() function - free(pointer); + // Release the memory using the default deallocation + MemoryManager::getBaseAllocator().release(pointer, size); return; } @@ -187,7 +194,7 @@ void PoolAllocator::release(void* pointer, size_t size) { // Insert the released memory unit into the list of free memory units of the // corresponding heap - MemoryUnit* releasedUnit = (MemoryUnit*) pointer; + MemoryUnit* releasedUnit = static_cast(pointer); releasedUnit->nextUnit = mFreeMemoryUnits[indexHeap]; mFreeMemoryUnits[indexHeap] = releasedUnit; } diff --git a/src/memory/PoolAllocator.h b/src/memory/PoolAllocator.h index b06778d5..25f31198 100644 --- a/src/memory/PoolAllocator.h +++ b/src/memory/PoolAllocator.h @@ -28,7 +28,7 @@ // Libraries #include "configuration.h" -#include "Allocator.h" +#include "MemoryAllocator.h" /// ReactPhysics3D namespace namespace reactphysics3d { @@ -40,7 +40,7 @@ namespace reactphysics3d { * efficiently. This implementation is inspired by the small block allocator * described here : http://www.codeproject.com/useritems/Small_Block_Allocator.asp */ -class PoolAllocator : public Allocator { +class PoolAllocator : public MemoryAllocator { private : @@ -131,23 +131,17 @@ class PoolAllocator : public Allocator { /// Destructor virtual ~PoolAllocator() override; + /// Assignment operator + PoolAllocator& operator=(PoolAllocator& allocator) = default; + /// Allocate memory of a given size (in bytes) and return a pointer to the /// allocated memory. virtual void* allocate(size_t size) override; /// Release previously allocated memory. virtual void release(void* pointer, size_t size) override; - - /// Return true if memory needs to be release with this allocator - virtual bool isReleaseNeeded() const override; - }; -// Return true if memory needs to be release with this allocator -inline bool PoolAllocator::isReleaseNeeded() const { - return true; -} - } #endif diff --git a/src/memory/SingleFrameAllocator.cpp b/src/memory/SingleFrameAllocator.cpp index a2e436cd..c9d6533a 100644 --- a/src/memory/SingleFrameAllocator.cpp +++ b/src/memory/SingleFrameAllocator.cpp @@ -25,17 +25,19 @@ // Libraries #include "SingleFrameAllocator.h" +#include "MemoryManager.h" #include #include using namespace reactphysics3d; // Constructor -SingleFrameAllocator::SingleFrameAllocator(size_t totalSizeBytes) - : mTotalSizeBytes(totalSizeBytes), mCurrentOffset(0) { +SingleFrameAllocator::SingleFrameAllocator() + : mTotalSizeBytes(INIT_SINGLE_FRAME_ALLOCATOR_BYTES), + mCurrentOffset(0), mNbFramesTooMuchAllocated(0), mNeedToAllocatedMore(false) { // Allocate a whole block of memory at the beginning - mMemoryBufferStart = static_cast(malloc(mTotalSizeBytes)); + mMemoryBufferStart = static_cast(MemoryManager::getBaseAllocator().allocate(mTotalSizeBytes)); assert(mMemoryBufferStart != nullptr); } @@ -43,7 +45,7 @@ SingleFrameAllocator::SingleFrameAllocator(size_t totalSizeBytes) SingleFrameAllocator::~SingleFrameAllocator() { // Release the memory allocated at the beginning - free(mMemoryBufferStart); + MemoryManager::getBaseAllocator().release(mMemoryBufferStart, mTotalSizeBytes); } @@ -52,14 +54,13 @@ SingleFrameAllocator::~SingleFrameAllocator() { void* SingleFrameAllocator::allocate(size_t size) { // Check that there is enough remaining memory in the buffer - if (static_cast(mCurrentOffset) + size > mTotalSizeBytes) { + if (mCurrentOffset + size > mTotalSizeBytes) { - // This should never occur. If it does, you must increase the initial - // size of memory of this allocator - assert(false); + // We need to allocate more memory next time reset() is called + mNeedToAllocatedMore = true; - // Return null - return nullptr; + // Return default memory allocation + return MemoryManager::getBaseAllocator().allocate(size); } // Next available memory location @@ -72,9 +73,63 @@ void* SingleFrameAllocator::allocate(size_t size) { return nextAvailableMemory; } +// Release previously allocated memory. +void SingleFrameAllocator::release(void* pointer, size_t size) { + + // If allocated memory is not within the single frame allocation range + char* p = static_cast(pointer); + if (p < mMemoryBufferStart || p > mMemoryBufferStart + mTotalSizeBytes) { + + // Use default deallocation + MemoryManager::getBaseAllocator().release(pointer, size); + } +} + // Reset the marker of the current allocated memory void SingleFrameAllocator::reset() { + // If too much memory is allocated + if (mCurrentOffset < mTotalSizeBytes / 2) { + + mNbFramesTooMuchAllocated++; + + if (mNbFramesTooMuchAllocated > NB_FRAMES_UNTIL_SHRINK) { + + // Release the memory allocated at the beginning + MemoryManager::getBaseAllocator().release(mMemoryBufferStart, mTotalSizeBytes); + + // Divide the total memory to allocate by two + mTotalSizeBytes /= 2; + if (mTotalSizeBytes <= 0) mTotalSizeBytes = 1; + + // Allocate a whole block of memory at the beginning + mMemoryBufferStart = static_cast(MemoryManager::getBaseAllocator().allocate(mTotalSizeBytes)); + assert(mMemoryBufferStart != nullptr); + + mNbFramesTooMuchAllocated = 0; + } + } + else { + mNbFramesTooMuchAllocated = 0; + } + + // If we need to allocate more memory + if (mNeedToAllocatedMore) { + + // Release the memory allocated at the beginning + MemoryManager::getBaseAllocator().release(mMemoryBufferStart, mTotalSizeBytes); + + // Multiply the total memory to allocate by two + mTotalSizeBytes *= 2; + + // Allocate a whole block of memory at the beginning + mMemoryBufferStart = static_cast(MemoryManager::getBaseAllocator().allocate(mTotalSizeBytes)); + assert(mMemoryBufferStart != nullptr); + + mNeedToAllocatedMore = false; + mNbFramesTooMuchAllocated = 0; + } + // Reset the current offset at the beginning of the block mCurrentOffset = 0; } diff --git a/src/memory/SingleFrameAllocator.h b/src/memory/SingleFrameAllocator.h index 426c2a2d..d3142908 100644 --- a/src/memory/SingleFrameAllocator.h +++ b/src/memory/SingleFrameAllocator.h @@ -27,7 +27,7 @@ #define REACTPHYSICS3D_SINGLE_FRAME_ALLOCATOR_H // Libraries -#include "Allocator.h" +#include "MemoryAllocator.h" #include "configuration.h" /// ReactPhysics3D namespace @@ -38,10 +38,16 @@ namespace reactphysics3d { * This class represent a memory allocator used to efficiently allocate * memory on the heap that is used during a single frame. */ -class SingleFrameAllocator : public Allocator { +class SingleFrameAllocator : public MemoryAllocator { private : + // -------------------- Constants -------------------- // + + /// Number of frames to wait before shrinking the allocated + /// memory if too much is allocated + static const int NB_FRAMES_UNTIL_SHRINK = 120; + // -------------------- Attributes -------------------- // /// Total size (in bytes) of memory of the allocator @@ -51,36 +57,38 @@ class SingleFrameAllocator : public Allocator { char* mMemoryBufferStart; /// Pointer to the next available memory location in the buffer - int mCurrentOffset; + size_t mCurrentOffset; + + /// Current number of frames since we detected too much memory + /// is allocated + size_t mNbFramesTooMuchAllocated; + + /// True if we need to allocate more memory in the next reset() call + bool mNeedToAllocatedMore; public : // -------------------- Methods -------------------- // /// Constructor - SingleFrameAllocator(size_t totalSizeBytes); + SingleFrameAllocator(); /// Destructor virtual ~SingleFrameAllocator() override; + /// Assignment operator + SingleFrameAllocator& operator=(SingleFrameAllocator& allocator) = default; + /// Allocate memory of a given size (in bytes) virtual void* allocate(size_t size) override; /// Release previously allocated memory. - virtual void release(void* pointer, size_t size) override { } + virtual void release(void* pointer, size_t size) override; /// Reset the marker of the current allocated memory virtual void reset(); - - /// Return true if memory needs to be release with this allocator - virtual bool isReleaseNeeded() const override; }; -// Return true if memory needs to be release with this allocator -inline bool SingleFrameAllocator::isReleaseNeeded() const { - return false; -} - } #endif From ceb27760cb15830c006fe2d939e8628557f74896 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 14 Jan 2018 10:47:39 +0100 Subject: [PATCH 154/248] Working on containers --- CMakeLists.txt | 1 + src/containers/List.h | 133 +++++- src/containers/Map.h | 532 ++++++++++++++++++++++ src/mathematics/mathematics_functions.cpp | 24 + src/mathematics/mathematics_functions.h | 3 + test/main.cpp | 7 + test/tests/containers/TestList.h | 331 ++++++++++++++ test/tests/containers/TestMap.h | 319 +++++++++++++ test/tests/mathematics/TestTransform.h | 15 +- 9 files changed, 1353 insertions(+), 12 deletions(-) create mode 100644 src/containers/Map.h create mode 100644 test/tests/containers/TestList.h create mode 100644 test/tests/containers/TestMap.h diff --git a/CMakeLists.txt b/CMakeLists.txt index bc11aebd..169476c9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -198,6 +198,7 @@ SET (REACTPHYSICS3D_SOURCES "src/containers/Stack.h" "src/containers/LinkedList.h" "src/containers/List.h" + "src/containers/Map.h" ) # Create the library diff --git a/src/containers/List.h b/src/containers/List.h index 176766a5..6391d52b 100644 --- a/src/containers/List.h +++ b/src/containers/List.h @@ -30,6 +30,7 @@ #include "configuration.h" #include "memory/MemoryAllocator.h" #include +#include namespace reactphysics3d { @@ -61,6 +62,102 @@ class List { public: + /// Class Iterator + /** + * This class represents an iterator for the List + */ + class Iterator { + + private: + + size_t mCurrentIndex; + T* mBuffer; + size_t mSize; + + public: + + // Iterator traits + using value_type = T; + using difference_type = std::ptrdiff_t; + using pointer = T*; + using reference = T&; + using iterator_category = std::bidirectional_iterator_tag; + + /// Constructor + Iterator() = default; + + /// Constructor + Iterator(T* buffer, size_t index, size_t size) + :mCurrentIndex(index), mBuffer(buffer), mSize(size) { + + } + + /// Copy constructor + Iterator(const Iterator& it) + :mCurrentIndex(it.mCurrentIndex), mBuffer(it.mBuffer), mSize(it.size) { + + } + + /// Deferencable + reference operator*() const { + assert(mCurrentIndex >= 0 && mCurrentIndex < mSize); + return mBuffer[mCurrentIndex]; + } + + /// Deferencable + pointer operator->() const { + assert(mCurrentIndex >= 0 && mCurrentIndex < mSize); + return &(mBuffer[mCurrentIndex]); + } + + /// Post increment (it++) + Iterator& operator++() { + assert(mCurrentIndex < mSize - 1); + mCurrentIndex++; + return *this; + } + + /// Pre increment (++it) + Iterator operator++(int number) { + assert(mCurrentIndex < mSize - 1); + Iterator tmp = *this; + mCurrentIndex++; + return tmp; + } + + /// Post decrement (it--) + Iterator& operator--() { + assert(mCurrentIndex > 0); + mCurrentIndex--; + return *this; + } + + /// Pre decrement (--it) + Iterator operator--(int number) { + assert(mCurrentIndex > 0); + Iterator tmp = *this; + mCurrentIndex--; + return tmp; + } + + /// Equality operator (it == end()) + bool operator==(const Iterator& iterator) const { + assert(mCurrentIndex >= 0 && mCurrentIndex <= mSize); + + // If both iterators points to the end of the list + if (mCurrentIndex == mSize && iterator.mCurrentIndex == iterator.mSize) { + return true; + } + + return &(mBuffer[mCurrentIndex]) == &(iterator.mBuffer[mCurrentIndex]); + } + + /// Inequality operator (it != end()) + bool operator!=(const Iterator& iterator) const { + return !(*this == iterator); + } + }; + // -------------------- Methods -------------------- // /// Constructor @@ -151,7 +248,7 @@ class List { } } - /// Append another list to the current one + /// Append another list at the end of the current one void addRange(const List& list) { // If we need to allocate more memory @@ -180,7 +277,7 @@ class List { mSize = 0; } - /// Return the number of elments in the list + /// Return the number of elements in the list size_t size() const { return mSize; } @@ -202,14 +299,38 @@ class List { return (static_cast(mBuffer)[index]); } + /// Overloaded equality operator + bool operator==(const List& list) const { + + if (mSize != list.mSize) return false; + + T* items = static_cast(mBuffer); + for (int i=0; i < mSize; i++) { + if (items[i] != list[i]) { + return false; + } + } + + return true; + } + + /// Overloaded not equal operator + bool operator!=(const List& list) const { + + return !((*this) == list); + } + /// Overloaded assignment operator List& operator=(const List& list) { - // Clear all the elements - clear(); + if (this != &list) { - // Add all the elements of the list to the current one - addRange(list); + // Clear all the elements + clear(); + + // Add all the elements of the list to the current one + addRange(list); + } return *this; } diff --git a/src/containers/Map.h b/src/containers/Map.h new file mode 100644 index 00000000..5510b98d --- /dev/null +++ b/src/containers/Map.h @@ -0,0 +1,532 @@ +/******************************************************************************** +* 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_MAP_H +#define REACTPHYSICS3D_MAP_H + +// Libraries +#include "memory/MemoryAllocator.h" +#include "mathematics/mathematics_functions.h" +#include +#include + +namespace reactphysics3d { + +// Class Map +/** + * This class represents a simple generic associative map + */ +template +class Map { + + private: + + /// An entry of the map + struct Entry { + + size_t hashCode; // Hash code of the entry + int next; // Index of the next entry + std::pair* keyValue; // Pointer to the pair with key and value + + /// Constructor + Entry() { + next = -1; + keyValue = nullptr; + } + + /// Destructor + ~Entry() { + + assert(keyValue == nullptr); + } + + }; + + // -------------------- Constants -------------------- // + + /// Number of prime numbers in array + static constexpr int NB_PRIMES = 70; + + /// Array of prime numbers for the size of the map + static const int PRIMES[NB_PRIMES]; + + /// Largest prime number + static int LARGEST_PRIME; + + // -------------------- Attributes -------------------- // + + /// Current number of used entries in the map + int mNbUsedEntries; + + /// Number of free entries among the used ones + int mNbFreeEntries; + + /// Current capacity of the map + int mCapacity; + + /// Array with all the buckets + int* mBuckets; + + /// Array with all the entries + Entry* mEntries; + + /// Memory allocator + MemoryAllocator& mAllocator; + + /// Index to the fist free entry + int mFreeIndex; + + // -------------------- Methods -------------------- // + + /// Initialize the map + void initialize(int capacity) { + + // Compute the next larger prime size + mCapacity = getPrimeSize(capacity); + + // Allocate memory for the buckets + mBuckets = static_cast(mAllocator.allocate(mCapacity * sizeof(int))); + + // Allocate memory for the entries + mEntries = static_cast(mAllocator.allocate(mCapacity * sizeof(Entry))); + + // Initialize the buckets and entries + for (int i=0; i mCapacity); + assert(isPrimeNumber(newCapacity)); + + // Allocate memory for the buckets + int* newBuckets = static_cast(mAllocator.allocate(newCapacity * sizeof(int))); + + // Allocate memory for the entries + Entry* newEntries = static_cast(mAllocator.allocate(newCapacity * sizeof(Entry))); + + // Initialize the new buckets + for (int i=0; i(&newEntries[i])) Entry(); + } + + // For each used entry + for (int i=0; i 0) { + + size_t hashCode = std::hash()(key); + int bucket = hashCode % mCapacity; + + for (int i = mBuckets[bucket]; i >= 0; i = mEntries[i].next) { + if (mEntries[i].hashCode == hashCode && mEntries[i].keyValue->first == key) { + return i; + } + } + } + + return -1; + } + + /// Return the prime number that is larger or equal to the number in parameter + /// for the size of the map + static int getPrimeSize(int number) { + + // Check if the next larger prime number is in the precomputed array of primes + for (int i = 0; i < NB_PRIMES; i++) { + if (PRIMES[i] >= number) return PRIMES[i]; + } + + // Manually compute the next larger prime number + for (int i = (number | 1); i < std::numeric_limits::max(); i+=2) { + + if (isPrimeNumber(i)) { + return i; + } + } + + return number; + } + + /// Clear and reset the map + void reset() { + + // If elements have been allocated + if (mCapacity > 0) { + + // Clear the list + clear(); + + // Destroy the entries + for (int i=0; i < mCapacity; i++) { + mEntries[i].~Entry(); + } + + mAllocator.release(mBuckets, mCapacity * sizeof(int)); + mAllocator.release(mEntries, mCapacity * sizeof(Entry)); + + mNbUsedEntries = 0; + mNbFreeEntries = 0; + mCapacity = 0; + mBuckets = nullptr; + mEntries = nullptr; + mFreeIndex = -1; + } + } + + public: + + // -------------------- Methods -------------------- // + + /// Constructor + Map(MemoryAllocator& allocator, size_t capacity = 0) + : mNbUsedEntries(0), mNbFreeEntries(0), mCapacity(0), mBuckets(nullptr), + mEntries(nullptr), mAllocator(allocator), mFreeIndex(-1) { + + // If the largest prime has not been computed yet + if (LARGEST_PRIME == -1) { + + // Compute the largest prime number (largest map capacity) + LARGEST_PRIME = getPrimeSize(PRIMES[NB_PRIMES - 1] + 2); + } + + if (capacity > 0) { + + initialize(capacity); + } + } + + /// Copy constructor + Map(const Map& map) + :mNbUsedEntries(map.mNbUsedEntries), mNbFreeEntries(map.mNbFreeEntries), mCapacity(map.mCapacity), + mAllocator(map.mAllocator), mFreeIndex(map.mFreeIndex) { + + // Allocate memory for the buckets + mBuckets = static_cast(mAllocator.allocate(mCapacity * sizeof(int))); + + // Allocate memory for the entries + mEntries = static_cast(mAllocator.allocate(mCapacity * sizeof(Entry))); + + // Copy the buckets + std::memcpy(mBuckets, map.mBuckets, mCapacity * sizeof(int)); + + // Copy the entries + std::memcpy(mEntries, map.mEntries, mCapacity * sizeof(Entry)); + } + + /// Destructor + ~Map() { + + reset(); + } + + /// Allocate memory for a given number of elements + void reserve(size_t capacity) { + + if (capacity <= mCapacity) return; + + if (capacity > LARGEST_PRIME && LARGEST_PRIME > mCapacity) { + capacity = LARGEST_PRIME; + } + else { + capacity = getPrimeSize(capacity); + } + + expand(capacity); + } + + /// Return true if the map contains an item with the given key + bool containsKey(const K& key) const { + return findEntry(key) != -1; + } + + /// Add an element into the map + void add(const std::pair& keyValue) { + + if (mCapacity == 0) { + initialize(0); + } + + // Compute the hash code of the key + size_t hashCode = std::hash()(keyValue.first); + + // Compute the corresponding bucket index + int bucket = hashCode % mCapacity; + + // Check if the item is already in the map + for (int i = mBuckets[bucket]; i >= 0; i = mEntries[i].next) { + + // If there is already an item with the same key in the map + if (mEntries[i].hashCode == hashCode && mEntries[i].keyValue->first == keyValue.first) { + + throw std::runtime_error("The key and value pair already exists in the map"); + } + } + + size_t entryIndex; + + // If there are free entries to use + if (mNbFreeEntries > 0) { + assert(mFreeIndex >= 0); + entryIndex = mFreeIndex; + mFreeIndex = mEntries[entryIndex].next; + mNbFreeEntries--; + } + else { + + // If we need to allocator more entries + if (mNbUsedEntries == mCapacity) { + + // Allocate more memory + reserve(mCapacity * 2); + + // Recompute the bucket index + bucket = hashCode % mCapacity; + } + + entryIndex = mNbUsedEntries; + mNbUsedEntries++; + } + + assert(mEntries[entryIndex].keyValue == nullptr); + mEntries[entryIndex].hashCode = hashCode; + mEntries[entryIndex].next = mBuckets[bucket]; + mEntries[entryIndex].keyValue = static_cast*>(mAllocator.allocate(sizeof(std::pair))); + assert(mEntries[entryIndex].keyValue != nullptr); + new (mEntries[entryIndex].keyValue) std::pair(keyValue); + mBuckets[bucket] = entryIndex; + } + + /// Remove the element from the map with a given key + bool remove(const K& key) { + + if (mCapacity > 0) { + + size_t hashcode = std::hash()(key); + int bucket = hashcode % mCapacity; + int last = -1; + for (int i = mBuckets[bucket]; i >= 0; last = i, i = mEntries[i].next) { + + if (mEntries[i].hashCode == hashcode && mEntries[i].keyValue->first == key) { + + if (last < 0 ) { + mBuckets[bucket] = mEntries[i].next; + } + else { + mEntries[last].next = mEntries[i].next; + } + + // Release memory for the key/value pair if any + if (mEntries[i].keyValue != nullptr) { + mEntries[i].keyValue->~pair(); + mAllocator.release(mEntries[i].keyValue, sizeof(std::pair)); + mEntries[i].keyValue = nullptr; + } + mEntries[i].hashCode = -1; + mEntries[i].next = mFreeIndex; + mFreeIndex = i; + mNbFreeEntries++; + + return true; + } + } + } + + return false; + } + + /// Clear the list + void clear() { + + if (mNbUsedEntries > 0) { + + for (int i=0; i < mCapacity; i++) { + mBuckets[i] = -1; + mEntries[i].next = -1; + if (mEntries[i].keyValue != nullptr) { + mEntries[i].keyValue->~pair(); + mAllocator.release(mEntries[i].keyValue, sizeof(std::pair)); + mEntries[i].keyValue = nullptr; + } + } + + mFreeIndex = -1; + mNbUsedEntries = 0; + mNbFreeEntries = 0; + } + + assert(size() == 0); + } + + /// Return the number of elements in the map + int size() const { + return mNbUsedEntries - mNbFreeEntries; + } + + /// Return the capacity of the map + int capacity() const { + return mCapacity; + } + + /// Overloaded index operator + V& operator[](const K& key) { + + int entry = -1; + + if (mCapacity > 0) { + entry = findEntry(key); + } + + if (entry == -1) { + throw std::runtime_error("No item with given key has been found in the map"); + } + + assert(mEntries[entry].keyValue != nullptr); + + return mEntries[entry].keyValue->second; + } + + /// Overloaded index operator + const V& operator[](const K& key) const { + + int entry = -1; + + if (mCapacity > 0) { + entry = findEntry(key); + } + + if (entry == -1) { + throw std::runtime_error("No item with given key has been found in the map"); + } + + return mEntries[entry]; + } + + /// Overloaded equality operator + bool operator==(const Map& map) const { + + // TODO : Implement this + return false; + } + + /// Overloaded not equal operator + bool operator!=(const Map& map) const { + + return !((*this) == map); + } + + /// Overloaded assignment operator + Map& operator=(const Map& map) { + + // Check for self assignment + if (this != &map) { + + // Reset the map + reset(); + + if (map.mCapacity > 0) { + + // Compute the next larger prime size + mCapacity = getPrimeSize(map.mCapacity); + + // Allocate memory for the buckets + mBuckets = static_cast(mAllocator.allocate(mCapacity * sizeof(int))); + + // Allocate memory for the entries + mEntries = static_cast(mAllocator.allocate(mCapacity * sizeof(Entry))); + + // Copy the buckets + std::memcpy(mBuckets, map.mBuckets, mCapacity * sizeof(int)); + + // Copy the entries + std::memcpy(mEntries, map.mEntries, mCapacity * sizeof(Entry)); + + mNbUsedEntries = map.mNbUsedEntries; + mNbFreeEntries = map.mNbFreeEntries; + mFreeIndex = map.mFreeIndex; + } + } + + return *this; + } +}; + +template +const int Map::PRIMES[NB_PRIMES] = {3, 7, 11, 17, 23, 29, 37, 47, 59, 71, 89, 107, 131, 163, 197, 239, 293, 353, 431, 521, 631, 761, 919, + 1103, 1327, 1597, 1931, 2333, 2801, 3371, 4049, 4861, 5839, 7013, 8419, 10103, 12143, 14591, + 17519, 21023, 25229, 30293, 36353, 43627, 52361, 62851, 75431, 90523, 108631, 130363, 156437, + 187751, 225307, 270371, 324449, 389357, 467237, 560689, 672827, 807403, 968897, 1162687, 1395263, + 1674319, 2009191, 2411033, 2893249, 3471899, 4166287, 4999559}; + +template +int Map::LARGEST_PRIME = -1; + +} + +#endif diff --git a/src/mathematics/mathematics_functions.cpp b/src/mathematics/mathematics_functions.cpp index 9fa13083..7e4a1427 100755 --- a/src/mathematics/mathematics_functions.cpp +++ b/src/mathematics/mathematics_functions.cpp @@ -383,4 +383,28 @@ Vector3 reactphysics3d::projectPointOntoPlane(const Vector3& point, const Vector return point - unitPlaneNormal.dot(point - planePoint) * unitPlaneNormal; } +// Return true if the given number is prime +bool reactphysics3d::isPrimeNumber(int number) { + + // If it's a odd number + if ((number & 1) != 0) { + + int limit = static_cast(std::sqrt(number)); + + for (int divisor = 3; divisor <= limit; divisor += 2) { + + // If we have found a divisor + if ((number % divisor) == 0) { + + // It is not a prime number + return false; + } + } + + return true; + } + + return number == 2; +} + diff --git a/src/mathematics/mathematics_functions.h b/src/mathematics/mathematics_functions.h index eda0fdd3..a72b0077 100755 --- a/src/mathematics/mathematics_functions.h +++ b/src/mathematics/mathematics_functions.h @@ -124,6 +124,9 @@ List clipPolygonWithPlanes(const List& polygonVertices, const /// Project a point onto a plane that is given by a point and its unit length normal Vector3 projectPointOntoPlane(const Vector3& point, const Vector3& planeNormal, const Vector3& planePoint); +/// Return true if the given number is prime +bool isPrimeNumber(int number); + } diff --git a/test/main.cpp b/test/main.cpp index 26d62803..8bb62ea4 100644 --- a/test/main.cpp +++ b/test/main.cpp @@ -39,6 +39,8 @@ #include "tests/collision/TestDynamicAABBTree.h" #include "tests/collision/TestHalfEdgeStructure.h" #include "tests/collision/TestTriangleVertexArray.h" +#include "tests/containers/TestList.h" +#include "tests/containers/TestMap.h" using namespace reactphysics3d; @@ -46,6 +48,11 @@ int main() { TestSuite testSuite("ReactPhysics3D Tests"); + // ---------- Containers tests ---------- // + + testSuite.addTest(new TestList("List")); + testSuite.addTest(new TestMap("Map")); + // ---------- Mathematics tests ---------- // testSuite.addTest(new TestVector2("Vector2")); diff --git a/test/tests/containers/TestList.h b/test/tests/containers/TestList.h new file mode 100644 index 00000000..ba1fbf61 --- /dev/null +++ b/test/tests/containers/TestList.h @@ -0,0 +1,331 @@ +/******************************************************************************** +* 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 TEST_LIST_H +#define TEST_LIST_H + +// Libraries +#include "Test.h" +#include "containers/List.h" +#include "memory/DefaultAllocator.h" + +/// Reactphysics3D namespace +namespace reactphysics3d { + +// Class TestList +/** + * Unit test for the List class + */ +class TestList : public Test { + + private : + + // ---------- Atributes ---------- // + + DefaultAllocator mAllocator; + + public : + + // ---------- Methods ---------- // + + /// Constructor + TestList(const std::string& name) : Test(name) { + + } + + /// Run the tests + void run() { + + testConstructors(); + testAddRemoveClear(); + testAssignment(); + testIndexing(); + testEquality(); + testReserve(); + testIteration(); + } + + void testConstructors() { + + // ----- Constructors ----- // + + List list1(mAllocator); + test(list1.capacity() == 0); + test(list1.size() == 0); + + List list2(mAllocator, 100); + test(list2.capacity() == 100); + test(list2.size() == 0); + + List list3(mAllocator); + list3.add(1); + list3.add(2); + list3.add(3); + test(list3.capacity() == 4); + test(list3.size() == 3); + + // ----- Copy Constructors ----- // + + List list4(list1); + test(list4.capacity() == 0); + test(list4.size() == 0); + + List list5(list3); + test(list5.capacity() == list3.size()); + test(list5.size() == list3.size()); + for (uint i=0; i list6(mAllocator, 20); + test(list6.capacity() == 20); + for (uint i=0; i<20; i++) { + list6.add("test"); + } + test(list6.capacity() == 20); + list6.add("test"); + test(list6.capacity() == 40); + } + + void testAddRemoveClear() { + + // ----- Test add() ----- // + + List list1(mAllocator); + list1.add(4); + test(list1.size() == 1); + test(list1[0] == 4); + list1.add(9); + test(list1.size() == 2); + test(list1[0] == 4); + test(list1[1] == 9); + + const int arraySize = 15; + int arrayTest[arraySize] = {3, 145, -182, 34, 12, 95, -1834, 4143, -111, -111, 4343, 234, 22983, -3432, 753}; + List list2(mAllocator); + for (uint i=0; i list3(mAllocator); + list3.add(1); + list3.add(2); + list3.add(3); + list3.add(4); + + list3.remove(3); + test(list3.size() == 3); + test(list3.capacity() == 4); + test(list3[0] = 1); + test(list3[1] = 2); + test(list3[2] = 3); + + list3.remove(1); + test(list3.size() == 2); + test(list3.capacity() == 4); + test(list3[0] = 1); + test(list3[1] = 3); + + list3.remove(0); + test(list3.size() == 1); + test(list3.capacity() == 4); + test(list3[0] = 3); + + list3.remove(0); + test(list3.size() == 0); + test(list3.capacity() == 4); + + // ----- Test addRange() ----- // + + List list4(mAllocator); + list4.add(1); + list4.add(2); + list4.add(3); + + List list5(mAllocator); + list5.add(4); + list5.add(5); + + List list6(mAllocator); + list6.addRange(list5); + test(list6.size() == list5.size()); + test(list6[0] == 4); + test(list6[1] == 5); + + list4.addRange(list5); + test(list4.size() == 3 + list5.size()); + test(list4[0] == 1); + test(list4[1] == 2); + test(list4[2] == 3); + test(list4[3] == 4); + test(list4[4] == 5); + + // ----- Test clear() ----- // + + List list7(mAllocator); + list7.add("test1"); + list7.add("test2"); + list7.add("test3"); + list7.clear(); + test(list7.size() == 0); + list7.add("new"); + test(list7.size() == 1); + test(list7[0] == "new"); + } + + void testAssignment() { + + List list1(mAllocator); + list1.add(1); + list1.add(2); + list1.add(3); + + List list2(mAllocator); + list2.add(5); + list2.add(6); + + List list3(mAllocator); + List list4(mAllocator); + list4.add(1); + list4.add(2); + + List list5(mAllocator); + list5.add(1); + list5.add(2); + list5.add(3); + + list3 = list2; + test(list2.size() == list3.size()); + test(list2[0] == list3[0]); + test(list2[1] == list3[1]); + + list4 = list1; + test(list4.size() == list1.size()) + test(list4[0] = list1[0]); + test(list4[1] = list1[1]); + test(list4[2] = list1[2]); + + list5 = list2; + test(list5.size() == list2.size()); + test(list5[0] = list2[0]); + test(list5[1] = list2[1]); + } + + void testIndexing() { + + List list1(mAllocator); + list1.add(1); + list1.add(2); + list1.add(3); + + test(list1[0] == 1); + test(list1[1] == 2); + test(list1[2] == 3); + + list1[0] = 6; + list1[1] = 7; + list1[2] = 8; + + test(list1[0] == 6); + test(list1[1] == 7); + test(list1[2] == 8); + + const int a = list1[0]; + const int b = list1[1]; + test(a == 6); + test(b == 7); + + list1[0]++; + list1[1]++; + test(list1[0] == 7); + test(list1[1] == 8); + } + + void testEquality() { + + List list1(mAllocator); + list1.add(1); + list1.add(2); + list1.add(3); + + List list2(mAllocator); + list2.add(1); + list2.add(2); + + List list3(mAllocator); + list3.add(1); + list3.add(2); + list3.add(3); + + List list4(mAllocator); + list4.add(1); + list4.add(5); + list4.add(3); + + test(list1 == list1); + test(list1 != list2); + test(list1 == list3); + test(list1 != list4); + test(list2 != list4); + } + + void testReserve() { + + List list1(mAllocator); + list1.reserve(10); + test(list1.size() == 0); + test(list1.capacity() == 10); + list1.add(1); + list1.add(2); + test(list1.capacity() == 10); + test(list1.size() == 2); + test(list1[0] == 1); + test(list1[1] == 2); + + list1.reserve(1); + test(list1.capacity() == 10); + + list1.reserve(100); + test(list1.capacity() == 100); + test(list1[0] == 1); + test(list1[1] == 2); + } + + void testIteration() { + // TODO : Implement this + } + + }; + +} + +#endif diff --git a/test/tests/containers/TestMap.h b/test/tests/containers/TestMap.h new file mode 100644 index 00000000..d7e084dc --- /dev/null +++ b/test/tests/containers/TestMap.h @@ -0,0 +1,319 @@ +/******************************************************************************** +* 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 TEST_MAP_H +#define TEST_MAP_H + +// Libraries +#include "Test.h" +#include "containers/Map.h" +#include "memory/DefaultAllocator.h" + +/// Reactphysics3D namespace +namespace reactphysics3d { + +// Class TestMap +/** + * Unit test for the Map class + */ +class TestMap : public Test { + + private : + + // ---------- Atributes ---------- // + + DefaultAllocator mAllocator; + + public : + + // ---------- Methods ---------- // + + /// Constructor + TestMap(const std::string& name) : Test(name) { + + } + + /// Run the tests + void run() { + + testConstructors(); + testReserve(); + testAddRemoveClear(); + testContainsKey(); + testIndexing(); + testEquality(); + testAssignment(); + testIteration(); + } + + void testConstructors() { + + // ----- Constructors ----- // + + Map map1(mAllocator); + test(map1.capacity() == 0); + test(map1.size() == 0); + + Map map2(mAllocator, 100); + test(map2.capacity() >= 100); + test(map2.size() == 0); + + // ----- Copy Constructors ----- // +/* + Map map3(map1); + test(map3.capacity() == map1.capacity()); + test(map3.size() == map1.size()); + + Map map4(mAllocator); + map4.add(std::make_pair(1, 10)); + map4.add(std::make_pair(2, 20)); + map4.add(std::make_pair(3, 30)); + test(map4.capacity() >= 3); + test(map4.size() == 3); + + Map map5(map4); + test(map5.capacity() == map4.capacity()); + test(map5.size() == map4.size()); + test(map5[1] == 10); + test(map5[2] == 20); + test(map5[3] == 30); + */ + } + + void testReserve() { + + Map map1(mAllocator); + map1.reserve(15); + test(map1.capacity() >= 15); + map1.add(std::make_pair(1, "test1")); + map1.add(std::make_pair(2, "test2")); + test(map1.capacity() >= 15); + + map1.reserve(10); + test(map1.capacity() >= 15); + + map1.reserve(100); + test(map1.capacity() >= 100); + test(map1[1] == "test1"); + test(map1[2] == "test2"); + } + + void testAddRemoveClear() { + + // ----- Test add() ----- // + + Map map1(mAllocator); + map1.add(std::make_pair(1, 10)); + map1.add(std::make_pair(8, 80)); + map1.add(std::make_pair(13, 130)); + test(map1[1] == 10); + test(map1[8] == 80); + test(map1[13] == 130); + test(map1.size() == 3); + + Map map2(mAllocator, 15); + for (int i = 0; i < 1000000; i++) { + map2.add(std::make_pair(i, i * 100)); + } + bool isValid = true; + for (int i = 0; i < 1000000; i++) { + if (map2[i] != i * 100) isValid = false; + } + test(isValid); + + map1.remove(1); + map1.add(std::make_pair(1, 10)); + test(map1.size() == 3); + test(map1[1] == 10); + + // ----- Test remove() ----- // + + map1.remove(1); + test(!map1.containsKey(1)); + test(map1.containsKey(8)); + test(map1.containsKey(13)); + test(map1.size() == 2); + + map1.remove(13); + test(!map1.containsKey(8)); + test(map1.containsKey(13)); + test(map1.size() == 1); + + map1.remove(8); + test(!map1.containsKey(8)); + test(map1.size() == 0); + + isValid = true; + for (int i = 0; i < 1000000; i++) { + map2.remove(i); + } + for (int i = 0; i < 1000000; i++) { + if (map2.containsKey(i)) isValid = false; + } + test(isValid); + test(map2.size() == 0); + + Map map3(mAllocator); + for (int i=0; i < 1000000; i++) { + map3.add(std::make_pair(i, i * 10)); + map3.remove(i); + } + + // ----- Test clear() ----- // + + Map map4(mAllocator); + map4.add(std::make_pair(2, 20)); + map4.add(std::make_pair(4, 40)); + map4.add(std::make_pair(6, 60)); + map4.clear(); + test(map4.size() == 0); + map4.add(std::make_pair(2, 20)); + test(map4.size() == 1); + test(map4[2] == 20); + map4.clear(); + test(map4.size() == 0); + + Map map5(mAllocator); + map5.clear(); + test(map5.size() == 0); + } + + void testContainsKey() { + + Map map1(mAllocator); + + test(!map1.containsKey(2)); + test(!map1.containsKey(4)); + test(!map1.containsKey(6)); + + map1.add(std::make_pair(2, 20)); + map1.add(std::make_pair(4, 40)); + map1.add(std::make_pair(6, 60)); + + test(map1.containsKey(2)); + test(map1.containsKey(4)); + test(map1.containsKey(6)); + + map1.remove(4); + test(!map1.containsKey(4)); + test(map1.containsKey(2)); + test(map1.containsKey(6)); + + map1.clear(); + test(!map1.containsKey(2)); + test(!map1.containsKey(6)); + } + + void testIndexing() { + + Map map1(mAllocator); + map1.add(std::make_pair(2, 20)); + map1.add(std::make_pair(4, 40)); + map1.add(std::make_pair(6, 60)); + test(map1[2] == 20); + test(map1[4] == 40); + test(map1[6] == 60); + + map1[2] = 10; + map1[4] = 20; + map1[6] = 30; + + test(map1[2] == 10); + test(map1[4] == 20); + test(map1[6] == 30); + } + + void testEquality() { + + Map map1(mAllocator, 10); + Map map2(mAllocator, 2); + + test(map1 == map2); + + map1.add(std::make_pair("a", 1)); + map1.add(std::make_pair("b", 2)); + map1.add(std::make_pair("c", 3)); + + map2.add(std::make_pair("a", 1)); + map2.add(std::make_pair("b", 2)); + map2.add(std::make_pair("c", 4)); + + test(map1 == map1); + test(map2 == map2); + test(map1 != map2); + + map2["c"] = 3; + + test(map1 == map2); + + Map map3(mAllocator); + map3.add(std::make_pair("a", 1)); + + test(map1 != map3); + test(map2 != map3); + } + + void testAssignment() { + + Map map1(mAllocator); + map1.add(std::make_pair(1, 3)); + map1.add(std::make_pair(2, 6)); + map1.add(std::make_pair(10, 30)); +/* + Map map2(mAllocator); + map2 = map1; + test(map2.size() == map1.size()); + test(map2[1] == 3); + test(map2[2] == 6); + test(map2[10] == 30); + + Map map3(mAllocator, 100); + map3 = map1; + test(map3.size() == map1.size()); + test(map3[1] == 3); + test(map3[2] == 6); + test(map3[10] == 30); + + Map map4(mAllocator); + map3 = map4; + test(map3.size() == 0); +*/ + Map map5(mAllocator); + map5.add(std::make_pair(7, 8)); + map5.add(std::make_pair(19, 70)); + map1 = map5; + test(map5.size() == map1.size()); + test(map1[7] == 8); + test(map1[19] == 70); + } + + void testIteration() { + + } + }; + +} + +#endif diff --git a/test/tests/mathematics/TestTransform.h b/test/tests/mathematics/TestTransform.h index 581b9c5e..815e3d54 100644 --- a/test/tests/mathematics/TestTransform.h +++ b/test/tests/mathematics/TestTransform.h @@ -61,13 +61,16 @@ class TestTransform : public Test { mIdentityTransform.setToIdentity(); - decimal sinA = sin(PI/8.0f); - decimal cosA = cos(PI/8.0f); - mTransform1 = Transform(Vector3(4, 5, 6), Quaternion(sinA, sinA, sinA, cosA)); + Vector3 unitVec(1, 1, 1); + unitVec.normalize(); - decimal sinB = sin(PI/3.0f); - decimal cosB = cos(PI/3.0f); - mTransform2 = Transform(Vector3(8, 45, -6), Quaternion(sinB, sinB, sinB, cosB)); + decimal sinA = std::sin(PI/8.0f); + decimal cosA = std::cos(PI/8.0f); + mTransform1 = Transform(Vector3(4, 5, 6), Quaternion(sinA * unitVec, cosA)); + + decimal sinB = std::sin(PI/3.0f); + decimal cosB = std::cos(PI/3.0f); + mTransform2 = Transform(Vector3(8, 45, -6), Quaternion(sinB * unitVec, cosB)); } /// Run the tests From 584b28a91c67745030df1482a3ab573063f2f6ad Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 14 Jan 2018 10:51:38 +0100 Subject: [PATCH 155/248] Add Cube stack scene in the testbed application --- testbed/CMakeLists.txt | 2 + testbed/common/AABB.h | 3 - .../CollisionDetectionScene.cpp | 4 +- testbed/scenes/concavemesh/ConcaveMeshScene.h | 8 +- testbed/scenes/cubestack/CubeStackScene.cpp | 146 ++++++++++++++++++ testbed/scenes/cubestack/CubeStackScene.h | 82 ++++++++++ testbed/src/TestbedApplication.cpp | 6 + 7 files changed, 242 insertions(+), 9 deletions(-) create mode 100644 testbed/scenes/cubestack/CubeStackScene.cpp create mode 100644 testbed/scenes/cubestack/CubeStackScene.h diff --git a/testbed/CMakeLists.txt b/testbed/CMakeLists.txt index e5e3b312..818cb026 100644 --- a/testbed/CMakeLists.txt +++ b/testbed/CMakeLists.txt @@ -114,6 +114,8 @@ SET(SCENES_SOURCES scenes/concavemesh/ConcaveMeshScene.cpp scenes/heightfield/HeightFieldScene.h scenes/heightfield/HeightFieldScene.cpp + scenes/cubestack/CubeStackScene.h + scenes/cubestack/CubeStackScene.cpp ) # Add .user file to set debug path in Visual Studio diff --git a/testbed/common/AABB.h b/testbed/common/AABB.h index e73326b5..2e8f82e1 100644 --- a/testbed/common/AABB.h +++ b/testbed/common/AABB.h @@ -37,9 +37,6 @@ class AABB { // -------------------- Attributes -------------------- // - /// Size of each side of the box - float mSize[3]; - /// Scaling matrix (applied to a cube to obtain the correct box dimensions) openglframework::Matrix4 mScalingMatrix; diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp index 6f2c65ae..02e8acc1 100755 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp @@ -168,8 +168,8 @@ void CollisionDetectionScene::reset() { mBox1->setTransform(rp3d::Transform(rp3d::Vector3(-4, -7, 0), rp3d::Quaternion::identity())); mBox2->setTransform(rp3d::Transform(rp3d::Vector3(0, 9, 0), rp3d::Quaternion::identity())); mConvexMesh->setTransform(rp3d::Transform(rp3d::Vector3(-5, 0, 0), rp3d::Quaternion::identity())); - mConcaveMesh->setTransform(rp3d::Transform(rp3d::Vector3(0, 0, 0), rp3d::Quaternion::identity())); - mHeightField->setTransform(rp3d::Transform(rp3d::Vector3(0, -12, 0), rp3d::Quaternion::identity())); + mConcaveMesh->setTransform(rp3d::Transform(rp3d::Vector3(0, 15, 0), rp3d::Quaternion::identity())); + mHeightField->setTransform(rp3d::Transform(rp3d::Vector3(0, -22, 0), rp3d::Quaternion::identity())); } // Destructor diff --git a/testbed/scenes/concavemesh/ConcaveMeshScene.h b/testbed/scenes/concavemesh/ConcaveMeshScene.h index a8d566a1..beca8f71 100644 --- a/testbed/scenes/concavemesh/ConcaveMeshScene.h +++ b/testbed/scenes/concavemesh/ConcaveMeshScene.h @@ -42,10 +42,10 @@ namespace trianglemeshscene { // Constants const float SCENE_RADIUS = 70.0f; // Radius of the scene in meters -static const int NB_BOXES = 10; -static const int NB_SPHERES = 5; -static const int NB_CAPSULES = 5; -static const int NB_MESHES = 3; +static const int NB_BOXES = 50; +static const int NB_SPHERES = 40; +static const int NB_CAPSULES = 20; +static const int NB_MESHES = 15; static const int NB_COMPOUND_SHAPES = 3; const openglframework::Vector3 BOX_SIZE(2, 2, 2); const float SPHERE_RADIUS = 1.5f; diff --git a/testbed/scenes/cubestack/CubeStackScene.cpp b/testbed/scenes/cubestack/CubeStackScene.cpp new file mode 100644 index 00000000..e4a0f859 --- /dev/null +++ b/testbed/scenes/cubestack/CubeStackScene.cpp @@ -0,0 +1,146 @@ +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +// Libraries +#include "CubeStackScene.h" + +// Namespaces +using namespace openglframework; +using namespace cubestackscene; + +// Constructor +CubeStackScene::CubeStackScene(const std::string& name, EngineSettings& settings) + : SceneDemo(name, settings, SCENE_RADIUS) { + + // Compute the radius and the center of the scene + openglframework::Vector3 center(0, 5, 0); + + // Set the center of the scene + setScenePosition(center, SCENE_RADIUS); + + // Gravity vector in the dynamics world + rp3d::Vector3 gravity(0, rp3d::decimal(-9.81), 0); + + // Create the dynamics world for the physics simulation + mPhysicsWorld = new rp3d::DynamicsWorld(gravity); + +#ifdef IS_PROFILING_ACTIVE + + mPhysicsWorld->setProfilerName(name + "_profiler"); + +#endif + + // Create all the cubes of the scene + for (int i=1; i<=NB_FLOORS; i++) { + + for (int j=0; jsetColor(mDemoColors[i % mNbDemoColors]); + cube->setSleepingColor(mRedColorDemo); + + // Change the material properties of the rigid body + rp3d::Material& material = cube->getRigidBody()->getMaterial(); + material.setBounciness(rp3d::decimal(0.4)); + + // Add the box the list of box in the scene + mBoxes.push_back(cube); + mPhysicsObjects.push_back(cube); + } + } + + // ------------------------- FLOOR ----------------------- // + + // Create the floor + mFloor = new Box(FLOOR_SIZE, FLOOR_MASS, getDynamicsWorld(), mMeshFolderPath); + mFloor->setColor(mGreyColorDemo); + mFloor->setSleepingColor(mGreyColorDemo); + + // The floor must be a static rigid body + mFloor->getRigidBody()->setType(rp3d::BodyType::STATIC); + mPhysicsObjects.push_back(mFloor); + + // Get the physics engine parameters + mEngineSettings.isGravityEnabled = getDynamicsWorld()->isGravityEnabled(); + rp3d::Vector3 gravityVector = getDynamicsWorld()->getGravity(); + mEngineSettings.gravity = openglframework::Vector3(gravityVector.x, gravityVector.y, gravityVector.z); + mEngineSettings.isSleepingEnabled = getDynamicsWorld()->isSleepingEnabled(); + mEngineSettings.sleepLinearVelocity = getDynamicsWorld()->getSleepLinearVelocity(); + mEngineSettings.sleepAngularVelocity = getDynamicsWorld()->getSleepAngularVelocity(); + mEngineSettings.nbPositionSolverIterations = getDynamicsWorld()->getNbIterationsPositionSolver(); + mEngineSettings.nbVelocitySolverIterations = getDynamicsWorld()->getNbIterationsVelocitySolver(); + mEngineSettings.timeBeforeSleep = getDynamicsWorld()->getTimeBeforeSleep(); +} + +// Destructor +CubeStackScene::~CubeStackScene() { + + // Destroy all the cubes of the scene + for (std::vector::iterator it = mBoxes.begin(); it != mBoxes.end(); ++it) { + + // Destroy the corresponding rigid body from the dynamics world + getDynamicsWorld()->destroyRigidBody((*it)->getRigidBody()); + + // Destroy the cube + delete (*it); + } + + // Destroy the rigid body of the floor + getDynamicsWorld()->destroyRigidBody(mFloor->getRigidBody()); + + // Destroy the floor + delete mFloor; + + // Destroy the dynamics world + delete getDynamicsWorld(); +} + +// Reset the scene +void CubeStackScene::reset() { + + int index = 0; + for (int i=NB_FLOORS; i > 0; i--) { + + for (int j=0; jsetTransform(rp3d::Transform(position, rp3d::Quaternion::identity())); + + index++; + } + } + + mFloor->setTransform(rp3d::Transform(rp3d::Vector3::zero(), rp3d::Quaternion::identity())); +} diff --git a/testbed/scenes/cubestack/CubeStackScene.h b/testbed/scenes/cubestack/CubeStackScene.h new file mode 100644 index 00000000..9bbc1c01 --- /dev/null +++ b/testbed/scenes/cubestack/CubeStackScene.h @@ -0,0 +1,82 @@ +/******************************************************************************** +* 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 CUBESTACK_SCENE_H +#define CUBESTACK_SCENE_H + +// Libraries +#include "openglframework.h" +#include "reactphysics3d.h" +#include "Box.h" +#include "SceneDemo.h" + +namespace cubestackscene { + +// Constants +const float SCENE_RADIUS = 30.0f; // Radius of the scene in meters +const int NB_FLOORS = 15; // Number of boxes in the scene +const openglframework::Vector3 BOX_SIZE(2, 2, 2); // Box dimensions in meters +const openglframework::Vector3 FLOOR_SIZE(50, 1, 50); // Floor dimensions in meters +const float BOX_MASS = 1.0f; // Box mass in kilograms +const float FLOOR_MASS = 100.0f; // Floor mass in kilograms + +// Class CubeStackScene +class CubeStackScene : public SceneDemo { + + protected : + + // -------------------- Attributes -------------------- // + + /// All the boxes of the scene + std::vector mBoxes; + + /// Box for the floor + Box* mFloor; + + public: + + // -------------------- Methods -------------------- // + + /// Constructor + CubeStackScene(const std::string& name, EngineSettings& settings); + + /// Destructor + virtual ~CubeStackScene() override; + + /// Reset the scene + virtual void reset() override; + + /// Return all the contact points of the scene + virtual std::vector getContactPoints() const override; +}; + +// Return all the contact points of the scene +inline std::vector CubeStackScene::getContactPoints() const { + return computeContactPointsOfWorld(getDynamicsWorld()); +} + +} + +#endif diff --git a/testbed/src/TestbedApplication.cpp b/testbed/src/TestbedApplication.cpp index f2a43bc1..63230e0c 100644 --- a/testbed/src/TestbedApplication.cpp +++ b/testbed/src/TestbedApplication.cpp @@ -36,6 +36,7 @@ #include "heightfield/HeightFieldScene.h" #include "raycast/RaycastScene.h" #include "concavemesh/ConcaveMeshScene.h" +#include "cubestack/CubeStackScene.h" using namespace openglframework; using namespace jointsscene; @@ -45,6 +46,7 @@ using namespace collisionshapesscene; using namespace trianglemeshscene; using namespace heightfieldscene; using namespace collisiondetectionscene; +using namespace cubestackscene; // Initialization of static variables const float TestbedApplication::SCROLL_SENSITIVITY = 0.08f; @@ -102,6 +104,10 @@ void TestbedApplication::createScenes() { CubesScene* cubeScene = new CubesScene("Cubes", mEngineSettings); mScenes.push_back(cubeScene); + // Cube Stack scene + CubeStackScene* cubeStackScene = new CubeStackScene("Cube Stack", mEngineSettings); + mScenes.push_back(cubeStackScene); + // Joints scene JointsScene* jointsScene = new JointsScene("Joints", mEngineSettings); mScenes.push_back(jointsScene); From c7f7a169f82341e7ce5c26ba29c11e5a394b0ffc Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 15 Jan 2018 07:18:00 +0100 Subject: [PATCH 156/248] Refactor the getter/setter for inertia tensor of a RigidBody --- src/body/RigidBody.cpp | 30 ++++++++++++++++------ src/body/RigidBody.h | 49 +++++++++++------------------------- src/engine/ContactSolver.cpp | 11 +++++++- 3 files changed, 47 insertions(+), 43 deletions(-) diff --git a/src/body/RigidBody.cpp b/src/body/RigidBody.cpp index 36c362dc..bad11916 100644 --- a/src/body/RigidBody.cpp +++ b/src/body/RigidBody.cpp @@ -91,14 +91,13 @@ void RigidBody::setType(BodyType type) { // Reset the inverse mass and inverse inertia tensor to zero mMassInverse = decimal(0.0); - mInertiaTensorLocal.setToZero(); mInertiaTensorLocalInverse.setToZero(); mInertiaTensorInverseWorld.setToZero(); } else { // If it is a dynamic body mMassInverse = decimal(1.0) / mInitMass; - mInertiaTensorLocalInverse = mInertiaTensorLocal.getInverse(); + mInertiaTensorLocalInverse = mUserInertiaTensorLocalInverse; // Update the world inverse inertia tensor updateInertiaTensorInverseWorld(); @@ -126,12 +125,26 @@ void RigidBody::setType(BodyType type) { */ void RigidBody::setInertiaTensorLocal(const Matrix3x3& inertiaTensorLocal) { + mUserInertiaTensorLocalInverse = inertiaTensorLocal.getInverse(); + if (mType != BodyType::DYNAMIC) return; - mInertiaTensorLocal = inertiaTensorLocal; + // Compute the inverse local inertia tensor + mInertiaTensorLocalInverse = mUserInertiaTensorLocalInverse; + + // Update the world inverse inertia tensor + updateInertiaTensorInverseWorld(); +} + +// Set the inverse local inertia tensor of the body (in body coordinates) +void RigidBody::setInverseInertiaTensorLocal(const Matrix3x3& inverseInertiaTensorLocal) { + + mUserInertiaTensorLocalInverse = inverseInertiaTensorLocal; + + if (mType != BodyType::DYNAMIC) return; // Compute the inverse local inertia tensor - mInertiaTensorLocalInverse = mInertiaTensorLocal.getInverse(); + mInertiaTensorLocalInverse = mUserInertiaTensorLocalInverse; // Update the world inverse inertia tensor updateInertiaTensorInverseWorld(); @@ -346,12 +359,13 @@ void RigidBody::recomputeMassInformation() { mInitMass = decimal(0.0); mMassInverse = decimal(0.0); - mInertiaTensorLocal.setToZero(); mInertiaTensorLocalInverse.setToZero(); mInertiaTensorInverseWorld.setToZero(); mCenterOfMassLocal.setToZero(); + Matrix3x3 inertiaTensorLocal; + inertiaTensorLocal.setToZero(); - // If it is STATIC or KINEMATIC body + // If it is a STATIC or a KINEMATIC body if (mType == BodyType::STATIC || mType == BodyType::KINEMATIC) { mCenterOfMassWorld = mTransform.getPosition(); return; @@ -403,11 +417,11 @@ void RigidBody::recomputeMassInformation() { offsetMatrix[2] += offset * (-offset.z); offsetMatrix *= shape->getMass(); - mInertiaTensorLocal += inertiaTensor + offsetMatrix; + inertiaTensorLocal += inertiaTensor + offsetMatrix; } // Compute the local inverse inertia tensor - mInertiaTensorLocalInverse = mInertiaTensorLocal.getInverse(); + mInertiaTensorLocalInverse = inertiaTensorLocal.getInverse(); // Update the world inverse inertia tensor updateInertiaTensorInverseWorld(); diff --git a/src/body/RigidBody.h b/src/body/RigidBody.h index 23603bda..eaadb59c 100644 --- a/src/body/RigidBody.h +++ b/src/body/RigidBody.h @@ -81,9 +81,9 @@ class RigidBody : public CollisionBody { /// Current external torque on the body Vector3 mExternalTorque; - /// Local inertia tensor of the body (in local-space) with respect to the - /// center of mass of the body - Matrix3x3 mInertiaTensorLocal; + /// Inverse Local inertia tensor of the body (in local-space) set + /// by the user with respect to the center of mass of the body + Matrix3x3 mUserInertiaTensorLocalInverse; /// Inverse of the inertia tensor of the body Matrix3x3 mInertiaTensorLocalInverse; @@ -163,24 +163,24 @@ class RigidBody : public CollisionBody { /// Set the variable to know whether or not the body is sleeping virtual void setIsSleeping(bool isSleeping) override; - /// Return the local inertia tensor of the body (in body coordinates) - const Matrix3x3& getInertiaTensorLocal() const; - /// Set the local inertia tensor of the body (in body coordinates) void setInertiaTensorLocal(const Matrix3x3& inertiaTensorLocal); + /// Set the inverse local inertia tensor of the body (in body coordinates) + void setInverseInertiaTensorLocal(const Matrix3x3& inverseInertiaTensorLocal); + + /// Get the inverse local inertia tensor of the body (in body coordinates) + const Matrix3x3& getInverseInertiaTensorLocal() const; + + /// Return the inverse of the inertia tensor in world coordinates. + Matrix3x3 getInertiaTensorInverseWorld() const; + /// Set the local center of mass of the body (in local-space coordinates) void setCenterOfMassLocal(const Vector3& centerOfMassLocal); /// Set the mass of the rigid body void setMass(decimal mass); - /// Return the inertia tensor in world coordinates. - Matrix3x3 getInertiaTensorWorld() const; - - /// Return the inverse of the inertia tensor in world coordinates. - Matrix3x3 getInertiaTensorInverseWorld() const; - /// Return true if the gravity needs to be applied to this rigid body bool isGravityEnabled() const; @@ -273,28 +273,9 @@ inline Vector3 RigidBody::getAngularVelocity() const { return mAngularVelocity; } -// Return the local inertia tensor of the body (in local-space coordinates) -/** - * @return The 3x3 inertia tensor matrix of the body (in local-space coordinates) - */ -inline const Matrix3x3& RigidBody::getInertiaTensorLocal() const { - return mInertiaTensorLocal; -} - -// Return the inertia tensor in world coordinates. -/// The inertia tensor I_w in world coordinates is computed -/// with the local inertia tensor I_b in body coordinates -/// by I_w = R * I_b * R^T -/// where R is the rotation matrix (and R^T its transpose) of -/// the current orientation quaternion of the body -/** - * @return The 3x3 inertia tensor matrix of the body in world-space coordinates - */ -inline Matrix3x3 RigidBody::getInertiaTensorWorld() const { - - // Compute and return the inertia tensor in world coordinates - return mTransform.getOrientation().getMatrix() * mInertiaTensorLocal * - mTransform.getOrientation().getMatrix().getTranspose(); +// Get the inverse local inertia tensor of the body (in body coordinates) +inline const Matrix3x3& RigidBody::getInverseInertiaTensorLocal() const { + return mInertiaTensorLocalInverse; } // Return the inverse of the inertia tensor in world coordinates. diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index f4762c49..a7b86b35 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -259,8 +259,17 @@ void ContactSolver::initializeForIsland(Island* island) { bool isBody2DynamicType = body2->getType() == BodyType::DYNAMIC; mContactConstraints[mNbContactManifolds].inverseRollingResistance.setToZero(); if (mContactConstraints[mNbContactManifolds].rollingResistanceFactor > 0 && (isBody1DynamicType || isBody2DynamicType)) { + mContactConstraints[mNbContactManifolds].inverseRollingResistance = mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody1 + mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody2; - mContactConstraints[mNbContactManifolds].inverseRollingResistance = mContactConstraints[mNbContactManifolds].inverseRollingResistance.getInverse(); + decimal det = mContactConstraints[mNbContactManifolds].inverseRollingResistance.getDeterminant(); + + // If the matrix is not inversible + if (approxEqual(det, decimal(0.0))) { + mContactConstraints[mNbContactManifolds].inverseRollingResistance.setToZero(); + } + else { + mContactConstraints[mNbContactManifolds].inverseRollingResistance = mContactConstraints[mNbContactManifolds].inverseRollingResistance.getInverse(); + } } mContactConstraints[mNbContactManifolds].normal.normalize(); From b93e358f5b157fe0c36bd58187dd87fcaad91eff Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 15 Jan 2018 18:34:20 +0100 Subject: [PATCH 157/248] Fix issue with zero penetration depth in Sphere vs Capsule collision --- src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp index 2e86dfe3..fa5d68b9 100755 --- a/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp +++ b/src/collision/narrowphase/SphereVsCapsuleAlgorithm.cpp @@ -121,6 +121,10 @@ bool SphereVsCapsuleAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, b contactPointCapsuleLocal = sphereCenter - normalCapsuleSpace * capsuleShape->getRadius(); } + if (penetrationDepth <= decimal(0.0)) { + return false; + } + // Create the contact info object narrowPhaseInfo->addContactPoint(normalWorld, penetrationDepth, isSphereShape1 ? contactPointSphereLocal : contactPointCapsuleLocal, From b1ecfb0fedd601fc04e6a0a1d2d3fcda96687557 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Fri, 19 Jan 2018 07:55:55 +0100 Subject: [PATCH 158/248] Working on containers (List, Map) --- src/containers/List.h | 26 ++-- src/containers/Map.h | 219 ++++++++++++++++++++++++++++++- test/tests/containers/TestList.h | 43 +++++- test/tests/containers/TestMap.h | 55 +++++++- 4 files changed, 322 insertions(+), 21 deletions(-) diff --git a/src/containers/List.h b/src/containers/List.h index 6391d52b..93ec0830 100644 --- a/src/containers/List.h +++ b/src/containers/List.h @@ -57,9 +57,6 @@ class List { /// Memory allocator MemoryAllocator& mAllocator; - // -------------------- Methods -------------------- // - - public: /// Class Iterator @@ -87,14 +84,14 @@ class List { Iterator() = default; /// Constructor - Iterator(T* buffer, size_t index, size_t size) - :mCurrentIndex(index), mBuffer(buffer), mSize(size) { + Iterator(void* buffer, size_t index, size_t size) + :mCurrentIndex(index), mBuffer(static_cast(buffer)), mSize(size) { } /// Copy constructor Iterator(const Iterator& it) - :mCurrentIndex(it.mCurrentIndex), mBuffer(it.mBuffer), mSize(it.size) { + :mCurrentIndex(it.mCurrentIndex), mBuffer(it.mBuffer), mSize(it.mSize) { } @@ -112,14 +109,14 @@ class List { /// Post increment (it++) Iterator& operator++() { - assert(mCurrentIndex < mSize - 1); + assert(mCurrentIndex < mSize); mCurrentIndex++; return *this; } /// Pre increment (++it) Iterator operator++(int number) { - assert(mCurrentIndex < mSize - 1); + assert(mCurrentIndex < mSize); Iterator tmp = *this; mCurrentIndex++; return tmp; @@ -149,13 +146,14 @@ class List { return true; } - return &(mBuffer[mCurrentIndex]) == &(iterator.mBuffer[mCurrentIndex]); + return &(mBuffer[mCurrentIndex]) == &(iterator.mBuffer[iterator.mCurrentIndex]); } /// Inequality operator (it != end()) bool operator!=(const Iterator& iterator) const { return !(*this == iterator); } + }; // -------------------- Methods -------------------- // @@ -334,6 +332,16 @@ class List { return *this; } + + /// Return a begin iterator + Iterator begin() const { + return Iterator(mBuffer, 0, mSize); + } + + /// Return a end iterator + Iterator end() const { + return Iterator(mBuffer, mSize, mSize); + } }; } diff --git a/src/containers/Map.h b/src/containers/Map.h index 5510b98d..21eb9759 100644 --- a/src/containers/Map.h +++ b/src/containers/Map.h @@ -56,6 +56,13 @@ class Map { keyValue = nullptr; } + /// Constructor + Entry(size_t hashcode, int nextValue) { + hashCode = hashcode; + next = nextValue; + keyValue = nullptr; + } + /// Destructor ~Entry() { @@ -242,6 +249,129 @@ class Map { public: + /// Class Iterator + /** + * This class represents an iterator for the Map + */ + class Iterator { + + private: + + /// Array of buckets + const int* mBuckets; + + /// Array of entries + const Entry* mEntries; + + /// Capacity of the map + int mCapacity; + + /// Index of the current bucket + int mCurrentBucket; + + /// Index of the current entry + int mCurrentEntry; + + /// Advance the iterator + void advance() { + + // If we are trying to move past the end + assert(mCurrentBucket < mCapacity); + + // If we are at the last entry for the current bucket + if (mEntries[mCurrentEntry].next == -1) { + + // Find the next occupied bucket + for (int b = mCurrentBucket + 1; mBuckets[b] > 0 || b == mCapacity; b++) { + + mCurrentBucket = b; + + // If we have reached the end of the map + if (mCurrentBucket == mCapacity) { + mCurrentEntry = mCapacity; + return; + } + + mCurrentEntry = mBuckets[mCurrentBucket]; + assert(mCurrentEntry != -1); + } + } + else { + + // Move to the next entry in the current bucket + mCurrentEntry = mEntries[mCurrentEntry].next; + assert(mEntries[mCurrentEntry].keyValue != nullptr); + } + } + + public: + + // Iterator traits + using value_type = std::pair; + using difference_type = std::ptrdiff_t; + using pointer = std::pair*; + using reference = std::pair&; + using iterator_category = std::forward_iterator_tag; + + /// Constructor + Iterator() = default; + + /// Constructor + Iterator(const int* buckets, const Entry* entries, int capacity, int currentBucket, int currentEntry) + :mBuckets(buckets), mEntries(entries), mCapacity(capacity), mCurrentBucket(currentBucket), mCurrentEntry(currentEntry) { + + } + + /// Copy constructor + Iterator(const Iterator& it) + :mBuckets(it.mBuckets), mEntries(it.mEntries), mCapacity(it.mCapacity), mCurrentBucket(it.mCurrentBucket), mCurrentEntry(it.mCurrentEntry) { + + } + + /// Deferencable + reference operator*() const { + assert(mCurrentBucket >= 0 && mCurrentBucket < mCapacity); + assert (mCurrentEntry != -1); + assert(mEntries[mCurrentEntry].keyValue != nullptr); + return mEntries[mCurrentEntry].keyValue; + } + + /// Deferencable + pointer operator->() const { + assert(mCurrentBucket >= 0 && mCurrentBucket < mCapacity); + assert (mCurrentEntry != -1); + assert(mEntries[mCurrentEntry].keyValue != nullptr); + return mEntries[mCurrentEntry].keyValue; + } + + /// Post increment (it++) + Iterator& operator++() { + advance(); + return *this; + } + + /// Pre increment (++it) + Iterator operator++(int number) { + Iterator tmp = *this; + advance(); + return tmp; + } + + /// Equality operator (it == end()) + bool operator==(const Iterator& iterator) const { + return mBuckets == iterator.mBuckets && + mEntries == iterator.mEntries && + mCurrentBucket == iterator.mCurrentBucket && + mCurrentEntry == iterator.mCurrentEntry; + } + + /// Inequality operator (it != end()) + bool operator!=(const Iterator& iterator) const { + return !(*this == iterator); + } + }; + + // -------------------- Methods -------------------- // /// Constructor @@ -434,6 +564,36 @@ class Map { return mCapacity; } + /// Try to find an item of the map given a key. + /// The method returns an iterator to the found item or + /// an iterator pointing to the end if not found + Iterator find(const K& key) const { + + int bucket; + int entry = -1; + + if (mCapacity > 0) { + + size_t hashCode = std::hash()(key); + bucket = hashCode % mCapacity; + + for (int i = mBuckets[bucket]; i >= 0; i = mEntries[i].next) { + if (mEntries[i].hashCode == hashCode && mEntries[i].keyValue->first == key) { + entry = i; + break; + } + } + } + + if (entry == -1) { + return end(); + } + + assert(mEntries[entry].keyValue != nullptr); + + return Iterator(mBuckets, mEntries, mCapacity, bucket, entry); + } + /// Overloaded index operator V& operator[](const K& key) { @@ -471,8 +631,23 @@ class Map { /// Overloaded equality operator bool operator==(const Map& map) const { - // TODO : Implement this - return false; + if (size() != map.size()) return false; + + for (auto it = begin(); it != end(); ++it) { + auto it2 = map.find(it->first); + if (it2 == map.end() || it2->second != it->second) { + return false; + } + } + + for (auto it = map.begin(); it != map.end(); ++it) { + auto it2 = find(it->first); + if (it2 == end() || it2->second != it->second) { + return false; + } + } + + return true; } /// Overloaded not equal operator @@ -505,7 +680,15 @@ class Map { std::memcpy(mBuckets, map.mBuckets, mCapacity * sizeof(int)); // Copy the entries - std::memcpy(mEntries, map.mEntries, mCapacity * sizeof(Entry)); + for (int i=0; i < mCapacity; i++) { + + new (&mEntries[i]) Entry(map.mEntries[i].hashCode, map.mEntries[i].next); + + if (map.mEntries[i].keyValue != nullptr) { + mEntries[i].keyValue = static_cast*>(mAllocator.allocate(sizeof(std::pair))); + new (mEntries[i].keyValue) std::pair(*(map.mEntries[i].keyValue)); + } + } mNbUsedEntries = map.mNbUsedEntries; mNbFreeEntries = map.mNbFreeEntries; @@ -515,6 +698,36 @@ class Map { return *this; } + + /// Return a begin iterator + Iterator begin() const { + + // If the map is empty + if (size() == 0) { + + // Return an iterator to the end + return end(); + } + + int bucket = -1; + + // Find the first used bucket + for (int i=0; i= 0) { + bucket = i; + break; + } + } + + assert(bucket >= 0); + + return Iterator(mBuckets, mEntries, mCapacity, bucket, mBuckets[bucket]); + } + + /// Return a end iterator + Iterator end() const { + return Iterator(mBuckets, mEntries, mCapacity, mCapacity, mCapacity); + } }; template diff --git a/test/tests/containers/TestList.h b/test/tests/containers/TestList.h index ba1fbf61..669b0bef 100644 --- a/test/tests/containers/TestList.h +++ b/test/tests/containers/TestList.h @@ -64,7 +64,7 @@ class TestList : public Test { testIndexing(); testEquality(); testReserve(); - testIteration(); + testIterators(); } void testConstructors() { @@ -320,8 +320,45 @@ class TestList : public Test { test(list1[1] == 2); } - void testIteration() { - // TODO : Implement this + void testIterators() { + + List list1(mAllocator); + + test(list1.begin() == list1.end()); + + list1.add(5); + list1.add(6); + list1.add(8); + list1.add(-1); + + List::Iterator itBegin = list1.begin(); + List::Iterator itEnd = list1.end(); + List::Iterator it = list1.begin(); + + test(itBegin == it); + test(*it == 5); + test(*(it++) == 5); + test(*it == 6); + test(*(it--) == 6); + test(*it == 5); + test(*(++it) == 6); + test(*it == 6); + test(*(--it) == 5); + test(*it == 5); + test(it == itBegin); + + it = list1.end(); + test(it == itEnd); + it--; + test(*it == -1); + it++; + test(it == itEnd); + + List list2(mAllocator); + for (auto it = list1.begin(); it != list1.end(); ++it) { + list2.add(*it); + } + test(list1 == list2); } }; diff --git a/test/tests/containers/TestMap.h b/test/tests/containers/TestMap.h index d7e084dc..a105fca8 100644 --- a/test/tests/containers/TestMap.h +++ b/test/tests/containers/TestMap.h @@ -62,10 +62,11 @@ class TestMap : public Test { testReserve(); testAddRemoveClear(); testContainsKey(); + testFind(); testIndexing(); testEquality(); testAssignment(); - testIteration(); + testIterators(); } void testConstructors() { @@ -122,6 +123,8 @@ class TestMap : public Test { void testAddRemoveClear() { + // TODO : ADD test with values with same hash for keys but different keys + // ----- Test add() ----- // Map map1(mAllocator); @@ -157,8 +160,8 @@ class TestMap : public Test { test(map1.size() == 2); map1.remove(13); - test(!map1.containsKey(8)); - test(map1.containsKey(13)); + test(map1.containsKey(8)); + test(!map1.containsKey(13)); test(map1.size() == 1); map1.remove(8); @@ -245,6 +248,26 @@ class TestMap : public Test { test(map1[6] == 30); } + void testFind() { + + Map map1(mAllocator); + map1.add(std::make_pair(2, 20)); + map1.add(std::make_pair(4, 40)); + map1.add(std::make_pair(6, 60)); + test(map1.find(2)->second == 20); + test(map1.find(4)->second == 40); + test(map1.find(6)->second == 60); + test(map1.find(45) == map1.end()); + + map1[2] = 10; + map1[4] = 20; + map1[6] = 30; + + test(map1.find(2)->second == 10); + test(map1.find(4)->second == 20); + test(map1.find(6)->second == 30); + } + void testEquality() { Map map1(mAllocator, 10); @@ -281,7 +304,7 @@ class TestMap : public Test { map1.add(std::make_pair(1, 3)); map1.add(std::make_pair(2, 6)); map1.add(std::make_pair(10, 30)); -/* + Map map2(mAllocator); map2 = map1; test(map2.size() == map1.size()); @@ -299,7 +322,7 @@ class TestMap : public Test { Map map4(mAllocator); map3 = map4; test(map3.size() == 0); -*/ + Map map5(mAllocator); map5.add(std::make_pair(7, 8)); map5.add(std::make_pair(19, 70)); @@ -309,8 +332,28 @@ class TestMap : public Test { test(map1[19] == 70); } - void testIteration() { + void testIterators() { + Map map1(mAllocator); + + test(map1.begin() == map1.end()); + + map1.add(std::make_pair(1, 5)); + map1.add(std::make_pair(2, 6)); + map1.add(std::make_pair(3, 8)); + map1.add(std::make_pair(4, -1)); + + Map::Iterator itBegin = map1.begin(); + Map::Iterator it = map1.begin(); + + test(itBegin == it); + + int size = 0; + for (auto it = map1.begin(); it != map1.end(); ++it) { + test(map1.containsKey(it->first)); + size++; + } + test(map1.size() == size); } }; From 3a0cc1feac1811555a95c9a9f4002c605fbc0e0a Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Fri, 19 Jan 2018 17:50:30 +0100 Subject: [PATCH 159/248] Working on Map --- src/containers/Map.h | 72 +++++++++++++++----------------------------- 1 file changed, 24 insertions(+), 48 deletions(-) diff --git a/src/containers/Map.h b/src/containers/Map.h index 21eb9759..3c6ccc41 100644 --- a/src/containers/Map.h +++ b/src/containers/Map.h @@ -257,17 +257,14 @@ class Map { private: - /// Array of buckets - const int* mBuckets; - /// Array of entries const Entry* mEntries; /// Capacity of the map int mCapacity; - /// Index of the current bucket - int mCurrentBucket; + /// Number of used entries in the map + int mNbUsedEntries; /// Index of the current entry int mCurrentEntry; @@ -276,32 +273,20 @@ class Map { void advance() { // If we are trying to move past the end - assert(mCurrentBucket < mCapacity); + assert(mCurrentEntry < mNbUsedEntries); - // If we are at the last entry for the current bucket - if (mEntries[mCurrentEntry].next == -1) { + for (mCurrentEntry += 1; mCurrentEntry < mNbUsedEntries; mCurrentEntry++) { - // Find the next occupied bucket - for (int b = mCurrentBucket + 1; mBuckets[b] > 0 || b == mCapacity; b++) { + // If the entry is not empty + if (mEntries[mCurrentEntry].keyValue != nullptr) { - mCurrentBucket = b; - - // If we have reached the end of the map - if (mCurrentBucket == mCapacity) { - mCurrentEntry = mCapacity; - return; - } - - mCurrentEntry = mBuckets[mCurrentBucket]; - assert(mCurrentEntry != -1); + // We have found the next non empty entry + return; } } - else { - // Move to the next entry in the current bucket - mCurrentEntry = mEntries[mCurrentEntry].next; - assert(mEntries[mCurrentEntry].keyValue != nullptr); - } + // We have not find a non empty entry, we return an iterator to the end + mCurrentEntry = mCapacity; } public: @@ -317,29 +302,27 @@ class Map { Iterator() = default; /// Constructor - Iterator(const int* buckets, const Entry* entries, int capacity, int currentBucket, int currentEntry) - :mBuckets(buckets), mEntries(entries), mCapacity(capacity), mCurrentBucket(currentBucket), mCurrentEntry(currentEntry) { + Iterator(const Entry* entries, int capacity, int nbUsedEntries, int currentEntry) + :mEntries(entries), mCapacity(capacity), mNbUsedEntries(nbUsedEntries), mCurrentEntry(currentEntry) { } /// Copy constructor Iterator(const Iterator& it) - :mBuckets(it.mBuckets), mEntries(it.mEntries), mCapacity(it.mCapacity), mCurrentBucket(it.mCurrentBucket), mCurrentEntry(it.mCurrentEntry) { + :mEntries(it.mEntries), mCapacity(it.mCapacity), mNbUsedEntries(it.mNbUsedEntries), mCurrentEntry(it.mCurrentEntry) { } /// Deferencable reference operator*() const { - assert(mCurrentBucket >= 0 && mCurrentBucket < mCapacity); - assert (mCurrentEntry != -1); + assert(mCurrentEntry >= 0 && mCurrentEntry < mNbUsedEntries); assert(mEntries[mCurrentEntry].keyValue != nullptr); return mEntries[mCurrentEntry].keyValue; } /// Deferencable pointer operator->() const { - assert(mCurrentBucket >= 0 && mCurrentBucket < mCapacity); - assert (mCurrentEntry != -1); + assert(mCurrentEntry >= 0 && mCurrentEntry < mNbUsedEntries); assert(mEntries[mCurrentEntry].keyValue != nullptr); return mEntries[mCurrentEntry].keyValue; } @@ -359,10 +342,7 @@ class Map { /// Equality operator (it == end()) bool operator==(const Iterator& iterator) const { - return mBuckets == iterator.mBuckets && - mEntries == iterator.mEntries && - mCurrentBucket == iterator.mCurrentBucket && - mCurrentEntry == iterator.mCurrentEntry; + return mCurrentEntry == iterator.mCurrentEntry && mEntries == iterator.mEntries; } /// Inequality operator (it != end()) @@ -591,7 +571,7 @@ class Map { assert(mEntries[entry].keyValue != nullptr); - return Iterator(mBuckets, mEntries, mCapacity, bucket, entry); + return Iterator(mEntries, mCapacity, mNbUsedEntries, entry); } /// Overloaded index operator @@ -709,24 +689,20 @@ class Map { return end(); } - int bucket = -1; - - // Find the first used bucket - for (int i=0; i= 0) { - bucket = i; - break; + // Find the first used entry + int entry; + for (entry=0; entry < mNbUsedEntries; entry++) { + if (mEntries[entry].keyValue != nullptr) { + return Iterator(mEntries, mCapacity, mNbUsedEntries, entry); } } - assert(bucket >= 0); - - return Iterator(mBuckets, mEntries, mCapacity, bucket, mBuckets[bucket]); + assert(false); } /// Return a end iterator Iterator end() const { - return Iterator(mBuckets, mEntries, mCapacity, mCapacity, mCapacity); + return Iterator(mEntries, mCapacity, mNbUsedEntries, mCapacity); } }; From 301823729d2269b390f26820778e6f41a4eddba8 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sat, 20 Jan 2018 17:30:36 +0100 Subject: [PATCH 160/248] Remove the use of std::vector --- src/collision/CollisionDetection.h | 1 - src/collision/ContactManifold.h | 1 - src/collision/HalfEdgeStructure.cpp | 8 +++++--- src/collision/HalfEdgeStructure.h | 1 - src/collision/PolyhedronMesh.h | 1 - src/collision/TriangleMesh.h | 11 +++++++---- src/collision/broadphase/BroadPhaseAlgorithm.h | 1 - src/collision/narrowphase/GJK/VoronoiSimplex.h | 1 - src/collision/shapes/BoxShape.cpp | 1 - src/collision/shapes/ConcaveMeshShape.cpp | 4 ++-- src/collision/shapes/ConcaveMeshShape.h | 5 +++-- src/collision/shapes/ConvexMeshShape.h | 1 - src/engine/CollisionWorld.cpp | 10 +++++----- src/engine/CollisionWorld.h | 4 ++-- src/engine/DynamicsWorld.cpp | 8 ++++---- src/engine/DynamicsWorld.h | 2 +- src/mathematics/Vector2.cpp | 1 - src/mathematics/Vector3.cpp | 1 - src/mathematics/mathematics.h | 1 - src/mathematics/mathematics_functions.cpp | 1 - src/mathematics/mathematics_functions.h | 1 - src/reactphysics3d.h | 1 + test/tests/collision/TestDynamicAABBTree.h | 1 - .../collisiondetection/CollisionDetectionScene.h | 4 ++-- testbed/scenes/collisionshapes/CollisionShapesScene.h | 4 ++-- testbed/scenes/concavemesh/ConcaveMeshScene.h | 4 ++-- testbed/scenes/cubes/CubesScene.h | 4 ++-- testbed/scenes/cubestack/CubeStackScene.h | 4 ++-- testbed/scenes/heightfield/HeightFieldScene.h | 4 ++-- testbed/scenes/joints/JointsScene.h | 4 ++-- testbed/scenes/raycast/RaycastScene.h | 4 ++-- testbed/src/Scene.h | 4 ++-- testbed/src/SceneDemo.cpp | 6 +++--- testbed/src/SceneDemo.h | 2 +- 34 files changed, 52 insertions(+), 59 deletions(-) diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index 6aeac709..53792245 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -34,7 +34,6 @@ #include "narrowphase/DefaultCollisionDispatch.h" #include "memory/MemoryManager.h" #include "constraint/ContactPoint.h" -#include #include #include #include diff --git a/src/collision/ContactManifold.h b/src/collision/ContactManifold.h index f513ad82..eea392d5 100644 --- a/src/collision/ContactManifold.h +++ b/src/collision/ContactManifold.h @@ -27,7 +27,6 @@ #define REACTPHYSICS3D_CONTACT_MANIFOLD_H // Libraries -#include #include "body/CollisionBody.h" #include "collision/ProxyShape.h" #include "constraint/ContactPoint.h" diff --git a/src/collision/HalfEdgeStructure.cpp b/src/collision/HalfEdgeStructure.cpp index 70a731d5..4378aeca 100644 --- a/src/collision/HalfEdgeStructure.cpp +++ b/src/collision/HalfEdgeStructure.cpp @@ -41,13 +41,13 @@ void HalfEdgeStructure::init() { std::map mapEdgeIndexToKey; std::map mapFaceIndexToEdgeKey; + List currentFaceEdges(mAllocator, mFaces[0].faceVertices.size()); + // For each face for (uint f=0; f currentFaceEdges; - edgeKey firstEdgeKey; // For each vertex of the face @@ -100,8 +100,10 @@ void HalfEdgeStructure::init() { mEdges.add(edge); } - currentFaceEdges.push_back(pairV1V2); + currentFaceEdges.add(pairV1V2); } + + currentFaceEdges.clear(); } // Set next edges diff --git a/src/collision/HalfEdgeStructure.h b/src/collision/HalfEdgeStructure.h index 15658a93..924d32bf 100644 --- a/src/collision/HalfEdgeStructure.h +++ b/src/collision/HalfEdgeStructure.h @@ -28,7 +28,6 @@ // Libraries #include "mathematics/mathematics.h" -#include namespace reactphysics3d { diff --git a/src/collision/PolyhedronMesh.h b/src/collision/PolyhedronMesh.h index b459723a..b8cd1f52 100644 --- a/src/collision/PolyhedronMesh.h +++ b/src/collision/PolyhedronMesh.h @@ -31,7 +31,6 @@ #include "HalfEdgeStructure.h" #include "collision/PolygonVertexArray.h" #include "memory/DefaultAllocator.h" -#include namespace reactphysics3d { diff --git a/src/collision/TriangleMesh.h b/src/collision/TriangleMesh.h index e33fad67..69196d22 100644 --- a/src/collision/TriangleMesh.h +++ b/src/collision/TriangleMesh.h @@ -27,9 +27,10 @@ #define REACTPHYSICS3D_TRIANGLE_MESH_H // Libraries -#include #include #include "TriangleVertexArray.h" +#include "memory/MemoryManager.h" +#include "containers/List.h" namespace reactphysics3d { @@ -46,12 +47,14 @@ class TriangleMesh { protected: /// All the triangle arrays of the mesh (one triangle array per part) - std::vector mTriangleArrays; + List mTriangleArrays; public: /// Constructor - TriangleMesh() = default; + TriangleMesh() : mTriangleArrays(MemoryManager::getBaseAllocator()) { + + } /// Destructor ~TriangleMesh() = default; @@ -68,7 +71,7 @@ class TriangleMesh { // Add a subpart of the mesh inline void TriangleMesh::addSubpart(TriangleVertexArray* triangleVertexArray) { - mTriangleArrays.push_back(triangleVertexArray ); + mTriangleArrays.add(triangleVertexArray ); } // Return a pointer to a given subpart (triangle vertex array) of the mesh diff --git a/src/collision/broadphase/BroadPhaseAlgorithm.h b/src/collision/broadphase/BroadPhaseAlgorithm.h index 30a67920..3ae18677 100644 --- a/src/collision/broadphase/BroadPhaseAlgorithm.h +++ b/src/collision/broadphase/BroadPhaseAlgorithm.h @@ -27,7 +27,6 @@ #define REACTPHYSICS3D_BROAD_PHASE_ALGORITHM_H // Libraries -#include #include "body/CollisionBody.h" #include "collision/ProxyShape.h" #include "DynamicAABBTree.h" diff --git a/src/collision/narrowphase/GJK/VoronoiSimplex.h b/src/collision/narrowphase/GJK/VoronoiSimplex.h index 9cbee47e..47f1b2c2 100644 --- a/src/collision/narrowphase/GJK/VoronoiSimplex.h +++ b/src/collision/narrowphase/GJK/VoronoiSimplex.h @@ -28,7 +28,6 @@ // Libraries #include "mathematics/mathematics.h" -#include /// ReactPhysics3D namespace namespace reactphysics3d { diff --git a/src/collision/shapes/BoxShape.cpp b/src/collision/shapes/BoxShape.cpp index c13e32f4..109b736a 100644 --- a/src/collision/shapes/BoxShape.cpp +++ b/src/collision/shapes/BoxShape.cpp @@ -28,7 +28,6 @@ #include "collision/ProxyShape.h" #include "configuration.h" #include "memory/MemoryManager.h" -#include #include using namespace reactphysics3d; diff --git a/src/collision/shapes/ConcaveMeshShape.cpp b/src/collision/shapes/ConcaveMeshShape.cpp index 8f215fc2..ec5fa913 100644 --- a/src/collision/shapes/ConcaveMeshShape.cpp +++ b/src/collision/shapes/ConcaveMeshShape.cpp @@ -155,7 +155,7 @@ uint ConcaveMeshShape::computeTriangleShapeId(uint subPart, uint triangleIndex) decimal ConcaveMeshRaycastCallback::raycastBroadPhaseShape(int32 nodeId, const Ray& ray) { // Add the id of the hit AABB node into - mHitAABBNodes.push_back(nodeId); + mHitAABBNodes.add(nodeId); return ray.maxFraction; } @@ -163,7 +163,7 @@ decimal ConcaveMeshRaycastCallback::raycastBroadPhaseShape(int32 nodeId, const R // Raycast all collision shapes that have been collected void ConcaveMeshRaycastCallback::raycastTriangles() { - std::vector::const_iterator it; + List::Iterator it; decimal smallestHitFraction = mRay.maxFraction; for (it = mHitAABBNodes.begin(); it != mHitAABBNodes.end(); ++it) { diff --git a/src/collision/shapes/ConcaveMeshShape.h b/src/collision/shapes/ConcaveMeshShape.h index c8c91972..2ecefb94 100644 --- a/src/collision/shapes/ConcaveMeshShape.h +++ b/src/collision/shapes/ConcaveMeshShape.h @@ -31,6 +31,7 @@ #include "collision/broadphase/DynamicAABBTree.h" #include "collision/TriangleMesh.h" #include "collision/shapes/TriangleShape.h" +#include "containers/List.h" #include "engine/Profiler.h" namespace reactphysics3d { @@ -70,7 +71,7 @@ class ConcaveMeshRaycastCallback : public DynamicAABBTreeRaycastCallback { private : - std::vector mHitAABBNodes; + List mHitAABBNodes; const DynamicAABBTree& mDynamicAABBTree; const ConcaveMeshShape& mConcaveMeshShape; ProxyShape* mProxyShape; @@ -91,7 +92,7 @@ class ConcaveMeshRaycastCallback : public DynamicAABBTreeRaycastCallback { // Constructor ConcaveMeshRaycastCallback(const DynamicAABBTree& dynamicAABBTree, const ConcaveMeshShape& concaveMeshShape, ProxyShape* proxyShape, RaycastInfo& raycastInfo, const Ray& ray, MemoryAllocator& allocator) - : mDynamicAABBTree(dynamicAABBTree), mConcaveMeshShape(concaveMeshShape), mProxyShape(proxyShape), + : mHitAABBNodes(allocator), mDynamicAABBTree(dynamicAABBTree), mConcaveMeshShape(concaveMeshShape), mProxyShape(proxyShape), mRaycastInfo(raycastInfo), mRay(ray), mIsHit(false), mAllocator(allocator) { } diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index 44d01df4..44e64ad3 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -33,7 +33,6 @@ #include "collision/TriangleMesh.h" #include "collision/PolyhedronMesh.h" #include "collision/narrowphase/GJK/GJKAlgorithm.h" -#include #include #include diff --git a/src/engine/CollisionWorld.cpp b/src/engine/CollisionWorld.cpp index da5bf609..1a462c60 100644 --- a/src/engine/CollisionWorld.cpp +++ b/src/engine/CollisionWorld.cpp @@ -34,7 +34,7 @@ using namespace std; // Constructor CollisionWorld::CollisionWorld() : mCollisionDetection(this, mMemoryManager), mCurrentBodyID(0), - mEventListener(nullptr) { + mFreeBodiesIDs(mMemoryManager.getPoolAllocator()), mEventListener(nullptr) { #ifdef IS_PROFILING_ACTIVE @@ -102,7 +102,7 @@ void CollisionWorld::destroyCollisionBody(CollisionBody* collisionBody) { collisionBody->removeAllCollisionShapes(); // Add the body ID to the list of free IDs - mFreeBodiesIDs.push_back(collisionBody->getID()); + mFreeBodiesIDs.add(collisionBody->getID()); // Call the destructor of the collision body collisionBody->~CollisionBody(); @@ -119,9 +119,9 @@ bodyindex CollisionWorld::computeNextAvailableBodyID() { // Compute the body ID bodyindex bodyID; - if (!mFreeBodiesIDs.empty()) { - bodyID = mFreeBodiesIDs.back(); - mFreeBodiesIDs.pop_back(); + if (mFreeBodiesIDs.size() != 0) { + bodyID = mFreeBodiesIDs[mFreeBodiesIDs.size() - 1]; + mFreeBodiesIDs.remove(mFreeBodiesIDs.size() - 1); } else { bodyID = mCurrentBodyID; diff --git a/src/engine/CollisionWorld.h b/src/engine/CollisionWorld.h index 9f1fea58..bdffe4d1 100644 --- a/src/engine/CollisionWorld.h +++ b/src/engine/CollisionWorld.h @@ -27,11 +27,11 @@ #define REACTPHYSICS3D_COLLISION_WORLD_H // Libraries -#include #include #include #include #include "mathematics/mathematics.h" +#include "containers/List.h" #include "Profiler.h" #include "body/CollisionBody.h" #include "collision/RaycastInfo.h" @@ -74,7 +74,7 @@ class CollisionWorld { bodyindex mCurrentBodyID; /// List of free ID for rigid bodies - std::vector mFreeBodiesIDs; + List mFreeBodiesIDs; /// Pointer to an event listener object EventListener* mEventListener; diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index 35b1ba04..b523a505 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -446,7 +446,7 @@ void DynamicsWorld::destroyRigidBody(RigidBody* rigidBody) { rigidBody->removeAllCollisionShapes(); // Add the body ID to the list of free IDs - mFreeBodiesIDs.push_back(rigidBody->getID()); + mFreeBodiesIDs.add(rigidBody->getID()); // Destroy all the joints in which the rigid body to be destroyed is involved JointListElement* element; @@ -828,9 +828,9 @@ void DynamicsWorld::enableSleeping(bool isSleepingEnabled) { } /// Return the list of all contacts of the world -std::vector DynamicsWorld::getContactsList() const { +List DynamicsWorld::getContactsList() { - std::vector contactManifolds; + List contactManifolds(mMemoryManager.getPoolAllocator()); // For each currently overlapping pair of bodies std::map::const_iterator it; @@ -845,7 +845,7 @@ std::vector DynamicsWorld::getContactsList() const { while (manifold != nullptr) { // Get the contact manifold - contactManifolds.push_back(manifold); + contactManifolds.add(manifold); manifold = manifold->getNext(); } diff --git a/src/engine/DynamicsWorld.h b/src/engine/DynamicsWorld.h index 0c614b65..705f63d5 100644 --- a/src/engine/DynamicsWorld.h +++ b/src/engine/DynamicsWorld.h @@ -249,7 +249,7 @@ class DynamicsWorld : public CollisionWorld { void setEventListener(EventListener* eventListener); /// Return the list of all contacts of the world - std::vector getContactsList() const; + List getContactsList(); // -------------------- Friendship -------------------- // diff --git a/src/mathematics/Vector2.cpp b/src/mathematics/Vector2.cpp index 271fd82f..eed109dc 100644 --- a/src/mathematics/Vector2.cpp +++ b/src/mathematics/Vector2.cpp @@ -25,7 +25,6 @@ // Libraries #include "Vector2.h" -#include // Namespaces using namespace reactphysics3d; diff --git a/src/mathematics/Vector3.cpp b/src/mathematics/Vector3.cpp index 33b760ba..9a0cc082 100644 --- a/src/mathematics/Vector3.cpp +++ b/src/mathematics/Vector3.cpp @@ -26,7 +26,6 @@ // Libraries #include "Vector3.h" #include -#include // Namespaces using namespace reactphysics3d; diff --git a/src/mathematics/mathematics.h b/src/mathematics/mathematics.h index b2f2bd1f..9fac1571 100644 --- a/src/mathematics/mathematics.h +++ b/src/mathematics/mathematics.h @@ -36,7 +36,6 @@ #include "Ray.h" #include "configuration.h" #include "mathematics_functions.h" -#include #include #include #include diff --git a/src/mathematics/mathematics_functions.cpp b/src/mathematics/mathematics_functions.cpp index 7e4a1427..52ac337b 100755 --- a/src/mathematics/mathematics_functions.cpp +++ b/src/mathematics/mathematics_functions.cpp @@ -28,7 +28,6 @@ #include "Vector3.h" #include "Vector2.h" #include -#include using namespace reactphysics3d; diff --git a/src/mathematics/mathematics_functions.h b/src/mathematics/mathematics_functions.h index a72b0077..d0968904 100755 --- a/src/mathematics/mathematics_functions.h +++ b/src/mathematics/mathematics_functions.h @@ -32,7 +32,6 @@ #include #include #include -#include #include "containers/List.h" /// ReactPhysics3D namespace diff --git a/src/reactphysics3d.h b/src/reactphysics3d.h index dd2a6265..f2ea5abe 100644 --- a/src/reactphysics3d.h +++ b/src/reactphysics3d.h @@ -64,6 +64,7 @@ #include "constraint/SliderJoint.h" #include "constraint/HingeJoint.h" #include "constraint/FixedJoint.h" +#include "containers/List.h" /// Alias to the ReactPhysics3D namespace namespace rp3d = reactphysics3d; diff --git a/test/tests/collision/TestDynamicAABBTree.h b/test/tests/collision/TestDynamicAABBTree.h index 53f5e618..e43c63e7 100755 --- a/test/tests/collision/TestDynamicAABBTree.h +++ b/test/tests/collision/TestDynamicAABBTree.h @@ -29,7 +29,6 @@ // Libraries #include "Test.h" #include "collision/broadphase/DynamicAABBTree.h" -#include /// Reactphysics3D namespace namespace reactphysics3d { diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.h b/testbed/scenes/collisiondetection/CollisionDetectionScene.h index 9a90f25c..e60893df 100644 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.h +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.h @@ -186,7 +186,7 @@ class CollisionDetectionScene : public SceneDemo { virtual void setIsContactPointsDisplayed(bool display) override; /// Return all the contact points of the scene - virtual std::vector getContactPoints() const override; + virtual std::vector getContactPoints() override; }; // Display or not the surface normals at hit points @@ -205,7 +205,7 @@ inline void CollisionDetectionScene::setIsContactPointsDisplayed(bool display) { } // Return all the contact points of the scene -inline std::vector CollisionDetectionScene::getContactPoints() const { +inline std::vector CollisionDetectionScene::getContactPoints() { return mContactManager.getContactPoints(); } diff --git a/testbed/scenes/collisionshapes/CollisionShapesScene.h b/testbed/scenes/collisionshapes/CollisionShapesScene.h index b22d8429..dbb49539 100644 --- a/testbed/scenes/collisionshapes/CollisionShapesScene.h +++ b/testbed/scenes/collisionshapes/CollisionShapesScene.h @@ -101,11 +101,11 @@ class CollisionShapesScene : public SceneDemo { virtual void reset() override; /// Return all the contact points of the scene - virtual std::vector getContactPoints() const override; + virtual std::vector getContactPoints() override; }; // Return all the contact points of the scene -inline std::vector CollisionShapesScene::getContactPoints() const { +inline std::vector CollisionShapesScene::getContactPoints() { return computeContactPointsOfWorld(getDynamicsWorld()); } diff --git a/testbed/scenes/concavemesh/ConcaveMeshScene.h b/testbed/scenes/concavemesh/ConcaveMeshScene.h index beca8f71..91ede1bb 100644 --- a/testbed/scenes/concavemesh/ConcaveMeshScene.h +++ b/testbed/scenes/concavemesh/ConcaveMeshScene.h @@ -98,11 +98,11 @@ class ConcaveMeshScene : public SceneDemo { virtual void reset() override; /// Return all the contact points of the scene - virtual std::vector getContactPoints() const override; + virtual std::vector getContactPoints() override; }; // Return all the contact points of the scene -inline std::vector ConcaveMeshScene::getContactPoints() const { +inline std::vector ConcaveMeshScene::getContactPoints() { return computeContactPointsOfWorld(getDynamicsWorld()); } diff --git a/testbed/scenes/cubes/CubesScene.h b/testbed/scenes/cubes/CubesScene.h index 6d553835..e284a91d 100755 --- a/testbed/scenes/cubes/CubesScene.h +++ b/testbed/scenes/cubes/CubesScene.h @@ -69,11 +69,11 @@ class CubesScene : public SceneDemo { virtual void reset() override; /// Return all the contact points of the scene - virtual std::vector getContactPoints() const override; + virtual std::vector getContactPoints() override; }; // Return all the contact points of the scene -inline std::vector CubesScene::getContactPoints() const { +inline std::vector CubesScene::getContactPoints() { return computeContactPointsOfWorld(getDynamicsWorld()); } diff --git a/testbed/scenes/cubestack/CubeStackScene.h b/testbed/scenes/cubestack/CubeStackScene.h index 9bbc1c01..d4a4dace 100644 --- a/testbed/scenes/cubestack/CubeStackScene.h +++ b/testbed/scenes/cubestack/CubeStackScene.h @@ -69,11 +69,11 @@ class CubeStackScene : public SceneDemo { virtual void reset() override; /// Return all the contact points of the scene - virtual std::vector getContactPoints() const override; + virtual std::vector getContactPoints() override; }; // Return all the contact points of the scene -inline std::vector CubeStackScene::getContactPoints() const { +inline std::vector CubeStackScene::getContactPoints() { return computeContactPointsOfWorld(getDynamicsWorld()); } diff --git a/testbed/scenes/heightfield/HeightFieldScene.h b/testbed/scenes/heightfield/HeightFieldScene.h index 2a3e68f5..90edda93 100644 --- a/testbed/scenes/heightfield/HeightFieldScene.h +++ b/testbed/scenes/heightfield/HeightFieldScene.h @@ -100,11 +100,11 @@ class HeightFieldScene : public SceneDemo { virtual void reset() override ; /// Return all the contact points of the scene - virtual std::vector getContactPoints() const override ; + virtual std::vector getContactPoints() override ; }; // Return all the contact points of the scene -inline std::vector HeightFieldScene::getContactPoints() const { +inline std::vector HeightFieldScene::getContactPoints() { return computeContactPointsOfWorld(getDynamicsWorld()); } diff --git a/testbed/scenes/joints/JointsScene.h b/testbed/scenes/joints/JointsScene.h index dad9af38..f101bf32 100644 --- a/testbed/scenes/joints/JointsScene.h +++ b/testbed/scenes/joints/JointsScene.h @@ -127,11 +127,11 @@ class JointsScene : public SceneDemo { virtual void reset() override; /// Return all the contact points of the scene - virtual std::vector getContactPoints() const override; + virtual std::vector getContactPoints() override; }; // Return all the contact points of the scene -inline std::vector JointsScene::getContactPoints() const { +inline std::vector JointsScene::getContactPoints() { return computeContactPointsOfWorld(getDynamicsWorld()); } diff --git a/testbed/scenes/raycast/RaycastScene.h b/testbed/scenes/raycast/RaycastScene.h index 8024ff1a..e8e4a854 100644 --- a/testbed/scenes/raycast/RaycastScene.h +++ b/testbed/scenes/raycast/RaycastScene.h @@ -198,7 +198,7 @@ class RaycastScene : public SceneDemo { virtual void setIsContactPointsDisplayed(bool display) override; /// Return all the contact points of the scene - virtual std::vector getContactPoints() const override; + virtual std::vector getContactPoints() override; }; // Display or not the surface normals at hit points @@ -217,7 +217,7 @@ inline void RaycastScene::setIsContactPointsDisplayed(bool display) { } // Return all the contact points of the scene -inline std::vector RaycastScene::getContactPoints() const { +inline std::vector RaycastScene::getContactPoints() { return mRaycastManager.getHitPoints(); } diff --git a/testbed/src/Scene.h b/testbed/src/Scene.h index 89a9afdd..6ccc3254 100644 --- a/testbed/src/Scene.h +++ b/testbed/src/Scene.h @@ -230,7 +230,7 @@ class Scene { void setIsWireframeEnabled(bool isEnabled); /// Return all the contact points of the scene - std::vector virtual getContactPoints() const; + std::vector virtual getContactPoints(); }; // Called when a keyboard event occurs @@ -303,7 +303,7 @@ inline void Scene::setIsWireframeEnabled(bool isEnabled) { } // Return all the contact points of the scene -inline std::vector Scene::getContactPoints() const { +inline std::vector Scene::getContactPoints() { // Return an empty list of contact points return std::vector(); diff --git a/testbed/src/SceneDemo.cpp b/testbed/src/SceneDemo.cpp index 5ef6fb95..8e2a92da 100644 --- a/testbed/src/SceneDemo.cpp +++ b/testbed/src/SceneDemo.cpp @@ -418,15 +418,15 @@ void SceneDemo::removeAllContactPoints() { } // Return all the contact points of the scene -std::vector SceneDemo::computeContactPointsOfWorld(const rp3d::DynamicsWorld* world) const { +std::vector SceneDemo::computeContactPointsOfWorld(rp3d::DynamicsWorld* world) { std::vector contactPoints; // Get the list of contact manifolds from the world - std::vector manifolds = world->getContactsList(); + rp3d::List manifolds = world->getContactsList(); // For each contact manifold - std::vector::const_iterator it; + rp3d::List::Iterator it; for (it = manifolds.begin(); it != manifolds.end(); ++it) { const rp3d::ContactManifold* manifold = *it; diff --git a/testbed/src/SceneDemo.h b/testbed/src/SceneDemo.h index 359c2374..1eaa30b9 100644 --- a/testbed/src/SceneDemo.h +++ b/testbed/src/SceneDemo.h @@ -158,7 +158,7 @@ class SceneDemo : public Scene { virtual void setIsShadowMappingEnabled(bool isShadowMappingEnabled) override; /// Return all the contact points of the scene - std::vector computeContactPointsOfWorld(const rp3d::DynamicsWorld* world) const; + std::vector computeContactPointsOfWorld(reactphysics3d::DynamicsWorld *world); }; // Enabled/Disable the shadow mapping From 010d7876ef8cd69d0fcbca91cd99d9db64aa2030 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 21 Jan 2018 13:11:11 +0100 Subject: [PATCH 161/248] Make sure we do not recompute automatically center of mass and inertia tensor when they are set by the user --- src/body/RigidBody.cpp | 106 +++++++++++++++++++++++++---------------- src/body/RigidBody.h | 6 +++ 2 files changed, 72 insertions(+), 40 deletions(-) diff --git a/src/body/RigidBody.cpp b/src/body/RigidBody.cpp index bad11916..5e5a67c7 100644 --- a/src/body/RigidBody.cpp +++ b/src/body/RigidBody.cpp @@ -42,7 +42,7 @@ RigidBody::RigidBody(const Transform& transform, CollisionWorld& world, bodyinde : CollisionBody(transform, world, id), mArrayIndex(0), mInitMass(decimal(1.0)), mCenterOfMassLocal(0, 0, 0), mCenterOfMassWorld(transform.getPosition()), mIsGravityEnabled(true), mLinearDamping(decimal(0.0)), mAngularDamping(decimal(0.0)), - mJointsList(nullptr) { + mJointsList(nullptr), mIsCenterOfMassSetByUser(false), mIsInertiaTensorSetByUser(false) { // Compute the inverse mass mMassInverse = decimal(1.0) / mInitMass; @@ -93,16 +93,18 @@ void RigidBody::setType(BodyType type) { mMassInverse = decimal(0.0); mInertiaTensorLocalInverse.setToZero(); mInertiaTensorInverseWorld.setToZero(); - } else { // If it is a dynamic body mMassInverse = decimal(1.0) / mInitMass; - mInertiaTensorLocalInverse = mUserInertiaTensorLocalInverse; - // Update the world inverse inertia tensor - updateInertiaTensorInverseWorld(); + if (mIsInertiaTensorSetByUser) { + mInertiaTensorLocalInverse = mUserInertiaTensorLocalInverse; + } } + // Update the world inverse inertia tensor + updateInertiaTensorInverseWorld(); + // Awake the body setIsSleeping(false); @@ -119,6 +121,8 @@ void RigidBody::setType(BodyType type) { } // Set the local inertia tensor of the body (in local-space coordinates) +/// If the inertia tensor is set with this method, it will not be computed +/// using the collision shapes of the body. /** * @param inertiaTensorLocal The 3x3 inertia tensor matrix of the body in local-space * coordinates @@ -126,6 +130,7 @@ void RigidBody::setType(BodyType type) { void RigidBody::setInertiaTensorLocal(const Matrix3x3& inertiaTensorLocal) { mUserInertiaTensorLocalInverse = inertiaTensorLocal.getInverse(); + mIsInertiaTensorSetByUser = true; if (mType != BodyType::DYNAMIC) return; @@ -136,10 +141,17 @@ void RigidBody::setInertiaTensorLocal(const Matrix3x3& inertiaTensorLocal) { updateInertiaTensorInverseWorld(); } -// Set the inverse local inertia tensor of the body (in body coordinates) +// Set the inverse local inertia tensor of the body (in local-space coordinates) +/// If the inverse inertia tensor is set with this method, it will not be computed +/// using the collision shapes of the body. +/** + * @param inverseInertiaTensorLocal The 3x3 inverse inertia tensor matrix of the body in local-space + * coordinates + */ void RigidBody::setInverseInertiaTensorLocal(const Matrix3x3& inverseInertiaTensorLocal) { mUserInertiaTensorLocalInverse = inverseInertiaTensorLocal; + mIsInertiaTensorSetByUser = true; if (mType != BodyType::DYNAMIC) return; @@ -151,6 +163,8 @@ void RigidBody::setInverseInertiaTensorLocal(const Matrix3x3& inverseInertiaTens } // Set the local center of mass of the body (in local-space coordinates) +/// If you set the center of mass with the method, it will not be computed +/// automatically using collision shapes. /** * @param centerOfMassLocal The center of mass of the body in local-space * coordinates @@ -159,6 +173,8 @@ void RigidBody::setCenterOfMassLocal(const Vector3& centerOfMassLocal) { if (mType != BodyType::DYNAMIC) return; + mIsCenterOfMassSetByUser = true; + const Vector3 oldCenterOfMass = mCenterOfMassWorld; mCenterOfMassLocal = centerOfMassLocal; @@ -359,9 +375,9 @@ void RigidBody::recomputeMassInformation() { mInitMass = decimal(0.0); mMassInverse = decimal(0.0); - mInertiaTensorLocalInverse.setToZero(); - mInertiaTensorInverseWorld.setToZero(); - mCenterOfMassLocal.setToZero(); + if (!mIsInertiaTensorSetByUser) mInertiaTensorLocalInverse.setToZero(); + if (!mIsInertiaTensorSetByUser) mInertiaTensorInverseWorld.setToZero(); + if (!mIsCenterOfMassSetByUser) mCenterOfMassLocal.setToZero(); Matrix3x3 inertiaTensorLocal; inertiaTensorLocal.setToZero(); @@ -376,7 +392,10 @@ void RigidBody::recomputeMassInformation() { // Compute the total mass of the body for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) { mInitMass += shape->getMass(); - mCenterOfMassLocal += shape->getLocalToBodyTransform().getPosition() * shape->getMass(); + + if (!mIsCenterOfMassSetByUser) { + mCenterOfMassLocal += shape->getLocalToBodyTransform().getPosition() * shape->getMass(); + } } if (mInitMass > decimal(0.0)) { @@ -389,39 +408,46 @@ void RigidBody::recomputeMassInformation() { // Compute the center of mass const Vector3 oldCenterOfMass = mCenterOfMassWorld; - mCenterOfMassLocal *= mMassInverse; - mCenterOfMassWorld = mTransform * mCenterOfMassLocal; - // Compute the total mass and inertia tensor using all the collision shapes - for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) { - - // Get the inertia tensor of the collision shape in its local-space - Matrix3x3 inertiaTensor; - shape->getCollisionShape()->computeLocalInertiaTensor(inertiaTensor, shape->getMass()); - - // Convert the collision shape inertia tensor into the local-space of the body - const Transform& shapeTransform = shape->getLocalToBodyTransform(); - Matrix3x3 rotationMatrix = shapeTransform.getOrientation().getMatrix(); - inertiaTensor = rotationMatrix * inertiaTensor * rotationMatrix.getTranspose(); - - // Use the parallel axis theorem to convert the inertia tensor w.r.t the collision shape - // center into a inertia tensor w.r.t to the body origin. - Vector3 offset = shapeTransform.getPosition() - mCenterOfMassLocal; - decimal offsetSquare = offset.lengthSquare(); - Matrix3x3 offsetMatrix; - offsetMatrix[0].setAllValues(offsetSquare, decimal(0.0), decimal(0.0)); - offsetMatrix[1].setAllValues(decimal(0.0), offsetSquare, decimal(0.0)); - offsetMatrix[2].setAllValues(decimal(0.0), decimal(0.0), offsetSquare); - offsetMatrix[0] += offset * (-offset.x); - offsetMatrix[1] += offset * (-offset.y); - offsetMatrix[2] += offset * (-offset.z); - offsetMatrix *= shape->getMass(); - - inertiaTensorLocal += inertiaTensor + offsetMatrix; + if (!mIsCenterOfMassSetByUser) { + mCenterOfMassLocal *= mMassInverse; } - // Compute the local inverse inertia tensor - mInertiaTensorLocalInverse = inertiaTensorLocal.getInverse(); + mCenterOfMassWorld = mTransform * mCenterOfMassLocal; + + if (!mIsInertiaTensorSetByUser) { + + // Compute the inertia tensor using all the collision shapes + for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) { + + // Get the inertia tensor of the collision shape in its local-space + Matrix3x3 inertiaTensor; + shape->getCollisionShape()->computeLocalInertiaTensor(inertiaTensor, shape->getMass()); + + // Convert the collision shape inertia tensor into the local-space of the body + const Transform& shapeTransform = shape->getLocalToBodyTransform(); + Matrix3x3 rotationMatrix = shapeTransform.getOrientation().getMatrix(); + inertiaTensor = rotationMatrix * inertiaTensor * rotationMatrix.getTranspose(); + + // Use the parallel axis theorem to convert the inertia tensor w.r.t the collision shape + // center into a inertia tensor w.r.t to the body origin. + Vector3 offset = shapeTransform.getPosition() - mCenterOfMassLocal; + decimal offsetSquare = offset.lengthSquare(); + Matrix3x3 offsetMatrix; + offsetMatrix[0].setAllValues(offsetSquare, decimal(0.0), decimal(0.0)); + offsetMatrix[1].setAllValues(decimal(0.0), offsetSquare, decimal(0.0)); + offsetMatrix[2].setAllValues(decimal(0.0), decimal(0.0), offsetSquare); + offsetMatrix[0] += offset * (-offset.x); + offsetMatrix[1] += offset * (-offset.y); + offsetMatrix[2] += offset * (-offset.z); + offsetMatrix *= shape->getMass(); + + inertiaTensorLocal += inertiaTensor + offsetMatrix; + } + + // Compute the local inverse inertia tensor + mInertiaTensorLocalInverse = inertiaTensorLocal.getInverse(); + } // Update the world inverse inertia tensor updateInertiaTensorInverseWorld(); diff --git a/src/body/RigidBody.h b/src/body/RigidBody.h index eaadb59c..22c784ef 100644 --- a/src/body/RigidBody.h +++ b/src/body/RigidBody.h @@ -109,6 +109,12 @@ class RigidBody : public CollisionBody { /// First element of the linked list of joints involving this body JointListElement* mJointsList; + /// True if the center of mass is set by the user + bool mIsCenterOfMassSetByUser; + + /// True if the inertia tensor is set by the user + bool mIsInertiaTensorSetByUser; + // -------------------- Methods -------------------- // /// Remove a joint from the joints list From a82bd12383c2479cebcb34e971461ee3bfa3ffb8 Mon Sep 17 00:00:00 2001 From: Konstantinos Chatzilygeroudis Date: Thu, 25 Jan 2018 19:00:09 +0100 Subject: [PATCH 162/248] Fix for compilation issues --- src/configuration.h | 2 +- src/engine/Profiler.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/configuration.h b/src/configuration.h index 96391e76..f0a2fd14 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -152,7 +152,7 @@ constexpr int NB_MAX_CONTACT_MANIFOLDS_CONCAVE_SHAPE = 3; constexpr decimal COS_ANGLE_SIMILAR_CONTACT_MANIFOLD = decimal(0.95); /// Size (in bytes) of the single frame allocator -constexpr size_t INIT_SINGLE_FRAME_ALLOCATOR_BYTES = 1048576; // 1Mb +constexpr std::size_t INIT_SINGLE_FRAME_ALLOCATOR_BYTES = 1048576; // 1Mb } diff --git a/src/engine/Profiler.h b/src/engine/Profiler.h index 45b9b2e9..84b7ed59 100644 --- a/src/engine/Profiler.h +++ b/src/engine/Profiler.h @@ -415,7 +415,7 @@ inline void Profiler::destroy() { #else // In profile is not active // Empty macro in case profiling is not active -#define PROFILE(name) +#define PROFILE(name, profiler) #endif From 220057a587718b895c322b60f83b581f33676de6 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Fri, 26 Jan 2018 17:34:26 +0100 Subject: [PATCH 163/248] Remove the use of std::map and fix issues in Map class --- src/collision/CollisionDetection.cpp | 33 ++++---- src/collision/CollisionDetection.h | 4 +- src/collision/HalfEdgeStructure.cpp | 61 +++++++++------ src/collision/HalfEdgeStructure.h | 21 ++++++ src/collision/shapes/ConvexMeshShape.h | 1 - src/containers/Map.h | 40 +++++++++- src/containers/containers_common.h | 44 +++++++++++ src/engine/ConstraintSolver.h | 2 - src/engine/ContactSolver.h | 2 - src/engine/DynamicsWorld.cpp | 2 +- src/engine/OverlappingPair.cpp | 14 ++-- src/engine/OverlappingPair.h | 100 +++++++++++++++++++------ test/tests/collision/TestRaycast.h | 26 +++---- test/tests/containers/TestMap.h | 71 ++++++++++++++++-- 14 files changed, 321 insertions(+), 100 deletions(-) create mode 100644 src/containers/containers_common.h diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 66cf1eb5..340bd823 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -48,7 +48,8 @@ using namespace std; // Constructor CollisionDetection::CollisionDetection(CollisionWorld* world, MemoryManager& memoryManager) - : mMemoryManager(memoryManager), mWorld(world), mNarrowPhaseInfoList(nullptr), mBroadPhaseAlgorithm(*this), + : mMemoryManager(memoryManager), mWorld(world), mNarrowPhaseInfoList(nullptr), + mOverlappingPairs(mMemoryManager.getPoolAllocator()), mBroadPhaseAlgorithm(*this), mIsCollisionShapesAdded(false) { // Set the default collision dispatch configuration @@ -104,7 +105,7 @@ void CollisionDetection::computeMiddlePhase() { PROFILE("CollisionDetection::computeMiddlePhase()", mProfiler); // For each possible collision pair of bodies - map::iterator it; + Map::Iterator it; for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ) { OverlappingPair* pair = it->second; @@ -126,14 +127,14 @@ void CollisionDetection::computeMiddlePhase() { // overlapping pair if (!mBroadPhaseAlgorithm.testOverlappingShapes(shape1, shape2)) { - std::map::iterator itToRemove = it; + Map::Iterator itToRemove = it; ++it; // Destroy the overlapping pair itToRemove->second->~OverlappingPair(); mWorld->mMemoryManager.release(MemoryManager::AllocationType::Pool, itToRemove->second, sizeof(OverlappingPair)); - mOverlappingPairs.erase(itToRemove); + mOverlappingPairs.remove(itToRemove); continue; } else { @@ -320,10 +321,10 @@ void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, Pro (shape1->getCollisionCategoryBits() & shape2->getCollideWithMaskBits()) == 0) return; // Compute the overlapping pair ID - overlappingpairid pairID = OverlappingPair::computeID(shape1, shape2); + OverlappingPair::OverlappingPairId pairID = OverlappingPair::computeID(shape1, shape2); // Check if the overlapping pair already exists - if (mOverlappingPairs.find(pairID) != mOverlappingPairs.end()) return; + if (mOverlappingPairs.containsKey(pairID)) return; // Create the overlapping pair and add it into the set of overlapping pairs OverlappingPair* newPair = new (mMemoryManager.allocate(MemoryManager::AllocationType::Pool, sizeof(OverlappingPair))) @@ -331,11 +332,7 @@ void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, Pro mMemoryManager.getSingleFrameAllocator()); assert(newPair != nullptr); -#ifndef NDEBUG - std::pair::iterator, bool> check = -#endif - mOverlappingPairs.insert(make_pair(pairID, newPair)); - assert(check.second); + mOverlappingPairs.add(make_pair(pairID, newPair)); // Wake up the two bodies shape1->getBody()->setIsSleeping(false); @@ -348,11 +345,11 @@ void CollisionDetection::removeProxyCollisionShape(ProxyShape* proxyShape) { assert(proxyShape->mBroadPhaseID != -1); // Remove all the overlapping pairs involving this proxy shape - std::map::iterator it; + Map::Iterator it; for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ) { if (it->second->getShape1()->mBroadPhaseID == proxyShape->mBroadPhaseID|| it->second->getShape2()->mBroadPhaseID == proxyShape->mBroadPhaseID) { - std::map::iterator itToRemove = it; + Map::Iterator itToRemove = it; ++it; // TODO : Remove all the contact manifold of the overlapping pair from the contact manifolds list of the two bodies involved @@ -360,7 +357,7 @@ void CollisionDetection::removeProxyCollisionShape(ProxyShape* proxyShape) { // Destroy the overlapping pair itToRemove->second->~OverlappingPair(); mWorld->mMemoryManager.release(MemoryManager::AllocationType::Pool, itToRemove->second, sizeof(OverlappingPair)); - mOverlappingPairs.erase(itToRemove); + mOverlappingPairs.remove(itToRemove); } else { ++it; @@ -376,7 +373,7 @@ void CollisionDetection::addAllContactManifoldsToBodies() { PROFILE("CollisionDetection::addAllContactManifoldsToBodies()", mProfiler); // For each overlapping pairs in contact during the narrow-phase - std::map::iterator it; + Map::Iterator it; for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ++it) { // Add all the contact manifolds of the pair into the list of contact manifolds @@ -427,7 +424,7 @@ void CollisionDetection::processAllPotentialContacts() { PROFILE("CollisionDetection::processAllPotentialContacts()", mProfiler); // For each overlapping pairs in contact during the narrow-phase - std::map::iterator it; + Map::Iterator it; for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ++it) { // Process the potential contacts of the overlapping pair @@ -466,7 +463,7 @@ void CollisionDetection::reportAllContacts() { PROFILE("CollisionDetection::reportAllContacts()", mProfiler); // For each overlapping pairs in contact during the narrow-phase - std::map::iterator it; + Map::Iterator it; for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ++it) { // If there is a user callback @@ -921,7 +918,7 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { computeBroadPhase(); // For each possible collision pair of bodies - map::iterator it; + Map::Iterator it; for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ++it) { OverlappingPair* originalPair = it->second; diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index 53792245..fa3e05c6 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -34,9 +34,9 @@ #include "narrowphase/DefaultCollisionDispatch.h" #include "memory/MemoryManager.h" #include "constraint/ContactPoint.h" +#include "containers/Map.h" #include #include -#include /// ReactPhysics3D namespace namespace reactphysics3d { @@ -79,7 +79,7 @@ class CollisionDetection { NarrowPhaseInfo* mNarrowPhaseInfoList; /// Broad-phase overlapping pairs - std::map mOverlappingPairs; + Map mOverlappingPairs; /// Broad-phase algorithm BroadPhaseAlgorithm mBroadPhaseAlgorithm; diff --git a/src/collision/HalfEdgeStructure.cpp b/src/collision/HalfEdgeStructure.cpp index 4378aeca..b9106d78 100644 --- a/src/collision/HalfEdgeStructure.cpp +++ b/src/collision/HalfEdgeStructure.cpp @@ -25,37 +25,52 @@ // Libraries #include "HalfEdgeStructure.h" -#include +#include "containers/Map.h" +#include "containers/containers_common.h" using namespace reactphysics3d; +// Hash function for struct VerticesPair +namespace std { + + template <> struct hash { + + size_t operator()(const HalfEdgeStructure::VerticesPair& pair) const { + + std::size_t seed = 0; + hash_combine(seed, pair.vertex1); + hash_combine(seed, pair.vertex2); + + return seed; + } + }; +} + // Initialize the structure (when all vertices and faces have been added) void HalfEdgeStructure::init() { - using edgeKey = std::pair; + Map edges(mAllocator); + Map nextEdges(mAllocator); + Map mapEdgeToStartVertex(mAllocator); + Map mapEdgeToIndex(mAllocator); + Map mapEdgeIndexToKey(mAllocator); + Map mapFaceIndexToEdgeKey(mAllocator); - std::map edges; - std::map nextEdges; - std::map mapEdgeToStartVertex; - std::map mapEdgeToIndex; - std::map mapEdgeIndexToKey; - std::map mapFaceIndexToEdgeKey; - - List currentFaceEdges(mAllocator, mFaces[0].faceVertices.size()); + List currentFaceEdges(mAllocator, mFaces[0].faceVertices.size()); // For each face for (uint f=0; f= 1) { - nextEdges.insert(std::make_pair(currentFaceEdges[currentFaceEdges.size() - 1], pairV1V2)); + nextEdges.add(std::make_pair(currentFaceEdges[currentFaceEdges.size() - 1], pairV1V2)); } if (v == (face.faceVertices.size() - 1)) { - nextEdges.insert(std::make_pair(pairV1V2, firstEdgeKey)); + nextEdges.add(std::make_pair(pairV1V2, firstEdgeKey)); } - edges.insert(std::make_pair(pairV1V2, edge)); + edges.add(std::make_pair(pairV1V2, edge)); - const edgeKey pairV2V1 = std::make_pair(v2Index, v1Index); + const VerticesPair pairV2V1(v2Index, v1Index); - mapEdgeToStartVertex.insert(std::make_pair(pairV1V2, v1Index)); - mapEdgeToStartVertex.insert(std::make_pair(pairV2V1, v2Index)); + mapEdgeToStartVertex.add(std::make_pair(pairV1V2, v1Index), true); + mapEdgeToStartVertex.add(std::make_pair(pairV2V1, v2Index), true); - mapFaceIndexToEdgeKey.insert(std::make_pair(f, pairV1V2)); + mapFaceIndexToEdgeKey.add(std::make_pair(f, pairV1V2), true); auto itEdge = edges.find(pairV2V1); if (itEdge != edges.end()) { @@ -87,14 +102,14 @@ void HalfEdgeStructure::init() { itEdge->second.twinEdgeIndex = edgeIndex + 1; edge.twinEdgeIndex = edgeIndex; - mapEdgeIndexToKey[edgeIndex] = pairV2V1; - mapEdgeIndexToKey[edgeIndex + 1] = pairV1V2; + mapEdgeIndexToKey.add(std::make_pair(edgeIndex, pairV2V1)); + mapEdgeIndexToKey.add(std::make_pair(edgeIndex + 1, pairV1V2)); mVertices[v1Index].edgeIndex = edgeIndex + 1; mVertices[v2Index].edgeIndex = edgeIndex; - mapEdgeToIndex.insert(std::make_pair(pairV1V2, edgeIndex + 1)); - mapEdgeToIndex.insert(std::make_pair(pairV2V1, edgeIndex)); + mapEdgeToIndex.add(std::make_pair(pairV1V2, edgeIndex + 1)); + mapEdgeToIndex.add(std::make_pair(pairV2V1, edgeIndex)); mEdges.add(itEdge->second); mEdges.add(edge); diff --git a/src/collision/HalfEdgeStructure.h b/src/collision/HalfEdgeStructure.h index 924d32bf..b5668182 100644 --- a/src/collision/HalfEdgeStructure.h +++ b/src/collision/HalfEdgeStructure.h @@ -41,6 +41,25 @@ class HalfEdgeStructure { public: + /// Pair of vertices + struct VerticesPair { + + uint vertex1; + uint vertex2; + + /// Constructor + VerticesPair() = default; + + /// Constructor + VerticesPair(uint v1, uint v2) : vertex1(v1), vertex2(v2) {} + + /// Equality operator + bool operator==(const VerticesPair& pair) const { + return vertex1 == pair.vertex1 && vertex2 == pair.vertex2; + } + }; + + /// Edge struct Edge { uint vertexIndex; // Index of the vertex at the beginning of the edge uint twinEdgeIndex; // Index of the twin edge @@ -48,6 +67,7 @@ class HalfEdgeStructure { uint nextEdgeIndex; // Index of the next edge }; + /// Face struct Face { uint edgeIndex; // Index of an half-edge of the face List faceVertices; // Index of the vertices of the face @@ -59,6 +79,7 @@ class HalfEdgeStructure { Face(List vertices) : faceVertices(vertices) {} }; + /// Vertex struct Vertex { uint vertexPointIndex; // Index of the vertex point in the origin vertex array uint edgeIndex; // Index of one edge emanting from this vertex diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index 44e64ad3..b84c16dd 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -34,7 +34,6 @@ #include "collision/PolyhedronMesh.h" #include "collision/narrowphase/GJK/GJKAlgorithm.h" #include -#include /// ReactPhysics3D namespace namespace reactphysics3d { diff --git a/src/containers/Map.h b/src/containers/Map.h index 3c6ccc41..da33448a 100644 --- a/src/containers/Map.h +++ b/src/containers/Map.h @@ -30,8 +30,11 @@ #include "memory/MemoryAllocator.h" #include "mathematics/mathematics_functions.h" #include +#include +#include #include + namespace reactphysics3d { // Class Map @@ -387,7 +390,15 @@ class Map { std::memcpy(mBuckets, map.mBuckets, mCapacity * sizeof(int)); // Copy the entries - std::memcpy(mEntries, map.mEntries, mCapacity * sizeof(Entry)); + for (int i=0; i < mCapacity; i++) { + + new (&mEntries[i]) Entry(map.mEntries[i].hashCode, map.mEntries[i].next); + + if (map.mEntries[i].keyValue != nullptr) { + mEntries[i].keyValue = static_cast*>(mAllocator.allocate(sizeof(std::pair))); + new (mEntries[i].keyValue) std::pair(*(map.mEntries[i].keyValue)); + } + } } /// Destructor @@ -417,7 +428,7 @@ class Map { } /// Add an element into the map - void add(const std::pair& keyValue) { + void add(const std::pair& keyValue, bool insertIfAlreadyPresent = false) { if (mCapacity == 0) { initialize(0); @@ -435,7 +446,19 @@ class Map { // If there is already an item with the same key in the map if (mEntries[i].hashCode == hashCode && mEntries[i].keyValue->first == keyValue.first) { - throw std::runtime_error("The key and value pair already exists in the map"); + if (insertIfAlreadyPresent) { + + // Destruct the previous key/value + mEntries[i].keyValue->~pair(); + + // Copy construct the new key/value + new (mEntries[i].keyValue) std::pair(keyValue); + + return; + } + else { + throw std::runtime_error("The key and value pair already exists in the map"); + } } } @@ -473,6 +496,13 @@ class Map { mBuckets[bucket] = entryIndex; } + /// Remove the element pointed by some iterator + bool remove(const Iterator& it) { + + const K& key = it->first; + return remove(key); + } + /// Remove the element from the map with a given key bool remove(const K& key) { @@ -605,7 +635,9 @@ class Map { throw std::runtime_error("No item with given key has been found in the map"); } - return mEntries[entry]; + assert(mEntries[entry].keyValue != nullptr); + + return mEntries[entry].keyValue->second; } /// Overloaded equality operator diff --git a/src/containers/containers_common.h b/src/containers/containers_common.h new file mode 100644 index 00000000..bdaa07f8 --- /dev/null +++ b/src/containers/containers_common.h @@ -0,0 +1,44 @@ +/******************************************************************************** +* 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_CONTAINERS_COMMON_H +#define REACTPHYSICS3D_CONTAINERS_COMMON_H + +// Libraries +#include +#include + +namespace reactphysics3d { + +/// This method is used to combine two hash values +template +inline void hash_combine(std::size_t& seed, const T& v) { + std::hash hasher; + seed ^= hasher(v) + 0x9e3779b9 + (seed<<6) + (seed>>2); +} + +} + +#endif diff --git a/src/engine/ConstraintSolver.h b/src/engine/ConstraintSolver.h index 105045e0..7c3994fc 100644 --- a/src/engine/ConstraintSolver.h +++ b/src/engine/ConstraintSolver.h @@ -31,8 +31,6 @@ #include "mathematics/mathematics.h" #include "constraint/Joint.h" #include "Island.h" -#include -#include namespace reactphysics3d { diff --git a/src/engine/ContactSolver.h b/src/engine/ContactSolver.h index 8799a1ad..aecab4fe 100644 --- a/src/engine/ContactSolver.h +++ b/src/engine/ContactSolver.h @@ -32,8 +32,6 @@ #include "constraint/Joint.h" #include "collision/ContactManifold.h" #include "Island.h" -#include -#include /// ReactPhysics3D namespace namespace reactphysics3d { diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index b523a505..3ef9cd30 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -833,7 +833,7 @@ List DynamicsWorld::getContactsList() { List contactManifolds(mMemoryManager.getPoolAllocator()); // For each currently overlapping pair of bodies - std::map::const_iterator it; + Map::Iterator it; for (it = mCollisionDetection.mOverlappingPairs.begin(); it != mCollisionDetection.mOverlappingPairs.end(); ++it) { diff --git a/src/engine/OverlappingPair.cpp b/src/engine/OverlappingPair.cpp index 7a95be95..a5ca870a 100644 --- a/src/engine/OverlappingPair.cpp +++ b/src/engine/OverlappingPair.cpp @@ -28,14 +28,17 @@ #include "OverlappingPair.h" #include "collision/ContactManifoldInfo.h" #include "collision/NarrowPhaseInfo.h" +#include "containers/containers_common.h" using namespace reactphysics3d; + // Constructor OverlappingPair::OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, MemoryAllocator& persistentMemoryAllocator, MemoryAllocator& temporaryMemoryAllocator) : mContactManifoldSet(shape1, shape2, persistentMemoryAllocator), mPotentialContactManifolds(nullptr), - mPersistentAllocator(persistentMemoryAllocator), mTempMemoryAllocator(temporaryMemoryAllocator) { + mPersistentAllocator(persistentMemoryAllocator), mTempMemoryAllocator(temporaryMemoryAllocator), + mLastFrameCollisionInfos(mPersistentAllocator) { } @@ -150,7 +153,8 @@ void OverlappingPair::reducePotentialContactManifolds() { void OverlappingPair::addLastFrameInfoIfNecessary(uint shapeId1, uint shapeId2) { // Try to get the corresponding last frame collision info - auto it = mLastFrameCollisionInfos.find(std::make_pair(shapeId1, shapeId2)); + const ShapeIdPair shapeIdPair(shapeId1, shapeId2); + auto it = mLastFrameCollisionInfos.find(shapeIdPair); // If there is no collision info for those two shapes already if (it == mLastFrameCollisionInfos.end()) { @@ -160,9 +164,7 @@ void OverlappingPair::addLastFrameInfoIfNecessary(uint shapeId1, uint shapeId2) LastFrameCollisionInfo(); // Add it into the map of collision infos - std::map, LastFrameCollisionInfo*>::iterator it; - auto ret = mLastFrameCollisionInfos.insert(std::make_pair(std::make_pair(shapeId1, shapeId2), collisionInfo)); - assert(ret.second); + mLastFrameCollisionInfos.add(std::make_pair(shapeIdPair, collisionInfo)); } else { @@ -185,7 +187,7 @@ void OverlappingPair::clearObsoleteLastFrameCollisionInfos() { it->second->~LastFrameCollisionInfo(); mPersistentAllocator.release(it->second, sizeof(LastFrameCollisionInfo)); - mLastFrameCollisionInfos.erase(it++); + mLastFrameCollisionInfos.remove(it++); } else { ++it; diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index f3631775..c7653942 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -30,14 +30,12 @@ #include "collision/ContactManifoldSet.h" #include "collision/ProxyShape.h" #include "collision/shapes/CollisionShape.h" -#include +#include "containers/Map.h" +#include "containers/containers_common.h" /// ReactPhysics3D namespace namespace reactphysics3d { -// Type for the overlapping pair ID -using overlappingpairid = std::pair; - // Structure LastFrameCollisionInfo /** * This structure contains collision info about the last frame. @@ -95,6 +93,38 @@ struct LastFrameCollisionInfo { */ class OverlappingPair { + public: + + /// Pair of shape ids + struct ShapeIdPair { + + uint shapeIdBody1; + uint shapeIdBody2; + + /// Constructor + ShapeIdPair(uint id1, uint id2) : shapeIdBody1(id1), shapeIdBody2(id2) {} + + /// Equality operator + bool operator==(const ShapeIdPair& pair) const { + return shapeIdBody1 == pair.shapeIdBody1 && shapeIdBody2 == pair.shapeIdBody2; + } + }; + + /// Pair of broad-phase ids + struct OverlappingPairId { + + uint body1Id; + uint body2Id; + + /// Constructor + OverlappingPairId(uint id1, uint id2) : body1Id(id1), body2Id(id2) {} + + /// Equality operator + bool operator==(const OverlappingPairId& pair) const { + return body1Id == pair.body1Id && body2Id == pair.body2Id; + } + }; + private: // -------------------- Attributes -------------------- // @@ -102,13 +132,6 @@ class OverlappingPair { /// Set of persistent contact manifolds ContactManifoldSet mContactManifoldSet; - /// Temporal coherence collision data for each overlapping collision shapes of this pair. - /// Temporal coherence data store collision information about the last frame. - /// If two convex shapes overlap, we have a single collision data but if one shape is concave, - /// we might have collision data for several overlapping triangles. The key in the map is the - /// shape Ids of the two collision shapes. - std::map, LastFrameCollisionInfo*> mLastFrameCollisionInfos; - /// Linked-list of potential contact manifold ContactManifoldInfo* mPotentialContactManifolds; @@ -118,6 +141,13 @@ class OverlappingPair { /// Memory allocator used to allocated memory for the ContactManifoldInfo and ContactPointInfo MemoryAllocator& mTempMemoryAllocator; + /// Temporal coherence collision data for each overlapping collision shapes of this pair. + /// Temporal coherence data store collision information about the last frame. + /// If two convex shapes overlap, we have a single collision data but if one shape is concave, + /// we might have collision data for several overlapping triangles. The key in the map is the + /// shape Ids of the two collision shapes. + Map mLastFrameCollisionInfos; + public: // -------------------- Methods -------------------- // @@ -142,7 +172,7 @@ class OverlappingPair { ProxyShape* getShape2() const; /// Return the last frame collision info - LastFrameCollisionInfo* getLastFrameCollisionInfo(std::pair shapeIds); + LastFrameCollisionInfo* getLastFrameCollisionInfo(ShapeIdPair& shapeIds); /// Return the a reference to the contact manifold set const ContactManifoldSet& getContactManifoldSet(); @@ -193,7 +223,7 @@ class OverlappingPair { void makeLastFrameCollisionInfosObsolete(); /// Return the pair of bodies index - static overlappingpairid computeID(ProxyShape* shape1, ProxyShape* shape2); + static OverlappingPairId computeID(ProxyShape* shape1, ProxyShape* shape2); /// Return the pair of bodies index of the pair static bodyindexpair computeBodiesIndexPair(CollisionBody* body1, CollisionBody* body2); @@ -219,8 +249,8 @@ inline void OverlappingPair::addContactManifold(const ContactManifoldInfo* conta } // Return the last frame collision info for a given shape id or nullptr if none is found -inline LastFrameCollisionInfo* OverlappingPair::getLastFrameCollisionInfo(std::pair shapeIds) { - std::map, LastFrameCollisionInfo*>::iterator it = mLastFrameCollisionInfos.find(shapeIds); +inline LastFrameCollisionInfo* OverlappingPair::getLastFrameCollisionInfo(ShapeIdPair& shapeIds) { + Map::Iterator it = mLastFrameCollisionInfos.find(shapeIds); if (it != mLastFrameCollisionInfos.end()) { return it->second; } @@ -240,14 +270,14 @@ inline void OverlappingPair::makeContactsObsolete() { } // Return the pair of bodies index -inline overlappingpairid OverlappingPair::computeID(ProxyShape* shape1, ProxyShape* shape2) { +inline OverlappingPair::OverlappingPairId OverlappingPair::computeID(ProxyShape* shape1, ProxyShape* shape2) { assert(shape1->mBroadPhaseID >= 0 && shape2->mBroadPhaseID >= 0); // Construct the pair of body index - overlappingpairid pairID = shape1->mBroadPhaseID < shape2->mBroadPhaseID ? - std::make_pair(shape1->mBroadPhaseID, shape2->mBroadPhaseID) : - std::make_pair(shape2->mBroadPhaseID, shape1->mBroadPhaseID); - assert(pairID.first != pairID.second); + OverlappingPairId pairID = shape1->mBroadPhaseID < shape2->mBroadPhaseID ? + OverlappingPairId(shape1->mBroadPhaseID, shape2->mBroadPhaseID) : + OverlappingPairId(shape2->mBroadPhaseID, shape1->mBroadPhaseID); + assert(pairID.body1Id != pairID.body2Id); return pairID; } @@ -296,10 +326,38 @@ inline void OverlappingPair::reduceContactManifolds() { // Return the last frame collision info for a given pair of shape ids inline LastFrameCollisionInfo* OverlappingPair::getLastFrameCollisionInfo(uint shapeId1, uint shapeId2) const { - return mLastFrameCollisionInfos.at(std::make_pair(shapeId1, shapeId2)); + return mLastFrameCollisionInfos[ShapeIdPair(shapeId1, shapeId2)]; } } +// Hash function for struct ShapeIdPair +namespace std { + + template <> struct hash { + + size_t operator()(const reactphysics3d::OverlappingPair::ShapeIdPair& pair) const { + + std::size_t seed = 0; + reactphysics3d::hash_combine(seed, pair.shapeIdBody1); + reactphysics3d::hash_combine(seed, pair.shapeIdBody2); + + return seed; + } + }; + + template <> struct hash { + + size_t operator()(const reactphysics3d::OverlappingPair::OverlappingPairId& pair) const { + + std::size_t seed = 0; + reactphysics3d::hash_combine(seed, pair.body1Id); + reactphysics3d::hash_combine(seed, pair.body2Id); + + return seed; + } + }; +} + #endif diff --git a/test/tests/collision/TestRaycast.h b/test/tests/collision/TestRaycast.h index d02ab847..3bae090c 100644 --- a/test/tests/collision/TestRaycast.h +++ b/test/tests/collision/TestRaycast.h @@ -211,23 +211,21 @@ class TestRaycast : public Test { mCapsuleShape = new CapsuleShape(2, 5); mCapsuleProxyShape = mCapsuleBody->addCollisionShape(mCapsuleShape, mShapeTransform); - // TODO : Create convex mesh shape with new way (polyhedron mesh) to add test again - // Box of extents (2, 3, 4) - mPolyhedronVertices[0] = Vector3(-2, -3, -4); - mPolyhedronVertices[1] = Vector3(2, -3, -4); - mPolyhedronVertices[2] = Vector3(2, -3, 4); - mPolyhedronVertices[3] = Vector3(-2, -3, 4); - mPolyhedronVertices[4] = Vector3(-2, 3, -4); + mPolyhedronVertices[0] = Vector3(-2, -3, 4); + mPolyhedronVertices[1] = Vector3(2, -3, 4); + mPolyhedronVertices[2] = Vector3(2, 3, 4); + mPolyhedronVertices[3] = Vector3(-2, 3, 4); + mPolyhedronVertices[4] = Vector3(2, -3, -4); mPolyhedronVertices[5] = Vector3(2, 3, -4); - mPolyhedronVertices[6] = Vector3(2, 3, 4); - mPolyhedronVertices[7] = Vector3(-2, 3, 4); + mPolyhedronVertices[6] = Vector3(-2, 3, -4); + mPolyhedronVertices[7] = Vector3(-2, -3, -4); mPolyhedronIndices[0] = 0; mPolyhedronIndices[1] = 1; mPolyhedronIndices[2] = 2; mPolyhedronIndices[3] = 3; - mPolyhedronIndices[4] = 1; mPolyhedronIndices[5] = 5; mPolyhedronIndices[6] = 6; mPolyhedronIndices[7] = 2; - mPolyhedronIndices[8] = 0; mPolyhedronIndices[9] = 4; mPolyhedronIndices[10] = 5; mPolyhedronIndices[11] = 1; - mPolyhedronIndices[12] = 0; mPolyhedronIndices[13] = 3; mPolyhedronIndices[14] = 7; mPolyhedronIndices[15] = 4; - mPolyhedronIndices[16] = 3; mPolyhedronIndices[17] = 2; mPolyhedronIndices[18] = 6; mPolyhedronIndices[19] = 7; - mPolyhedronIndices[20] = 2; mPolyhedronIndices[21] = 5; mPolyhedronIndices[22] = 4; mPolyhedronIndices[23] = 7; + mPolyhedronIndices[4] = 1; mPolyhedronIndices[5] = 4; mPolyhedronIndices[6] = 5; mPolyhedronIndices[7] = 2; + mPolyhedronIndices[8] = 4; mPolyhedronIndices[9] = 7; mPolyhedronIndices[10] = 6; mPolyhedronIndices[11] = 5; + mPolyhedronIndices[12] = 0; mPolyhedronIndices[13] = 3; mPolyhedronIndices[14] = 6; mPolyhedronIndices[15] = 7; + mPolyhedronIndices[16] = 2; mPolyhedronIndices[17] = 5; mPolyhedronIndices[18] = 6; mPolyhedronIndices[19] = 3; + mPolyhedronIndices[20] = 1; mPolyhedronIndices[21] = 0; mPolyhedronIndices[22] = 7; mPolyhedronIndices[23] = 4; // Polygon faces descriptions for the polyhedron for (int f=0; f < 8; f++) { diff --git a/test/tests/containers/TestMap.h b/test/tests/containers/TestMap.h index a105fca8..503b0c24 100644 --- a/test/tests/containers/TestMap.h +++ b/test/tests/containers/TestMap.h @@ -31,6 +31,30 @@ #include "containers/Map.h" #include "memory/DefaultAllocator.h" +// Key to test map with always same hash values +namespace reactphysics3d { + struct TestKey { + int key; + + TestKey(int k) :key(k) {} + + bool operator==(const TestKey& testKey) const { + return key == testKey.key; + } + }; +} + +// Hash function for struct VerticesPair +namespace std { + + template <> struct hash { + + size_t operator()(const reactphysics3d::TestKey& key) const { + return 1; + } + }; +} + /// Reactphysics3D namespace namespace reactphysics3d { @@ -82,7 +106,6 @@ class TestMap : public Test { test(map2.size() == 0); // ----- Copy Constructors ----- // -/* Map map3(map1); test(map3.capacity() == map1.capacity()); test(map3.size() == map1.size()); @@ -100,7 +123,6 @@ class TestMap : public Test { test(map5[1] == 10); test(map5[2] == 20); test(map5[3] == 30); - */ } void testReserve() { @@ -123,8 +145,6 @@ class TestMap : public Test { void testAddRemoveClear() { - // TODO : ADD test with values with same hash for keys but different keys - // ----- Test add() ----- // Map map1(mAllocator); @@ -151,21 +171,32 @@ class TestMap : public Test { test(map1.size() == 3); test(map1[1] == 10); + map1.add(std::make_pair(56, 34)); + test(map1[56] == 34); + test(map1.size() == 4); + map1.add(std::make_pair(56, 13), true); + test(map1[56] == 13); + test(map1.size() == 4); + // ----- Test remove() ----- // map1.remove(1); test(!map1.containsKey(1)); test(map1.containsKey(8)); test(map1.containsKey(13)); - test(map1.size() == 2); + test(map1.size() == 3); map1.remove(13); test(map1.containsKey(8)); test(!map1.containsKey(13)); - test(map1.size() == 1); + test(map1.size() == 2); map1.remove(8); test(!map1.containsKey(8)); + test(map1.size() == 1); + + map1.remove(56); + test(!map1.containsKey(56)); test(map1.size() == 0); isValid = true; @@ -184,6 +215,16 @@ class TestMap : public Test { map3.remove(i); } + map3.add(std::make_pair(1, 10)); + map3.add(std::make_pair(2, 20)); + map3.add(std::make_pair(3, 30)); + test(map3.size() == 3); + auto it = map3.begin(); + map3.remove(it++); + test(!map3.containsKey(1)); + test(map3.size() == 2); + test(it->second == 20); + // ----- Test clear() ----- // Map map4(mAllocator); @@ -201,6 +242,24 @@ class TestMap : public Test { Map map5(mAllocator); map5.clear(); test(map5.size() == 0); + + // ----- Test map with always same hash value for keys ----- // + + Map map6(mAllocator); + for (int i=0; i < 1000; i++) { + map6.add(std::make_pair(TestKey(i), i)); + } + bool isTestValid = true; + for (int i=0; i < 1000; i++) { + if (map6[TestKey(i)] != i) { + isTestValid = false; + } + } + test(isTestValid); + for (int i=0; i < 1000; i++) { + map6.remove(TestKey(i)); + } + test(map6.size() == 0); } void testContainsKey() { From b3e771838da1ba7c42d6208540c3dfe3c9844c91 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sat, 3 Feb 2018 20:48:08 +0100 Subject: [PATCH 164/248] Replace std::set by Set and fix issues with List and Map --- CMakeLists.txt | 1 + src/collision/CollisionDetection.cpp | 32 +- src/collision/CollisionDetection.h | 26 +- src/collision/shapes/ConvexMeshShape.h | 1 - src/containers/List.h | 37 +- src/containers/Map.h | 37 +- src/containers/Pair.h | 264 +++++++++ src/containers/Set.h | 712 +++++++++++++++++++++++++ src/engine/CollisionWorld.cpp | 19 +- src/engine/CollisionWorld.h | 26 +- src/engine/DynamicsWorld.cpp | 41 +- src/engine/DynamicsWorld.h | 28 +- src/engine/OverlappingPair.cpp | 2 +- test/main.cpp | 2 + test/tests/containers/TestList.h | 48 +- test/tests/containers/TestMap.h | 16 +- test/tests/containers/TestSet.h | 417 +++++++++++++++ 17 files changed, 1581 insertions(+), 128 deletions(-) create mode 100644 src/containers/Pair.h create mode 100644 src/containers/Set.h create mode 100644 test/tests/containers/TestSet.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 169476c9..636c6295 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -199,6 +199,7 @@ SET (REACTPHYSICS3D_SOURCES "src/containers/LinkedList.h" "src/containers/List.h" "src/containers/Map.h" + "src/containers/Set.h" ) # Create the library diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 340bd823..c337e10a 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -37,20 +37,19 @@ #include "collision/OverlapCallback.h" #include #include -#include #include #include -#include // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; using namespace std; + // Constructor CollisionDetection::CollisionDetection(CollisionWorld* world, MemoryManager& memoryManager) : mMemoryManager(memoryManager), mWorld(world), mNarrowPhaseInfoList(nullptr), mOverlappingPairs(mMemoryManager.getPoolAllocator()), mBroadPhaseAlgorithm(*this), - mIsCollisionShapesAdded(false) { + mNoCollisionPairs(mMemoryManager.getPoolAllocator()), mIsCollisionShapesAdded(false) { // Set the default collision dispatch configuration setCollisionDispatch(&mDefaultCollisionDispatch); @@ -127,14 +126,11 @@ void CollisionDetection::computeMiddlePhase() { // overlapping pair if (!mBroadPhaseAlgorithm.testOverlappingShapes(shape1, shape2)) { - Map::Iterator itToRemove = it; - ++it; - // Destroy the overlapping pair - itToRemove->second->~OverlappingPair(); + it->second->~OverlappingPair(); - mWorld->mMemoryManager.release(MemoryManager::AllocationType::Pool, itToRemove->second, sizeof(OverlappingPair)); - mOverlappingPairs.remove(itToRemove); + mWorld->mMemoryManager.release(MemoryManager::AllocationType::Pool, it->second, sizeof(OverlappingPair)); + it = mOverlappingPairs.remove(it); continue; } else { @@ -155,7 +151,7 @@ void CollisionDetection::computeMiddlePhase() { // Check if the bodies are in the set of bodies that cannot collide between each other bodyindexpair bodiesIndex = OverlappingPair::computeBodiesIndexPair(body1, body2); - if (mNoCollisionPairs.count(bodiesIndex) > 0) continue; + if (mNoCollisionPairs.contains(bodiesIndex) > 0) continue; bool isShape1Convex = shape1->getCollisionShape()->isConvex(); bool isShape2Convex = shape2->getCollisionShape()->isConvex(); @@ -349,15 +345,13 @@ void CollisionDetection::removeProxyCollisionShape(ProxyShape* proxyShape) { for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ) { if (it->second->getShape1()->mBroadPhaseID == proxyShape->mBroadPhaseID|| it->second->getShape2()->mBroadPhaseID == proxyShape->mBroadPhaseID) { - Map::Iterator itToRemove = it; - ++it; // TODO : Remove all the contact manifold of the overlapping pair from the contact manifolds list of the two bodies involved // Destroy the overlapping pair - itToRemove->second->~OverlappingPair(); - mWorld->mMemoryManager.release(MemoryManager::AllocationType::Pool, itToRemove->second, sizeof(OverlappingPair)); - mOverlappingPairs.remove(itToRemove); + it->second->~OverlappingPair(); + mWorld->mMemoryManager.release(MemoryManager::AllocationType::Pool, it->second, sizeof(OverlappingPair)); + it = mOverlappingPairs.remove(it); } else { ++it; @@ -521,7 +515,7 @@ void CollisionDetection::testAABBOverlap(const AABB& aabb, OverlapCallback* over unsigned short categoryMaskBits) { assert(overlapCallback != nullptr); - std::unordered_set reportedBodies; + Set reportedBodies(mMemoryManager.getPoolAllocator()); // Ask the broad-phase to get all the overlapping shapes LinkedList overlappingNodes(mMemoryManager.getPoolAllocator()); @@ -544,7 +538,7 @@ void CollisionDetection::testAABBOverlap(const AABB& aabb, OverlapCallback* over if ((proxyShape->getCollisionCategoryBits() & categoryMaskBits) != 0) { // Add the body into the set of reported bodies - reportedBodies.insert(overlapBody->getID()); + reportedBodies.add(overlapBody->getID()); // Notify the overlap to the user overlapCallback->notifyOverlap(overlapBody); @@ -637,7 +631,7 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl assert(overlapCallback != nullptr); - std::unordered_set reportedBodies; + Set reportedBodies(mMemoryManager.getPoolAllocator()); // For each proxy shape proxy shape of the body ProxyShape* bodyProxyShape = body->getProxyShapesList(); @@ -717,7 +711,7 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl CollisionBody* overlapBody = proxyShape->getBody(); // Add the body into the set of reported bodies - reportedBodies.insert(overlapBody->getID()); + reportedBodies.add(overlapBody->getID()); // Notify the overlap to the user overlapCallback->notifyOverlap(overlapBody); diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index fa3e05c6..36bede7e 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -35,9 +35,26 @@ #include "memory/MemoryManager.h" #include "constraint/ContactPoint.h" #include "containers/Map.h" -#include +#include "containers/Set.h" #include +// Hash function for struct VerticesPair +// TOOD : REMOVE THIS +namespace std { + + template <> struct hash { + + size_t operator()(const reactphysics3d::bodyindexpair& pair) const { + + std::size_t seed = 0; + reactphysics3d::hash_combine(seed, pair.first); + reactphysics3d::hash_combine(seed, pair.second); + + return seed; + } + }; +} + /// ReactPhysics3D namespace namespace reactphysics3d { @@ -88,9 +105,8 @@ class CollisionDetection { // TODO : Delete this GJKAlgorithm mNarrowPhaseGJKAlgorithm; - // TODO : Maybe delete this set (what is the purpose ?) /// Set of pair of bodies that cannot collide between each other - std::set mNoCollisionPairs; + Set mNoCollisionPairs; /// True if some collision shapes have been added previously bool mIsCollisionShapesAdded; @@ -263,13 +279,13 @@ inline void CollisionDetection::addProxyCollisionShape(ProxyShape* proxyShape, // Add a pair of bodies that cannot collide with each other inline void CollisionDetection::addNoCollisionPair(CollisionBody* body1, CollisionBody* body2) { - mNoCollisionPairs.insert(OverlappingPair::computeBodiesIndexPair(body1, body2)); + mNoCollisionPairs.add(OverlappingPair::computeBodiesIndexPair(body1, body2)); } // Remove a pair of bodies that cannot collide with each other inline void CollisionDetection::removeNoCollisionPair(CollisionBody* body1, CollisionBody* body2) { - mNoCollisionPairs.erase(OverlappingPair::computeBodiesIndexPair(body1, body2)); + mNoCollisionPairs.remove(OverlappingPair::computeBodiesIndexPair(body1, body2)); } // Ask for a collision shape to be tested again during broad-phase. diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index b84c16dd..a24aa85b 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -33,7 +33,6 @@ #include "collision/TriangleMesh.h" #include "collision/PolyhedronMesh.h" #include "collision/narrowphase/GJK/GJKAlgorithm.h" -#include /// ReactPhysics3D namespace namespace reactphysics3d { diff --git a/src/containers/List.h b/src/containers/List.h index 93ec0830..49bd2d21 100644 --- a/src/containers/List.h +++ b/src/containers/List.h @@ -154,6 +154,9 @@ class List { return !(*this == iterator); } + /// Frienship + friend class List; + }; // -------------------- Methods -------------------- // @@ -227,8 +230,35 @@ class List { mSize++; } - /// Remove an element from the list at a given index - void remove(uint index) { + /// Try to find a given item of the list and return an iterator + /// pointing to that element if it exists in the list. Otherwise, + /// this method returns the end() iterator + Iterator find(const T& element) { + + for (uint i=0; i(mBuffer)[i]) { + return Iterator(mBuffer, i, mSize); + } + } + + return end(); + } + + /// Look for an element in the list and remove it + Iterator remove(const T& element) { + return remove(find(element)); + } + + /// Remove an element from the list and return a iterator + /// pointing to the element after the removed one (or end() if none) + Iterator remove(const Iterator& it) { + assert(it.mBuffer == mBuffer); + return removeAt(it.mCurrentIndex); + } + + /// Remove an element from the list at a given index and return an + /// iterator pointing to the element after the removed one (or end() if none) + Iterator removeAt(uint index) { assert(index >= 0 && index < mSize); @@ -244,6 +274,9 @@ class List { char* src = dest + sizeof(T); std::memcpy(static_cast(dest), static_cast(src), (mSize - index) * sizeof(T)); } + + // Return an iterator pointing to the element after the removed one + return Iterator(mBuffer, index, mSize); } /// Append another list at the end of the current one diff --git a/src/containers/Map.h b/src/containers/Map.h index da33448a..89594370 100644 --- a/src/containers/Map.h +++ b/src/containers/Map.h @@ -39,7 +39,8 @@ namespace reactphysics3d { // Class Map /** - * This class represents a simple generic associative map + * This class represents a simple generic associative map. This map is + * implemented with a hash table. */ template class Map { @@ -60,9 +61,9 @@ class Map { } /// Constructor - Entry(size_t hashcode, int nextValue) { + Entry(size_t hashcode, int nextEntry) { hashCode = hashcode; - next = nextValue; + next = nextEntry; keyValue = nullptr; } @@ -230,7 +231,7 @@ class Map { // If elements have been allocated if (mCapacity > 0) { - // Clear the list + // Clear the map clear(); // Destroy the entries @@ -320,7 +321,7 @@ class Map { reference operator*() const { assert(mCurrentEntry >= 0 && mCurrentEntry < mNbUsedEntries); assert(mEntries[mCurrentEntry].keyValue != nullptr); - return mEntries[mCurrentEntry].keyValue; + return *(mEntries[mCurrentEntry].keyValue); } /// Deferencable @@ -497,14 +498,18 @@ class Map { } /// Remove the element pointed by some iterator - bool remove(const Iterator& it) { + /// This method returns an iterator pointing to the element after + /// the one that has been removed + Iterator remove(const Iterator& it) { const K& key = it->first; return remove(key); } /// Remove the element from the map with a given key - bool remove(const K& key) { + /// This method returns an iterator pointing to the element after + /// the one that has been removed + Iterator remove(const K& key) { if (mCapacity > 0) { @@ -533,15 +538,27 @@ class Map { mFreeIndex = i; mNbFreeEntries++; - return true; + // Find the next entry to return the iterator + for (i += 1; i < mNbUsedEntries; i++) { + + // If the entry is not empty + if (mEntries[i].keyValue != nullptr) { + + // We have found the next non empty entry + return Iterator(mEntries, mCapacity, mNbUsedEntries, i); + } + } + + return end(); } } } - return false; + // Return the end iterator + return end(); } - /// Clear the list + /// Clear the map void clear() { if (mNbUsedEntries > 0) { diff --git a/src/containers/Pair.h b/src/containers/Pair.h new file mode 100644 index 00000000..e6a9ff8f --- /dev/null +++ b/src/containers/Pair.h @@ -0,0 +1,264 @@ +/******************************************************************************** +* 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_PAIR_H +#define REACTPHYSICS3D_PAIR_H + +// Libraries +#include "configuration.h" +#include "memory/MemoryAllocator.h" +#include +#include + +namespace reactphysics3d { + +// Class Pair +/** + * This class represents a simple generic pair + */ +template +class Pair { + + public: + + // -------------------- Attributes -------------------- // + + /// First element of the pair + T1 first; + + /// Second element of the pair + T2 second; + + // -------------------- Methods -------------------- // + + /// Constructor + List(MemoryAllocator& allocator, size_t capacity = 0) + : mBuffer(nullptr), mSize(0), mCapacity(0), mAllocator(allocator) { + + if (capacity > 0) { + + // Allocate memory + reserve(capacity); + } + } + + /// Copy constructor + List(const List& list) : mBuffer(nullptr), mSize(0), mCapacity(0), mAllocator(list.mAllocator) { + + // All all the elements of the list to the current one + addRange(list); + } + + /// Destructor + ~List() { + + // If elements have been allocated + if (mCapacity > 0) { + + // Clear the list + clear(); + + // Release the memory allocated on the heap + 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) { + reserve(mCapacity == 0 ? 1 : mCapacity * 2); + } + + // Use the copy-constructor to construct the element + new (static_cast(mBuffer) + mSize * sizeof(T)) T(element); + + mSize++; + } + + /// Try to find a given item of the list and return an iterator + /// pointing to that element if it exists in the list. Otherwise, + /// this method returns the end() iterator + Iterator find(const T& element) { + + for (uint i=0; i(mBuffer)[i])) { + return Iterator(mBuffer, i, mSize); + } + } + + return end(); + } + + /// Remove an element from the list + void remove(const Iterator& it) { + assert(it.mBuffer == mBuffer); + remove(it.mCurrentIndex); + } + + /// Remove an element from the list at a given index + void remove(uint index) { + + assert(index >= 0 && index < mSize); + + // Call the destructor + (static_cast(mBuffer)[index]).~T(); + + mSize--; + + if (index != mSize) { + + // Move the elements to fill in the empty slot + char* dest = static_cast(mBuffer) + index * sizeof(T); + char* src = dest + sizeof(T); + std::memcpy(static_cast(dest), static_cast(src), (mSize - index) * sizeof(T)); + } + } + + /// Append another list at the end of the current one + void addRange(const List& list) { + + // If we need to allocate more memory + if (mSize + list.size() > mCapacity) { + + // Allocate memory + reserve(mSize + list.size()); + } + + // Add the elements of the list to the current one + for(uint i=0; i(mBuffer) + mSize * sizeof(T)) T(list[i]); + mSize++; + } + } + + /// Clear the list + void clear() { + + // Call the destructor of each element + for (uint i=0; i < mSize; i++) { + (static_cast(mBuffer)[i]).~T(); + } + + mSize = 0; + } + + /// Return the number of elements in the list + 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 (static_cast(mBuffer)[index]); + } + + /// Overloaded const index operator + const T& operator[](const uint index) const { + assert(index >= 0 && index < mSize); + return (static_cast(mBuffer)[index]); + } + + /// Overloaded equality operator + bool operator==(const List& list) const { + + if (mSize != list.mSize) return false; + + T* items = static_cast(mBuffer); + for (int i=0; i < mSize; i++) { + if (items[i] != list[i]) { + return false; + } + } + + return true; + } + + /// Overloaded not equal operator + bool operator!=(const List& list) const { + + return !((*this) == list); + } + + /// Overloaded assignment operator + List& operator=(const List& list) { + + if (this != &list) { + + // Clear all the elements + clear(); + + // Add all the elements of the list to the current one + addRange(list); + } + + return *this; + } + + /// Return a begin iterator + Iterator begin() const { + return Iterator(mBuffer, 0, mSize); + } + + /// Return a end iterator + Iterator end() const { + return Iterator(mBuffer, mSize, mSize); + } +}; + +} + +#endif diff --git a/src/containers/Set.h b/src/containers/Set.h new file mode 100644 index 00000000..646507a1 --- /dev/null +++ b/src/containers/Set.h @@ -0,0 +1,712 @@ +/******************************************************************************** +* 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_SET_H +#define REACTPHYSICS3D_SET_H + +// Libraries +#include "memory/MemoryAllocator.h" +#include "mathematics/mathematics_functions.h" +#include +#include +#include +#include + + +namespace reactphysics3d { + +// Class Set +/** + * This class represents a simple generic set. This set is implemented + * with a hash table. + */ +template +class Set { + + private: + + /// An entry of the set + struct Entry { + + size_t hashCode; // Hash code of the entry + int next; // Index of the next entry + V* value; // Pointer to the value stored in the entry + + /// Constructor + Entry() { + next = -1; + value = nullptr; + } + + /// Constructor + Entry(size_t hashcode, int nextEntry) { + hashCode = hashcode; + next = nextEntry; + value = nullptr; + } + + /// Destructor + ~Entry() { + + assert(value == nullptr); + } + + }; + + // -------------------- Constants -------------------- // + + /// Number of prime numbers in array + static constexpr int NB_PRIMES = 70; + + /// Array of prime numbers for the size of the set + static const int PRIMES[NB_PRIMES]; + + /// Largest prime number + static int LARGEST_PRIME; + + // -------------------- Attributes -------------------- // + + /// Current number of used entries in the set + int mNbUsedEntries; + + /// Number of free entries among the used ones + int mNbFreeEntries; + + /// Current capacity of the set + int mCapacity; + + /// Array with all the buckets + int* mBuckets; + + /// Array with all the entries + Entry* mEntries; + + /// Memory allocator + MemoryAllocator& mAllocator; + + /// Index to the fist free entry + int mFreeIndex; + + // -------------------- Methods -------------------- // + + /// Initialize the set + void initialize(int capacity) { + + // Compute the next larger prime size + mCapacity = getPrimeSize(capacity); + + // Allocate memory for the buckets + mBuckets = static_cast(mAllocator.allocate(mCapacity * sizeof(int))); + + // Allocate memory for the entries + mEntries = static_cast(mAllocator.allocate(mCapacity * sizeof(Entry))); + + // Initialize the buckets and entries + for (int i=0; i mCapacity); + assert(isPrimeNumber(newCapacity)); + + // Allocate memory for the buckets + int* newBuckets = static_cast(mAllocator.allocate(newCapacity * sizeof(int))); + + // Allocate memory for the entries + Entry* newEntries = static_cast(mAllocator.allocate(newCapacity * sizeof(Entry))); + + // Initialize the new buckets + for (int i=0; i(&newEntries[i])) Entry(); + } + + // For each used entry + for (int i=0; i 0) { + + size_t hashCode = std::hash()(value); + int bucket = hashCode % mCapacity; + + for (int i = mBuckets[bucket]; i >= 0; i = mEntries[i].next) { + if (mEntries[i].hashCode == hashCode && (*mEntries[i].value) == value) { + return i; + } + } + } + + return -1; + } + + /// Return the prime number that is larger or equal to the number in parameter + /// for the size of the set + static int getPrimeSize(int number) { + + // Check if the next larger prime number is in the precomputed array of primes + for (int i = 0; i < NB_PRIMES; i++) { + if (PRIMES[i] >= number) return PRIMES[i]; + } + + // Manually compute the next larger prime number + for (int i = (number | 1); i < std::numeric_limits::max(); i+=2) { + + if (isPrimeNumber(i)) { + return i; + } + } + + return number; + } + + /// Clear and reset the set + void reset() { + + // If elements have been allocated + if (mCapacity > 0) { + + // Clear the list + clear(); + + // Destroy the entries + for (int i=0; i < mCapacity; i++) { + mEntries[i].~Entry(); + } + + mAllocator.release(mBuckets, mCapacity * sizeof(int)); + mAllocator.release(mEntries, mCapacity * sizeof(Entry)); + + mNbUsedEntries = 0; + mNbFreeEntries = 0; + mCapacity = 0; + mBuckets = nullptr; + mEntries = nullptr; + mFreeIndex = -1; + } + } + + public: + + /// Class Iterator + /** + * This class represents an iterator for the Set + */ + class Iterator { + + private: + + /// Array of entries + const Entry* mEntries; + + /// Capacity of the map + int mCapacity; + + /// Number of used entries in the map + int mNbUsedEntries; + + /// Index of the current entry + int mCurrentEntry; + + /// Advance the iterator + void advance() { + + // If we are trying to move past the end + assert(mCurrentEntry < mNbUsedEntries); + + for (mCurrentEntry += 1; mCurrentEntry < mNbUsedEntries; mCurrentEntry++) { + + // If the entry is not empty + if (mEntries[mCurrentEntry].value != nullptr) { + + // We have found the next non empty entry + return; + } + } + + // We have not find a non empty entry, we return an iterator to the end + mCurrentEntry = mCapacity; + } + + public: + + // Iterator traits + using value_type = V; + using difference_type = std::ptrdiff_t; + using pointer = V*; + using reference = V&; + using iterator_category = std::forward_iterator_tag; + + /// Constructor + Iterator() = default; + + /// Constructor + Iterator(const Entry* entries, int capacity, int nbUsedEntries, int currentEntry) + :mEntries(entries), mCapacity(capacity), mNbUsedEntries(nbUsedEntries), mCurrentEntry(currentEntry) { + + } + + /// Copy constructor + Iterator(const Iterator& it) + :mEntries(it.mEntries), mCapacity(it.mCapacity), mNbUsedEntries(it.mNbUsedEntries), mCurrentEntry(it.mCurrentEntry) { + + } + + /// Deferencable + reference operator*() const { + assert(mCurrentEntry >= 0 && mCurrentEntry < mNbUsedEntries); + assert(mEntries[mCurrentEntry].value != nullptr); + return *(mEntries[mCurrentEntry].value); + } + + /// Deferencable + pointer operator->() const { + assert(mCurrentEntry >= 0 && mCurrentEntry < mNbUsedEntries); + assert(mEntries[mCurrentEntry].value != nullptr); + return mEntries[mCurrentEntry].value; + } + + /// Post increment (it++) + Iterator& operator++() { + advance(); + return *this; + } + + /// Pre increment (++it) + Iterator operator++(int number) { + Iterator tmp = *this; + advance(); + return tmp; + } + + /// Equality operator (it == end()) + bool operator==(const Iterator& iterator) const { + return mCurrentEntry == iterator.mCurrentEntry && mEntries == iterator.mEntries; + } + + /// Inequality operator (it != end()) + bool operator!=(const Iterator& iterator) const { + return !(*this == iterator); + } + }; + + + // -------------------- Methods -------------------- // + + /// Constructor + Set(MemoryAllocator& allocator, size_t capacity = 0) + : mNbUsedEntries(0), mNbFreeEntries(0), mCapacity(0), mBuckets(nullptr), + mEntries(nullptr), mAllocator(allocator), mFreeIndex(-1) { + + // If the largest prime has not been computed yet + if (LARGEST_PRIME == -1) { + + // Compute the largest prime number (largest map capacity) + LARGEST_PRIME = getPrimeSize(PRIMES[NB_PRIMES - 1] + 2); + } + + if (capacity > 0) { + + initialize(capacity); + } + } + + /// Copy constructor + Set(const Set& set) + :mNbUsedEntries(set.mNbUsedEntries), mNbFreeEntries(set.mNbFreeEntries), mCapacity(set.mCapacity), + mAllocator(set.mAllocator), mFreeIndex(set.mFreeIndex) { + + // Allocate memory for the buckets + mBuckets = static_cast(mAllocator.allocate(mCapacity * sizeof(int))); + + // Allocate memory for the entries + mEntries = static_cast(mAllocator.allocate(mCapacity * sizeof(Entry))); + + // Copy the buckets + std::memcpy(mBuckets, set.mBuckets, mCapacity * sizeof(int)); + + // Copy the entries + for (int i=0; i < mCapacity; i++) { + + new (&mEntries[i]) Entry(set.mEntries[i].hashCode, set.mEntries[i].next); + + if (set.mEntries[i].value != nullptr) { + mEntries[i].value = static_cast(mAllocator.allocate(sizeof(V))); + new (mEntries[i].value) V(*(set.mEntries[i].value)); + } + } + } + + /// Destructor + ~Set() { + + reset(); + } + + /// Allocate memory for a given number of elements + void reserve(size_t capacity) { + + if (capacity <= mCapacity) return; + + if (capacity > LARGEST_PRIME && LARGEST_PRIME > mCapacity) { + capacity = LARGEST_PRIME; + } + else { + capacity = getPrimeSize(capacity); + } + + expand(capacity); + } + + /// Return true if the set contains a given value + bool contains(const V& value) const { + return findEntry(value) != -1; + } + + /// Add a value into the set + void add(const V& value) { + + if (mCapacity == 0) { + initialize(0); + } + + // Compute the hash code of the value + size_t hashCode = std::hash()(value); + + // Compute the corresponding bucket index + int bucket = hashCode % mCapacity; + + // Check if the item is already in the set + for (int i = mBuckets[bucket]; i >= 0; i = mEntries[i].next) { + + // If there is already an item with the same value in the set + if (mEntries[i].hashCode == hashCode && (*mEntries[i].value) == value) { + + return; + } + } + + size_t entryIndex; + + // If there are free entries to use + if (mNbFreeEntries > 0) { + assert(mFreeIndex >= 0); + entryIndex = mFreeIndex; + mFreeIndex = mEntries[entryIndex].next; + mNbFreeEntries--; + } + else { + + // If we need to allocator more entries + if (mNbUsedEntries == mCapacity) { + + // Allocate more memory + reserve(mCapacity * 2); + + // Recompute the bucket index + bucket = hashCode % mCapacity; + } + + entryIndex = mNbUsedEntries; + mNbUsedEntries++; + } + + assert(mEntries[entryIndex].value == nullptr); + mEntries[entryIndex].hashCode = hashCode; + mEntries[entryIndex].next = mBuckets[bucket]; + mEntries[entryIndex].value = static_cast(mAllocator.allocate(sizeof(V))); + assert(mEntries[entryIndex].value != nullptr); + new (mEntries[entryIndex].value) V(value); + mBuckets[bucket] = entryIndex; + } + + /// Remove the element pointed by some iterator + /// This method returns an iterator pointing to the + /// element after the one that has been removed + Iterator remove(const Iterator& it) { + + return remove(*it); + } + + /// Remove the element from the set with a given value + /// This method returns an iterator pointing to the + /// element after the one that has been removed + Iterator remove(const V& value) { + + if (mCapacity > 0) { + + size_t hashcode = std::hash()(value); + int bucket = hashcode % mCapacity; + int last = -1; + for (int i = mBuckets[bucket]; i >= 0; last = i, i = mEntries[i].next) { + + if (mEntries[i].hashCode == hashcode && (*mEntries[i].value) == value) { + + if (last < 0 ) { + mBuckets[bucket] = mEntries[i].next; + } + else { + mEntries[last].next = mEntries[i].next; + } + + // Release memory for the value if any + if (mEntries[i].value != nullptr) { + mEntries[i].value->~V(); + mAllocator.release(mEntries[i].value, sizeof(V)); + mEntries[i].value = nullptr; + } + mEntries[i].hashCode = -1; + mEntries[i].next = mFreeIndex; + mFreeIndex = i; + mNbFreeEntries++; + + // Find the next valid entry to return an iterator + for (i += 1; i < mNbUsedEntries; i++) { + + // If the entry is not empty + if (mEntries[i].value != nullptr) { + + // We have found the next non empty entry + return Iterator(mEntries, mCapacity, mNbUsedEntries, i); + } + } + + return end(); + } + } + } + + return end(); + } + + /// Clear the set + void clear() { + + if (mNbUsedEntries > 0) { + + for (int i=0; i < mCapacity; i++) { + mBuckets[i] = -1; + mEntries[i].next = -1; + if (mEntries[i].value != nullptr) { + mEntries[i].value->~V(); + mAllocator.release(mEntries[i].value, sizeof(V)); + mEntries[i].value = nullptr; + } + } + + mFreeIndex = -1; + mNbUsedEntries = 0; + mNbFreeEntries = 0; + } + + assert(size() == 0); + } + + /// Return the number of elements in the set + int size() const { + return mNbUsedEntries - mNbFreeEntries; + } + + /// Return the capacity of the set + int capacity() const { + return mCapacity; + } + + /// Try to find an item of the set given a key. + /// The method returns an iterator to the found item or + /// an iterator pointing to the end if not found + Iterator find(const V& value) const { + + int bucket; + int entry = -1; + + if (mCapacity > 0) { + + size_t hashCode = std::hash()(value); + bucket = hashCode % mCapacity; + + for (int i = mBuckets[bucket]; i >= 0; i = mEntries[i].next) { + if (mEntries[i].hashCode == hashCode && *(mEntries[i].value) == value) { + entry = i; + break; + } + } + } + + if (entry == -1) { + return end(); + } + + assert(mEntries[entry].value != nullptr); + + return Iterator(mEntries, mCapacity, mNbUsedEntries, entry); + } + + /// Overloaded equality operator + bool operator==(const Set& set) const { + + if (size() != set.size()) return false; + + for (auto it = begin(); it != end(); ++it) { + if(!set.contains(*it)) { + return false; + } + } + + return true; + } + + /// Overloaded not equal operator + bool operator!=(const Set& set) const { + + return !((*this) == set); + } + + /// Overloaded assignment operator + Set& operator=(const Set& set) { + + // Check for self assignment + if (this != &set) { + + // Reset the set + reset(); + + if (set.mCapacity > 0) { + + // Compute the next larger prime size + mCapacity = getPrimeSize(set.mCapacity); + + // Allocate memory for the buckets + mBuckets = static_cast(mAllocator.allocate(mCapacity * sizeof(int))); + + // Allocate memory for the entries + mEntries = static_cast(mAllocator.allocate(mCapacity * sizeof(Entry))); + + // Copy the buckets + std::memcpy(mBuckets, set.mBuckets, mCapacity * sizeof(int)); + + // Copy the entries + for (int i=0; i < mCapacity; i++) { + + new (&mEntries[i]) Entry(set.mEntries[i].hashCode, set.mEntries[i].next); + + if (set.mEntries[i].value != nullptr) { + mEntries[i].value = static_cast(mAllocator.allocate(sizeof(V))); + new (mEntries[i].value) V(*(set.mEntries[i].value)); + } + } + + mNbUsedEntries = set.mNbUsedEntries; + mNbFreeEntries = set.mNbFreeEntries; + mFreeIndex = set.mFreeIndex; + } + } + + return *this; + } + + /// Return a begin iterator + Iterator begin() const { + + // If the map is empty + if (size() == 0) { + + // Return an iterator to the end + return end(); + } + + // Find the first used entry + int entry; + for (entry=0; entry < mNbUsedEntries; entry++) { + if (mEntries[entry].value != nullptr) { + return Iterator(mEntries, mCapacity, mNbUsedEntries, entry); + } + } + + assert(false); + } + + /// Return a end iterator + Iterator end() const { + return Iterator(mEntries, mCapacity, mNbUsedEntries, mCapacity); + } +}; + +template +const int Set::PRIMES[NB_PRIMES] = {3, 7, 11, 17, 23, 29, 37, 47, 59, 71, 89, 107, 131, 163, 197, 239, 293, 353, 431, 521, 631, 761, 919, + 1103, 1327, 1597, 1931, 2333, 2801, 3371, 4049, 4861, 5839, 7013, 8419, 10103, 12143, 14591, + 17519, 21023, 25229, 30293, 36353, 43627, 52361, 62851, 75431, 90523, 108631, 130363, 156437, + 187751, 225307, 270371, 324449, 389357, 467237, 560689, 672827, 807403, 968897, 1162687, 1395263, + 1674319, 2009191, 2411033, 2893249, 3471899, 4166287, 4999559}; + +template +int Set::LARGEST_PRIME = -1; + +} + +#endif diff --git a/src/engine/CollisionWorld.cpp b/src/engine/CollisionWorld.cpp index 1a462c60..9388acda 100644 --- a/src/engine/CollisionWorld.cpp +++ b/src/engine/CollisionWorld.cpp @@ -33,7 +33,7 @@ using namespace std; // Constructor CollisionWorld::CollisionWorld() - : mCollisionDetection(this, mMemoryManager), mCurrentBodyID(0), + : mCollisionDetection(this, mMemoryManager), mBodies(mMemoryManager.getPoolAllocator()), mCurrentBodyID(0), mFreeBodiesIDs(mMemoryManager.getPoolAllocator()), mEventListener(nullptr) { #ifdef IS_PROFILING_ACTIVE @@ -49,14 +49,11 @@ CollisionWorld::CollisionWorld() CollisionWorld::~CollisionWorld() { // Destroy all the collision bodies that have not been removed - std::set::iterator itBodies; - for (itBodies = mBodies.begin(); itBodies != mBodies.end(); ) { - std::set::iterator itToRemove = itBodies; - ++itBodies; - destroyCollisionBody(*itToRemove); + for (int i=mBodies.size() - 1 ; i >= 0; i--) { + destroyCollisionBody(mBodies[i]); } - assert(mBodies.empty()); + assert(mBodies.size() == 0); } // Create a collision body and add it to the world @@ -80,7 +77,7 @@ CollisionBody* CollisionWorld::createCollisionBody(const Transform& transform) { assert(collisionBody != nullptr); // Add the collision body to the world - mBodies.insert(collisionBody); + mBodies.add(collisionBody); #ifdef IS_PROFILING_ACTIVE @@ -108,7 +105,7 @@ void CollisionWorld::destroyCollisionBody(CollisionBody* collisionBody) { collisionBody->~CollisionBody(); // Remove the collision body from the list of bodies - mBodies.erase(collisionBody); + mBodies.remove(collisionBody); // Free the object from the memory allocator mMemoryManager.release(MemoryManager::AllocationType::Pool, collisionBody, sizeof(CollisionBody)); @@ -121,7 +118,7 @@ bodyindex CollisionWorld::computeNextAvailableBodyID() { bodyindex bodyID; if (mFreeBodiesIDs.size() != 0) { bodyID = mFreeBodiesIDs[mFreeBodiesIDs.size() - 1]; - mFreeBodiesIDs.remove(mFreeBodiesIDs.size() - 1); + mFreeBodiesIDs.removeAt(mFreeBodiesIDs.size() - 1); } else { bodyID = mCurrentBodyID; @@ -135,7 +132,7 @@ bodyindex CollisionWorld::computeNextAvailableBodyID() { void CollisionWorld::resetContactManifoldListsOfBodies() { // For each rigid body of the world - for (std::set::iterator it = mBodies.begin(); it != mBodies.end(); ++it) { + for (List::Iterator it = mBodies.begin(); it != mBodies.end(); ++it) { // Reset the contact manifold list of the body (*it)->resetContactManifoldsList(); diff --git a/src/engine/CollisionWorld.h b/src/engine/CollisionWorld.h index bdffe4d1..1cc501e2 100644 --- a/src/engine/CollisionWorld.h +++ b/src/engine/CollisionWorld.h @@ -27,8 +27,6 @@ #define REACTPHYSICS3D_COLLISION_WORLD_H // Libraries -#include -#include #include #include "mathematics/mathematics.h" #include "containers/List.h" @@ -68,7 +66,7 @@ class CollisionWorld { CollisionDetection mCollisionDetection; /// All the bodies (rigid and soft) of the world - std::set mBodies; + List mBodies; /// Current body ID bodyindex mCurrentBodyID; @@ -109,12 +107,6 @@ class CollisionWorld { /// Deleted assignment operator CollisionWorld& operator=(const CollisionWorld& world) = delete; - /// Return an iterator to the beginning of the bodies of the physics world - std::set::iterator getBodiesBeginIterator(); - - /// Return an iterator to the end of the bodies of the physics world - std::set::iterator getBodiesEndIterator(); - /// Create a collision body CollisionBody* createCollisionBody(const Transform& transform); @@ -167,22 +159,6 @@ class CollisionWorld { friend class ConvexMeshShape; }; -// Return an iterator to the beginning of the bodies of the physics world -/** - * @return An starting iterator to the set of bodies of the world - */ -inline std::set::iterator CollisionWorld::getBodiesBeginIterator() { - return mBodies.begin(); -} - -// Return an iterator to the end of the bodies of the physics world -/** - * @return An ending iterator to the set of bodies of the world - */ -inline std::set::iterator CollisionWorld::getBodiesEndIterator() { - return mBodies.end(); -} - // Set the collision dispatch configuration /// This can be used to replace default collision detection algorithms by your /// custom algorithm for instance. diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index 3ef9cd30..77938f9e 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -44,7 +44,8 @@ DynamicsWorld::DynamicsWorld(const Vector3 &gravity) mContactSolver(mMemoryManager), mNbVelocitySolverIterations(DEFAULT_VELOCITY_SOLVER_NB_ITERATIONS), mNbPositionSolverIterations(DEFAULT_POSITION_SOLVER_NB_ITERATIONS), - mIsSleepingEnabled(SLEEPING_ENABLED), mGravity(gravity), mTimeStep(decimal(1.0f / 60.0f)), + mIsSleepingEnabled(SLEEPING_ENABLED), mRigidBodies(mMemoryManager.getPoolAllocator()), + mJoints(mMemoryManager.getPoolAllocator()), mGravity(gravity), mTimeStep(decimal(1.0f / 60.0f)), mIsGravityEnabled(true), mConstrainedLinearVelocities(nullptr), mConstrainedAngularVelocities(nullptr), mSplitLinearVelocities(nullptr), mSplitAngularVelocities(nullptr), mConstrainedPositions(nullptr), @@ -67,19 +68,13 @@ DynamicsWorld::DynamicsWorld(const Vector3 &gravity) DynamicsWorld::~DynamicsWorld() { // Destroy all the joints that have not been removed - std::set::iterator itJoints; - for (itJoints = mJoints.begin(); itJoints != mJoints.end();) { - std::set::iterator itToRemove = itJoints; - ++itJoints; - destroyJoint(*itToRemove); + for (int i=mJoints.size() - 1; i >= 0; i--) { + destroyJoint(mJoints[i]); } // Destroy all the rigid bodies that have not been removed - std::set::iterator itRigidBodies; - for (itRigidBodies = mRigidBodies.begin(); itRigidBodies != mRigidBodies.end();) { - std::set::iterator itToRemove = itRigidBodies; - ++itRigidBodies; - destroyRigidBody(*itToRemove); + for (int i=mRigidBodies.size() - 1; i >= 0; i--) { + destroyRigidBody(mRigidBodies[i]); } assert(mJoints.size() == 0); @@ -257,7 +252,7 @@ void DynamicsWorld::initVelocityArrays() { // Initialize the map of body indexes in the velocity arrays uint i = 0; - for (std::set::iterator it = mRigidBodies.begin(); it != mRigidBodies.end(); ++it) { + for (List::Iterator it = mRigidBodies.begin(); it != mRigidBodies.end(); ++it) { mSplitLinearVelocities[i].setToZero(); mSplitAngularVelocities[i].setToZero(); @@ -388,7 +383,7 @@ void DynamicsWorld::solvePositionCorrection() { PROFILE("DynamicsWorld::solvePositionCorrection()", &mProfiler); // Do not continue if there is no constraints - if (mJoints.empty()) return; + if (mJoints.size() == 0) return; // For each island of the world for (uint islandIndex = 0; islandIndex < mNbIslands; islandIndex++) { @@ -423,8 +418,8 @@ RigidBody* DynamicsWorld::createRigidBody(const Transform& transform) { assert(rigidBody != nullptr); // Add the rigid body to the physics world - mBodies.insert(rigidBody); - mRigidBodies.insert(rigidBody); + mBodies.add(rigidBody); + mRigidBodies.add(rigidBody); #ifdef IS_PROFILING_ACTIVE @@ -461,8 +456,8 @@ void DynamicsWorld::destroyRigidBody(RigidBody* rigidBody) { rigidBody->~RigidBody(); // Remove the rigid body from the list of rigid bodies - mBodies.erase(rigidBody); - mRigidBodies.erase(rigidBody); + mBodies.remove(rigidBody); + mRigidBodies.remove(rigidBody); // Free the object from the memory allocator mMemoryManager.release(MemoryManager::AllocationType::Pool, rigidBody, sizeof(RigidBody)); @@ -536,7 +531,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { } // Add the joint into the world - mJoints.insert(newJoint); + mJoints.add(newJoint); // Add the joint into the joint list of the bodies involved in the joint addJointToBody(newJoint); @@ -565,7 +560,7 @@ void DynamicsWorld::destroyJoint(Joint* joint) { joint->getBody2()->setIsSleeping(false); // Remove the joint from the world - mJoints.erase(joint); + mJoints.remove(joint); // Remove the joint from the joint list of the bodies involved in the joint joint->mBody1->removeJointFromJointsList(mMemoryManager, joint); @@ -622,11 +617,11 @@ void DynamicsWorld::computeIslands() { int nbContactManifolds = 0; // Reset all the isAlreadyInIsland variables of bodies, joints and contact manifolds - for (std::set::iterator it = mRigidBodies.begin(); it != mRigidBodies.end(); ++it) { + for (List::Iterator it = mRigidBodies.begin(); it != mRigidBodies.end(); ++it) { int nbBodyManifolds = (*it)->resetIsAlreadyInIslandAndCountManifolds(); nbContactManifolds += nbBodyManifolds; } - for (std::set::iterator it = mJoints.begin(); it != mJoints.end(); ++it) { + for (List::Iterator it = mJoints.begin(); it != mJoints.end(); ++it) { (*it)->mIsAlreadyInIsland = false; } @@ -636,7 +631,7 @@ void DynamicsWorld::computeIslands() { nbBytesStack)); // For each rigid body of the world - for (std::set::iterator it = mRigidBodies.begin(); it != mRigidBodies.end(); ++it) { + for (List::Iterator it = mRigidBodies.begin(); it != mRigidBodies.end(); ++it) { RigidBody* body = *it; @@ -818,7 +813,7 @@ void DynamicsWorld::enableSleeping(bool isSleepingEnabled) { if (!mIsSleepingEnabled) { // For each body of the world - std::set::iterator it; + List::Iterator it; for (it = mRigidBodies.begin(); it != mRigidBodies.end(); ++it) { // Wake up the rigid body diff --git a/src/engine/DynamicsWorld.h b/src/engine/DynamicsWorld.h index 705f63d5..af2fb659 100644 --- a/src/engine/DynamicsWorld.h +++ b/src/engine/DynamicsWorld.h @@ -66,10 +66,10 @@ class DynamicsWorld : public CollisionWorld { bool mIsSleepingEnabled; /// All the rigid bodies of the physics world - std::set mRigidBodies; + List mRigidBodies; /// All the joints of the world - std::set mJoints; + List mJoints; /// Gravity vector of the world Vector3 mGravity; @@ -215,12 +215,6 @@ class DynamicsWorld : public CollisionWorld { /// Return the number of joints in the world uint getNbJoints() const; - /// Return an iterator to the beginning of the rigid bodies of the physics world - std::set::iterator getRigidBodiesBeginIterator(); - - /// Return an iterator to the end of the rigid bodies of the physics world - std::set::iterator getRigidBodiesEndIterator(); - /// Return true if the sleeping technique is enabled bool isSleepingEnabled() const; @@ -260,7 +254,7 @@ class DynamicsWorld : public CollisionWorld { inline void DynamicsWorld::resetBodiesForceAndTorque() { // For each body of the world - std::set::iterator it; + List::Iterator it; for (it = mRigidBodies.begin(); it != mRigidBodies.end(); ++it) { (*it)->mExternalForce.setToZero(); (*it)->mExternalTorque.setToZero(); @@ -370,22 +364,6 @@ inline uint DynamicsWorld::getNbJoints() const { return mJoints.size(); } -// Return an iterator to the beginning of the bodies of the physics world -/** - * @return Starting iterator of the set of rigid bodies - */ -inline std::set::iterator DynamicsWorld::getRigidBodiesBeginIterator() { - return mRigidBodies.begin(); -} - -// Return an iterator to the end of the bodies of the physics world -/** - * @return Ending iterator of the set of rigid bodies - */ -inline std::set::iterator DynamicsWorld::getRigidBodiesEndIterator() { - return mRigidBodies.end(); -} - // Return true if the sleeping technique is enabled /** * @return True if the sleeping technique is enabled and false otherwise diff --git a/src/engine/OverlappingPair.cpp b/src/engine/OverlappingPair.cpp index a5ca870a..3dbdc2f4 100644 --- a/src/engine/OverlappingPair.cpp +++ b/src/engine/OverlappingPair.cpp @@ -187,7 +187,7 @@ void OverlappingPair::clearObsoleteLastFrameCollisionInfos() { it->second->~LastFrameCollisionInfo(); mPersistentAllocator.release(it->second, sizeof(LastFrameCollisionInfo)); - mLastFrameCollisionInfos.remove(it++); + it = mLastFrameCollisionInfos.remove(it); } else { ++it; diff --git a/test/main.cpp b/test/main.cpp index 8bb62ea4..24b9f003 100644 --- a/test/main.cpp +++ b/test/main.cpp @@ -41,6 +41,7 @@ #include "tests/collision/TestTriangleVertexArray.h" #include "tests/containers/TestList.h" #include "tests/containers/TestMap.h" +#include "tests/containers/TestSet.h" using namespace reactphysics3d; @@ -52,6 +53,7 @@ int main() { testSuite.addTest(new TestList("List")); testSuite.addTest(new TestMap("Map")); + testSuite.addTest(new TestSet("Set")); // ---------- Mathematics tests ---------- // diff --git a/test/tests/containers/TestList.h b/test/tests/containers/TestList.h index 669b0bef..750d0788 100644 --- a/test/tests/containers/TestList.h +++ b/test/tests/containers/TestList.h @@ -62,6 +62,7 @@ class TestList : public Test { testAddRemoveClear(); testAssignment(); testIndexing(); + testFind(); testEquality(); testReserve(); testIterators(); @@ -142,27 +143,52 @@ class TestList : public Test { list3.add(3); list3.add(4); - list3.remove(3); + auto it = list3.removeAt(3); test(list3.size() == 3); test(list3.capacity() == 4); + test(it == list3.end()); test(list3[0] = 1); test(list3[1] = 2); test(list3[2] = 3); - list3.remove(1); + it = list3.removeAt(1); test(list3.size() == 2); test(list3.capacity() == 4); test(list3[0] = 1); test(list3[1] = 3); + test(*it = 3); - list3.remove(0); + list3.removeAt(0); test(list3.size() == 1); test(list3.capacity() == 4); test(list3[0] = 3); - list3.remove(0); + it = list3.removeAt(0); test(list3.size() == 0); test(list3.capacity() == 4); + test(it == list3.end()); + + list3.add(1); + list3.add(2); + list3.add(3); + it = list3.begin(); + list3.remove(it); + test(list3.size() == 2); + test(list3[0] == 2); + test(list3[1] == 3); + it = list3.find(3); + list3.remove(it); + test(list3.size() == 1); + test(list3[0] == 2); + + list3.add(5); + list3.add(6); + list3.add(7); + it = list3.remove(7); + test(it == list3.end()); + test(list3.size() == 3); + it = list3.remove(5); + test((*it) == 6); // ----- Test addRange() ----- // @@ -270,6 +296,20 @@ class TestList : public Test { test(list1[1] == 8); } + void testFind() { + + List list1(mAllocator); + list1.add(1); + list1.add(2); + list1.add(3); + list1.add(4); + list1.add(5); + + test(list1.find(1) == list1.begin()); + test(*(list1.find(2)) == 2); + test(*(list1.find(5)) == 5); + } + void testEquality() { List list1(mAllocator); diff --git a/test/tests/containers/TestMap.h b/test/tests/containers/TestMap.h index 503b0c24..2e9b3133 100644 --- a/test/tests/containers/TestMap.h +++ b/test/tests/containers/TestMap.h @@ -195,9 +195,10 @@ class TestMap : public Test { test(!map1.containsKey(8)); test(map1.size() == 1); - map1.remove(56); + auto it = map1.remove(56); test(!map1.containsKey(56)); test(map1.size() == 0); + test(it == map1.end()); isValid = true; for (int i = 0; i < 1000000; i++) { @@ -219,12 +220,19 @@ class TestMap : public Test { map3.add(std::make_pair(2, 20)); map3.add(std::make_pair(3, 30)); test(map3.size() == 3); - auto it = map3.begin(); + it = map3.begin(); map3.remove(it++); test(!map3.containsKey(1)); test(map3.size() == 2); test(it->second == 20); + map3.add(std::make_pair(56, 32)); + map3.add(std::make_pair(23, 89)); + for (it = map3.begin(); it != map3.end();) { + it = map3.remove(it); + } + test(map3.size() == 0); + // ----- Test clear() ----- // Map map4(mAllocator); @@ -367,6 +375,7 @@ class TestMap : public Test { Map map2(mAllocator); map2 = map1; test(map2.size() == map1.size()); + test(map1 == map2); test(map2[1] == 3); test(map2[2] == 6); test(map2[10] == 30); @@ -374,6 +383,7 @@ class TestMap : public Test { Map map3(mAllocator, 100); map3 = map1; test(map3.size() == map1.size()); + test(map3 == map1); test(map3[1] == 3); test(map3[2] == 6); test(map3[10] == 30); @@ -381,12 +391,14 @@ class TestMap : public Test { Map map4(mAllocator); map3 = map4; test(map3.size() == 0); + test(map3 == map4); Map map5(mAllocator); map5.add(std::make_pair(7, 8)); map5.add(std::make_pair(19, 70)); map1 = map5; test(map5.size() == map1.size()); + test(map5 == map1); test(map1[7] == 8); test(map1[19] == 70); } diff --git a/test/tests/containers/TestSet.h b/test/tests/containers/TestSet.h new file mode 100644 index 00000000..ddf2c245 --- /dev/null +++ b/test/tests/containers/TestSet.h @@ -0,0 +1,417 @@ +/******************************************************************************** +* 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 TEST_SET_H +#define TEST_SET_H + +// Libraries +#include "Test.h" +#include "containers/Set.h" +#include "memory/DefaultAllocator.h" + +// Key to test map with always same hash values +namespace reactphysics3d { + struct TestValueSet { + int key; + + TestValueSet(int k) :key(k) {} + + bool operator==(const TestValueSet& testValue) const { + return key == testValue.key; + } + }; +} + +// Hash function for struct VerticesPair +namespace std { + + template <> struct hash { + + size_t operator()(const reactphysics3d::TestValueSet& value) const { + return 1; + } + }; +} + +/// Reactphysics3D namespace +namespace reactphysics3d { + +// Class TestSet +/** + * Unit test for the Set class + */ +class TestSet : public Test { + + private : + + // ---------- Atributes ---------- // + + DefaultAllocator mAllocator; + + public : + + // ---------- Methods ---------- // + + /// Constructor + TestSet(const std::string& name) : Test(name) { + + } + + /// Run the tests + void run() { + + testConstructors(); + testReserve(); + testAddRemoveClear(); + testContains(); + testFind(); + testEquality(); + testAssignment(); + testIterators(); + } + + void testConstructors() { + + // ----- Constructors ----- // + + Set set1(mAllocator); + test(set1.capacity() == 0); + test(set1.size() == 0); + + Set set2(mAllocator, 100); + test(set2.capacity() >= 100); + test(set2.size() == 0); + + // ----- Copy Constructors ----- // + Set set3(set1); + test(set3.capacity() == set1.capacity()); + test(set3.size() == set1.size()); + + Set set4(mAllocator); + set4.add(10); + set4.add(20); + set4.add(30); + test(set4.capacity() >= 3); + test(set4.size() == 3); + set4.add(30); + test(set4.size() == 3); + + Set set5(set4); + test(set5.capacity() == set4.capacity()); + test(set5.size() == set4.size()); + test(set5.contains(10)); + test(set5.contains(20)); + test(set5.contains(30)); + } + + void testReserve() { + + Set set1(mAllocator); + set1.reserve(15); + test(set1.capacity() >= 15); + set1.add("test1"); + set1.add("test2"); + test(set1.capacity() >= 15); + + set1.reserve(10); + test(set1.capacity() >= 15); + + set1.reserve(100); + test(set1.capacity() >= 100); + test(set1.contains("test1")); + test(set1.contains("test2")); + } + + void testAddRemoveClear() { + + // ----- Test add() ----- // + + Set set1(mAllocator); + set1.add(10); + set1.add(80); + set1.add(130); + test(set1.contains(10)); + test(set1.contains(80)); + test(set1.contains(130)); + test(set1.size() == 3); + + Set set2(mAllocator, 15); + for (int i = 0; i < 1000000; i++) { + set2.add(i); + } + bool isValid = true; + for (int i = 0; i < 1000000; i++) { + if (!set2.contains(i)) isValid = false; + } + test(isValid); + + set1.remove(10); + set1.add(10); + test(set1.size() == 3); + test(set1.contains(10)); + + set1.add(34); + test(set1.contains(34)); + test(set1.size() == 4); + + // ----- Test remove() ----- // + + set1.remove(10); + test(!set1.contains(10)); + test(set1.contains(80)); + test(set1.contains(130)); + test(set1.contains(34)); + test(set1.size() == 3); + + set1.remove(80); + test(!set1.contains(80)); + test(set1.contains(130)); + test(set1.contains(34)); + test(set1.size() == 2); + + set1.remove(130); + test(!set1.contains(130)); + test(set1.contains(34)); + test(set1.size() == 1); + + set1.remove(34); + test(!set1.contains(34)); + test(set1.size() == 0); + + isValid = true; + for (int i = 0; i < 1000000; i++) { + set2.remove(i); + } + for (int i = 0; i < 1000000; i++) { + if (set2.contains(i)) isValid = false; + } + test(isValid); + test(set2.size() == 0); + + Set set3(mAllocator); + for (int i=0; i < 1000000; i++) { + set3.add(i); + set3.remove(i); + } + + set3.add(1); + set3.add(2); + set3.add(3); + test(set3.size() == 3); + auto it = set3.begin(); + set3.remove(it++); + test(!set3.contains(1)); + test(set3.size() == 2); + test(*it == 2); + + set3.add(6); + set3.add(7); + set3.add(8); + for (it = set3.begin(); it != set3.end();) { + it = set3.remove(it); + } + test(set3.size() == 0); + + // ----- Test clear() ----- // + + Set set4(mAllocator); + set4.add(2); + set4.add(4); + set4.add(6); + set4.clear(); + test(set4.size() == 0); + set4.add(2); + test(set4.size() == 1); + test(set4.contains(2)); + set4.clear(); + test(set4.size() == 0); + + Set set5(mAllocator); + set5.clear(); + test(set5.size() == 0); + + // ----- Test map with always same hash value for keys ----- // + + Set set6(mAllocator); + for (int i=0; i < 1000; i++) { + set6.add(TestValueSet(i)); + } + bool isTestValid = true; + for (int i=0; i < 1000; i++) { + if (!set6.contains(TestValueSet(i))) { + isTestValid = false; + } + } + test(isTestValid); + for (int i=0; i < 1000; i++) { + set6.remove(TestValueSet(i)); + } + test(set6.size() == 0); + } + + void testContains() { + + Set set1(mAllocator); + + test(!set1.contains(2)); + test(!set1.contains(4)); + test(!set1.contains(6)); + + set1.add(2); + set1.add(4); + set1.add(6); + + test(set1.contains(2)); + test(set1.contains(4)); + test(set1.contains(6)); + + set1.remove(4); + test(!set1.contains(4)); + test(set1.contains(2)); + test(set1.contains(6)); + + set1.clear(); + test(!set1.contains(2)); + test(!set1.contains(6)); + } + + void testFind() { + + Set set1(mAllocator); + set1.add(2); + set1.add(4); + set1.add(6); + test(set1.find(2) != set1.end()); + test(set1.find(4) != set1.end()); + test(set1.find(6) != set1.end()); + test(set1.find(45) == set1.end()); + + set1.remove(2); + + test(set1.find(2) == set1.end()); + } + + void testEquality() { + + Set set1(mAllocator, 10); + Set set2(mAllocator, 2); + + test(set1 == set2); + + set1.add("a"); + set1.add("b"); + set1.add("c"); + + set2.add("a"); + set2.add("b"); + set2.add("h"); + + test(set1 == set1); + test(set2 == set2); + test(set1 != set2); + test(set2 != set1); + + set1.add("a"); + set2.remove("h"); + set2.add("c"); + + test(set1 == set2); + test(set2 == set1); + + Set set3(mAllocator); + set3.add("a"); + + test(set1 != set3); + test(set2 != set3); + test(set3 != set1); + test(set3 != set2); + } + + void testAssignment() { + + Set set1(mAllocator); + set1.add(1); + set1.add(2); + set1.add(10); + + Set set2(mAllocator); + set2 = set1; + test(set2.size() == set1.size()); + test(set2.contains(1)); + test(set2.contains(2)); + test(set2.contains(10)); + test(set1 == set2); + + Set set3(mAllocator, 100); + set3 = set1; + test(set3.size() == set1.size()); + test(set3 == set1); + test(set3.contains(1)); + test(set3.contains(2)); + test(set3.contains(10)); + + Set set4(mAllocator); + set3 = set4; + test(set3.size() == 0); + test(set3 == set4); + + Set set5(mAllocator); + set5.add(7); + set5.add(19); + set1 = set5; + test(set5.size() == set1.size()); + test(set1 == set5); + test(set1.contains(7)); + test(set1.contains(19)); + } + + void testIterators() { + + Set set1(mAllocator); + + test(set1.begin() == set1.end()); + + set1.add(1); + set1.add(2); + set1.add(3); + set1.add(4); + + Set::Iterator itBegin = set1.begin(); + Set::Iterator it = set1.begin(); + + test(itBegin == it); + + int size = 0; + for (auto it = set1.begin(); it != set1.end(); ++it) { + test(set1.contains(*it)); + size++; + } + test(set1.size() == size); + } + }; + +} + +#endif From e0fda1844626c4599d47e556bd8a6a3352f4d246 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 4 Feb 2018 19:43:17 +0100 Subject: [PATCH 165/248] Replace malloc/free calls by use of the MemoryManager of ReactPhysics3D --- src/collision/CollisionDetection.h | 8 +++ .../broadphase/BroadPhaseAlgorithm.cpp | 50 +++++++++++++------ src/collision/broadphase/DynamicAABBTree.cpp | 20 ++++---- src/collision/broadphase/DynamicAABBTree.h | 6 ++- src/collision/shapes/ConcaveMeshShape.cpp | 3 +- src/containers/Stack.h | 14 ++++-- test/tests/collision/TestDynamicAABBTree.h | 7 +-- 7 files changed, 76 insertions(+), 32 deletions(-) diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index 36bede7e..f06d52f0 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -228,6 +228,9 @@ class CollisionDetection { /// Allow the broadphase to notify the collision detection about an overlapping pair. void broadPhaseNotifyOverlappingPair(ProxyShape* shape1, ProxyShape* shape2); + /// Return a reference to the memory manager + MemoryManager& getMemoryManager() const; + /// Return a pointer to the world CollisionWorld* getWorld(); @@ -342,6 +345,11 @@ inline CollisionWorld* CollisionDetection::getWorld() { return mWorld; } +// Return a reference to the memory manager +inline MemoryManager& CollisionDetection::getMemoryManager() const { + return mMemoryManager; +} + #ifdef IS_PROFILING_ACTIVE // Set the profiler diff --git a/src/collision/broadphase/BroadPhaseAlgorithm.cpp b/src/collision/broadphase/BroadPhaseAlgorithm.cpp index 8998859e..5f76e2c2 100644 --- a/src/collision/broadphase/BroadPhaseAlgorithm.cpp +++ b/src/collision/broadphase/BroadPhaseAlgorithm.cpp @@ -33,16 +33,19 @@ using namespace reactphysics3d; // Constructor BroadPhaseAlgorithm::BroadPhaseAlgorithm(CollisionDetection& collisionDetection) - :mDynamicAABBTree(DYNAMIC_TREE_AABB_GAP), mNbMovedShapes(0), mNbAllocatedMovedShapes(8), + :mDynamicAABBTree(collisionDetection.getMemoryManager().getPoolAllocator(), DYNAMIC_TREE_AABB_GAP), + mNbMovedShapes(0), mNbAllocatedMovedShapes(8), mNbNonUsedMovedShapes(0), mNbPotentialPairs(0), mNbAllocatedPotentialPairs(8), mCollisionDetection(collisionDetection) { + PoolAllocator& poolAllocator = collisionDetection.getMemoryManager().getPoolAllocator(); + // Allocate memory for the array of non-static proxy shapes IDs - mMovedShapes = (int*) malloc(mNbAllocatedMovedShapes * sizeof(int)); + mMovedShapes = static_cast(poolAllocator.allocate(mNbAllocatedMovedShapes * sizeof(int))); assert(mMovedShapes != nullptr); // Allocate memory for the array of potential overlapping pairs - mPotentialPairs = (BroadPhasePair*) malloc(mNbAllocatedPotentialPairs * sizeof(BroadPhasePair)); + mPotentialPairs = static_cast(poolAllocator.allocate(mNbAllocatedPotentialPairs * sizeof(BroadPhasePair))); assert(mPotentialPairs != nullptr); #ifdef IS_PROFILING_ACTIVE @@ -56,25 +59,34 @@ BroadPhaseAlgorithm::BroadPhaseAlgorithm(CollisionDetection& collisionDetection) // Destructor BroadPhaseAlgorithm::~BroadPhaseAlgorithm() { + // Get the memory pool allocatory + PoolAllocator& poolAllocator = mCollisionDetection.getMemoryManager().getPoolAllocator(); + // Release the memory for the array of non-static proxy shapes IDs - free(mMovedShapes); + poolAllocator.release(mMovedShapes, mNbAllocatedMovedShapes * sizeof (int)); // Release the memory for the array of potential overlapping pairs - free(mPotentialPairs); + poolAllocator.release(mPotentialPairs, mNbAllocatedPotentialPairs * sizeof(BroadPhasePair)); } // Add a collision shape in the array of shapes that have moved in the last simulation step // and that need to be tested again for broad-phase overlapping. void BroadPhaseAlgorithm::addMovedCollisionShape(int broadPhaseID) { + // Allocate more elements in the array of shapes that have moved if necessary if (mNbAllocatedMovedShapes == mNbMovedShapes) { + + // Get the memory pool allocatory + PoolAllocator& poolAllocator = mCollisionDetection.getMemoryManager().getPoolAllocator(); + + uint oldNbAllocatedMovedShapes = mNbAllocatedMovedShapes; mNbAllocatedMovedShapes *= 2; int* oldArray = mMovedShapes; - mMovedShapes = (int*) malloc(mNbAllocatedMovedShapes * sizeof(int)); + mMovedShapes = static_cast(poolAllocator.allocate(mNbAllocatedMovedShapes * sizeof(int))); assert(mMovedShapes != nullptr); - memcpy(mMovedShapes, oldArray, mNbMovedShapes * sizeof(int)); - free(oldArray); + std::memcpy(mMovedShapes, oldArray, mNbMovedShapes * sizeof(int)); + poolAllocator.release(oldArray, oldNbAllocatedMovedShapes * sizeof(int)); } // Store the broad-phase ID into the array of shapes that have moved @@ -95,9 +107,13 @@ void BroadPhaseAlgorithm::removeMovedCollisionShape(int broadPhaseID) { if ((mNbMovedShapes - mNbNonUsedMovedShapes) < mNbAllocatedMovedShapes / 4 && mNbAllocatedMovedShapes > 8) { + // Get the memory pool allocatory + PoolAllocator& poolAllocator = mCollisionDetection.getMemoryManager().getPoolAllocator(); + + uint oldNbAllocatedMovedShapes = mNbAllocatedMovedShapes; mNbAllocatedMovedShapes /= 2; int* oldArray = mMovedShapes; - mMovedShapes = (int*) malloc(mNbAllocatedMovedShapes * sizeof(int)); + mMovedShapes = static_cast(poolAllocator.allocate(mNbAllocatedMovedShapes * sizeof(int))); assert(mMovedShapes != nullptr); uint nbElements = 0; for (uint i=0; i 8) { + PoolAllocator& poolAllocator = mCollisionDetection.getMemoryManager().getPoolAllocator(); + // Reduce the number of allocated potential overlapping pairs BroadPhasePair* oldPairs = mPotentialPairs; + uint oldNbAllocatedPotentialPairs = mNbAllocatedPotentialPairs; mNbAllocatedPotentialPairs /= 2; - mPotentialPairs = (BroadPhasePair*) malloc(mNbAllocatedPotentialPairs * sizeof(BroadPhasePair)); + mPotentialPairs = static_cast(poolAllocator.allocate(mNbAllocatedPotentialPairs * sizeof(BroadPhasePair))); assert(mPotentialPairs); memcpy(mPotentialPairs, oldPairs, mNbPotentialPairs * sizeof(BroadPhasePair)); - free(oldPairs); + poolAllocator.release(oldPairs, oldNbAllocatedPotentialPairs * sizeof(BroadPhasePair)); } } @@ -289,13 +308,16 @@ void BroadPhaseAlgorithm::addOverlappingNodes(int referenceNodeId, const LinkedL // If we need to allocate more memory for the array of potential overlapping pairs if (mNbPotentialPairs == mNbAllocatedPotentialPairs) { + PoolAllocator& poolAllocator = mCollisionDetection.getMemoryManager().getPoolAllocator(); + // Allocate more memory for the array of potential pairs BroadPhasePair* oldPairs = mPotentialPairs; + uint oldNbAllocatedPotentialPairs = mNbAllocatedPotentialPairs; mNbAllocatedPotentialPairs *= 2; - mPotentialPairs = (BroadPhasePair*) malloc(mNbAllocatedPotentialPairs * sizeof(BroadPhasePair)); + mPotentialPairs = static_cast(poolAllocator.allocate(mNbAllocatedPotentialPairs * sizeof(BroadPhasePair))); assert(mPotentialPairs); memcpy(mPotentialPairs, oldPairs, mNbPotentialPairs * sizeof(BroadPhasePair)); - free(oldPairs); + poolAllocator.release(oldPairs, oldNbAllocatedPotentialPairs * sizeof(BroadPhasePair)); } // Add the new potential pair into the array of potential overlapping pairs diff --git a/src/collision/broadphase/DynamicAABBTree.cpp b/src/collision/broadphase/DynamicAABBTree.cpp index 5fa33d9d..bbc4b109 100644 --- a/src/collision/broadphase/DynamicAABBTree.cpp +++ b/src/collision/broadphase/DynamicAABBTree.cpp @@ -35,7 +35,8 @@ using namespace reactphysics3d; const int TreeNode::NULL_TREE_NODE = -1; // Constructor -DynamicAABBTree::DynamicAABBTree(decimal extraAABBGap) : mExtraAABBGap(extraAABBGap) { +DynamicAABBTree::DynamicAABBTree(MemoryAllocator& allocator, decimal extraAABBGap) + : mAllocator(allocator), mExtraAABBGap(extraAABBGap) { init(); } @@ -44,7 +45,7 @@ DynamicAABBTree::DynamicAABBTree(decimal extraAABBGap) : mExtraAABBGap(extraAABB DynamicAABBTree::~DynamicAABBTree() { // Free the allocated memory for the nodes - free(mNodes); + mAllocator.release(mNodes, mNbAllocatedNodes * sizeof(TreeNode)); } // Initialize the tree @@ -55,9 +56,9 @@ void DynamicAABBTree::init() { mNbAllocatedNodes = 8; // Allocate memory for the nodes of the tree - mNodes = (TreeNode*) malloc(mNbAllocatedNodes * sizeof(TreeNode)); + mNodes = static_cast(mAllocator.allocate(mNbAllocatedNodes * sizeof(TreeNode))); assert(mNodes); - memset(mNodes, 0, mNbAllocatedNodes * sizeof(TreeNode)); + std::memset(mNodes, 0, mNbAllocatedNodes * sizeof(TreeNode)); // Initialize the allocated nodes for (int i=0; i(mAllocator.allocate(mNbAllocatedNodes * sizeof(TreeNode))); assert(mNodes); memcpy(mNodes, oldNodes, mNbNodes * sizeof(TreeNode)); - free(oldNodes); + mAllocator.release(oldNodes, oldNbAllocatedNodes * sizeof(TreeNode)); // Initialize the allocated nodes for (int i=mNbNodes; i stack; + Stack stack(mAllocator); stack.push(mRootNodeID); // While there are still nodes to visit @@ -637,7 +639,7 @@ void DynamicAABBTree::raycast(const Ray& ray, DynamicAABBTreeRaycastCallback &ca decimal maxFraction = ray.maxFraction; - Stack stack; + Stack stack(mAllocator); stack.push(mRootNodeID); // Walk through the tree from the root looking for proxy shapes diff --git a/src/collision/broadphase/DynamicAABBTree.h b/src/collision/broadphase/DynamicAABBTree.h index 54751138..936595a5 100644 --- a/src/collision/broadphase/DynamicAABBTree.h +++ b/src/collision/broadphase/DynamicAABBTree.h @@ -30,6 +30,7 @@ #include "configuration.h" #include "collision/shapes/AABB.h" #include "body/CollisionBody.h" +#include "memory/MemoryAllocator.h" /// Namespace ReactPhysics3D namespace reactphysics3d { @@ -136,6 +137,9 @@ class DynamicAABBTree { // -------------------- Attributes -------------------- // + /// Memory allocator + MemoryAllocator& mAllocator; + /// Pointer to the memory location of the nodes of the tree TreeNode* mNodes; @@ -203,7 +207,7 @@ class DynamicAABBTree { // -------------------- Methods -------------------- // /// Constructor - DynamicAABBTree(decimal extraAABBGap = decimal(0.0)); + DynamicAABBTree(MemoryAllocator& allocator, decimal extraAABBGap = decimal(0.0)); /// Destructor ~DynamicAABBTree(); diff --git a/src/collision/shapes/ConcaveMeshShape.cpp b/src/collision/shapes/ConcaveMeshShape.cpp index ec5fa913..d2046adc 100644 --- a/src/collision/shapes/ConcaveMeshShape.cpp +++ b/src/collision/shapes/ConcaveMeshShape.cpp @@ -25,12 +25,13 @@ // Libraries #include "ConcaveMeshShape.h" +#include "memory/MemoryManager.h" using namespace reactphysics3d; // Constructor ConcaveMeshShape::ConcaveMeshShape(TriangleMesh* triangleMesh) - : ConcaveShape(CollisionShapeName::TRIANGLE_MESH) { + : ConcaveShape(CollisionShapeName::TRIANGLE_MESH), mDynamicAABBTree(MemoryManager::getBaseAllocator()) { mTriangleMesh = triangleMesh; mRaycastTestType = TriangleRaycastSide::FRONT; diff --git a/src/containers/Stack.h b/src/containers/Stack.h index 904486f1..84e470ba 100644 --- a/src/containers/Stack.h +++ b/src/containers/Stack.h @@ -28,6 +28,7 @@ // Libraries #include "configuration.h" +#include "memory/MemoryAllocator.h" namespace reactphysics3d { @@ -43,6 +44,9 @@ class Stack { // -------------------- Attributes -------------------- // + /// Reference to the memory allocator + MemoryAllocator& mAllocator; + /// Initial array that contains the elements of the stack T mInitArray[capacity]; @@ -60,7 +64,8 @@ class Stack { // -------------------- Methods -------------------- // /// Constructor - Stack() : mElements(mInitArray), mNbElements(0), mNbAllocatedElements(capacity) { + Stack(MemoryAllocator& allocator) + :mAllocator(allocator), mElements(mInitArray), mNbElements(0), mNbAllocatedElements(capacity) { } @@ -71,7 +76,7 @@ class Stack { if (mInitArray != mElements) { // Release the memory allocated on the heap - free(mElements); + mAllocator.release(mElements, mNbAllocatedElements * sizeof(T)); } } @@ -93,12 +98,13 @@ inline void Stack::push(const T& element) { // If we need to allocate more elements if (mNbElements == mNbAllocatedElements) { T* oldElements = mElements; + uint oldNbAllocatedElements = mNbAllocatedElements; mNbAllocatedElements *= 2; - mElements = (T*) malloc(mNbAllocatedElements * sizeof(T)); + mElements = static_cast(mAllocator.allocate(mNbAllocatedElements * sizeof(T))); assert(mElements); memcpy(mElements, oldElements, mNbElements * sizeof(T)); if (oldElements != mInitArray) { - free(oldElements); + mAllocator.release(oldElements, oldNbAllocatedElements * sizeof(T)); } } diff --git a/test/tests/collision/TestDynamicAABBTree.h b/test/tests/collision/TestDynamicAABBTree.h index e43c63e7..a117df57 100755 --- a/test/tests/collision/TestDynamicAABBTree.h +++ b/test/tests/collision/TestDynamicAABBTree.h @@ -29,6 +29,7 @@ // Libraries #include "Test.h" #include "collision/broadphase/DynamicAABBTree.h" +#include "memory/MemoryManager.h" /// Reactphysics3D namespace namespace reactphysics3d { @@ -112,7 +113,7 @@ class TestDynamicAABBTree : public Test { // ------------ Create tree ---------- // // Dynamic AABB Tree - DynamicAABBTree tree; + DynamicAABBTree tree(MemoryManager::getBaseAllocator()); #ifdef IS_PROFILING_ACTIVE /// Pointer to the profiler @@ -168,7 +169,7 @@ class TestDynamicAABBTree : public Test { // ------------- Create tree ----------- // // Dynamic AABB Tree - DynamicAABBTree tree; + DynamicAABBTree tree(MemoryManager::getBaseAllocator()); #ifdef IS_PROFILING_ACTIVE /// Pointer to the profiler @@ -367,7 +368,7 @@ class TestDynamicAABBTree : public Test { // ------------- Create tree ----------- // // Dynamic AABB Tree - DynamicAABBTree tree; + DynamicAABBTree tree(MemoryManager::getBaseAllocator()); #ifdef IS_PROFILING_ACTIVE /// Pointer to the profiler From 1a787453e81f2e36da3237c352ce4f098794bea7 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 5 Feb 2018 07:41:02 +0100 Subject: [PATCH 166/248] Replace std::pair by rp3d::Pair --- CMakeLists.txt | 1 + src/collision/CollisionDetection.cpp | 16 +- src/collision/CollisionDetection.h | 19 +-- src/collision/HalfEdgeStructure.cpp | 39 ++--- src/collision/HalfEdgeStructure.h | 18 +-- src/configuration.h | 3 +- src/containers/Map.h | 35 ++--- src/containers/Pair.h | 214 ++++----------------------- src/engine/DynamicsWorld.cpp | 2 +- src/engine/OverlappingPair.cpp | 2 +- src/engine/OverlappingPair.h | 66 +-------- test/tests/containers/TestMap.h | 96 ++++++------ 12 files changed, 127 insertions(+), 384 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 636c6295..0566a735 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -200,6 +200,7 @@ SET (REACTPHYSICS3D_SOURCES "src/containers/List.h" "src/containers/Map.h" "src/containers/Set.h" + "src/containers/Pair.h" ) # Create the library diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index c337e10a..32269336 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -104,7 +104,7 @@ void CollisionDetection::computeMiddlePhase() { PROFILE("CollisionDetection::computeMiddlePhase()", mProfiler); // For each possible collision pair of bodies - Map::Iterator it; + Map, OverlappingPair*>::Iterator it; for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ) { OverlappingPair* pair = it->second; @@ -317,7 +317,7 @@ void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, Pro (shape1->getCollisionCategoryBits() & shape2->getCollideWithMaskBits()) == 0) return; // Compute the overlapping pair ID - OverlappingPair::OverlappingPairId pairID = OverlappingPair::computeID(shape1, shape2); + Pair pairID = OverlappingPair::computeID(shape1, shape2); // Check if the overlapping pair already exists if (mOverlappingPairs.containsKey(pairID)) return; @@ -328,7 +328,7 @@ void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, Pro mMemoryManager.getSingleFrameAllocator()); assert(newPair != nullptr); - mOverlappingPairs.add(make_pair(pairID, newPair)); + mOverlappingPairs.add(Pair, OverlappingPair*>(pairID, newPair)); // Wake up the two bodies shape1->getBody()->setIsSleeping(false); @@ -341,7 +341,7 @@ void CollisionDetection::removeProxyCollisionShape(ProxyShape* proxyShape) { assert(proxyShape->mBroadPhaseID != -1); // Remove all the overlapping pairs involving this proxy shape - Map::Iterator it; + Map, OverlappingPair*>::Iterator it; for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ) { if (it->second->getShape1()->mBroadPhaseID == proxyShape->mBroadPhaseID|| it->second->getShape2()->mBroadPhaseID == proxyShape->mBroadPhaseID) { @@ -367,7 +367,7 @@ void CollisionDetection::addAllContactManifoldsToBodies() { PROFILE("CollisionDetection::addAllContactManifoldsToBodies()", mProfiler); // For each overlapping pairs in contact during the narrow-phase - Map::Iterator it; + Map, OverlappingPair*>::Iterator it; for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ++it) { // Add all the contact manifolds of the pair into the list of contact manifolds @@ -418,7 +418,7 @@ void CollisionDetection::processAllPotentialContacts() { PROFILE("CollisionDetection::processAllPotentialContacts()", mProfiler); // For each overlapping pairs in contact during the narrow-phase - Map::Iterator it; + Map, OverlappingPair*>::Iterator it; for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ++it) { // Process the potential contacts of the overlapping pair @@ -457,7 +457,7 @@ void CollisionDetection::reportAllContacts() { PROFILE("CollisionDetection::reportAllContacts()", mProfiler); // For each overlapping pairs in contact during the narrow-phase - Map::Iterator it; + Map, OverlappingPair*>::Iterator it; for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ++it) { // If there is a user callback @@ -912,7 +912,7 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { computeBroadPhase(); // For each possible collision pair of bodies - Map::Iterator it; + Map, OverlappingPair*>::Iterator it; for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ++it) { OverlappingPair* originalPair = it->second; diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index f06d52f0..4dc45634 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -38,23 +38,6 @@ #include "containers/Set.h" #include -// Hash function for struct VerticesPair -// TOOD : REMOVE THIS -namespace std { - - template <> struct hash { - - size_t operator()(const reactphysics3d::bodyindexpair& pair) const { - - std::size_t seed = 0; - reactphysics3d::hash_combine(seed, pair.first); - reactphysics3d::hash_combine(seed, pair.second); - - return seed; - } - }; -} - /// ReactPhysics3D namespace namespace reactphysics3d { @@ -96,7 +79,7 @@ class CollisionDetection { NarrowPhaseInfo* mNarrowPhaseInfoList; /// Broad-phase overlapping pairs - Map mOverlappingPairs; + Map, OverlappingPair*> mOverlappingPairs; /// Broad-phase algorithm BroadPhaseAlgorithm mBroadPhaseAlgorithm; diff --git a/src/collision/HalfEdgeStructure.cpp b/src/collision/HalfEdgeStructure.cpp index b9106d78..b5fd6140 100644 --- a/src/collision/HalfEdgeStructure.cpp +++ b/src/collision/HalfEdgeStructure.cpp @@ -26,26 +26,11 @@ // Libraries #include "HalfEdgeStructure.h" #include "containers/Map.h" +#include "containers/Pair.h" #include "containers/containers_common.h" using namespace reactphysics3d; -// Hash function for struct VerticesPair -namespace std { - - template <> struct hash { - - size_t operator()(const HalfEdgeStructure::VerticesPair& pair) const { - - std::size_t seed = 0; - hash_combine(seed, pair.vertex1); - hash_combine(seed, pair.vertex2); - - return seed; - } - }; -} - // Initialize the structure (when all vertices and faces have been added) void HalfEdgeStructure::init() { @@ -63,7 +48,7 @@ void HalfEdgeStructure::init() { Face face = mFaces[f]; - VerticesPair firstEdgeKey; + VerticesPair firstEdgeKey(0, 0); // For each vertex of the face for (uint v=0; v < face.faceVertices.size(); v++) { @@ -80,19 +65,19 @@ void HalfEdgeStructure::init() { firstEdgeKey = pairV1V2; } else if (v >= 1) { - nextEdges.add(std::make_pair(currentFaceEdges[currentFaceEdges.size() - 1], pairV1V2)); + nextEdges.add(Pair(currentFaceEdges[currentFaceEdges.size() - 1], pairV1V2)); } if (v == (face.faceVertices.size() - 1)) { - nextEdges.add(std::make_pair(pairV1V2, firstEdgeKey)); + nextEdges.add(Pair(pairV1V2, firstEdgeKey)); } - edges.add(std::make_pair(pairV1V2, edge)); + edges.add(Pair(pairV1V2, edge)); const VerticesPair pairV2V1(v2Index, v1Index); - mapEdgeToStartVertex.add(std::make_pair(pairV1V2, v1Index), true); - mapEdgeToStartVertex.add(std::make_pair(pairV2V1, v2Index), true); + mapEdgeToStartVertex.add(Pair(pairV1V2, v1Index), true); + mapEdgeToStartVertex.add(Pair(pairV2V1, v2Index), true); - mapFaceIndexToEdgeKey.add(std::make_pair(f, pairV1V2), true); + mapFaceIndexToEdgeKey.add(Pair(f, pairV1V2), true); auto itEdge = edges.find(pairV2V1); if (itEdge != edges.end()) { @@ -102,14 +87,14 @@ void HalfEdgeStructure::init() { itEdge->second.twinEdgeIndex = edgeIndex + 1; edge.twinEdgeIndex = edgeIndex; - mapEdgeIndexToKey.add(std::make_pair(edgeIndex, pairV2V1)); - mapEdgeIndexToKey.add(std::make_pair(edgeIndex + 1, pairV1V2)); + mapEdgeIndexToKey.add(Pair(edgeIndex, pairV2V1)); + mapEdgeIndexToKey.add(Pair(edgeIndex + 1, pairV1V2)); mVertices[v1Index].edgeIndex = edgeIndex + 1; mVertices[v2Index].edgeIndex = edgeIndex; - mapEdgeToIndex.add(std::make_pair(pairV1V2, edgeIndex + 1)); - mapEdgeToIndex.add(std::make_pair(pairV2V1, edgeIndex)); + mapEdgeToIndex.add(Pair(pairV1V2, edgeIndex + 1)); + mapEdgeToIndex.add(Pair(pairV2V1, edgeIndex)); mEdges.add(itEdge->second); mEdges.add(edge); diff --git a/src/collision/HalfEdgeStructure.h b/src/collision/HalfEdgeStructure.h index b5668182..3f351533 100644 --- a/src/collision/HalfEdgeStructure.h +++ b/src/collision/HalfEdgeStructure.h @@ -41,23 +41,7 @@ class HalfEdgeStructure { public: - /// Pair of vertices - struct VerticesPair { - - uint vertex1; - uint vertex2; - - /// Constructor - VerticesPair() = default; - - /// Constructor - VerticesPair(uint v1, uint v2) : vertex1(v1), vertex2(v2) {} - - /// Equality operator - bool operator==(const VerticesPair& pair) const { - return vertex1 == pair.vertex1 && vertex2 == pair.vertex2; - } - }; + using VerticesPair = Pair; /// Edge struct Edge { diff --git a/src/configuration.h b/src/configuration.h index 96391e76..3cde138c 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -32,6 +32,7 @@ #include #include #include "decimal.h" +#include "containers/Pair.h" // Windows platform #if defined(WIN32) ||defined(_WIN32) || defined(_WIN64) ||defined(__WIN32__) || defined(__WINDOWS__) @@ -52,7 +53,7 @@ using uchar = unsigned char; using ushort = unsigned short; using luint = long unsigned int; using bodyindex = luint; -using bodyindexpair = std::pair; +using bodyindexpair = Pair; using int8 = std::int8_t; using uint8 = std::uint8_t; diff --git a/src/containers/Map.h b/src/containers/Map.h index 89594370..cea9342c 100644 --- a/src/containers/Map.h +++ b/src/containers/Map.h @@ -29,6 +29,7 @@ // Libraries #include "memory/MemoryAllocator.h" #include "mathematics/mathematics_functions.h" +#include "containers/Pair.h" #include #include #include @@ -52,7 +53,7 @@ class Map { size_t hashCode; // Hash code of the entry int next; // Index of the next entry - std::pair* keyValue; // Pointer to the pair with key and value + Pair* keyValue; // Pointer to the pair with key and value /// Constructor Entry() { @@ -296,10 +297,10 @@ class Map { public: // Iterator traits - using value_type = std::pair; + using value_type = Pair; using difference_type = std::ptrdiff_t; - using pointer = std::pair*; - using reference = std::pair&; + using pointer = Pair*; + using reference = Pair&; using iterator_category = std::forward_iterator_tag; /// Constructor @@ -396,8 +397,8 @@ class Map { new (&mEntries[i]) Entry(map.mEntries[i].hashCode, map.mEntries[i].next); if (map.mEntries[i].keyValue != nullptr) { - mEntries[i].keyValue = static_cast*>(mAllocator.allocate(sizeof(std::pair))); - new (mEntries[i].keyValue) std::pair(*(map.mEntries[i].keyValue)); + mEntries[i].keyValue = static_cast*>(mAllocator.allocate(sizeof(Pair))); + new (mEntries[i].keyValue) Pair(*(map.mEntries[i].keyValue)); } } } @@ -429,7 +430,7 @@ class Map { } /// Add an element into the map - void add(const std::pair& keyValue, bool insertIfAlreadyPresent = false) { + void add(const Pair& keyValue, bool insertIfAlreadyPresent = false) { if (mCapacity == 0) { initialize(0); @@ -450,10 +451,10 @@ class Map { if (insertIfAlreadyPresent) { // Destruct the previous key/value - mEntries[i].keyValue->~pair(); + mEntries[i].keyValue->~Pair(); // Copy construct the new key/value - new (mEntries[i].keyValue) std::pair(keyValue); + new (mEntries[i].keyValue) Pair(keyValue); return; } @@ -491,9 +492,9 @@ class Map { assert(mEntries[entryIndex].keyValue == nullptr); mEntries[entryIndex].hashCode = hashCode; mEntries[entryIndex].next = mBuckets[bucket]; - mEntries[entryIndex].keyValue = static_cast*>(mAllocator.allocate(sizeof(std::pair))); + mEntries[entryIndex].keyValue = static_cast*>(mAllocator.allocate(sizeof(Pair))); assert(mEntries[entryIndex].keyValue != nullptr); - new (mEntries[entryIndex].keyValue) std::pair(keyValue); + new (mEntries[entryIndex].keyValue) Pair(keyValue); mBuckets[bucket] = entryIndex; } @@ -529,8 +530,8 @@ class Map { // Release memory for the key/value pair if any if (mEntries[i].keyValue != nullptr) { - mEntries[i].keyValue->~pair(); - mAllocator.release(mEntries[i].keyValue, sizeof(std::pair)); + mEntries[i].keyValue->~Pair(); + mAllocator.release(mEntries[i].keyValue, sizeof(Pair)); mEntries[i].keyValue = nullptr; } mEntries[i].hashCode = -1; @@ -567,8 +568,8 @@ class Map { mBuckets[i] = -1; mEntries[i].next = -1; if (mEntries[i].keyValue != nullptr) { - mEntries[i].keyValue->~pair(); - mAllocator.release(mEntries[i].keyValue, sizeof(std::pair)); + mEntries[i].keyValue->~Pair(); + mAllocator.release(mEntries[i].keyValue, sizeof(Pair)); mEntries[i].keyValue = nullptr; } } @@ -714,8 +715,8 @@ class Map { new (&mEntries[i]) Entry(map.mEntries[i].hashCode, map.mEntries[i].next); if (map.mEntries[i].keyValue != nullptr) { - mEntries[i].keyValue = static_cast*>(mAllocator.allocate(sizeof(std::pair))); - new (mEntries[i].keyValue) std::pair(*(map.mEntries[i].keyValue)); + mEntries[i].keyValue = static_cast*>(mAllocator.allocate(sizeof(Pair))); + new (mEntries[i].keyValue) Pair(*(map.mEntries[i].keyValue)); } } diff --git a/src/containers/Pair.h b/src/containers/Pair.h index e6a9ff8f..8c34b4ac 100644 --- a/src/containers/Pair.h +++ b/src/containers/Pair.h @@ -29,6 +29,7 @@ // Libraries #include "configuration.h" #include "memory/MemoryAllocator.h" +#include "containers/containers_common.h" #include #include @@ -54,211 +55,52 @@ class Pair { // -------------------- Methods -------------------- // /// Constructor - List(MemoryAllocator& allocator, size_t capacity = 0) - : mBuffer(nullptr), mSize(0), mCapacity(0), mAllocator(allocator) { + Pair(const T1& item1, const T2& item2) : first(item1), second(item2) { - if (capacity > 0) { - - // Allocate memory - reserve(capacity); - } } /// Copy constructor - List(const List& list) : mBuffer(nullptr), mSize(0), mCapacity(0), mAllocator(list.mAllocator) { + Pair(const Pair& pair) : first(pair.first), second(pair.second) { - // All all the elements of the list to the current one - addRange(list); } /// Destructor - ~List() { - - // If elements have been allocated - if (mCapacity > 0) { - - // Clear the list - clear(); - - // Release the memory allocated on the heap - 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) { - reserve(mCapacity == 0 ? 1 : mCapacity * 2); - } - - // Use the copy-constructor to construct the element - new (static_cast(mBuffer) + mSize * sizeof(T)) T(element); - - mSize++; - } - - /// Try to find a given item of the list and return an iterator - /// pointing to that element if it exists in the list. Otherwise, - /// this method returns the end() iterator - Iterator find(const T& element) { - - for (uint i=0; i(mBuffer)[i])) { - return Iterator(mBuffer, i, mSize); - } - } - - return end(); - } - - /// Remove an element from the list - void remove(const Iterator& it) { - assert(it.mBuffer == mBuffer); - remove(it.mCurrentIndex); - } - - /// Remove an element from the list at a given index - void remove(uint index) { - - assert(index >= 0 && index < mSize); - - // Call the destructor - (static_cast(mBuffer)[index]).~T(); - - mSize--; - - if (index != mSize) { - - // Move the elements to fill in the empty slot - char* dest = static_cast(mBuffer) + index * sizeof(T); - char* src = dest + sizeof(T); - std::memcpy(static_cast(dest), static_cast(src), (mSize - index) * sizeof(T)); - } - } - - /// Append another list at the end of the current one - void addRange(const List& list) { - - // If we need to allocate more memory - if (mSize + list.size() > mCapacity) { - - // Allocate memory - reserve(mSize + list.size()); - } - - // Add the elements of the list to the current one - for(uint i=0; i(mBuffer) + mSize * sizeof(T)) T(list[i]); - mSize++; - } - } - - /// Clear the list - void clear() { - - // Call the destructor of each element - for (uint i=0; i < mSize; i++) { - (static_cast(mBuffer)[i]).~T(); - } - - mSize = 0; - } - - /// Return the number of elements in the list - 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 (static_cast(mBuffer)[index]); - } - - /// Overloaded const index operator - const T& operator[](const uint index) const { - assert(index >= 0 && index < mSize); - return (static_cast(mBuffer)[index]); - } + ~Pair() = default; /// Overloaded equality operator - bool operator==(const List& list) const { - - if (mSize != list.mSize) return false; - - T* items = static_cast(mBuffer); - for (int i=0; i < mSize; i++) { - if (items[i] != list[i]) { - return false; - } - } - - return true; + bool operator==(const Pair& pair) const { + return first == pair.first && second == pair.second; } /// Overloaded not equal operator - bool operator!=(const List& list) const { - - return !((*this) == list); + bool operator!=(const Pair& pair) const { + return !((*this) == pair); } /// Overloaded assignment operator - List& operator=(const List& list) { - - if (this != &list) { - - // Clear all the elements - clear(); - - // Add all the elements of the list to the current one - addRange(list); - } - - return *this; - } - - /// Return a begin iterator - Iterator begin() const { - return Iterator(mBuffer, 0, mSize); - } - - /// Return a end iterator - Iterator end() const { - return Iterator(mBuffer, mSize, mSize); + Pair& operator=(const Pair& pair) { + first = pair.first; + second = pair.second; } }; } +// Hash function for struct VerticesPair +namespace std { + + template struct hash> { + + size_t operator()(const reactphysics3d::Pair& pair) const { + + std::size_t seed = 0; + reactphysics3d::hash_combine(seed, pair.first); + reactphysics3d::hash_combine(seed, pair.second); + + return seed; + } + }; +} + + #endif diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index 77938f9e..ee270519 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -828,7 +828,7 @@ List DynamicsWorld::getContactsList() { List contactManifolds(mMemoryManager.getPoolAllocator()); // For each currently overlapping pair of bodies - Map::Iterator it; + Map, OverlappingPair*>::Iterator it; for (it = mCollisionDetection.mOverlappingPairs.begin(); it != mCollisionDetection.mOverlappingPairs.end(); ++it) { diff --git a/src/engine/OverlappingPair.cpp b/src/engine/OverlappingPair.cpp index 3dbdc2f4..16e077e9 100644 --- a/src/engine/OverlappingPair.cpp +++ b/src/engine/OverlappingPair.cpp @@ -164,7 +164,7 @@ void OverlappingPair::addLastFrameInfoIfNecessary(uint shapeId1, uint shapeId2) LastFrameCollisionInfo(); // Add it into the map of collision infos - mLastFrameCollisionInfos.add(std::make_pair(shapeIdPair, collisionInfo)); + mLastFrameCollisionInfos.add(Pair(shapeIdPair, collisionInfo)); } else { diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index c7653942..e93658d0 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -31,6 +31,7 @@ #include "collision/ProxyShape.h" #include "collision/shapes/CollisionShape.h" #include "containers/Map.h" +#include "containers/Pair.h" #include "containers/containers_common.h" /// ReactPhysics3D namespace @@ -95,35 +96,8 @@ class OverlappingPair { public: - /// Pair of shape ids - struct ShapeIdPair { - - uint shapeIdBody1; - uint shapeIdBody2; - - /// Constructor - ShapeIdPair(uint id1, uint id2) : shapeIdBody1(id1), shapeIdBody2(id2) {} - - /// Equality operator - bool operator==(const ShapeIdPair& pair) const { - return shapeIdBody1 == pair.shapeIdBody1 && shapeIdBody2 == pair.shapeIdBody2; - } - }; - - /// Pair of broad-phase ids - struct OverlappingPairId { - - uint body1Id; - uint body2Id; - - /// Constructor - OverlappingPairId(uint id1, uint id2) : body1Id(id1), body2Id(id2) {} - - /// Equality operator - bool operator==(const OverlappingPairId& pair) const { - return body1Id == pair.body1Id && body2Id == pair.body2Id; - } - }; + using OverlappingPairId = Pair; + using ShapeIdPair = Pair; private: @@ -277,7 +251,7 @@ inline OverlappingPair::OverlappingPairId OverlappingPair::computeID(ProxyShape* OverlappingPairId pairID = shape1->mBroadPhaseID < shape2->mBroadPhaseID ? OverlappingPairId(shape1->mBroadPhaseID, shape2->mBroadPhaseID) : OverlappingPairId(shape2->mBroadPhaseID, shape1->mBroadPhaseID); - assert(pairID.body1Id != pairID.body2Id); + assert(pairID.first != pairID.second); return pairID; } @@ -287,8 +261,8 @@ inline bodyindexpair OverlappingPair::computeBodiesIndexPair(CollisionBody* body // Construct the pair of body index bodyindexpair indexPair = body1->getID() < body2->getID() ? - std::make_pair(body1->getID(), body2->getID()) : - std::make_pair(body2->getID(), body1->getID()); + bodyindexpair(body1->getID(), body2->getID()) : + bodyindexpair(body2->getID(), body1->getID()); assert(indexPair.first != indexPair.second); return indexPair; } @@ -331,33 +305,5 @@ inline LastFrameCollisionInfo* OverlappingPair::getLastFrameCollisionInfo(uint s } -// Hash function for struct ShapeIdPair -namespace std { - - template <> struct hash { - - size_t operator()(const reactphysics3d::OverlappingPair::ShapeIdPair& pair) const { - - std::size_t seed = 0; - reactphysics3d::hash_combine(seed, pair.shapeIdBody1); - reactphysics3d::hash_combine(seed, pair.shapeIdBody2); - - return seed; - } - }; - - template <> struct hash { - - size_t operator()(const reactphysics3d::OverlappingPair::OverlappingPairId& pair) const { - - std::size_t seed = 0; - reactphysics3d::hash_combine(seed, pair.body1Id); - reactphysics3d::hash_combine(seed, pair.body2Id); - - return seed; - } - }; -} - #endif diff --git a/test/tests/containers/TestMap.h b/test/tests/containers/TestMap.h index 2e9b3133..d75de2aa 100644 --- a/test/tests/containers/TestMap.h +++ b/test/tests/containers/TestMap.h @@ -111,9 +111,9 @@ class TestMap : public Test { test(map3.size() == map1.size()); Map map4(mAllocator); - map4.add(std::make_pair(1, 10)); - map4.add(std::make_pair(2, 20)); - map4.add(std::make_pair(3, 30)); + map4.add(Pair(1, 10)); + map4.add(Pair(2, 20)); + map4.add(Pair(3, 30)); test(map4.capacity() >= 3); test(map4.size() == 3); @@ -130,8 +130,8 @@ class TestMap : public Test { Map map1(mAllocator); map1.reserve(15); test(map1.capacity() >= 15); - map1.add(std::make_pair(1, "test1")); - map1.add(std::make_pair(2, "test2")); + map1.add(Pair(1, "test1")); + map1.add(Pair(2, "test2")); test(map1.capacity() >= 15); map1.reserve(10); @@ -148,9 +148,9 @@ class TestMap : public Test { // ----- Test add() ----- // Map map1(mAllocator); - map1.add(std::make_pair(1, 10)); - map1.add(std::make_pair(8, 80)); - map1.add(std::make_pair(13, 130)); + map1.add(Pair(1, 10)); + map1.add(Pair(8, 80)); + map1.add(Pair(13, 130)); test(map1[1] == 10); test(map1[8] == 80); test(map1[13] == 130); @@ -158,7 +158,7 @@ class TestMap : public Test { Map map2(mAllocator, 15); for (int i = 0; i < 1000000; i++) { - map2.add(std::make_pair(i, i * 100)); + map2.add(Pair(i, i * 100)); } bool isValid = true; for (int i = 0; i < 1000000; i++) { @@ -167,14 +167,14 @@ class TestMap : public Test { test(isValid); map1.remove(1); - map1.add(std::make_pair(1, 10)); + map1.add(Pair(1, 10)); test(map1.size() == 3); test(map1[1] == 10); - map1.add(std::make_pair(56, 34)); + map1.add(Pair(56, 34)); test(map1[56] == 34); test(map1.size() == 4); - map1.add(std::make_pair(56, 13), true); + map1.add(Pair(56, 13), true); test(map1[56] == 13); test(map1.size() == 4); @@ -212,13 +212,13 @@ class TestMap : public Test { Map map3(mAllocator); for (int i=0; i < 1000000; i++) { - map3.add(std::make_pair(i, i * 10)); + map3.add(Pair(i, i * 10)); map3.remove(i); } - map3.add(std::make_pair(1, 10)); - map3.add(std::make_pair(2, 20)); - map3.add(std::make_pair(3, 30)); + map3.add(Pair(1, 10)); + map3.add(Pair(2, 20)); + map3.add(Pair(3, 30)); test(map3.size() == 3); it = map3.begin(); map3.remove(it++); @@ -226,8 +226,8 @@ class TestMap : public Test { test(map3.size() == 2); test(it->second == 20); - map3.add(std::make_pair(56, 32)); - map3.add(std::make_pair(23, 89)); + map3.add(Pair(56, 32)); + map3.add(Pair(23, 89)); for (it = map3.begin(); it != map3.end();) { it = map3.remove(it); } @@ -236,12 +236,12 @@ class TestMap : public Test { // ----- Test clear() ----- // Map map4(mAllocator); - map4.add(std::make_pair(2, 20)); - map4.add(std::make_pair(4, 40)); - map4.add(std::make_pair(6, 60)); + map4.add(Pair(2, 20)); + map4.add(Pair(4, 40)); + map4.add(Pair(6, 60)); map4.clear(); test(map4.size() == 0); - map4.add(std::make_pair(2, 20)); + map4.add(Pair(2, 20)); test(map4.size() == 1); test(map4[2] == 20); map4.clear(); @@ -255,7 +255,7 @@ class TestMap : public Test { Map map6(mAllocator); for (int i=0; i < 1000; i++) { - map6.add(std::make_pair(TestKey(i), i)); + map6.add(Pair(TestKey(i), i)); } bool isTestValid = true; for (int i=0; i < 1000; i++) { @@ -278,9 +278,9 @@ class TestMap : public Test { test(!map1.containsKey(4)); test(!map1.containsKey(6)); - map1.add(std::make_pair(2, 20)); - map1.add(std::make_pair(4, 40)); - map1.add(std::make_pair(6, 60)); + map1.add(Pair(2, 20)); + map1.add(Pair(4, 40)); + map1.add(Pair(6, 60)); test(map1.containsKey(2)); test(map1.containsKey(4)); @@ -299,9 +299,9 @@ class TestMap : public Test { void testIndexing() { Map map1(mAllocator); - map1.add(std::make_pair(2, 20)); - map1.add(std::make_pair(4, 40)); - map1.add(std::make_pair(6, 60)); + map1.add(Pair(2, 20)); + map1.add(Pair(4, 40)); + map1.add(Pair(6, 60)); test(map1[2] == 20); test(map1[4] == 40); test(map1[6] == 60); @@ -318,9 +318,9 @@ class TestMap : public Test { void testFind() { Map map1(mAllocator); - map1.add(std::make_pair(2, 20)); - map1.add(std::make_pair(4, 40)); - map1.add(std::make_pair(6, 60)); + map1.add(Pair(2, 20)); + map1.add(Pair(4, 40)); + map1.add(Pair(6, 60)); test(map1.find(2)->second == 20); test(map1.find(4)->second == 40); test(map1.find(6)->second == 60); @@ -342,13 +342,13 @@ class TestMap : public Test { test(map1 == map2); - map1.add(std::make_pair("a", 1)); - map1.add(std::make_pair("b", 2)); - map1.add(std::make_pair("c", 3)); + map1.add(Pair("a", 1)); + map1.add(Pair("b", 2)); + map1.add(Pair("c", 3)); - map2.add(std::make_pair("a", 1)); - map2.add(std::make_pair("b", 2)); - map2.add(std::make_pair("c", 4)); + map2.add(Pair("a", 1)); + map2.add(Pair("b", 2)); + map2.add(Pair("c", 4)); test(map1 == map1); test(map2 == map2); @@ -359,7 +359,7 @@ class TestMap : public Test { test(map1 == map2); Map map3(mAllocator); - map3.add(std::make_pair("a", 1)); + map3.add(Pair("a", 1)); test(map1 != map3); test(map2 != map3); @@ -368,9 +368,9 @@ class TestMap : public Test { void testAssignment() { Map map1(mAllocator); - map1.add(std::make_pair(1, 3)); - map1.add(std::make_pair(2, 6)); - map1.add(std::make_pair(10, 30)); + map1.add(Pair(1, 3)); + map1.add(Pair(2, 6)); + map1.add(Pair(10, 30)); Map map2(mAllocator); map2 = map1; @@ -394,8 +394,8 @@ class TestMap : public Test { test(map3 == map4); Map map5(mAllocator); - map5.add(std::make_pair(7, 8)); - map5.add(std::make_pair(19, 70)); + map5.add(Pair(7, 8)); + map5.add(Pair(19, 70)); map1 = map5; test(map5.size() == map1.size()); test(map5 == map1); @@ -409,10 +409,10 @@ class TestMap : public Test { test(map1.begin() == map1.end()); - map1.add(std::make_pair(1, 5)); - map1.add(std::make_pair(2, 6)); - map1.add(std::make_pair(3, 8)); - map1.add(std::make_pair(4, -1)); + map1.add(Pair(1, 5)); + map1.add(Pair(2, 6)); + map1.add(Pair(3, 8)); + map1.add(Pair(4, -1)); Map::Iterator itBegin = map1.begin(); Map::Iterator it = map1.begin(); From 2146dd442726d82d5a0c34808c877bae9ec3058c Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 6 Feb 2018 07:39:56 +0100 Subject: [PATCH 167/248] Working on collision detection unit tests --- test/tests/collision/TestCollisionWorld.h | 1256 +++++++++++++++++++-- 1 file changed, 1190 insertions(+), 66 deletions(-) mode change 100755 => 100644 test/tests/collision/TestCollisionWorld.h diff --git a/test/tests/collision/TestCollisionWorld.h b/test/tests/collision/TestCollisionWorld.h old mode 100755 new mode 100644 index ad0c92cf..9161fce7 --- a/test/tests/collision/TestCollisionWorld.h +++ b/test/tests/collision/TestCollisionWorld.h @@ -29,6 +29,7 @@ // Libraries #include "reactphysics3d.h" #include "Test.h" +#include /// Reactphysics3D namespace namespace reactphysics3d { @@ -53,7 +54,7 @@ struct CollisionPointData { penetrationDepth = penDepth; } - bool isContactPointSimilarTo(const Vector3& pointBody1, const Vector3& pointBody2, decimal penDepth, decimal epsilon = 0.001) { + bool isContactPointSimilarTo(const Vector3& pointBody1, const Vector3& pointBody2, decimal penDepth, decimal epsilon = 0.001) const { return approxEqual(pointBody1, localPointBody1, epsilon) && approxEqual(pointBody2, localPointBody2, epsilon) && @@ -70,11 +71,12 @@ struct CollisionManifoldData { return contactPoints.size(); } - bool hasContactPointSimilarTo(const Vector3& localPointBody1, const Vector3& localPointBody2, decimal penetrationDepth, decimal epsilon = 0.001) { + bool hasContactPointSimilarTo(const Vector3& localPointBody1, const Vector3& localPointBody2, decimal penetrationDepth, decimal epsilon = 0.001) const { - std::vector::iterator it; - for (it = contactPoints.begin(); it != contactPoints.end(); ++it) { + std::vector::const_iterator it; + for (it = contactPoints.cbegin(); it != contactPoints.cend(); ++it) { + Vector3 vec = it->localPointBody1; if (it->isContactPointSimilarTo(localPointBody1, localPointBody2, penetrationDepth)) { return true; } @@ -109,10 +111,18 @@ struct CollisionData { return nbPoints; } - bool hasContactPointSimilarTo(const Vector3& localPointBody1, const Vector3& localPointBody2, decimal penetrationDepth, decimal epsilon = 0.001) { + const CollisionBody* getBody1() const { + return bodies.first; + } - std::vector::iterator it; - for (it = contactManifolds.begin(); it != contactManifolds.end(); ++it) { + const CollisionBody* getBody2() const { + return bodies.second; + } + + bool hasContactPointSimilarTo(const Vector3& localPointBody1, const Vector3& localPointBody2, decimal penetrationDepth, decimal epsilon = 0.001) const { + + std::vector::const_iterator it; + for (it = contactManifolds.cbegin(); it != contactManifolds.cend(); ++it) { if (it->hasContactPointSimilarTo(localPointBody1, localPointBody2, penetrationDepth)) { return true; @@ -129,7 +139,7 @@ class WorldCollisionCallback : public CollisionCallback { private: - std::vector> mCollisionData; + std::map, CollisionData> mCollisionDatas; std::pair getCollisionKeyPair(std::pair pair) const { @@ -149,15 +159,25 @@ class WorldCollisionCallback : public CollisionCallback void reset() { - mCollisionData.clear(); + mCollisionDatas.clear(); } bool hasContacts() const { - return mCollisionData.size() > 0; + return mCollisionDatas.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(); + return mCollisionDatas.find(getCollisionKeyPair(std::make_pair(proxyShape1, proxyShape2))) != mCollisionDatas.end(); + } + + const CollisionData* getCollisionData(const ProxyShape* proxyShape1, const ProxyShape* proxyShape2) const { + std::map, CollisionData>::const_iterator it = mCollisionDatas.find(getCollisionKeyPair(std::make_pair(proxyShape1, proxyShape2))); + if (it != mCollisionDatas.end()) { + return &(it->second); + } + else { + return nullptr; + } } // This method will be called for each contact @@ -184,6 +204,7 @@ class WorldCollisionCallback : public CollisionCallback } collisionData.contactManifolds.push_back(collisionManifold); + mCollisionDatas.insert(std::make_pair(getCollisionKeyPair(collisionData.proxyShapes), collisionData)); element = element->getNext(); } @@ -195,7 +216,7 @@ class WorldOverlapCallback : public OverlapCallback { private: - CollisionBody* mOverlapBody; + std::vector mOverlapBodies; public: @@ -206,19 +227,19 @@ class WorldOverlapCallback : public OverlapCallback { /// This method will be called for each reported overlapping bodies virtual void notifyOverlap(CollisionBody* collisionBody) override { - + mOverlapBodies.push_back(collisionBody); } void reset() { - mOverlapBody = nullptr; + mOverlapBodies.clear(); } bool hasOverlap() const { - return mOverlapBody != nullptr; + return !mOverlapBodies.empty(); } - CollisionBody* getOverlapBody() { - return mOverlapBody; + std::vector& getOverlapBodies() { + return mOverlapBodies; } }; @@ -240,18 +261,48 @@ class TestCollisionWorld : public Test { CollisionBody* mBoxBody2; CollisionBody* mSphereBody1; CollisionBody* mSphereBody2; + CollisionBody* mCapsuleBody1; + CollisionBody* mCapsuleBody2; + CollisionBody* mConvexMeshBody1; + CollisionBody* mConvexMeshBody2; + CollisionBody* mConcaveMeshBody; // Collision shapes BoxShape* mBoxShape1; BoxShape* mBoxShape2; SphereShape* mSphereShape1; SphereShape* mSphereShape2; + CapsuleShape* mCapsuleShape1; + CapsuleShape* mCapsuleShape2; + ConvexMeshShape* mConvexMeshShape1; + ConvexMeshShape* mConvexMeshShape2; + ConcaveMeshShape* mConcaveMeshShape; // Proxy shapes ProxyShape* mBoxProxyShape1; ProxyShape* mBoxProxyShape2; ProxyShape* mSphereProxyShape1; ProxyShape* mSphereProxyShape2; + ProxyShape* mCapsuleProxyShape1; + ProxyShape* mCapsuleProxyShape2; + ProxyShape* mConvexMeshProxyShape1; + ProxyShape* mConvexMeshProxyShape2; + ProxyShape* mConcaveMeshProxyShape; + + PolygonVertexArray* mConvexMesh1PolygonVertexArray; + PolygonVertexArray* mConvexMesh2PolygonVertexArray; + PolyhedronMesh* mConvexMesh1PolyhedronMesh; + PolyhedronMesh* mConvexMesh2PolyhedronMesh; + PolygonVertexArray::PolygonFace* mConvexMeshPolygonFaces; + + TriangleVertexArray* mConcaveMeshTriangleVertexArray; + Vector3 mConvexMesh1CubeVertices[8]; + Vector3 mConvexMesh2CubeVertices[8]; + int mConvexMeshCubeIndices[24]; + + Vector3 mConcaveMeshPlaneVertices[36]; + int mConcaveMeshPlaneIndices[25 * 2 * 3]; + TriangleMesh* mConcaveTriangleMesh; // Collision callback WorldCollisionCallback mCollisionCallback; @@ -277,7 +328,7 @@ class TestCollisionWorld : public Test { Transform boxTransform2(Vector3(-10, 20, 0), Quaternion::identity()); mBoxBody2 = mWorld->createCollisionBody(boxTransform2); - mBoxShape2 = new BoxShape(Vector3(2, 2, 2)); + mBoxShape2 = new BoxShape(Vector3(4, 2, 8)); mBoxProxyShape2 = mBoxBody2->addCollisionShape(mBoxShape1, Transform::identity()); // ---------- Spheres ---------- // @@ -290,6 +341,107 @@ class TestCollisionWorld : public Test { Transform sphereTransform2(Vector3(20, 20, 0), Quaternion::identity()); mSphereBody2 = mWorld->createCollisionBody(sphereTransform2); mSphereProxyShape2 = mSphereBody2->addCollisionShape(mSphereShape2, Transform::identity()); + + // ---------- Capsules ---------- // + mCapsuleShape1 = new CapsuleShape(2, 6); + Transform capsuleTransform1(Vector3(-10, 0, 0), Quaternion::identity()); + mCapsuleBody1 = mWorld->createCollisionBody(capsuleTransform1); + mCapsuleProxyShape1 = mCapsuleBody1->addCollisionShape(mCapsuleShape1, Transform::identity()); + + mCapsuleShape2 = new CapsuleShape(3, 4); + Transform capsuleTransform2(Vector3(-20, 0, 0), Quaternion::identity()); + mCapsuleBody2 = mWorld->createCollisionBody(capsuleTransform2); + mCapsuleProxyShape2 = mCapsuleBody2->addCollisionShape(mCapsuleShape2, Transform::identity()); + + // ---------- Convex Meshes ---------- // + mConvexMesh1CubeVertices[0] = Vector3(-3, -3, 3); + mConvexMesh1CubeVertices[1] = Vector3(3, -3, 3); + mConvexMesh1CubeVertices[2] = Vector3(3, -3, -3); + mConvexMesh1CubeVertices[3] = Vector3(-3, -3, -3); + mConvexMesh1CubeVertices[4] = Vector3(-3, 3, 3); + mConvexMesh1CubeVertices[5] = Vector3(3, 3, 3); + mConvexMesh1CubeVertices[6] = Vector3(3, 3, -3); + mConvexMesh1CubeVertices[7] = Vector3(-3, 3, -3); + + mConvexMeshCubeIndices[0] = 0; mConvexMeshCubeIndices[1] = 3; mConvexMeshCubeIndices[2] = 2; mConvexMeshCubeIndices[3] = 1; + mConvexMeshCubeIndices[4] = 4; mConvexMeshCubeIndices[5] = 5; mConvexMeshCubeIndices[6] = 6; mConvexMeshCubeIndices[7] = 7; + mConvexMeshCubeIndices[8] = 0; mConvexMeshCubeIndices[9] = 1; mConvexMeshCubeIndices[10] = 5; mConvexMeshCubeIndices[11] = 4; + mConvexMeshCubeIndices[12] = 1; mConvexMeshCubeIndices[13] = 2; mConvexMeshCubeIndices[14] = 6; mConvexMeshCubeIndices[15] = 5; + mConvexMeshCubeIndices[16] = 2; mConvexMeshCubeIndices[17] = 3; mConvexMeshCubeIndices[18] = 7; mConvexMeshCubeIndices[19] = 6; + mConvexMeshCubeIndices[20] = 0; mConvexMeshCubeIndices[21] = 4; mConvexMeshCubeIndices[22] = 7; mConvexMeshCubeIndices[23] = 3; + + mConvexMeshPolygonFaces = new rp3d::PolygonVertexArray::PolygonFace[6]; + rp3d::PolygonVertexArray::PolygonFace* face = mConvexMeshPolygonFaces; + for (int f = 0; f < 6; f++) { + face->indexBase = f * 4; + face->nbVertices = 4; + face++; + } + mConvexMesh1PolygonVertexArray = new rp3d::PolygonVertexArray(8, &(mConvexMesh1CubeVertices[0]), sizeof(Vector3), + &(mConvexMeshCubeIndices[0]), sizeof(int), 6, mConvexMeshPolygonFaces, + rp3d::PolygonVertexArray::VertexDataType::VERTEX_FLOAT_TYPE, + rp3d::PolygonVertexArray::IndexDataType::INDEX_INTEGER_TYPE); + mConvexMesh1PolyhedronMesh = new rp3d::PolyhedronMesh(mConvexMesh1PolygonVertexArray); + mConvexMeshShape1 = new rp3d::ConvexMeshShape(mConvexMesh1PolyhedronMesh); + Transform convexMeshTransform1(Vector3(10, 0, 0), Quaternion::identity()); + mConvexMeshBody1 = mWorld->createCollisionBody(convexMeshTransform1); + mConvexMeshProxyShape1 = mConvexMeshBody1->addCollisionShape(mConvexMeshShape1, Transform::identity()); + + mConvexMesh2CubeVertices[0] = Vector3(-4, -2, 8); + mConvexMesh2CubeVertices[1] = Vector3(4, -2, 8); + mConvexMesh2CubeVertices[2] = Vector3(4, -2, -8); + mConvexMesh2CubeVertices[3] = Vector3(-4, -2, -8); + mConvexMesh2CubeVertices[4] = Vector3(-4, 2, 8); + mConvexMesh2CubeVertices[5] = Vector3(4, 2, 8); + mConvexMesh2CubeVertices[6] = Vector3(4, 2, -8); + mConvexMesh2CubeVertices[7] = Vector3(-4, 2, -8); + + mConvexMesh2PolygonVertexArray = new rp3d::PolygonVertexArray(8, &(mConvexMesh2CubeVertices[0]), sizeof(Vector3), + &(mConvexMeshCubeIndices[0]), sizeof(int), 6, mConvexMeshPolygonFaces, + rp3d::PolygonVertexArray::VertexDataType::VERTEX_FLOAT_TYPE, + rp3d::PolygonVertexArray::IndexDataType::INDEX_INTEGER_TYPE); + mConvexMesh2PolyhedronMesh = new rp3d::PolyhedronMesh(mConvexMesh2PolygonVertexArray); + mConvexMeshShape2 = new rp3d::ConvexMeshShape(mConvexMesh2PolyhedronMesh); + Transform convexMeshTransform2(Vector3(20, 0, 0), Quaternion::identity()); + mConvexMeshBody2 = mWorld->createCollisionBody(convexMeshTransform2); + mConvexMeshProxyShape2 = mConvexMeshBody2->addCollisionShape(mConvexMeshShape2, Transform::identity()); + + // ---------- Concave Meshes ---------- // + for (int i = 0; i < 6; i++) { + for (int j = 0; j < 6; j++) { + mConcaveMeshPlaneVertices[i * 6 + j] = Vector3(-2.5f + i, 0, -2.5f + j); + } + } + int triangleIndex = 0; + for (int i = 0; i < 5; i++) { + for (int j = 0; j < 5; j++) { + + // Triangle 1 + mConcaveMeshPlaneIndices[triangleIndex * 3] = i * 6 + j; + mConcaveMeshPlaneIndices[triangleIndex * 3 + 1] = (i+1) * 6 + (j+1); + mConcaveMeshPlaneIndices[triangleIndex * 3 + 2] = i * 6 + (j+1); + triangleIndex++; + + // Triangle 2 + mConcaveMeshPlaneIndices[triangleIndex * 3] = i * 6 + j; + mConcaveMeshPlaneIndices[triangleIndex * 3 + 1] = (i+1) * 6 + j; + mConcaveMeshPlaneIndices[triangleIndex * 3 + 2] = (i+1) * 6 + (j+1); + triangleIndex++; + } + } + + mConcaveMeshTriangleVertexArray = new rp3d::TriangleVertexArray(36, &(mConcaveMeshPlaneVertices[0]), sizeof(Vector3), + 25, &(mConcaveMeshPlaneIndices[0]), 3 * sizeof(int), + rp3d::TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE, + rp3d::TriangleVertexArray::IndexDataType::INDEX_INTEGER_TYPE); + + // Add the triangle vertex array of the subpart to the triangle mesh + Transform concaveMeshTransform(Vector3(0, -20, 0), Quaternion::identity()); + mConcaveTriangleMesh = new TriangleMesh(); + mConcaveTriangleMesh->addSubpart(mConcaveMeshTriangleVertexArray); + mConcaveMeshShape = new rp3d::ConcaveMeshShape(mConcaveTriangleMesh); + mConcaveMeshBody = mWorld->createCollisionBody(concaveMeshTransform); + mConcaveMeshProxyShape = mConcaveMeshBody->addCollisionShape(mConcaveMeshShape, rp3d::Transform::identity()); } /// Destructor @@ -301,6 +453,21 @@ class TestCollisionWorld : public Test { delete mSphereShape1; delete mSphereShape2; + delete mCapsuleShape1; + delete mCapsuleShape2; + + delete mConvexMeshShape1; + delete mConvexMeshShape2; + delete mConvexMesh1PolyhedronMesh; + delete mConvexMesh2PolyhedronMesh; + delete mConvexMesh1PolygonVertexArray; + delete mConvexMesh2PolygonVertexArray; + delete mConvexMeshPolygonFaces; + + delete mConcaveMeshShape; + delete mConcaveTriangleMesh; + delete mConcaveMeshTriangleVertexArray; + delete mWorld; } @@ -311,10 +478,10 @@ class TestCollisionWorld : public Test { testNoOverlap(); testNoAABBOverlap(); - testAABBOverlap(); - testSphereVsSphereCollision(); testSphereVsBoxCollision(); + testSphereVsCapsuleCollision(); + testSphereVsConvexMeshCollision(); testMultipleCollisions(); } @@ -373,7 +540,6 @@ class TestCollisionWorld : public Test { mCollisionCallback.reset(); mWorld->testCollision(mBoxBody2, mSphereBody2, &mCollisionCallback); test(!mCollisionCallback.hasContacts()); - } void testNoOverlap() { @@ -424,72 +590,1030 @@ class TestCollisionWorld : public Test { test(!mWorld->testAABBOverlap(mBoxBody2, mSphereBody2)); } - void testAABBOverlap() { - - // TODO : Test the CollisionWorld::testAABBOverlap() method here - } - void testSphereVsSphereCollision() { + Transform initTransform1 = mSphereBody1->getTransform(); + Transform initTransform2 = mSphereBody2->getTransform(); + Transform transform1(Vector3(10, 20, 50), Quaternion::identity()); + Transform transform2(Vector3(17, 20, 50), Quaternion::fromEulerAngles(rp3d::PI / 8.0f, rp3d::PI / 4.0f, rp3d::PI / 16.0f)); - // Move sphere 1 to collide with sphere 2 - mSphereBody1->setTransform(Transform(Vector3(30, 15, 10), Quaternion::identity())); + // Move spheres to collide with each other + mSphereBody1->setTransform(transform1); + mSphereBody2->setTransform(transform2); + // ----- Test AABB overlap ----- // + + test(mWorld->testAABBOverlap(mSphereBody1, mSphereBody2)); + + mOverlapCallback.reset(); + mWorld->testOverlap(mSphereBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + mOverlapCallback.reset(); + mWorld->testOverlap(mSphereBody2, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + // ----- Test global collision test ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(&mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mSphereProxyShape2)); + + // Get collision data + const CollisionData* collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mSphereProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + Vector3 localBody1Point(3, 0, 0); + Vector3 localBody2Point = transform2.getInverse() * Vector3(12, 20, 50); + decimal penetrationDepth = 1.0f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 1 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mSphereProxyShape2)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mSphereProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 2 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody2, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mSphereProxyShape2)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mSphereProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against selected body 1 and 2 ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody1, mSphereBody2, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mSphereProxyShape2)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mSphereProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // Reset the init transforms + mSphereBody1->setTransform(initTransform1); + mSphereBody2->setTransform(initTransform2); } void testSphereVsBoxCollision() { - // Move sphere 1 to collide with box - mSphereBody1->setTransform(Transform(Vector3(10, 5, 0), Quaternion::identity())); + Transform initTransform1 = mSphereBody1->getTransform(); + Transform initTransform2 = mBoxBody1->getTransform(); - // --------- Test collision with inactive bodies --------- // + /******************************************************************************** + * Test Sphere vs Box Face collision * + *********************************************************************************/ - mCollisionCallback.reset(); - mBoxBody1->setIsActive(false); - mSphereBody1->setIsActive(false); - mSphereBody2->setIsActive(false); - mWorld->testCollision(&mCollisionCallback); - + Transform transform1(Vector3(10, 20, 50), Quaternion::identity()); + Transform transform2(Vector3(14, 20, 50), Quaternion::identity()); - mBoxBody1->setIsActive(true); - mSphereBody1->setIsActive(true); - mSphereBody2->setIsActive(true); + // Move spheres to collide with each other + mSphereBody1->setTransform(transform1); + mBoxBody1->setTransform(transform2); - // --------- Test collision with collision filtering -------- // + // ----- Test AABB overlap ----- // - //mBoxProxyShape->setCollideWithMaskBits(CATEGORY_1 | CATEGORY_3); - //mSphere1ProxyShape->setCollideWithMaskBits(CATEGORY_1 | CATEGORY_2); - //mSphere2ProxyShape->setCollideWithMaskBits(CATEGORY_1); + test(mWorld->testAABBOverlap(mSphereBody1, mBoxBody1)); - //mCollisionCallback.reset(); - //mWorld->testCollision(&mCollisionCallback); - //test(mCollisionCallback.boxCollideWithSphere1); - //test(!mCollisionCallback.sphere1CollideWithSphere2); + mOverlapCallback.reset(); + mWorld->testOverlap(mSphereBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); - //// Move sphere 1 to collide with sphere 2 - //mSphere1Body->setTransform(Transform(Vector3(30, 15, 10), Quaternion::identity())); + mOverlapCallback.reset(); + mWorld->testOverlap(mBoxBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); - //mCollisionCallback.reset(); - //mWorld->testCollision(&mCollisionCallback); - //test(!mCollisionCallback.boxCollideWithSphere1); - //test(mCollisionCallback.sphere1CollideWithSphere2); + // ----- Test global collision test ----- // - //mBoxProxyShape->setCollideWithMaskBits(CATEGORY_2); - //mSphere1ProxyShape->setCollideWithMaskBits(CATEGORY_2); - //mSphere2ProxyShape->setCollideWithMaskBits(CATEGORY_3); + mCollisionCallback.reset(); + mWorld->testCollision(&mCollisionCallback); - //mCollisionCallback.reset(); - //mWorld->testCollision(&mCollisionCallback); - //test(!mCollisionCallback.boxCollideWithSphere1); - //test(!mCollisionCallback.sphere1CollideWithSphere2); + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mBoxProxyShape1)); - //// Move sphere 1 to collide with box - //mSphere1Body->setTransform(Transform(Vector3(10, 5, 0), Quaternion::identity())); + // Get collision data + const CollisionData* collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mBoxProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); - //mBoxProxyShape->setCollideWithMaskBits(0xFFFF); - //mSphere1ProxyShape->setCollideWithMaskBits(0xFFFF); - //mSphere2ProxyShape->setCollideWithMaskBits(0xFFFF); + // True if the bodies are swapped in the collision callback response + bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + Vector3 localBody1Point(3, 0, 0); + Vector3 localBody2Point(-3, 0, 0); + decimal penetrationDepth = 2.0f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 1 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mBoxProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mBoxProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 2 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mBoxBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mBoxProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mBoxProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against selected body 1 and 2 ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody1, mBoxBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mBoxProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mBoxProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + /******************************************************************************** + * Test Sphere vs Box Edge collision * + *********************************************************************************/ + + transform1 = Transform(Vector3(10, 20, 50), Quaternion::identity()); + transform2 = Transform(Vector3(14, 16, 50), Quaternion::identity()); + + // Move spheres to collide with each other + mSphereBody1->setTransform(transform1); + mBoxBody1->setTransform(transform2); + + // ----- Test AABB overlap ----- // + + test(mWorld->testAABBOverlap(mSphereBody1, mBoxBody1)); + + mOverlapCallback.reset(); + mWorld->testOverlap(mSphereBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + mOverlapCallback.reset(); + mWorld->testOverlap(mBoxBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + // ----- Test global collision test ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(&mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mBoxProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mBoxProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + localBody1Point = std::sqrt(4.5f) * Vector3(1, -1, 0); + localBody2Point = Vector3(-3, 3, 0); + penetrationDepth = decimal(3.0) - std::sqrt(2); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 1 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mBoxProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mBoxProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 2 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mBoxBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mBoxProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mBoxProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against selected body 1 and 2 ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody1, mBoxBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mBoxProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mBoxProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + /******************************************************************************** + * Test Sphere vs Box Vertex collision * + *********************************************************************************/ + + transform1 = Transform(Vector3(10, 20, 50), Quaternion::identity()); + transform2 = Transform(Vector3(14, 16, 46), Quaternion::identity()); + + // Move spheres to collide with each other + mSphereBody1->setTransform(transform1); + mBoxBody1->setTransform(transform2); + + // ----- Test AABB overlap ----- // + + test(mWorld->testAABBOverlap(mSphereBody1, mBoxBody1)); + + mOverlapCallback.reset(); + mWorld->testOverlap(mSphereBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + mOverlapCallback.reset(); + mWorld->testOverlap(mBoxBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + // ----- Test global collision test ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(&mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mBoxProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mBoxProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + localBody1Point = std::sqrt(9.0f / 3.0f) * Vector3(1, -1, -1); + localBody2Point = Vector3(-3, 3, 3); + penetrationDepth = decimal(3.0) - std::sqrt(3); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 1 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mBoxProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mBoxProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 2 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mBoxBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mBoxProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mBoxProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against selected body 1 and 2 ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody1, mBoxBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mBoxProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mBoxProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // Reset the init transforms + mSphereBody1->setTransform(initTransform1); + mBoxBody1->setTransform(initTransform2); + } + + void testSphereVsCapsuleCollision() { + + Transform initTransform1 = mSphereBody1->getTransform(); + Transform initTransform2 = mCapsuleBody1->getTransform(); + + /******************************************************************************** + * Test Sphere vs Capsule (sphere side) collision * + *********************************************************************************/ + + Transform transform1(Vector3(10, 20, 50), Quaternion::identity()); + Transform transform2(Vector3(10, 14, 50), Quaternion::identity()); + + // Move spheres to collide with each other + mSphereBody1->setTransform(transform1); + mCapsuleBody1->setTransform(transform2); + + // ----- Test AABB overlap ----- // + + test(mWorld->testAABBOverlap(mSphereBody1, mCapsuleBody1)); + + mOverlapCallback.reset(); + mWorld->testOverlap(mSphereBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + mOverlapCallback.reset(); + mWorld->testOverlap(mCapsuleBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + // ----- Test global collision test ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(&mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mCapsuleProxyShape1)); + + // Get collision data + const CollisionData* collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mCapsuleProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + Vector3 localBody1Point(0, -3, 0); + Vector3 localBody2Point(0, 5, 0); + decimal penetrationDepth = 2.0f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 1 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mCapsuleProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mCapsuleProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 2 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mCapsuleBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mCapsuleProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mCapsuleProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against selected body 1 and 2 ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody1, mCapsuleBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mCapsuleProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mCapsuleProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + /******************************************************************************** + * Test Sphere vs Box Capsule (cylinder side) collision * + *********************************************************************************/ + + transform1 = Transform(Vector3(10, 20, 50), Quaternion::identity()); + transform2 = Transform(Vector3(14, 19, 50), Quaternion::identity()); + + // Move spheres to collide with each other + mSphereBody1->setTransform(transform1); + mCapsuleBody1->setTransform(transform2); + + // ----- Test AABB overlap ----- // + + test(mWorld->testAABBOverlap(mSphereBody1, mCapsuleBody1)); + + mOverlapCallback.reset(); + mWorld->testOverlap(mSphereBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + mOverlapCallback.reset(); + mWorld->testOverlap(mCapsuleBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + // ----- Test global collision test ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(&mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mCapsuleProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mCapsuleProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + localBody1Point = Vector3(3, 0, 0); + localBody2Point = Vector3(-2, 1, 0); + penetrationDepth = decimal(1.0); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 1 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mCapsuleProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mCapsuleProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 2 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mCapsuleBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mCapsuleProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mCapsuleProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against selected body 1 and 2 ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody1, mCapsuleBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mCapsuleProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mCapsuleProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // Reset the init transforms + mSphereBody1->setTransform(initTransform1); + mCapsuleBody1->setTransform(initTransform2); + } + + void testSphereVsConvexMeshCollision() { + + Transform initTransform1 = mSphereBody1->getTransform(); + Transform initTransform2 = mConvexMeshBody1->getTransform(); + + /******************************************************************************** + * Test Sphere vs Convex Mesh (Cube Face) collision * + *********************************************************************************/ + + Transform transform1(Vector3(10, 20, 50), Quaternion::identity()); + Transform transform2(Vector3(14, 20, 50), Quaternion::identity()); + + // Move spheres to collide with each other + mSphereBody1->setTransform(transform1); + mConvexMeshBody1->setTransform(transform2); + + // ----- Test AABB overlap ----- // + + test(mWorld->testAABBOverlap(mSphereBody1, mConvexMeshBody1)); + + mOverlapCallback.reset(); + mWorld->testOverlap(mSphereBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + mOverlapCallback.reset(); + mWorld->testOverlap(mConvexMeshBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + // ----- Test global collision test ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(&mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mConvexMeshProxyShape1)); + + // Get collision data + const CollisionData* collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mConvexMeshProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + Vector3 localBody1Point(3, 0, 0); + Vector3 localBody2Point(-3, 0, 0); + decimal penetrationDepth = 2.0f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 1 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mConvexMeshProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mConvexMeshProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 2 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mConvexMeshBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mConvexMeshProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mConvexMeshProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against selected body 1 and 2 ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody1, mConvexMeshBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mConvexMeshProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mConvexMeshProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + /******************************************************************************** + * Test Sphere vs Convex Mesh (Cube Edge) collision * + *********************************************************************************/ + + transform1 = Transform(Vector3(10, 20, 50), Quaternion::identity()); + transform2 = Transform(Vector3(14, 16, 50), Quaternion::identity()); + + // Move spheres to collide with each other + mSphereBody1->setTransform(transform1); + mConvexMeshBody1->setTransform(transform2); + + // ----- Test AABB overlap ----- // + + test(mWorld->testAABBOverlap(mSphereBody1, mConvexMeshBody1)); + + mOverlapCallback.reset(); + mWorld->testOverlap(mSphereBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + mOverlapCallback.reset(); + mWorld->testOverlap(mConvexMeshBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + // ----- Test global collision test ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(&mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mConvexMeshProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mConvexMeshProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + localBody1Point = std::sqrt(4.5f) * Vector3(1, -1, 0); + localBody2Point = Vector3(-3, 3, 0); + penetrationDepth = decimal(3.0) - std::sqrt(2); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 1 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mConvexMeshProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mConvexMeshProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 2 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mConvexMeshBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mConvexMeshProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mConvexMeshProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against selected body 1 and 2 ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody1, mConvexMeshBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mConvexMeshProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mConvexMeshProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + /******************************************************************************** + * Test Sphere vs ConvexMesh (Cube Vertex) collision * + *********************************************************************************/ + + transform1 = Transform(Vector3(10, 20, 50), Quaternion::identity()); + transform2 = Transform(Vector3(14, 16, 46), Quaternion::identity()); + + // Move spheres to collide with each other + mSphereBody1->setTransform(transform1); + mConvexMeshBody1->setTransform(transform2); + + // ----- Test AABB overlap ----- // + + test(mWorld->testAABBOverlap(mSphereBody1, mConvexMeshBody1)); + + mOverlapCallback.reset(); + mWorld->testOverlap(mSphereBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + mOverlapCallback.reset(); + mWorld->testOverlap(mConvexMeshBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + // ----- Test global collision test ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(&mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mConvexMeshProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mConvexMeshProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + localBody1Point = std::sqrt(9.0f / 3.0f) * Vector3(1, -1, -1); + localBody2Point = Vector3(-3, 3, 3); + penetrationDepth = decimal(3.0) - std::sqrt(3); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 1 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mConvexMeshProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mConvexMeshProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 2 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mConvexMeshBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mConvexMeshProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mConvexMeshProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against selected body 1 and 2 ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody1, mConvexMeshBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mConvexMeshProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mConvexMeshProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // Reset the init transforms + mSphereBody1->setTransform(initTransform1); + mConvexMeshBody1->setTransform(initTransform2); } void testMultipleCollisions() { From 6dac7e0916bdc725055764922ea45c865df1060d Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 11 Feb 2018 14:42:11 +0100 Subject: [PATCH 168/248] Fix issue with clipping methods --- src/mathematics/mathematics_functions.cpp | 137 ++++++++++------------ 1 file changed, 65 insertions(+), 72 deletions(-) diff --git a/src/mathematics/mathematics_functions.cpp b/src/mathematics/mathematics_functions.cpp index 52ac337b..99640c58 100755 --- a/src/mathematics/mathematics_functions.cpp +++ b/src/mathematics/mathematics_functions.cpp @@ -225,30 +225,26 @@ List reactphysics3d::clipSegmentWithPlanes(const Vector3& segA, const V const List& planesPoints, const List& planesNormals, MemoryAllocator& allocator) { - assert(planesPoints.size() == planesNormals.size()); - List list1(allocator, 2); - List list2(allocator, 2); + List inputVertices(allocator, 2); + List outputVertices(allocator, 2); - List* inputVertices = &list1; - List* outputVertices = &list2; - - inputVertices->add(segA); - inputVertices->add(segB); + inputVertices.add(segA); + inputVertices.add(segB); // For each clipping plane for (uint p=0; psize() == 0) return *inputVertices; + if (inputVertices.size() == 0) return inputVertices; - assert(inputVertices->size() == 2); + assert(inputVertices.size() == 2); - outputVertices->clear(); + outputVertices.clear(); - Vector3& v1 = (*inputVertices)[0]; - Vector3& v2 = (*inputVertices)[1]; + Vector3& v1 = inputVertices[0]; + Vector3& v2 = inputVertices[1]; decimal v1DotN = (v1 - planesPoints[p]).dot(planesNormals[p]); decimal v2DotN = (v2 - planesPoints[p]).dot(planesNormals[p]); @@ -263,40 +259,39 @@ List reactphysics3d::clipSegmentWithPlanes(const Vector3& segA, const V decimal t = computePlaneSegmentIntersection(v1, v2, planesNormals[p].dot(planesPoints[p]), planesNormals[p]); if (t >= decimal(0) && t <= decimal(1.0)) { - outputVertices->add(v1 + t * (v2 - v1)); + outputVertices.add(v1 + t * (v2 - v1)); } else { - outputVertices->add(v2); + outputVertices.add(v2); } } else { - outputVertices->add(v1); + outputVertices.add(v1); } // Add the second vertex - outputVertices->add(v2); + outputVertices.add(v2); } else { // If the second vertex is behind the clipping plane // If the first vertex is in front of the clippling plane if (v1DotN >= decimal(0.0)) { - outputVertices->add(v1); + outputVertices.add(v1); // The first point we keep is the intersection between the segment v1, v2 and the clipping plane decimal t = computePlaneSegmentIntersection(v1, v2, -planesNormals[p].dot(planesPoints[p]), -planesNormals[p]); if (t >= decimal(0.0) && t <= decimal(1.0)) { - outputVertices->add(v1 + t * (v2 - v1)); + outputVertices.add(v1 + t * (v2 - v1)); } } } inputVertices = outputVertices; - outputVertices = p % 2 == 0 ? &list1 : &list2; } - return *outputVertices; + return outputVertices; } // Clip a polygon against multiple planes and return the clipped polygon vertices @@ -306,75 +301,73 @@ List reactphysics3d::clipPolygonWithPlanes(const List& polygon assert(planesPoints.size() == planesNormals.size()); - uint nbMaxElements = polygonVertices.size() + planesPoints.size(); - List list1(allocator, nbMaxElements); - List list2(allocator, nbMaxElements); + uint nbMaxElements = polygonVertices.size() + planesPoints.size(); + List inputVertices(allocator, nbMaxElements); + List outputVertices(allocator, nbMaxElements); - const List* inputVertices = &polygonVertices; - List* outputVertices = &list2; + inputVertices.addRange(polygonVertices); - // For each clipping plane - for (uint p=0; pclear(); + outputVertices.clear(); - uint nbInputVertices = inputVertices->size(); - uint vStart = nbInputVertices - 1; + uint nbInputVertices = inputVertices.size(); + uint vStart = nbInputVertices - 1; - // For each edge of the polygon - for (uint vEnd = 0; vEnd= decimal(0.0)) { + // If the second vertex is in front of the clippling plane + if (v2DotN >= decimal(0.0)) { - // If the first vertex is not in front of the clippling plane - if (v1DotN < decimal(0.0)) { + // If the first vertex is not in front of the clippling plane + if (v1DotN < decimal(0.0)) { - // The second point we keep is the intersection between the segment v1, v2 and the clipping plane - decimal t = computePlaneSegmentIntersection(v1, v2, planesNormals[p].dot(planesPoints[p]), planesNormals[p]); + // The second point we keep is the intersection between the segment v1, v2 and the clipping plane + decimal t = computePlaneSegmentIntersection(v1, v2, planesNormals[p].dot(planesPoints[p]), planesNormals[p]); - if (t >= decimal(0) && t <= decimal(1.0)) { - outputVertices->add(v1 + t * (v2 - v1)); + if (t >= decimal(0) && t <= decimal(1.0)) { + outputVertices.add(v1 + t * (v2 - v1)); + } + else { + outputVertices.add(v2); + } + } + + // Add the second vertex + outputVertices.add(v2); + } + else { // If the second vertex is behind the clipping plane + + // If the first vertex is in front of the clippling plane + if (v1DotN >= decimal(0.0)) { + + // The first point we keep is the intersection between the segment v1, v2 and the clipping plane + decimal t = computePlaneSegmentIntersection(v1, v2, -planesNormals[p].dot(planesPoints[p]), -planesNormals[p]); + + if (t >= decimal(0.0) && t <= decimal(1.0)) { + outputVertices.add(v1 + t * (v2 - v1)); + } + else { + outputVertices.add(v1); + } } - else { - outputVertices->add(v2); - } } - // Add the second vertex - outputVertices->add(v2); - } - else { // If the second vertex is behind the clipping plane - - // If the first vertex is in front of the clippling plane - if (v1DotN >= decimal(0.0)) { - - // The first point we keep is the intersection between the segment v1, v2 and the clipping plane - decimal t = computePlaneSegmentIntersection(v1, v2, -planesNormals[p].dot(planesPoints[p]), -planesNormals[p]); - - if (t >= decimal(0.0) && t <= decimal(1.0)) { - outputVertices->add(v1 + t * (v2 - v1)); - } - else { - outputVertices->add(v1); - } - } + vStart = vEnd; } - vStart = vEnd; + inputVertices = outputVertices; } - inputVertices = outputVertices; - outputVertices = p % 2 == 0 ? &list1 : &list2; - } - - return *outputVertices; + return outputVertices; } // Project a point onto a plane that is given by a point and its unit length normal From 1ac9bc3dba796aa626807d2669a3831760ec2265 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 13 Feb 2018 07:20:00 +0100 Subject: [PATCH 169/248] Working on collision detection unit tests --- test/tests/collision/TestCollisionWorld.h | 862 +++++++++++++++++++++- 1 file changed, 860 insertions(+), 2 deletions(-) diff --git a/test/tests/collision/TestCollisionWorld.h b/test/tests/collision/TestCollisionWorld.h index 9161fce7..c7e8084a 100644 --- a/test/tests/collision/TestCollisionWorld.h +++ b/test/tests/collision/TestCollisionWorld.h @@ -329,7 +329,7 @@ class TestCollisionWorld : public Test { Transform boxTransform2(Vector3(-10, 20, 0), Quaternion::identity()); mBoxBody2 = mWorld->createCollisionBody(boxTransform2); mBoxShape2 = new BoxShape(Vector3(4, 2, 8)); - mBoxProxyShape2 = mBoxBody2->addCollisionShape(mBoxShape1, Transform::identity()); + mBoxProxyShape2 = mBoxBody2->addCollisionShape(mBoxShape2, Transform::identity()); // ---------- Spheres ---------- // mSphereShape1 = new SphereShape(3.0); @@ -482,6 +482,14 @@ class TestCollisionWorld : public Test { testSphereVsBoxCollision(); testSphereVsCapsuleCollision(); testSphereVsConvexMeshCollision(); + testSphereVsConcaveMeshCollision(); + + testBoxVsBoxCollision(); + testBoxVsConvexMeshCollision(); + testBoxVsCapsuleCollision(); + + testConvexMeshVsConvexMeshCollision(); + testConvexMeshVsCapsuleCollision(); testMultipleCollisions(); } @@ -1616,7 +1624,857 @@ class TestCollisionWorld : public Test { mConvexMeshBody1->setTransform(initTransform2); } - void testMultipleCollisions() { + void testSphereVsConcaveMeshCollision() { + + Transform initTransform1 = mSphereBody1->getTransform(); + Transform initTransform2 = mConcaveMeshBody->getTransform(); + + /******************************************************************************** + * Test Sphere vs Concave Mesh + *********************************************************************************/ + + Transform transform1(Vector3(10, 22.98f, 50), Quaternion::identity()); + Transform transform2(Vector3(10, 20, 50), Quaternion::identity()); + + // Move spheres to collide with each other + mSphereBody1->setTransform(transform1); + mConcaveMeshBody->setTransform(transform2); + + // ----- Test AABB overlap ----- // + + test(mWorld->testAABBOverlap(mSphereBody1, mConcaveMeshBody)); + + mOverlapCallback.reset(); + mWorld->testOverlap(mSphereBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + mOverlapCallback.reset(); + mWorld->testOverlap(mConcaveMeshBody, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + // ----- Test global collision test ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(&mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mConcaveMeshProxyShape)); + + // Get collision data + const CollisionData* collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mConcaveMeshProxyShape); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + Vector3 localBody1Point(0, -3, 0); + Vector3 localBody2Point(0, 0, 0); + decimal penetrationDepth = 0.02f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 1 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mConcaveMeshProxyShape)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mConcaveMeshProxyShape); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 2 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mConcaveMeshBody, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mConcaveMeshProxyShape)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mConcaveMeshProxyShape); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against selected body 1 and 2 ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mSphereBody1, mConcaveMeshBody, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mSphereProxyShape1, mConcaveMeshProxyShape)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mSphereProxyShape1, mConcaveMeshProxyShape); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // Reset the init transforms + mSphereBody1->setTransform(initTransform1); + mConcaveMeshBody->setTransform(initTransform2); + } + + void testBoxVsBoxCollision() { + + Transform initTransform1 = mBoxBody1->getTransform(); + Transform initTransform2 = mBoxBody2->getTransform(); + + /******************************************************************************** + * Test Box vs Box Face collision * + *********************************************************************************/ + + Transform transform1(Vector3(11, 20, 50), Quaternion::identity()); + Transform transform2(Vector3(4.5, 16, 40), Quaternion::identity()); + + // Move spheres to collide with each other + mBoxBody1->setTransform(transform1); + mBoxBody2->setTransform(transform2); + + // ----- Test AABB overlap ----- // + + test(mWorld->testAABBOverlap(mBoxBody1, mBoxBody2)); + + mOverlapCallback.reset(); + mWorld->testOverlap(mBoxBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + mOverlapCallback.reset(); + mWorld->testOverlap(mBoxBody2, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + // ----- Test global collision test ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(&mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mBoxProxyShape1, mBoxProxyShape2)); + + // Get collision data + const CollisionData* collisionData = mCollisionCallback.getCollisionData(mBoxProxyShape1, mBoxProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 4); + + // True if the bodies are swapped in the collision callback response + bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + + // Test contact points + Vector3 localBody1Point1(-3, -2, -2); + Vector3 localBody2Point1(4, 2, 8); + decimal penetrationDepth1 = 0.5f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, + swappedBodiesCollisionData ? localBody1Point1 : localBody2Point1, + penetrationDepth1)); + Vector3 localBody1Point2(-3, -2, -3); + Vector3 localBody2Point2(4, 2, 7); + decimal penetrationDepth2 = 0.5f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point2 : localBody1Point2, + swappedBodiesCollisionData ? localBody1Point2 : localBody2Point2, + penetrationDepth2)); + Vector3 localBody1Point3(-3, -3, -2); + Vector3 localBody2Point3(4, 1, 8); + decimal penetrationDepth3 = 0.5f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point3 : localBody1Point3, + swappedBodiesCollisionData ? localBody1Point3 : localBody2Point3, + penetrationDepth3)); + Vector3 localBody1Point4(-3, -3, -3); + Vector3 localBody2Point4(4, 1, 7); + decimal penetrationDepth4 = 0.5f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point4 : localBody1Point4, + swappedBodiesCollisionData ? localBody1Point4 : localBody2Point4, + penetrationDepth4)); + + // ----- Test collision against body 1 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mBoxBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mBoxProxyShape1, mBoxProxyShape2)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mBoxProxyShape1, mBoxProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 4); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, + swappedBodiesCollisionData ? localBody1Point1 : localBody2Point1, + penetrationDepth1)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point2 : localBody1Point2, + swappedBodiesCollisionData ? localBody1Point2 : localBody2Point2, + penetrationDepth2)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point3 : localBody1Point3, + swappedBodiesCollisionData ? localBody1Point3 : localBody2Point3, + penetrationDepth3)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point4 : localBody1Point4, + swappedBodiesCollisionData ? localBody1Point4 : localBody2Point4, + penetrationDepth4)); + // ----- Test collision against body 2 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mBoxBody2, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mBoxProxyShape1, mBoxProxyShape2)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mBoxProxyShape1, mBoxProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 4); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, + swappedBodiesCollisionData ? localBody1Point1 : localBody2Point1, + penetrationDepth1)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point2 : localBody1Point2, + swappedBodiesCollisionData ? localBody1Point2 : localBody2Point2, + penetrationDepth2)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point3 : localBody1Point3, + swappedBodiesCollisionData ? localBody1Point3 : localBody2Point3, + penetrationDepth3)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point4 : localBody1Point4, + swappedBodiesCollisionData ? localBody1Point4 : localBody2Point4, + penetrationDepth4)); + + // ----- Test collision against selected body 1 and 2 ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mBoxBody1, mBoxBody2, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mBoxProxyShape1, mBoxProxyShape2)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mBoxProxyShape1, mBoxProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 4); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, + swappedBodiesCollisionData ? localBody1Point1 : localBody2Point1, + penetrationDepth1)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point2 : localBody1Point2, + swappedBodiesCollisionData ? localBody1Point2 : localBody2Point2, + penetrationDepth2)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point3 : localBody1Point3, + swappedBodiesCollisionData ? localBody1Point3 : localBody2Point3, + penetrationDepth3)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point4 : localBody1Point4, + swappedBodiesCollisionData ? localBody1Point4 : localBody2Point4, + penetrationDepth4)); + + // reset the init transforms + mBoxBody1->setTransform(initTransform1); + mBoxBody2->setTransform(initTransform2); + } + + void testBoxVsConvexMeshCollision() { + + Transform initTransform1 = mBoxBody1->getTransform(); + Transform initTransform2 = mConvexMeshBody2->getTransform(); + + /******************************************************************************** + * Test Box vs Convex Mesh collision * + *********************************************************************************/ + + Transform transform1(Vector3(11, 20, 50), Quaternion::identity()); + Transform transform2(Vector3(4.5, 16, 40), Quaternion::identity()); + + // Move spheres to collide with each other + mBoxBody1->setTransform(transform1); + mConvexMeshBody2->setTransform(transform2); + + // ----- Test AABB overlap ----- // + + test(mWorld->testAABBOverlap(mBoxBody1, mConvexMeshBody2)); + + mOverlapCallback.reset(); + mWorld->testOverlap(mBoxBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + mOverlapCallback.reset(); + mWorld->testOverlap(mConvexMeshBody2, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + // ----- Test global collision test ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(&mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mBoxProxyShape1, mConvexMeshProxyShape2)); + + // Get collision data + const CollisionData* collisionData = mCollisionCallback.getCollisionData(mBoxProxyShape1, mConvexMeshProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 4); + + // True if the bodies are swapped in the collision callback response + bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + + // Test contact points + Vector3 localBody1Point1(-3, -2, -2); + Vector3 localBody2Point1(4, 2, 8); + decimal penetrationDepth1 = 0.5f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, + swappedBodiesCollisionData ? localBody1Point1 : localBody2Point1, + penetrationDepth1)); + Vector3 localBody1Point2(-3, -2, -3); + Vector3 localBody2Point2(4, 2, 7); + decimal penetrationDepth2 = 0.5f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point2 : localBody1Point2, + swappedBodiesCollisionData ? localBody1Point2 : localBody2Point2, + penetrationDepth2)); + Vector3 localBody1Point3(-3, -3, -2); + Vector3 localBody2Point3(4, 1, 8); + decimal penetrationDepth3 = 0.5f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point3 : localBody1Point3, + swappedBodiesCollisionData ? localBody1Point3 : localBody2Point3, + penetrationDepth3)); + Vector3 localBody1Point4(-3, -3, -3); + Vector3 localBody2Point4(4, 1, 7); + decimal penetrationDepth4 = 0.5f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point4 : localBody1Point4, + swappedBodiesCollisionData ? localBody1Point4 : localBody2Point4, + penetrationDepth4)); + + // ----- Test collision against body 1 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mBoxBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mBoxProxyShape1, mConvexMeshProxyShape2)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mBoxProxyShape1, mConvexMeshProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 4); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, + swappedBodiesCollisionData ? localBody1Point1 : localBody2Point1, + penetrationDepth1)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point2 : localBody1Point2, + swappedBodiesCollisionData ? localBody1Point2 : localBody2Point2, + penetrationDepth2)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point3 : localBody1Point3, + swappedBodiesCollisionData ? localBody1Point3 : localBody2Point3, + penetrationDepth3)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point4 : localBody1Point4, + swappedBodiesCollisionData ? localBody1Point4 : localBody2Point4, + penetrationDepth4)); + // ----- Test collision against body 2 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mConvexMeshBody2, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mBoxProxyShape1, mConvexMeshProxyShape2)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mBoxProxyShape1, mConvexMeshProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 4); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, + swappedBodiesCollisionData ? localBody1Point1 : localBody2Point1, + penetrationDepth1)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point2 : localBody1Point2, + swappedBodiesCollisionData ? localBody1Point2 : localBody2Point2, + penetrationDepth2)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point3 : localBody1Point3, + swappedBodiesCollisionData ? localBody1Point3 : localBody2Point3, + penetrationDepth3)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point4 : localBody1Point4, + swappedBodiesCollisionData ? localBody1Point4 : localBody2Point4, + penetrationDepth4)); + + // ----- Test collision against selected body 1 and 2 ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mBoxBody1, mConvexMeshBody2, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mBoxProxyShape1, mConvexMeshProxyShape2)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mBoxProxyShape1, mConvexMeshProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 4); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, + swappedBodiesCollisionData ? localBody1Point1 : localBody2Point1, + penetrationDepth1)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point2 : localBody1Point2, + swappedBodiesCollisionData ? localBody1Point2 : localBody2Point2, + penetrationDepth2)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point3 : localBody1Point3, + swappedBodiesCollisionData ? localBody1Point3 : localBody2Point3, + penetrationDepth3)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point4 : localBody1Point4, + swappedBodiesCollisionData ? localBody1Point4 : localBody2Point4, + penetrationDepth4)); + + // reset the init transforms + mBoxBody1->setTransform(initTransform1); + mConvexMeshBody2->setTransform(initTransform2); + } + + void testConvexMeshVsConvexMeshCollision() { + + Transform initTransform1 = mConvexMeshBody1->getTransform(); + Transform initTransform2 = mConvexMeshBody2->getTransform(); + + /******************************************************************************** + * Test Convex Mesh vs Convex Mesh collision * + *********************************************************************************/ + + Transform transform1(Vector3(11, 20, 50), Quaternion::identity()); + Transform transform2(Vector3(4.5, 16, 40), Quaternion::identity()); + + // Move spheres to collide with each other + mConvexMeshBody1->setTransform(transform1); + mConvexMeshBody2->setTransform(transform2); + + // ----- Test AABB overlap ----- // + + test(mWorld->testAABBOverlap(mConvexMeshBody1, mConvexMeshBody2)); + + mOverlapCallback.reset(); + mWorld->testOverlap(mConvexMeshBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + mOverlapCallback.reset(); + mWorld->testOverlap(mConvexMeshBody2, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + // ----- Test global collision test ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(&mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mConvexMeshProxyShape1, mConvexMeshProxyShape2)); + + // Get collision data + const CollisionData* collisionData = mCollisionCallback.getCollisionData(mConvexMeshProxyShape1, mConvexMeshProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 4); + + // True if the bodies are swapped in the collision callback response + bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + + // Test contact points + Vector3 localBody1Point1(-3, -2, -2); + Vector3 localBody2Point1(4, 2, 8); + decimal penetrationDepth1 = 0.5f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, + swappedBodiesCollisionData ? localBody1Point1 : localBody2Point1, + penetrationDepth1)); + Vector3 localBody1Point2(-3, -2, -3); + Vector3 localBody2Point2(4, 2, 7); + decimal penetrationDepth2 = 0.5f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point2 : localBody1Point2, + swappedBodiesCollisionData ? localBody1Point2 : localBody2Point2, + penetrationDepth2)); + Vector3 localBody1Point3(-3, -3, -2); + Vector3 localBody2Point3(4, 1, 8); + decimal penetrationDepth3 = 0.5f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point3 : localBody1Point3, + swappedBodiesCollisionData ? localBody1Point3 : localBody2Point3, + penetrationDepth3)); + Vector3 localBody1Point4(-3, -3, -3); + Vector3 localBody2Point4(4, 1, 7); + decimal penetrationDepth4 = 0.5f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point4 : localBody1Point4, + swappedBodiesCollisionData ? localBody1Point4 : localBody2Point4, + penetrationDepth4)); + + // ----- Test collision against body 1 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mConvexMeshBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mConvexMeshProxyShape1, mConvexMeshProxyShape2)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mConvexMeshProxyShape1, mConvexMeshProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 4); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, + swappedBodiesCollisionData ? localBody1Point1 : localBody2Point1, + penetrationDepth1)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point2 : localBody1Point2, + swappedBodiesCollisionData ? localBody1Point2 : localBody2Point2, + penetrationDepth2)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point3 : localBody1Point3, + swappedBodiesCollisionData ? localBody1Point3 : localBody2Point3, + penetrationDepth3)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point4 : localBody1Point4, + swappedBodiesCollisionData ? localBody1Point4 : localBody2Point4, + penetrationDepth4)); + // ----- Test collision against body 2 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mConvexMeshBody2, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mConvexMeshProxyShape1, mConvexMeshProxyShape2)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mConvexMeshProxyShape1, mConvexMeshProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 4); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, + swappedBodiesCollisionData ? localBody1Point1 : localBody2Point1, + penetrationDepth1)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point2 : localBody1Point2, + swappedBodiesCollisionData ? localBody1Point2 : localBody2Point2, + penetrationDepth2)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point3 : localBody1Point3, + swappedBodiesCollisionData ? localBody1Point3 : localBody2Point3, + penetrationDepth3)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point4 : localBody1Point4, + swappedBodiesCollisionData ? localBody1Point4 : localBody2Point4, + penetrationDepth4)); + + // ----- Test collision against selected body 1 and 2 ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mConvexMeshBody1, mConvexMeshBody2, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mConvexMeshProxyShape1, mConvexMeshProxyShape2)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mConvexMeshProxyShape1, mConvexMeshProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 4); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, + swappedBodiesCollisionData ? localBody1Point1 : localBody2Point1, + penetrationDepth1)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point2 : localBody1Point2, + swappedBodiesCollisionData ? localBody1Point2 : localBody2Point2, + penetrationDepth2)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point3 : localBody1Point3, + swappedBodiesCollisionData ? localBody1Point3 : localBody2Point3, + penetrationDepth3)); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point4 : localBody1Point4, + swappedBodiesCollisionData ? localBody1Point4 : localBody2Point4, + penetrationDepth4)); + + // reset the init transforms + mConvexMeshBody1->setTransform(initTransform1); + mConvexMeshBody2->setTransform(initTransform2); + } + + void testBoxVsCapsuleCollision() { + + Transform initTransform1 = mBoxBody1->getTransform(); + Transform initTransform2 = mCapsuleBody1->getTransform(); + + /******************************************************************************** + * Test Box vs Capsule collision * + *********************************************************************************/ + + Transform transform1(Vector3(10, 20, 50), Quaternion::identity()); + Transform transform2(Vector3(17, 21, 50), Quaternion::fromEulerAngles(0, 0, rp3d::PI * 0.5f)); + + // Move spheres to collide with each other + mBoxBody1->setTransform(transform1); + mCapsuleBody1->setTransform(transform2); + + // ----- Test AABB overlap ----- // + + test(mWorld->testAABBOverlap(mBoxBody1, mCapsuleBody1)); + + mOverlapCallback.reset(); + mWorld->testOverlap(mBoxBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + mOverlapCallback.reset(); + mWorld->testOverlap(mCapsuleBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + // ----- Test global collision test ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(&mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mBoxProxyShape1, mCapsuleProxyShape1)); + + // Get collision data + const CollisionData* collisionData = mCollisionCallback.getCollisionData(mBoxProxyShape1, mCapsuleProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + + // Test contact points + Vector3 localBody1Point1(3, 1, 0); + Vector3 localBody2Point1(0, 5, 0); + decimal penetrationDepth1 = 1.0f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, + swappedBodiesCollisionData ? localBody1Point1 : localBody2Point1, + penetrationDepth1)); + // ----- Test collision against body 1 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mBoxBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mBoxProxyShape1, mCapsuleProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mBoxProxyShape1, mCapsuleProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, + swappedBodiesCollisionData ? localBody1Point1 : localBody2Point1, + penetrationDepth1)); + + // ----- Test collision against body 2 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mCapsuleBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mBoxProxyShape1, mCapsuleProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mBoxProxyShape1, mCapsuleProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, + swappedBodiesCollisionData ? localBody1Point1 : localBody2Point1, + penetrationDepth1)); + + // ----- Test collision against selected body 1 and 2 ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mBoxBody1, mCapsuleBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mBoxProxyShape1, mCapsuleProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mBoxProxyShape1, mCapsuleProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, + swappedBodiesCollisionData ? localBody1Point1 : localBody2Point1, + penetrationDepth1)); + + // reset the init transforms + mBoxBody1->setTransform(initTransform1); + mCapsuleBody1->setTransform(initTransform2); + } + + void testConvexMeshVsCapsuleCollision() { + + Transform initTransform1 = mConvexMeshBody1->getTransform(); + Transform initTransform2 = mCapsuleBody1->getTransform(); + + /******************************************************************************** + * Test Box vs Capsule collision * + *********************************************************************************/ + + Transform transform1(Vector3(10, 20, 50), Quaternion::identity()); + Transform transform2(Vector3(17, 21, 50), Quaternion::fromEulerAngles(0, 0, rp3d::PI * 0.5f)); + + // Move spheres to collide with each other + mConvexMeshBody1->setTransform(transform1); + mCapsuleBody1->setTransform(transform2); + + // ----- Test AABB overlap ----- // + + test(mWorld->testAABBOverlap(mConvexMeshBody1, mCapsuleBody1)); + + mOverlapCallback.reset(); + mWorld->testOverlap(mConvexMeshBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + mOverlapCallback.reset(); + mWorld->testOverlap(mCapsuleBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + // ----- Test global collision test ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(&mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mConvexMeshProxyShape1, mCapsuleProxyShape1)); + + // Get collision data + const CollisionData* collisionData = mCollisionCallback.getCollisionData(mConvexMeshProxyShape1, mCapsuleProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + + // Test contact points + Vector3 localBody1Point1(3, 1, 0); + Vector3 localBody2Point1(0, 5, 0); + decimal penetrationDepth1 = 1.0f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, + swappedBodiesCollisionData ? localBody1Point1 : localBody2Point1, + penetrationDepth1)); + // ----- Test collision against body 1 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mConvexMeshBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mConvexMeshProxyShape1, mCapsuleProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mConvexMeshProxyShape1, mCapsuleProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, + swappedBodiesCollisionData ? localBody1Point1 : localBody2Point1, + penetrationDepth1)); + + // ----- Test collision against body 2 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mCapsuleBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mConvexMeshProxyShape1, mCapsuleProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mConvexMeshProxyShape1, mCapsuleProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, + swappedBodiesCollisionData ? localBody1Point1 : localBody2Point1, + penetrationDepth1)); + + // ----- Test collision against selected body 1 and 2 ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mConvexMeshBody1, mCapsuleBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mConvexMeshProxyShape1, mCapsuleProxyShape1)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mConvexMeshProxyShape1, mCapsuleProxyShape1); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, + swappedBodiesCollisionData ? localBody1Point1 : localBody2Point1, + penetrationDepth1)); + + // reset the init transforms + mConvexMeshBody1->setTransform(initTransform1); + mCapsuleBody1->setTransform(initTransform2); + } + + void testMultipleCollisions() { // TODO : Test collisions without categories set From f73e54bb6d6ae77bfe5eb59f42389c497160f852 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 14 Feb 2018 07:35:30 +0100 Subject: [PATCH 170/248] Working on collision detection unit tests --- test/tests/collision/TestCollisionWorld.h | 591 +++++++++++++++++++++- 1 file changed, 580 insertions(+), 11 deletions(-) diff --git a/test/tests/collision/TestCollisionWorld.h b/test/tests/collision/TestCollisionWorld.h index c7e8084a..64abab25 100644 --- a/test/tests/collision/TestCollisionWorld.h +++ b/test/tests/collision/TestCollisionWorld.h @@ -487,11 +487,14 @@ class TestCollisionWorld : public Test { testBoxVsBoxCollision(); testBoxVsConvexMeshCollision(); testBoxVsCapsuleCollision(); + testBoxVsConcaveMeshCollision(); + + testCapsuleVsCapsuleCollision(); + testCapsuleVsConcaveMeshCollision(); testConvexMeshVsConvexMeshCollision(); testConvexMeshVsCapsuleCollision(); - - testMultipleCollisions(); + testConvexMeshVsConcaveMeshCollision(); } void testNoCollisions() { @@ -2361,7 +2364,7 @@ class TestCollisionWorld : public Test { Transform initTransform2 = mCapsuleBody1->getTransform(); /******************************************************************************** - * Test Box vs Capsule collision * + * Test Convex Mesh vs Capsule collision * *********************************************************************************/ Transform transform1(Vector3(10, 20, 50), Quaternion::identity()); @@ -2474,17 +2477,583 @@ class TestCollisionWorld : public Test { mCapsuleBody1->setTransform(initTransform2); } - void testMultipleCollisions() { + void testBoxVsConcaveMeshCollision() { - // TODO : Test collisions without categories set + Transform initTransform1 = mBoxBody1->getTransform(); + Transform initTransform2 = mConcaveMeshBody->getTransform(); - // TODO : Test colliisons with categories set + /******************************************************************************** + * Test Box vs Concave Mesh + *********************************************************************************/ - // Assign collision categories to proxy shapes - //mBoxProxyShape->setCollisionCategoryBits(CATEGORY_1); - //mSphere1ProxyShape->setCollisionCategoryBits(CATEGORY_1); - //mSphere2ProxyShape->setCollisionCategoryBits(CATEGORY_2); - } + Transform transform1(Vector3(10, 22, 50), Quaternion::identity()); + Transform transform2(Vector3(10, 20, 50), Quaternion::identity()); + + // Move spheres to collide with each other + mBoxBody1->setTransform(transform1); + mConcaveMeshBody->setTransform(transform2); + + // ----- Test AABB overlap ----- // + + test(mWorld->testAABBOverlap(mBoxBody1, mConcaveMeshBody)); + + mOverlapCallback.reset(); + mWorld->testOverlap(mBoxBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + mOverlapCallback.reset(); + mWorld->testOverlap(mConcaveMeshBody, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + // ----- Test global collision test ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(&mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mBoxProxyShape1, mConcaveMeshProxyShape)); + + // Get collision data + const CollisionData* collisionData = mCollisionCallback.getCollisionData(mBoxProxyShape1, mConcaveMeshProxyShape); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 4); + + // True if the bodies are swapped in the collision callback response + bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + + for (int i=0; icontactManifolds[0].contactPoints.size(); i++) { + test(approxEqual(collisionData->contactManifolds[0].contactPoints[i].penetrationDepth, 1.0f)); + } + + // ----- Test collision against body 1 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mBoxBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mBoxProxyShape1, mConcaveMeshProxyShape)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mBoxProxyShape1, mConcaveMeshProxyShape); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 4); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + + for (int i=0; icontactManifolds[0].contactPoints.size(); i++) { + test(approxEqual(collisionData->contactManifolds[0].contactPoints[i].penetrationDepth, 1.0f)); + } + + // ----- Test collision against body 2 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mConcaveMeshBody, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mBoxProxyShape1, mConcaveMeshProxyShape)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mBoxProxyShape1, mConcaveMeshProxyShape); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 4); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + + for (int i=0; icontactManifolds[0].contactPoints.size(); i++) { + test(approxEqual(collisionData->contactManifolds[0].contactPoints[i].penetrationDepth, 1.0f)); + } + + // ----- Test collision against selected body 1 and 2 ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mBoxBody1, mConcaveMeshBody, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mBoxProxyShape1, mConcaveMeshProxyShape)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mBoxProxyShape1, mConcaveMeshProxyShape); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 4); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + + // Test contact points + for (int i=0; icontactManifolds[0].contactPoints.size(); i++) { + test(approxEqual(collisionData->contactManifolds[0].contactPoints[i].penetrationDepth, 1.0f)); + } + + // Reset the init transforms + mBoxBody1->setTransform(initTransform1); + mConcaveMeshBody->setTransform(initTransform2); + } + + void testConvexMeshVsConcaveMeshCollision() { + + Transform initTransform1 = mConvexMeshBody1->getTransform(); + Transform initTransform2 = mConcaveMeshBody->getTransform(); + + /******************************************************************************** + * Test Box vs Concave Mesh + *********************************************************************************/ + + Transform transform1(Vector3(10, 22, 50), Quaternion::identity()); + Transform transform2(Vector3(10, 20, 50), Quaternion::identity()); + + // Move spheres to collide with each other + mConvexMeshBody1->setTransform(transform1); + mConcaveMeshBody->setTransform(transform2); + + // ----- Test AABB overlap ----- // + + test(mWorld->testAABBOverlap(mConvexMeshBody1, mConcaveMeshBody)); + + mOverlapCallback.reset(); + mWorld->testOverlap(mConvexMeshBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + mOverlapCallback.reset(); + mWorld->testOverlap(mConcaveMeshBody, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + // ----- Test global collision test ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(&mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mConvexMeshProxyShape1, mConcaveMeshProxyShape)); + + // Get collision data + const CollisionData* collisionData = mCollisionCallback.getCollisionData(mConvexMeshProxyShape1, mConcaveMeshProxyShape); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 4); + + // True if the bodies are swapped in the collision callback response + bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + + for (int i=0; icontactManifolds[0].contactPoints.size(); i++) { + test(approxEqual(collisionData->contactManifolds[0].contactPoints[i].penetrationDepth, 1.0f)); + } + + // ----- Test collision against body 1 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mConvexMeshBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mConvexMeshProxyShape1, mConcaveMeshProxyShape)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mConvexMeshProxyShape1, mConcaveMeshProxyShape); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 4); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + + for (int i=0; icontactManifolds[0].contactPoints.size(); i++) { + test(approxEqual(collisionData->contactManifolds[0].contactPoints[i].penetrationDepth, 1.0f)); + } + + // ----- Test collision against body 2 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mConcaveMeshBody, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mConvexMeshProxyShape1, mConcaveMeshProxyShape)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mConvexMeshProxyShape1, mConcaveMeshProxyShape); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 4); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + + for (int i=0; icontactManifolds[0].contactPoints.size(); i++) { + test(approxEqual(collisionData->contactManifolds[0].contactPoints[i].penetrationDepth, 1.0f)); + } + + // ----- Test collision against selected body 1 and 2 ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mConvexMeshBody1, mConcaveMeshBody, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mConvexMeshProxyShape1, mConcaveMeshProxyShape)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mConvexMeshProxyShape1, mConcaveMeshProxyShape); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 4); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + + // Test contact points + for (int i=0; icontactManifolds[0].contactPoints.size(); i++) { + test(approxEqual(collisionData->contactManifolds[0].contactPoints[i].penetrationDepth, 1.0f)); + } + + // Reset the init transforms + mConvexMeshBody1->setTransform(initTransform1); + mConcaveMeshBody->setTransform(initTransform2); + } + + void testCapsuleVsCapsuleCollision() { + + Transform initTransform1 = mCapsuleBody1->getTransform(); + Transform initTransform2 = mCapsuleBody2->getTransform(); + + /******************************************************************************** + * Test Capsule (sphere cap) vs Capsule (sphere cap) collision * + *********************************************************************************/ + + Transform transform1(Vector3(10, 20, 50), Quaternion::identity()); + Transform transform2(Vector3(16, 23, 50), Quaternion::fromEulerAngles(0, 0, rp3d::PI * 0.5f)); + + // Move spheres to collide with each other + mCapsuleBody1->setTransform(transform1); + mCapsuleBody2->setTransform(transform2); + + // ----- Test AABB overlap ----- // + + test(mWorld->testAABBOverlap(mCapsuleBody1, mCapsuleBody2)); + + mOverlapCallback.reset(); + mWorld->testOverlap(mCapsuleBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + mOverlapCallback.reset(); + mWorld->testOverlap(mCapsuleBody2, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + // ----- Test global collision test ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(&mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mCapsuleProxyShape1, mCapsuleProxyShape2)); + + // Get collision data + const CollisionData* collisionData = mCollisionCallback.getCollisionData(mCapsuleProxyShape1, mCapsuleProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + + // Test contact points + Vector3 localBody1Point(2, 3, 0); + Vector3 localBody2Point(0, 5, 0); + decimal penetrationDepth = 1.0f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 1 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mCapsuleBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mCapsuleProxyShape1, mCapsuleProxyShape2)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mCapsuleProxyShape1, mCapsuleProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 2 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mCapsuleBody2, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mCapsuleProxyShape1, mCapsuleProxyShape2)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mCapsuleProxyShape1, mCapsuleProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against selected body 1 and 2 ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mCapsuleBody1, mCapsuleBody2, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mCapsuleProxyShape1, mCapsuleProxyShape2)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mCapsuleProxyShape1, mCapsuleProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + /******************************************************************************** + * Test Capsule (sphere cap) vs Capsule (cylinder side) collision * + *********************************************************************************/ + + transform1 = Transform(Vector3(10, 20, 50), Quaternion::identity()); + transform2 = Transform(Vector3(10, 27, 50), Quaternion::fromEulerAngles(0, 0, rp3d::PI * 0.5f)); + + // Move spheres to collide with each other + mCapsuleBody1->setTransform(transform1); + mCapsuleBody2->setTransform(transform2); + + // ----- Test AABB overlap ----- // + + test(mWorld->testAABBOverlap(mCapsuleBody1, mCapsuleBody2)); + + mOverlapCallback.reset(); + mWorld->testOverlap(mCapsuleBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + mOverlapCallback.reset(); + mWorld->testOverlap(mCapsuleBody2, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + // ----- Test global collision test ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(&mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mCapsuleProxyShape1, mCapsuleProxyShape2)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mCapsuleProxyShape1, mCapsuleProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + + // Test contact points + localBody1Point = Vector3(0, 5, 0); + localBody2Point = Vector3(-3, 0, 0); + penetrationDepth = decimal(1.0); + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 1 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mCapsuleBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mCapsuleProxyShape1, mCapsuleProxyShape2)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mCapsuleProxyShape1, mCapsuleProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 2 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mCapsuleBody2, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mCapsuleProxyShape1, mCapsuleProxyShape2)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mCapsuleProxyShape1, mCapsuleProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against selected body 1 and 2 ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mCapsuleBody1, mCapsuleBody2, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mCapsuleProxyShape1, mCapsuleProxyShape2)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mCapsuleProxyShape1, mCapsuleProxyShape2); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // Reset the init transforms + mCapsuleBody1->setTransform(initTransform1); + mCapsuleBody2->setTransform(initTransform2); + } + + void testCapsuleVsConcaveMeshCollision() { + + Transform initTransform1 = mCapsuleBody1->getTransform(); + Transform initTransform2 = mConcaveMeshBody->getTransform(); + + /******************************************************************************** + * Test Capsule vs Concave Mesh + *********************************************************************************/ + + Transform transform1(Vector3(10, 24.98f, 50), Quaternion::identity()); + Transform transform2(Vector3(10, 20, 50), Quaternion::identity()); + + // Move spheres to collide with each other + mCapsuleBody1->setTransform(transform1); + mConcaveMeshBody->setTransform(transform2); + + // ----- Test AABB overlap ----- // + + test(mWorld->testAABBOverlap(mCapsuleBody1, mConcaveMeshBody)); + + mOverlapCallback.reset(); + mWorld->testOverlap(mCapsuleBody1, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + mOverlapCallback.reset(); + mWorld->testOverlap(mConcaveMeshBody, &mOverlapCallback); + test(mOverlapCallback.hasOverlap()); + + // ----- Test global collision test ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(&mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mCapsuleProxyShape1, mConcaveMeshProxyShape)); + + // Get collision data + const CollisionData* collisionData = mCollisionCallback.getCollisionData(mCapsuleProxyShape1, mConcaveMeshProxyShape); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + + // Test contact points + Vector3 localBody1Point(0, -5, 0); + Vector3 localBody2Point(0, 0, 0); + decimal penetrationDepth = 0.02f; + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 1 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mCapsuleBody1, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mCapsuleProxyShape1, mConcaveMeshProxyShape)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mCapsuleProxyShape1, mConcaveMeshProxyShape); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against body 2 only ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mConcaveMeshBody, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mCapsuleProxyShape1, mConcaveMeshProxyShape)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mCapsuleProxyShape1, mConcaveMeshProxyShape); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // ----- Test collision against selected body 1 and 2 ----- // + + mCollisionCallback.reset(); + mWorld->testCollision(mCapsuleBody1, mConcaveMeshBody, &mCollisionCallback); + + test(mCollisionCallback.areProxyShapesColliding(mCapsuleProxyShape1, mConcaveMeshProxyShape)); + + // Get collision data + collisionData = mCollisionCallback.getCollisionData(mCapsuleProxyShape1, mConcaveMeshProxyShape); + test(collisionData != nullptr); + test(collisionData->getNbContactManifolds() == 1); + test(collisionData->getTotalNbContactPoints() == 1); + + // True if the bodies are swapped in the collision callback response + swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + + // Test contact points + test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, + swappedBodiesCollisionData ? localBody1Point : localBody2Point, + penetrationDepth)); + + // Reset the init transforms + mCapsuleBody1->setTransform(initTransform1); + mConcaveMeshBody->setTransform(initTransform2); + } }; } From 4177044f740301d43f60add7172f698432e9d806 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 26 Feb 2018 07:17:54 +0100 Subject: [PATCH 171/248] Replace testPointInside() and raycast() methods for ConvexMeshShape (do not used GJK anymore) and some small refactoring --- src/collision/PolyhedronMesh.h | 8 + src/collision/ProxyShape.cpp | 2 +- .../narrowphase/GJK/GJKAlgorithm.cpp | 168 -------------- src/collision/narrowphase/GJK/GJKAlgorithm.h | 6 - src/collision/shapes/ConvexMeshShape.cpp | 119 ++++++++-- src/collision/shapes/ConvexMeshShape.h | 9 - src/mathematics/Ray.h | 4 +- src/mathematics/mathematics_functions.cpp | 5 + src/mathematics/mathematics_functions.h | 3 + test/tests/collision/TestPointInside.h | 219 +++++++----------- test/tests/collision/TestRaycast.h | 35 +-- .../mathematics/TestMathematicsFunctions.h | 10 + 12 files changed, 229 insertions(+), 359 deletions(-) diff --git a/src/collision/PolyhedronMesh.h b/src/collision/PolyhedronMesh.h index b8cd1f52..8720a8db 100644 --- a/src/collision/PolyhedronMesh.h +++ b/src/collision/PolyhedronMesh.h @@ -85,6 +85,9 @@ class PolyhedronMesh { /// Return a vertex Vector3 getVertex(uint index) const; + /// Return the number of faces + uint getNbFaces() const; + /// Return a face normal Vector3 getFaceNormal(uint faceIndex) const; @@ -100,6 +103,11 @@ inline uint PolyhedronMesh::getNbVertices() const { return mHalfEdgeStructure.getNbVertices(); } +// Return the number of faces +inline uint PolyhedronMesh::getNbFaces() const { + return mHalfEdgeStructure.getNbFaces(); +} + // Return a face normal inline Vector3 PolyhedronMesh::getFaceNormal(uint faceIndex) const { assert(faceIndex < mHalfEdgeStructure.getNbFaces()); diff --git a/src/collision/ProxyShape.cpp b/src/collision/ProxyShape.cpp index 8847d094..e20ae485 100644 --- a/src/collision/ProxyShape.cpp +++ b/src/collision/ProxyShape.cpp @@ -62,7 +62,7 @@ bool ProxyShape::testPointInside(const Vector3& worldPoint) { * @param ray Ray to use for the raycasting * @param[out] raycastInfo Result of the raycasting that is valid only if the * methods returned true - * @return True if the ray hit the collision shape + * @return True if the ray hits the collision shape */ bool ProxyShape::raycast(const Ray& ray, RaycastInfo& raycastInfo) { diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp index 62685867..a7bc8667 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp @@ -212,171 +212,3 @@ GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhase return GJKResult::INTERPENETRATE; } - - -// Use the GJK Algorithm to find if a point is inside a convex collision shape -bool GJKAlgorithm::testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) { - - Vector3 suppA; // Support point of object A - Vector3 w; // Support point of Minkowski difference A-B - decimal prevDistSquare; - - assert(proxyShape->getCollisionShape()->isConvex()); - - const ConvexShape* shape = static_cast(proxyShape->getCollisionShape()); - - // Support point of object B (object B is a single point) - const Vector3 suppB(localPoint); - - // Create a simplex set - VoronoiSimplex simplex; - - // Initial supporting direction - Vector3 v(1, 1, 1); - - // Initialize the upper bound for the square distance - decimal distSquare = DECIMAL_LARGEST; - - do { - - // Compute the support points for original objects (without margins) A and B - suppA = shape->getLocalSupportPointWithoutMargin(-v); - - // Compute the support point for the Minkowski difference A-B - w = suppA - suppB; - - // Add the new support point to the simplex - simplex.addPoint(w, suppA, suppB); - - // If the simplex is affinely dependent - if (simplex.isAffinelyDependent()) { - - return false; - } - - // Compute the point of the simplex closest to the origin - // If the computation of the closest point fail - if (!simplex.computeClosestPoint(v)) { - - return false; - } - - // Store and update the squared distance of the closest point - prevDistSquare = distSquare; - distSquare = v.lengthSquare(); - - // If the distance to the closest point doesn't improve a lot - if (prevDistSquare - distSquare <= MACHINE_EPSILON * prevDistSquare) { - - return false; - } - } while(!simplex.isFull() && distSquare > MACHINE_EPSILON * - simplex.getMaxLengthSquareOfAPoint()); - - // The point is inside the collision shape - return true; -} - -// Ray casting algorithm agains a convex collision shape using the GJK Algorithm -/// This method implements the GJK ray casting algorithm described by Gino Van Den Bergen in -/// "Ray Casting against General Convex Objects with Application to Continuous Collision Detection". -bool GJKAlgorithm::raycast(const Ray& ray, ProxyShape* proxyShape, RaycastInfo& raycastInfo) { - - assert(proxyShape->getCollisionShape()->isConvex()); - - const ConvexShape* shape = static_cast(proxyShape->getCollisionShape()); - - Vector3 suppA; // Current lower bound point on the ray (starting at ray's origin) - Vector3 suppB; // Support point on the collision shape - const decimal machineEpsilonSquare = MACHINE_EPSILON * MACHINE_EPSILON; - const decimal epsilon = decimal(0.0001); - - // Convert the ray origin and direction into the local-space of the collision shape - Vector3 rayDirection = ray.point2 - ray.point1; - - // If the points of the segment are two close, return no hit - if (rayDirection.lengthSquare() < machineEpsilonSquare) return false; - - Vector3 w; - - // Create a simplex set - VoronoiSimplex simplex; - - Vector3 n(decimal(0.0), decimal(0.0), decimal(0.0)); - decimal lambda = decimal(0.0); - suppA = ray.point1; // Current lower bound point on the ray (starting at ray's origin) - suppB = shape->getLocalSupportPointWithoutMargin(rayDirection); - Vector3 v = suppA - suppB; - decimal vDotW, vDotR; - decimal distSquare = v.lengthSquare(); - int nbIterations = 0; - - // GJK Algorithm loop - while (distSquare > epsilon && nbIterations < MAX_ITERATIONS_GJK_RAYCAST) { - - // Compute the support points - suppB = shape->getLocalSupportPointWithoutMargin(v); - w = suppA - suppB; - - vDotW = v.dot(w); - - if (vDotW > decimal(0)) { - - vDotR = v.dot(rayDirection); - - if (vDotR >= -machineEpsilonSquare) { - return false; - } - else { - - // We have found a better lower bound for the hit point along the ray - lambda = lambda - vDotW / vDotR; - suppA = ray.point1 + lambda * rayDirection; - w = suppA - suppB; - n = v; - } - } - - // Add the new support point to the simplex - if (!simplex.isPointInSimplex(w)) { - simplex.addPoint(w, suppA, suppB); - } - - // Compute the closest point - if (simplex.computeClosestPoint(v)) { - - distSquare = v.lengthSquare(); - } - else { - distSquare = decimal(0.0); - } - - // If the current lower bound distance is larger than the maximum raycasting distance - if (lambda > ray.maxFraction) return false; - - nbIterations++; - } - - // If the origin was inside the shape, we return no hit - if (lambda < MACHINE_EPSILON) return false; - - // Compute the closet points of both objects (without the margins) - Vector3 pointA; - Vector3 pointB; - simplex.computeClosestPointsOfAandB(pointA, pointB); - - // A raycast hit has been found, we fill in the raycast info - raycastInfo.hitFraction = lambda; - raycastInfo.worldPoint = pointB; - raycastInfo.body = proxyShape->getBody(); - raycastInfo.proxyShape = proxyShape; - - if (n.lengthSquare() >= machineEpsilonSquare) { // The normal vector is valid - raycastInfo.worldNormal = n; - } - else { // Degenerated normal vector, we return a zero normal vector - raycastInfo.worldNormal = Vector3(decimal(0), decimal(0), decimal(0)); - } - - return true; -} diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.h b/src/collision/narrowphase/GJK/GJKAlgorithm.h index a9daa897..ac9cd652 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.h +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.h @@ -96,12 +96,6 @@ class GJKAlgorithm { /// Compute a contact info if the two bounding volumes collide. GJKResult testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts); - /// Use the GJK Algorithm to find if a point is inside a convex collision shape - bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape); - - /// Ray casting algorithm agains a convex collision shape using the GJK Algorithm - bool raycast(const Ray& ray, ProxyShape* proxyShape, RaycastInfo& raycastInfo); - #ifdef IS_PROFILING_ACTIVE /// Set the profiler diff --git a/src/collision/shapes/ConvexMeshShape.cpp b/src/collision/shapes/ConvexMeshShape.cpp index 5b6c70d6..d4037a8c 100644 --- a/src/collision/shapes/ConvexMeshShape.cpp +++ b/src/collision/shapes/ConvexMeshShape.cpp @@ -30,9 +30,6 @@ using namespace reactphysics3d; -// TODO : Check in every collision shape that localScalling is used correctly and even with SAT -// algorithm (not only in getLocalSupportPoint***() methods) - // Constructor to initialize with an array of 3D vertices. /// This method creates an internal copy of the input vertices. /** @@ -58,14 +55,14 @@ ConvexMeshShape::ConvexMeshShape(PolyhedronMesh* polyhedronMesh) /// runs in almost constant time. Vector3 ConvexMeshShape::getLocalSupportPointWithoutMargin(const Vector3& direction) const { - double maxDotProduct = DECIMAL_SMALLEST; + decimal maxDotProduct = DECIMAL_SMALLEST; uint indexMaxDotProduct = 0; // For each vertex of the mesh for (uint i=0; igetNbVertices(); i++) { // Compute the dot product of the current vertex - double dotProduct = direction.dot(mPolyhedronMesh->getVertex(i)); + decimal dotProduct = direction.dot(mPolyhedronMesh->getVertex(i)); // If the current dot product is larger than the maximum one if (dotProduct > maxDotProduct) { @@ -83,14 +80,11 @@ Vector3 ConvexMeshShape::getLocalSupportPointWithoutMargin(const Vector3& direct // Recompute the bounds of the mesh void ConvexMeshShape::recalculateBounds() { - // TODO : Only works if the local origin is inside the mesh - // => Make it more robust (init with first vertex of mesh instead) - - mMinBounds.setToZero(); - mMaxBounds.setToZero(); + mMinBounds = mPolyhedronMesh->getVertex(0); + mMaxBounds = mPolyhedronMesh->getVertex(0); // For each vertex of the mesh - for (uint i=0; igetNbVertices(); i++) { + for (uint i=1; igetNbVertices(); i++) { if (mPolyhedronMesh->getVertex(i).x > mMaxBounds.x) mMaxBounds.x = mPolyhedronMesh->getVertex(i).x; if (mPolyhedronMesh->getVertex(i).x < mMinBounds.x) mMinBounds.x = mPolyhedronMesh->getVertex(i).x; @@ -105,14 +99,105 @@ void ConvexMeshShape::recalculateBounds() { // Apply the local scaling factor mMaxBounds = mMaxBounds * mScaling; mMinBounds = mMinBounds * mScaling; - - // Add the object margin to the bounds - mMaxBounds += Vector3(mMargin, mMargin, mMargin); - mMinBounds -= Vector3(mMargin, mMargin, mMargin); } // Raycast method with feedback information +/// This method implements the technique in the book "Real-time Collision Detection" by +/// Christer Ericson. bool ConvexMeshShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, MemoryAllocator& allocator) const { - return proxyShape->mBody->mWorld.mCollisionDetection.mNarrowPhaseGJKAlgorithm.raycast( - ray, proxyShape, raycastInfo); + + // Ray direction + Vector3 direction = ray.point2 - ray.point1; + + decimal tMin = decimal(0.0); + decimal tMax = ray.maxFraction; + Vector3 currentFaceNormal; + bool isIntersectionFound = false; + + const HalfEdgeStructure& halfEdgeStructure = mPolyhedronMesh->getHalfEdgeStructure(); + + // For each face of the convex mesh + for (uint f=0; f < mPolyhedronMesh->getNbFaces(); f++) { + + const HalfEdgeStructure::Face& face = halfEdgeStructure.getFace(f); + const Vector3 faceNormal = mPolyhedronMesh->getFaceNormal(f); + const HalfEdgeStructure::Vertex& faceVertex = halfEdgeStructure.getVertex(face.faceVertices[0]); + const Vector3 facePoint = mPolyhedronMesh->getVertex(faceVertex.vertexPointIndex); + decimal denom = faceNormal.dot(direction); + decimal planeD = faceNormal.dot(facePoint); + decimal dist = planeD - faceNormal.dot(ray.point1); + + // If ray is parallel to the face + if (denom == decimal(0.0)) { + + // If ray is outside the clipping face, we return no intersection + if (dist < decimal(0.0)) return false; + } + else { + + // Compute the intersection between the ray and the current face plane + decimal t = dist / denom; + + // Update the current ray intersection by clipping it with the current face plane + // If the place faces the ray + if (denom < decimal(0.0)) { + // Clip the current ray intersection as it enters the convex mesh + if (t > tMin) { + tMin = t; + currentFaceNormal = faceNormal; + isIntersectionFound = true; + } + } + else { + // Clip the current ray intersection as it exits the convex mesh + if (t < tMax) tMax = t; + } + + // If the ray intersection with the convex mesh becomes empty, report no intersection + if (tMin > tMax) return false; + } + } + + if (isIntersectionFound) { + + // The ray intersects with the convex mesh + assert(tMin >= decimal(0.0)); + assert(tMax <= ray.maxFraction); + assert(tMin <= tMax); + assert(currentFaceNormal.lengthSquare() > decimal(0.0)); + + // The ray intersects the three slabs, we compute the hit point + Vector3 localHitPoint = ray.point1 + tMin * direction; + + raycastInfo.hitFraction = tMin; + raycastInfo.body = proxyShape->getBody(); + raycastInfo.proxyShape = proxyShape; + raycastInfo.worldPoint = localHitPoint; + raycastInfo.worldNormal = currentFaceNormal; + + return true; + } + + return false; } + +// Return true if a point is inside the collision shape +bool ConvexMeshShape::testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const { + + const HalfEdgeStructure& halfEdgeStructure = mPolyhedronMesh->getHalfEdgeStructure(); + + // For each face plane of the convex mesh + for (uint f=0; f < mPolyhedronMesh->getNbFaces(); f++) { + + const HalfEdgeStructure::Face& face = halfEdgeStructure.getFace(f); + const Vector3 faceNormal = mPolyhedronMesh->getFaceNormal(f); + const HalfEdgeStructure::Vertex& faceVertex = halfEdgeStructure.getVertex(face.faceVertices[0]); + const Vector3 facePoint = mPolyhedronMesh->getVertex(faceVertex.vertexPointIndex); + + // If the point is out of the face plane, it is outside of the convex mesh + if (computePointToPlaneDistance(localPoint, faceNormal, facePoint) > decimal(0.0)) return false; + } + + return true; +} + diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index a24aa85b..49d3f773 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -173,15 +173,6 @@ inline void ConvexMeshShape::computeLocalInertiaTensor(Matrix3x3& tensor, decima 0.0, 0.0, factor * (xSquare + ySquare)); } -// Return true if a point is inside the collision shape -inline bool ConvexMeshShape::testPointInside(const Vector3& localPoint, - ProxyShape* proxyShape) const { - - // Use the GJK algorithm to test if the point is inside the convex mesh - return proxyShape->mBody->mWorld.mCollisionDetection. - mNarrowPhaseGJKAlgorithm.testPointInside(localPoint, proxyShape); -} - // Return the number of faces of the polyhedron inline uint ConvexMeshShape::getNbFaces() const { return mPolyhedronMesh->getHalfEdgeStructure().getNbFaces(); diff --git a/src/mathematics/Ray.h b/src/mathematics/Ray.h index 938e8960..8efc7416 100644 --- a/src/mathematics/Ray.h +++ b/src/mathematics/Ray.h @@ -44,10 +44,10 @@ struct Ray { // -------------------- Attributes -------------------- // - /// First point of the ray (origin) + /// First point of the ray (origin) in world-space Vector3 point1; - /// Second point of the ray + /// Second point of the ray in world-space Vector3 point2; /// Maximum fraction value diff --git a/src/mathematics/mathematics_functions.cpp b/src/mathematics/mathematics_functions.cpp index 99640c58..4494e1ec 100755 --- a/src/mathematics/mathematics_functions.cpp +++ b/src/mathematics/mathematics_functions.cpp @@ -375,6 +375,11 @@ Vector3 reactphysics3d::projectPointOntoPlane(const Vector3& point, const Vector return point - unitPlaneNormal.dot(point - planePoint) * unitPlaneNormal; } +// Return the distance between a point and a plane (the plane normal must be normalized) +decimal reactphysics3d::computePointToPlaneDistance(const Vector3& point, const Vector3& planeNormal, const Vector3& planePoint) { + return planeNormal.dot(point - planePoint); +} + // Return true if the given number is prime bool reactphysics3d::isPrimeNumber(int number) { diff --git a/src/mathematics/mathematics_functions.h b/src/mathematics/mathematics_functions.h index d0968904..62c10c74 100755 --- a/src/mathematics/mathematics_functions.h +++ b/src/mathematics/mathematics_functions.h @@ -123,6 +123,9 @@ List clipPolygonWithPlanes(const List& polygonVertices, const /// Project a point onto a plane that is given by a point and its unit length normal Vector3 projectPointOntoPlane(const Vector3& point, const Vector3& planeNormal, const Vector3& planePoint); +/// Return the distance between a point and a plane (the plane normal must be normalized) +decimal computePointToPlaneDistance(const Vector3& point, const Vector3& planeNormal, const Vector3& planePoint); + /// Return true if the given number is prime bool isPrimeNumber(int number); diff --git a/test/tests/collision/TestPointInside.h b/test/tests/collision/TestPointInside.h index afdb415c..540f9f03 100644 --- a/test/tests/collision/TestPointInside.h +++ b/test/tests/collision/TestPointInside.h @@ -59,12 +59,17 @@ class TestPointInside : public Test { CollisionBody* mCylinderBody; CollisionBody* mCompoundBody; + Vector3 mConvexMeshCubeVertices[8]; + int mConvexMeshCubeIndices[24]; + PolygonVertexArray* mConvexMeshPolygonVertexArray; + PolyhedronMesh* mConvexMeshPolyhedronMesh; + PolygonVertexArray::PolygonFace* mConvexMeshPolygonFaces; + // Collision shapes BoxShape* mBoxShape; SphereShape* mSphereShape; CapsuleShape* mCapsuleShape; ConvexMeshShape* mConvexMeshShape; - ConvexMeshShape* mConvexMeshShapeBodyEdgesInfo; // Transform Transform mBodyTransform; @@ -76,10 +81,7 @@ class TestPointInside : public Test { ProxyShape* mBoxProxyShape; ProxyShape* mSphereProxyShape; ProxyShape* mCapsuleProxyShape; - ProxyShape* mConeProxyShape; ProxyShape* mConvexMeshProxyShape; - ProxyShape* mConvexMeshProxyShapeEdgesInfo; - ProxyShape* mCylinderProxyShape; public : @@ -104,6 +106,7 @@ class TestPointInside : public Test { mConvexMeshBody = mWorld->createCollisionBody(mBodyTransform); mConvexMeshBodyEdgesInfo = mWorld->createCollisionBody(mBodyTransform); mCylinderBody = mWorld->createCollisionBody(mBodyTransform); + mConvexMeshBody = mWorld->createCollisionBody(mBodyTransform); mCompoundBody = mWorld->createCollisionBody(mBodyTransform); // Collision shape transform @@ -121,51 +124,44 @@ class TestPointInside : public Test { mSphereShape = new SphereShape(3); mSphereProxyShape = mSphereBody->addCollisionShape(mSphereShape, mShapeTransform); - mCapsuleShape = new CapsuleShape(2, 10); + mCapsuleShape = new CapsuleShape(3, 10); mCapsuleProxyShape = mCapsuleBody->addCollisionShape(mCapsuleShape, mShapeTransform); - // TODO : Create convex mesh shape with new way (polyhedron mesh) to add test again - /*mConvexMeshShape = new ConvexMeshShape(0.0); // Box of dimension (2, 3, 4) - mConvexMeshShape->addVertex(Vector3(-2, -3, -4)); - mConvexMeshShape->addVertex(Vector3(2, -3, -4)); - mConvexMeshShape->addVertex(Vector3(2, -3, 4)); - mConvexMeshShape->addVertex(Vector3(-2, -3, 4)); - mConvexMeshShape->addVertex(Vector3(-2, 3, -4)); - mConvexMeshShape->addVertex(Vector3(2, 3, -4)); - mConvexMeshShape->addVertex(Vector3(2, 3, 4)); - mConvexMeshShape->addVertex(Vector3(-2, 3, 4)); - mConvexMeshProxyShape = mConvexMeshBody->addCollisionShape(mConvexMeshShape, mShapeTransform); + mConvexMeshCubeVertices[0] = Vector3(-2, -3, 4); + mConvexMeshCubeVertices[1] = Vector3(2, -3, 4); + mConvexMeshCubeVertices[2] = Vector3(2, -3, -4); + mConvexMeshCubeVertices[3] = Vector3(-2, -3, -4); + mConvexMeshCubeVertices[4] = Vector3(-2, 3, 4); + mConvexMeshCubeVertices[5] = Vector3(2, 3, 4); + mConvexMeshCubeVertices[6] = Vector3(2, 3, -4); + mConvexMeshCubeVertices[7] = Vector3(-2, 3, -4); - mConvexMeshShapeBodyEdgesInfo = new ConvexMeshShape(0.0); - mConvexMeshShapeBodyEdgesInfo->addVertex(Vector3(-2, -3, -4)); - mConvexMeshShapeBodyEdgesInfo->addVertex(Vector3(2, -3, -4)); - mConvexMeshShapeBodyEdgesInfo->addVertex(Vector3(2, -3, 4)); - mConvexMeshShapeBodyEdgesInfo->addVertex(Vector3(-2, -3, 4)); - mConvexMeshShapeBodyEdgesInfo->addVertex(Vector3(-2, 3, -4)); - mConvexMeshShapeBodyEdgesInfo->addVertex(Vector3(2, 3, -4)); - mConvexMeshShapeBodyEdgesInfo->addVertex(Vector3(2, 3, 4)); - mConvexMeshShapeBodyEdgesInfo->addVertex(Vector3(-2, 3, 4)); - mConvexMeshShapeBodyEdgesInfo->addEdge(0, 1); - mConvexMeshShapeBodyEdgesInfo->addEdge(1, 2); - mConvexMeshShapeBodyEdgesInfo->addEdge(2, 3); - mConvexMeshShapeBodyEdgesInfo->addEdge(0, 3); - mConvexMeshShapeBodyEdgesInfo->addEdge(4, 5); - mConvexMeshShapeBodyEdgesInfo->addEdge(5, 6); - mConvexMeshShapeBodyEdgesInfo->addEdge(6, 7); - mConvexMeshShapeBodyEdgesInfo->addEdge(4, 7); - mConvexMeshShapeBodyEdgesInfo->addEdge(0, 4); - mConvexMeshShapeBodyEdgesInfo->addEdge(1, 5); - mConvexMeshShapeBodyEdgesInfo->addEdge(2, 6); - mConvexMeshShapeBodyEdgesInfo->addEdge(3, 7); - mConvexMeshShapeBodyEdgesInfo->setIsEdgesInformationUsed(true); - mConvexMeshProxyShapeEdgesInfo = mConvexMeshBodyEdgesInfo->addCollisionShape( - mConvexMeshShapeBodyEdgesInfo, - mShapeTransform); - */ + mConvexMeshCubeIndices[0] = 0; mConvexMeshCubeIndices[1] = 3; mConvexMeshCubeIndices[2] = 2; mConvexMeshCubeIndices[3] = 1; + mConvexMeshCubeIndices[4] = 4; mConvexMeshCubeIndices[5] = 5; mConvexMeshCubeIndices[6] = 6; mConvexMeshCubeIndices[7] = 7; + mConvexMeshCubeIndices[8] = 0; mConvexMeshCubeIndices[9] = 1; mConvexMeshCubeIndices[10] = 5; mConvexMeshCubeIndices[11] = 4; + mConvexMeshCubeIndices[12] = 1; mConvexMeshCubeIndices[13] = 2; mConvexMeshCubeIndices[14] = 6; mConvexMeshCubeIndices[15] = 5; + mConvexMeshCubeIndices[16] = 2; mConvexMeshCubeIndices[17] = 3; mConvexMeshCubeIndices[18] = 7; mConvexMeshCubeIndices[19] = 6; + mConvexMeshCubeIndices[20] = 0; mConvexMeshCubeIndices[21] = 4; mConvexMeshCubeIndices[22] = 7; mConvexMeshCubeIndices[23] = 3; + + mConvexMeshPolygonFaces = new PolygonVertexArray::PolygonFace[6]; + PolygonVertexArray::PolygonFace* face = mConvexMeshPolygonFaces; + for (int f = 0; f < 6; f++) { + face->indexBase = f * 4; + face->nbVertices = 4; + face++; + } + mConvexMeshPolygonVertexArray = new PolygonVertexArray(8, &(mConvexMeshCubeVertices[0]), sizeof(Vector3), + &(mConvexMeshCubeIndices[0]), sizeof(int), 6, mConvexMeshPolygonFaces, + PolygonVertexArray::VertexDataType::VERTEX_FLOAT_TYPE, + PolygonVertexArray::IndexDataType::INDEX_INTEGER_TYPE); + mConvexMeshPolyhedronMesh = new PolyhedronMesh(mConvexMeshPolygonVertexArray); + mConvexMeshShape = new ConvexMeshShape(mConvexMeshPolyhedronMesh); + Transform convexMeshTransform(Vector3(10, 0, 0), Quaternion::identity()); + mConvexMeshProxyShape = mConvexMeshBody->addCollisionShape(mConvexMeshShape, mShapeTransform); // Compound shape is a capsule and a sphere Vector3 positionShape2(Vector3(4, 2, -3)); - Quaternion orientationShape2 = Quaternion::fromEulerAngles(-3 *PI / 8, 1.5 * PI/ 3, PI / 13); + Quaternion orientationShape2 = Quaternion::fromEulerAngles(-3 * PI / 8, 1.5 * PI/ 3, PI / 13); Transform shapeTransform2(positionShape2, orientationShape2); mLocalShape2ToWorld = mBodyTransform * shapeTransform2; mCompoundBody->addCollisionShape(mCapsuleShape, mShapeTransform); @@ -177,8 +173,10 @@ class TestPointInside : public Test { delete mBoxShape; delete mSphereShape; delete mCapsuleShape; - //delete mConvexMeshShape; - //delete mConvexMeshShapeBodyEdgesInfo; + delete mConvexMeshShape; + delete mConvexMeshPolygonFaces; + delete mConvexMeshPolygonVertexArray; + delete mConvexMeshPolyhedronMesh; } /// Run the tests @@ -328,24 +326,24 @@ class TestPointInside : public Test { test(mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(-1, 2, 0.4))); test(mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(1.3, 1, 1.5))); - test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(0, -7.1, 0))); - test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(0, 7.1, 0))); - test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 2.1))); - test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(0, 0, -2.1))); - test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(2.1, 0, 0))); - test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(-2.1, 0, 0))); - test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(0, 5, 2.1))); - test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(0, 5, -2.1))); - test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(2.1, 5, 0))); - test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(-2.1, 5, 0))); - test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(1.5, 5, 1.6))); - test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(1.5, 5, -1.7))); - test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(0, -5, 2.1))); - test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(0, -5, -2.1))); - test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(2.1, -5, 0))); - test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(-2.1, -5, 0))); - test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(1.5, -5, 1.6))); - test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(1.5, -5, -1.7))); + test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(0, -13.1, 0))); + test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(0, 13.1, 0))); + test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 3.1))); + test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(0, 0, -3.1))); + test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(3.1, 0, 0))); + test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(-3.1, 0, 0))); + test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(0, 5, 3.1))); + test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(0, 5, -3.1))); + test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(3.1, 5, 0))); + test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(-3.1, 5, 0))); + test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(2.5, 5, 2.6))); + test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(2.5, 5, -2.7))); + test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(0, -5, 3.1))); + test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(0, -5, -3.1))); + test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(3.1, -5, 0))); + test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(-3.1, -5, 0))); + test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(2.5, -5, 2.6))); + test(!mCapsuleBody->testPointInside(mLocalShapeToWorld * Vector3(2.5, -5, -2.7))); // Tests with ProxyCapsuleShape test(mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 0))); @@ -375,33 +373,30 @@ class TestPointInside : public Test { test(mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-1, 2, 0.4))); test(mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(1.3, 1, 1.5))); - test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, -7.1, 0))); - test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 7.1, 0))); - test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 2.1))); - test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 0, -2.1))); - test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(2.1, 0, 0))); - test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-2.1, 0, 0))); - test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 5, 2.1))); - test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 5, -2.1))); - test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(2.1, 5, 0))); - test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-2.1, 5, 0))); - test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(1.5, 5, 1.6))); - test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(1.5, 5, -1.7))); - test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, -5, 2.1))); - test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, -5, -2.1))); - test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(2.1, -5, 0))); - test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-2.1, -5, 0))); - test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(1.5, -5, 1.6))); - test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(1.5, -5, -1.7))); + test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, -13.1, 0))); + test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 13.1, 0))); + test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 3.1))); + test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 0, -3.1))); + test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(3.1, 0, 0))); + test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-3.1, 0, 0))); + test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 5, 3.1))); + test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, 5, -3.1))); + test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(3.1, 5, 0))); + test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-3.1, 5, 0))); + test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(2.5, 5, 2.6))); + test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(2.5, 5, -2.7))); + test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, -5, 3.1))); + test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(0, -5, -3.1))); + test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(3.1, -5, 0))); + test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-3.1, -5, 0))); + test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(2.5, -5, 2.6))); + test(!mCapsuleProxyShape->testPointInside(mLocalShapeToWorld * Vector3(2.5, -5, -2.7))); } /// Test the ProxyConvexMeshShape::testPointInside() and /// CollisionBody::testPointInside() methods void testConvexMesh() { - // ----- Tests without using edges information ----- // - - /* // Tests with CollisionBody test(mConvexMeshBody->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 0))); test(mConvexMeshBody->testPointInside(mLocalShapeToWorld * Vector3(-1.9, 0, 0))); @@ -453,68 +448,12 @@ class TestPointInside : public Test { test(!mConvexMeshProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-10, -2, -1.5))); test(!mConvexMeshProxyShape->testPointInside(mLocalShapeToWorld * Vector3(-1, 4, -2.5))); test(!mConvexMeshProxyShape->testPointInside(mLocalShapeToWorld * Vector3(1, -2, 4.5))); - - // ----- Tests using edges information ----- // - - // Tests with CollisionBody - test(mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 0))); - test(mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(-1.9, 0, 0))); - test(mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(1.9, 0, 0))); - test(mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(0, -2.9, 0))); - test(mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(0, 2.9, 0))); - test(mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(0, 0, -3.9))); - test(mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 3.9))); - test(mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(-1.9, -2.9, -3.9))); - test(mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(1.9, 2.9, 3.9))); - test(mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(-1, -2, -1.5))); - test(mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(-1, 2, -2.5))); - test(mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(1, -2, 3.5))); - - test(!mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(-2.1, 0, 0))); - test(!mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(2.1, 0, 0))); - test(!mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(0, -3.1, 0))); - test(!mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(0, 3.1, 0))); - test(!mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(0, 0, -4.1))); - test(!mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 4.1))); - test(!mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(-2.1, -3.1, -4.1))); - test(!mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(2.1, 3.1, 4.1))); - test(!mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(-10, -2, -1.5))); - test(!mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(-1, 4, -2.5))); - test(!mConvexMeshBodyEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(1, -2, 4.5))); - - // Tests with ProxyConvexMeshShape - test(mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 0))); - test(mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(-1.9, 0, 0))); - test(mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(1.9, 0, 0))); - test(mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(0, -2.9, 0))); - test(mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(0, 2.9, 0))); - test(mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(0, 0, -3.9))); - test(mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 3.9))); - test(mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(-1.9, -2.9, -3.9))); - test(mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(1.9, 2.9, 3.9))); - test(mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(-1, -2, -1.5))); - test(mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(-1, 2, -2.5))); - test(mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(1, -2, 3.5))); - - test(!mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(-2.1, 0, 0))); - test(!mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(2.1, 0, 0))); - test(!mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(0, -3.1, 0))); - test(!mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(0, 3.1, 0))); - test(!mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(0, 0, -4.1))); - test(!mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 4.1))); - test(!mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(-2.1, -3.1, -4.1))); - test(!mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(2.1, 3.1, 4.1))); - test(!mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(-10, -2, -1.5))); - test(!mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(-1, 4, -2.5))); - test(!mConvexMeshProxyShapeEdgesInfo->testPointInside(mLocalShapeToWorld * Vector3(1, -2, 4.5))); - */ } /// Test the CollisionBody::testPointInside() method void testCompound() { // Points on the capsule - // TODO : Previous it was a cylinder (not a capsule). Maybe those tests are wrong now test(mCompoundBody->testPointInside(mLocalShapeToWorld * Vector3(0, 0, 0))); test(mCompoundBody->testPointInside(mLocalShapeToWorld * Vector3(0, 3.9, 0))); test(mCompoundBody->testPointInside(mLocalShapeToWorld * Vector3(0, -3.9, 0))); diff --git a/test/tests/collision/TestRaycast.h b/test/tests/collision/TestRaycast.h index 3bae090c..60d3068b 100644 --- a/test/tests/collision/TestRaycast.h +++ b/test/tests/collision/TestRaycast.h @@ -213,25 +213,26 @@ class TestRaycast : public Test { mPolyhedronVertices[0] = Vector3(-2, -3, 4); mPolyhedronVertices[1] = Vector3(2, -3, 4); - mPolyhedronVertices[2] = Vector3(2, 3, 4); - mPolyhedronVertices[3] = Vector3(-2, 3, 4); - mPolyhedronVertices[4] = Vector3(2, -3, -4); - mPolyhedronVertices[5] = Vector3(2, 3, -4); - mPolyhedronVertices[6] = Vector3(-2, 3, -4); - mPolyhedronVertices[7] = Vector3(-2, -3, -4); + mPolyhedronVertices[2] = Vector3(2, -3, -4); + mPolyhedronVertices[3] = Vector3(-2, -3, -4); + mPolyhedronVertices[4] = Vector3(-2, 3, 4); + mPolyhedronVertices[5] = Vector3(2, 3, 4); + mPolyhedronVertices[6] = Vector3(2, 3, -4); + mPolyhedronVertices[7] = Vector3(-2, 3, -4); - mPolyhedronIndices[0] = 0; mPolyhedronIndices[1] = 1; mPolyhedronIndices[2] = 2; mPolyhedronIndices[3] = 3; - mPolyhedronIndices[4] = 1; mPolyhedronIndices[5] = 4; mPolyhedronIndices[6] = 5; mPolyhedronIndices[7] = 2; - mPolyhedronIndices[8] = 4; mPolyhedronIndices[9] = 7; mPolyhedronIndices[10] = 6; mPolyhedronIndices[11] = 5; - mPolyhedronIndices[12] = 0; mPolyhedronIndices[13] = 3; mPolyhedronIndices[14] = 6; mPolyhedronIndices[15] = 7; - mPolyhedronIndices[16] = 2; mPolyhedronIndices[17] = 5; mPolyhedronIndices[18] = 6; mPolyhedronIndices[19] = 3; - mPolyhedronIndices[20] = 1; mPolyhedronIndices[21] = 0; mPolyhedronIndices[22] = 7; mPolyhedronIndices[23] = 4; + mPolyhedronIndices[0] = 0; mPolyhedronIndices[1] = 3; mPolyhedronIndices[2] = 2; mPolyhedronIndices[3] = 1; + mPolyhedronIndices[4] = 4; mPolyhedronIndices[5] = 5; mPolyhedronIndices[6] = 6; mPolyhedronIndices[7] = 7; + mPolyhedronIndices[8] = 0; mPolyhedronIndices[9] = 1; mPolyhedronIndices[10] = 5; mPolyhedronIndices[11] = 4; + mPolyhedronIndices[12] = 1; mPolyhedronIndices[13] = 2; mPolyhedronIndices[14] = 6; mPolyhedronIndices[15] = 5; + mPolyhedronIndices[16] = 2; mPolyhedronIndices[17] = 3; mPolyhedronIndices[18] = 7; mPolyhedronIndices[19] = 6; + mPolyhedronIndices[20] = 0; mPolyhedronIndices[21] = 4; mPolyhedronIndices[22] = 7; mPolyhedronIndices[23] = 3; // Polygon faces descriptions for the polyhedron - for (int f=0; f < 8; f++) { - PolygonVertexArray::PolygonFace& face = mPolygonFaces[f]; - face.indexBase = f * 4; - face.nbVertices = 4; + PolygonVertexArray::PolygonFace* face = mPolygonFaces; + for (int f = 0; f < 6; f++) { + face->indexBase = f * 4; + face->nbVertices = 4; + face++; } // Create the polygon vertex array @@ -1302,12 +1303,14 @@ class TestRaycast : public Test { Vector3 point2 = mLocalShapeToWorld * Vector3(1, 2, -4); Ray ray(point1, point2); Vector3 hitPoint = mLocalShapeToWorld * Vector3(1, 2, 4); + Transform inverse = mLocalShapeToWorld.getInverse(); mCallback.shapeToTest = mConvexMeshProxyShape; // CollisionWorld::raycast() mCallback.reset(); mWorld->raycast(ray, &mCallback); + Vector3 localTest = inverse * mCallback.raycastInfo.worldPoint; test(mCallback.isHit); test(mCallback.raycastInfo.body == mConvexMeshBody); test(mCallback.raycastInfo.proxyShape == mConvexMeshProxyShape); diff --git a/test/tests/mathematics/TestMathematicsFunctions.h b/test/tests/mathematics/TestMathematicsFunctions.h index b76cb78c..5af12e60 100644 --- a/test/tests/mathematics/TestMathematicsFunctions.h +++ b/test/tests/mathematics/TestMathematicsFunctions.h @@ -103,6 +103,16 @@ class TestMathematicsFunctions : public Test { test(!sameSign(4, -7)); test(!sameSign(-4, 53)); + // Test computePointToPlaneDistance() + Vector3 p(8, 4, 0); + Vector3 n1(1, 0, 0); + Vector3 n2(-1, 0, 0); + Vector3 q1(1, 54, 0); + Vector3 q2(8, 17, 0); + test(approxEqual(computePointToPlaneDistance(q1, n1, p), decimal(-7))); + test(approxEqual(computePointToPlaneDistance(q1, n2, p), decimal(7))); + test(approxEqual(computePointToPlaneDistance(q2, n2, p), decimal(0.0))); + // Test computeBarycentricCoordinatesInTriangle() Vector3 a(0, 0, 0); Vector3 b(5, 0, 0); From cd2bc9665ec65ee93f2902e7faa0bf86d873ba60 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Sun, 4 Mar 2018 19:10:32 +0100 Subject: [PATCH 172/248] Add WorldSettings class for world configuration settings --- src/body/RigidBody.cpp | 2 +- src/collision/CollisionDetection.cpp | 12 ++-- src/collision/ContactManifold.cpp | 8 ++- src/collision/ContactManifold.h | 5 +- src/collision/ContactManifoldSet.cpp | 8 +-- src/collision/ContactManifoldSet.h | 9 ++- src/configuration.h | 98 +++++++++++++++------------- src/constraint/ContactPoint.cpp | 5 +- src/constraint/ContactPoint.h | 9 ++- src/engine/CollisionWorld.cpp | 4 +- src/engine/CollisionWorld.h | 5 +- src/engine/ContactSolver.cpp | 6 +- src/engine/ContactSolver.h | 5 +- src/engine/DynamicsWorld.cpp | 18 ++--- src/engine/DynamicsWorld.h | 2 +- src/engine/Material.cpp | 8 +-- src/engine/Material.h | 2 +- src/engine/OverlappingPair.cpp | 9 +-- src/engine/OverlappingPair.h | 5 +- src/memory/SingleFrameAllocator.cpp | 2 +- src/memory/SingleFrameAllocator.h | 3 + testbed/src/Scene.h | 13 ++-- 22 files changed, 134 insertions(+), 104 deletions(-) diff --git a/src/body/RigidBody.cpp b/src/body/RigidBody.cpp index 5e5a67c7..4d79f186 100644 --- a/src/body/RigidBody.cpp +++ b/src/body/RigidBody.cpp @@ -41,7 +41,7 @@ using namespace reactphysics3d; RigidBody::RigidBody(const Transform& transform, CollisionWorld& world, bodyindex id) : CollisionBody(transform, world, id), mArrayIndex(0), mInitMass(decimal(1.0)), mCenterOfMassLocal(0, 0, 0), mCenterOfMassWorld(transform.getPosition()), - mIsGravityEnabled(true), mLinearDamping(decimal(0.0)), mAngularDamping(decimal(0.0)), + mIsGravityEnabled(true), mMaterial(world.mConfig), mLinearDamping(decimal(0.0)), mAngularDamping(decimal(0.0)), mJointsList(nullptr), mIsCenterOfMassSetByUser(false), mIsInertiaTensorSetByUser(false) { // Compute the inverse mass diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index 32269336..ffbc56c7 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -325,7 +325,7 @@ void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, Pro // Create the overlapping pair and add it into the set of overlapping pairs OverlappingPair* newPair = new (mMemoryManager.allocate(MemoryManager::AllocationType::Pool, sizeof(OverlappingPair))) OverlappingPair(shape1, shape2, mMemoryManager.getPoolAllocator(), - mMemoryManager.getSingleFrameAllocator()); + mMemoryManager.getSingleFrameAllocator(), mWorld->mConfig); assert(newPair != nullptr); mOverlappingPairs.add(Pair, OverlappingPair*>(pairID, newPair)); @@ -570,7 +570,7 @@ bool CollisionDetection::testOverlap(CollisionBody* body1, CollisionBody* body2) // Create a temporary overlapping pair OverlappingPair pair(body1ProxyShape, body2ProxyShape, mMemoryManager.getPoolAllocator(), - mMemoryManager.getPoolAllocator()); + mMemoryManager.getPoolAllocator(), mWorld->mConfig); // Compute the middle-phase collision detection between the two shapes NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); @@ -666,7 +666,7 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl // Create a temporary overlapping pair OverlappingPair pair(bodyProxyShape, proxyShape, mMemoryManager.getPoolAllocator(), - mMemoryManager.getPoolAllocator()); + mMemoryManager.getPoolAllocator(), mWorld->mConfig); // Compute the middle-phase collision detection between the two shapes NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); @@ -751,7 +751,7 @@ void CollisionDetection::testCollision(CollisionBody* body1, CollisionBody* body // Create a temporary overlapping pair OverlappingPair pair(body1ProxyShape, body2ProxyShape, mMemoryManager.getPoolAllocator(), - mMemoryManager.getPoolAllocator()); + mMemoryManager.getPoolAllocator(), mWorld->mConfig); // Compute the middle-phase collision detection between the two shapes NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); @@ -844,7 +844,7 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c // Create a temporary overlapping pair OverlappingPair pair(bodyProxyShape, proxyShape, mMemoryManager.getPoolAllocator(), - mMemoryManager.getPoolAllocator()); + mMemoryManager.getPoolAllocator(), mWorld->mConfig); // Compute the middle-phase collision detection between the two shapes NarrowPhaseInfo* narrowPhaseInfo = computeMiddlePhaseForProxyShapes(&pair); @@ -919,7 +919,7 @@ void CollisionDetection::testCollision(CollisionCallback* callback) { // Create a new overlapping pair so that we do not work on the original one OverlappingPair pair(originalPair->getShape1(), originalPair->getShape2(), mMemoryManager.getPoolAllocator(), - mMemoryManager.getPoolAllocator()); + mMemoryManager.getPoolAllocator(), mWorld->mConfig); ProxyShape* shape1 = pair.getShape1(); ProxyShape* shape2 = pair.getShape2(); diff --git a/src/collision/ContactManifold.cpp b/src/collision/ContactManifold.cpp index ba1bcb1e..06374734 100644 --- a/src/collision/ContactManifold.cpp +++ b/src/collision/ContactManifold.cpp @@ -30,11 +30,13 @@ using namespace reactphysics3d; // Constructor -ContactManifold::ContactManifold(const ContactManifoldInfo* manifoldInfo, ProxyShape* shape1, ProxyShape* shape2, MemoryAllocator& memoryAllocator) +ContactManifold::ContactManifold(const ContactManifoldInfo* manifoldInfo, ProxyShape* shape1, ProxyShape* shape2, + MemoryAllocator& memoryAllocator, const WorldSettings& worldSettings) : mShape1(shape1), mShape2(shape2), mContactPoints(nullptr), mNbContactPoints(0), mFrictionImpulse1(0.0), mFrictionImpulse2(0.0), mFrictionTwistImpulse(0.0), mIsAlreadyInIsland(false), - mMemoryAllocator(memoryAllocator), mNext(nullptr), mPrevious(nullptr), mIsObsolete(false) { + mMemoryAllocator(memoryAllocator), mNext(nullptr), mPrevious(nullptr), mIsObsolete(false), + mWorldSettings(worldSettings) { // For each contact point info in the manifold const ContactPointInfo* pointInfo = manifoldInfo->getFirstContactPointInfo(); @@ -102,7 +104,7 @@ void ContactManifold::addContactPoint(const ContactPointInfo* contactPointInfo) assert(contactPointInfo != nullptr); // Create the new contact point - ContactPoint* contactPoint = new (mMemoryAllocator.allocate(sizeof(ContactPoint))) ContactPoint(contactPointInfo); + ContactPoint* contactPoint = new (mMemoryAllocator.allocate(sizeof(ContactPoint))) ContactPoint(contactPointInfo, mWorldSettings); // Add the new contact point into the manifold contactPoint->setNext(mContactPoints); diff --git a/src/collision/ContactManifold.h b/src/collision/ContactManifold.h index eea392d5..ab0afe5f 100644 --- a/src/collision/ContactManifold.h +++ b/src/collision/ContactManifold.h @@ -139,6 +139,9 @@ class ContactManifold { /// True if the contact manifold is obsolete bool mIsObsolete; + /// World settings + const WorldSettings& mWorldSettings; + // -------------------- Methods -------------------- // /// Return true if the contact manifold has already been added into an island @@ -216,7 +219,7 @@ class ContactManifold { /// Constructor ContactManifold(const ContactManifoldInfo* manifoldInfo, ProxyShape* shape1, ProxyShape* shape2, - MemoryAllocator& memoryAllocator); + MemoryAllocator& memoryAllocator, const WorldSettings& worldSettings); /// Destructor ~ContactManifold(); diff --git a/src/collision/ContactManifoldSet.cpp b/src/collision/ContactManifoldSet.cpp index c63e6a11..c60f01f6 100644 --- a/src/collision/ContactManifoldSet.cpp +++ b/src/collision/ContactManifoldSet.cpp @@ -30,9 +30,9 @@ using namespace reactphysics3d; // Constructor ContactManifoldSet::ContactManifoldSet(ProxyShape* shape1, ProxyShape* shape2, - MemoryAllocator& memoryAllocator) + MemoryAllocator& memoryAllocator, const WorldSettings& worldSettings) : mNbManifolds(0), mShape1(shape1), - mShape2(shape2), mMemoryAllocator(memoryAllocator), mManifolds(nullptr) { + mShape2(shape2), mMemoryAllocator(memoryAllocator), mManifolds(nullptr), mWorldSettings(worldSettings) { // Compute the maximum number of manifolds allowed between the two shapes mNbMaxManifolds = computeNbMaxContactManifolds(shape1->getCollisionShape(), shape2->getCollisionShape()); @@ -157,7 +157,7 @@ ContactManifold* ContactManifoldSet::selectManifoldWithSimilarNormal(const Conta assert(point != nullptr); // If the contact normal of the two manifolds are close enough - if (contactPoint->normal.dot(point->getNormal()) >= COS_ANGLE_SIMILAR_CONTACT_MANIFOLD) { + if (contactPoint->normal.dot(point->getNormal()) >= mWorldSettings.cosAngleSimilarContactManifold) { return manifold; } @@ -191,7 +191,7 @@ void ContactManifoldSet::clear() { void ContactManifoldSet::createManifold(const ContactManifoldInfo* manifoldInfo) { ContactManifold* manifold = new (mMemoryAllocator.allocate(sizeof(ContactManifold))) - ContactManifold(manifoldInfo, mShape1, mShape2, mMemoryAllocator); + ContactManifold(manifoldInfo, mShape1, mShape2, mMemoryAllocator, mWorldSettings); manifold->setPrevious(nullptr); manifold->setNext(mManifolds); if (mManifolds != nullptr) { diff --git a/src/collision/ContactManifoldSet.h b/src/collision/ContactManifoldSet.h index 56b09b04..4c6e0b85 100644 --- a/src/collision/ContactManifoldSet.h +++ b/src/collision/ContactManifoldSet.h @@ -66,6 +66,9 @@ class ContactManifoldSet { /// Contact manifolds of the set ContactManifold* mManifolds; + /// World settings + const WorldSettings& mWorldSettings; + // -------------------- Methods -------------------- // /// Create a new contact manifold and add it to the set @@ -95,7 +98,7 @@ class ContactManifoldSet { /// Constructor ContactManifoldSet(ProxyShape* shape1, ProxyShape* shape2, - MemoryAllocator& memoryAllocator); + MemoryAllocator& memoryAllocator, const WorldSettings& worldSettings); /// Destructor ~ContactManifoldSet(); @@ -167,11 +170,11 @@ inline int ContactManifoldSet::computeNbMaxContactManifolds(const CollisionShape // If both shapes are convex if (shape1->isConvex() && shape2->isConvex()) { - return NB_MAX_CONTACT_MANIFOLDS_CONVEX_SHAPE; + return mWorldSettings.nbMaxContactManifoldsConvexShape; } // If there is at least one concave shape else { - return NB_MAX_CONTACT_MANIFOLDS_CONCAVE_SHAPE; + return mWorldSettings.nbMaxContactManifoldsConcaveShape; } } diff --git a/src/configuration.h b/src/configuration.h index 5c6545e2..539f66b9 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -94,41 +94,6 @@ constexpr decimal PI = decimal(3.14159265); /// 2*Pi constant constexpr decimal PI_TIMES_2 = decimal(6.28318530); -/// Default friction coefficient for a rigid body -constexpr decimal DEFAULT_FRICTION_COEFFICIENT = decimal(0.3); - -/// Default bounciness factor for a rigid body -constexpr decimal DEFAULT_BOUNCINESS = decimal(0.5); - -/// Default rolling resistance -constexpr decimal DEFAULT_ROLLING_RESISTANCE = decimal(0.0); - -/// True if the sleeping technique is enabled -constexpr bool SLEEPING_ENABLED = true; - -/// Distance threshold for two contact points for a valid persistent contact (in meters) -constexpr decimal PERSISTENT_CONTACT_DIST_THRESHOLD = decimal(0.03); - -/// Velocity threshold for contact velocity restitution -constexpr decimal RESTITUTION_VELOCITY_THRESHOLD = decimal(1.0); - -/// Number of iterations when solving the velocity constraints of the Sequential Impulse technique -constexpr uint DEFAULT_VELOCITY_SOLVER_NB_ITERATIONS = 10; - -/// Number of iterations when solving the position constraints of the Sequential Impulse technique -constexpr uint DEFAULT_POSITION_SOLVER_NB_ITERATIONS = 5; - -/// Time (in seconds) that a body must stay still to be considered sleeping -constexpr float DEFAULT_TIME_BEFORE_SLEEP = 1.0f; - -/// A body with a linear velocity smaller than the sleep linear velocity (in m/s) -/// might enter sleeping mode. -constexpr decimal DEFAULT_SLEEP_LINEAR_VELOCITY = decimal(0.02); - -/// A body with angular velocity smaller than the sleep angular velocity (in rad/s) -/// might enter sleeping mode -constexpr decimal DEFAULT_SLEEP_ANGULAR_VELOCITY = decimal(3.0 * (PI / 180.0)); - /// In the broad-phase collision detection (dynamic AABB tree), the AABBs are /// inflated with a constant gap to allow the collision shape to move a little bit /// without triggering a large modification of the tree which can be costly @@ -139,21 +104,60 @@ constexpr decimal DYNAMIC_TREE_AABB_GAP = decimal(0.1); /// followin constant with the linear velocity and the elapsed time between two frames. constexpr decimal DYNAMIC_TREE_AABB_LIN_GAP_MULTIPLIER = decimal(1.7); -/// Maximum number of contact manifolds in an overlapping pair that involves two -/// convex collision shapes. -constexpr int NB_MAX_CONTACT_MANIFOLDS_CONVEX_SHAPE = 1; +/// Structure WorldSettings +/** + * This class is used to describe some settings of a physics world. + */ +struct WorldSettings { -/// Maximum number of contact manifolds in an overlapping pair that involves at -/// least one concave collision shape. -constexpr int NB_MAX_CONTACT_MANIFOLDS_CONCAVE_SHAPE = 3; + /// Distance threshold for two contact points for a valid persistent contact (in meters) + decimal persistentContactDistanceThreshold = decimal(0.03); -/// This is used to test if two contact manifold are similar (same contact normal) in order to -/// merge them. If the cosine of the angle between the normals of the two manifold are larger -/// than the value bellow, the manifold are considered to be similar. -constexpr decimal COS_ANGLE_SIMILAR_CONTACT_MANIFOLD = decimal(0.95); + /// Default friction coefficient for a rigid body + decimal defaultFrictionCoefficient = decimal(0.3); -/// Size (in bytes) of the single frame allocator -constexpr std::size_t INIT_SINGLE_FRAME_ALLOCATOR_BYTES = 1048576; // 1Mb + /// Default bounciness factor for a rigid body + decimal defaultBounciness = decimal(0.5); + + /// Velocity threshold for contact velocity restitution + decimal restitutionVelocityThreshold = decimal(1.0); + + /// Default rolling resistance + decimal defaultRollingRestistance = decimal(0.0); + + /// True if the sleeping technique is enabled + bool isSleepingEnabled = true; + + /// Number of iterations when solving the velocity constraints of the Sequential Impulse technique + uint defaultVelocitySolverNbIterations = 10; + + /// Number of iterations when solving the position constraints of the Sequential Impulse technique + uint defaultPositionSolverNbIterations = 5; + + /// Time (in seconds) that a body must stay still to be considered sleeping + float defaultTimeBeforeSleep = 1.0f; + + /// A body with a linear velocity smaller than the sleep linear velocity (in m/s) + /// might enter sleeping mode. + decimal defaultSleepLinearVelocity = decimal(0.02); + + /// A body with angular velocity smaller than the sleep angular velocity (in rad/s) + /// might enter sleeping mode + decimal defaultSleepAngularVelocity = decimal(3.0) * (PI / decimal(180.0)); + + /// Maximum number of contact manifolds in an overlapping pair that involves two + /// convex collision shapes. + int nbMaxContactManifoldsConvexShape = 1; + + /// Maximum number of contact manifolds in an overlapping pair that involves at + /// least one concave collision shape. + int nbMaxContactManifoldsConcaveShape = 3; + + /// This is used to test if two contact manifold are similar (same contact normal) in order to + /// merge them. If the cosine of the angle between the normals of the two manifold are larger + /// than the value bellow, the manifold are considered to be similar. + decimal cosAngleSimilarContactManifold = decimal(0.95); +}; } diff --git a/src/constraint/ContactPoint.cpp b/src/constraint/ContactPoint.cpp index 37dc34a3..f684eb34 100644 --- a/src/constraint/ContactPoint.cpp +++ b/src/constraint/ContactPoint.cpp @@ -31,12 +31,13 @@ using namespace reactphysics3d; using namespace std; // Constructor -ContactPoint::ContactPoint(const ContactPointInfo* contactInfo) +ContactPoint::ContactPoint(const ContactPointInfo* contactInfo, const WorldSettings& worldSettings) : mNormal(contactInfo->normal), mPenetrationDepth(contactInfo->penetrationDepth), mLocalPointOnShape1(contactInfo->localPoint1), mLocalPointOnShape2(contactInfo->localPoint2), - mIsRestingContact(false), mIsObsolete(false), mNext(nullptr), mPrevious(nullptr) { + mIsRestingContact(false), mIsObsolete(false), mNext(nullptr), mPrevious(nullptr), + mWorldSettings(worldSettings) { assert(mPenetrationDepth > decimal(0.0)); assert(mNormal.lengthSquare() > decimal(0.8)); diff --git a/src/constraint/ContactPoint.h b/src/constraint/ContactPoint.h index d78659f8..eec8c6a7 100644 --- a/src/constraint/ContactPoint.h +++ b/src/constraint/ContactPoint.h @@ -75,6 +75,9 @@ class ContactPoint { /// Pointer to the previous contact point in the double linked-list ContactPoint* mPrevious; + /// World settings + const WorldSettings& mWorldSettings; + // -------------------- Methods -------------------- // /// Update the contact point with a new one that is similar (very close) @@ -107,7 +110,7 @@ class ContactPoint { // -------------------- Methods -------------------- // /// Constructor - ContactPoint(const ContactPointInfo* contactInfo); + ContactPoint(const ContactPointInfo* contactInfo, const WorldSettings& worldSettings); /// Destructor ~ContactPoint() = default; @@ -173,8 +176,8 @@ inline decimal ContactPoint::getPenetrationImpulse() const { // Return true if the contact point is similar (close enougth) to another given contact point inline bool ContactPoint::isSimilarWithContactPoint(const ContactPointInfo* localContactPointBody1) const { - return (localContactPointBody1->localPoint1 - mLocalPointOnShape1).lengthSquare() <= (PERSISTENT_CONTACT_DIST_THRESHOLD * - PERSISTENT_CONTACT_DIST_THRESHOLD); + return (localContactPointBody1->localPoint1 - mLocalPointOnShape1).lengthSquare() <= (mWorldSettings.persistentContactDistanceThreshold * + mWorldSettings.persistentContactDistanceThreshold); } // Set the cached penetration impulse diff --git a/src/engine/CollisionWorld.cpp b/src/engine/CollisionWorld.cpp index 9388acda..b91897e1 100644 --- a/src/engine/CollisionWorld.cpp +++ b/src/engine/CollisionWorld.cpp @@ -32,8 +32,8 @@ using namespace reactphysics3d; using namespace std; // Constructor -CollisionWorld::CollisionWorld() - : mCollisionDetection(this, mMemoryManager), mBodies(mMemoryManager.getPoolAllocator()), mCurrentBodyID(0), +CollisionWorld::CollisionWorld(const WorldSettings& worldSettings) + : mConfig(worldSettings), mCollisionDetection(this, mMemoryManager), mBodies(mMemoryManager.getPoolAllocator()), mCurrentBodyID(0), mFreeBodiesIDs(mMemoryManager.getPoolAllocator()), mEventListener(nullptr) { #ifdef IS_PROFILING_ACTIVE diff --git a/src/engine/CollisionWorld.h b/src/engine/CollisionWorld.h index 1cc501e2..b3664ea1 100644 --- a/src/engine/CollisionWorld.h +++ b/src/engine/CollisionWorld.h @@ -62,6 +62,9 @@ class CollisionWorld { /// Memory manager MemoryManager mMemoryManager; + /// Configuration of the physics world + WorldSettings mConfig; + /// Reference to the collision detection CollisionDetection mCollisionDetection; @@ -96,7 +99,7 @@ class CollisionWorld { // -------------------- Methods -------------------- // /// Constructor - CollisionWorld(); + CollisionWorld(const WorldSettings& worldSettings = WorldSettings()); /// Destructor virtual ~CollisionWorld(); diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index a7b86b35..c6ef746e 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -39,11 +39,11 @@ const decimal ContactSolver::BETA_SPLIT_IMPULSE = decimal(0.2); const decimal ContactSolver::SLOP = decimal(0.01); // Constructor -ContactSolver::ContactSolver(MemoryManager& memoryManager) +ContactSolver::ContactSolver(MemoryManager& memoryManager, const WorldSettings& worldSettings) :mMemoryManager(memoryManager), mSplitLinearVelocities(nullptr), mSplitAngularVelocities(nullptr), mContactConstraints(nullptr), mLinearVelocities(nullptr), mAngularVelocities(nullptr), - mIsSplitImpulseActive(true) { + mIsSplitImpulseActive(true), mWorldSettings(worldSettings) { } @@ -225,7 +225,7 @@ void ContactSolver::initializeForIsland(Island* island) { deltaV.y * mContactPoints[mNbContactPoints].normal.y + deltaV.z * mContactPoints[mNbContactPoints].normal.z; const decimal restitutionFactor = computeMixedRestitutionFactor(body1, body2); - if (deltaVDotN < -RESTITUTION_VELOCITY_THRESHOLD) { + if (deltaVDotN < -mWorldSettings.restitutionVelocityThreshold) { mContactPoints[mNbContactPoints].restitutionBias = restitutionFactor * deltaVDotN; } diff --git a/src/engine/ContactSolver.h b/src/engine/ContactSolver.h index aecab4fe..ca5a9903 100644 --- a/src/engine/ContactSolver.h +++ b/src/engine/ContactSolver.h @@ -304,6 +304,9 @@ class ContactSolver { /// True if the split impulse position correction is active bool mIsSplitImpulseActive; + /// World settings + const WorldSettings& mWorldSettings; + #ifdef IS_PROFILING_ACTIVE /// Pointer to the profiler @@ -338,7 +341,7 @@ class ContactSolver { // -------------------- Methods -------------------- // /// Constructor - ContactSolver(MemoryManager& memoryManager); + ContactSolver(MemoryManager& memoryManager, const WorldSettings& worldSettings); /// Destructor ~ContactSolver() = default; diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index ee270519..3199b775 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -39,20 +39,20 @@ using namespace std; /** * @param gravity Gravity vector in the world (in meters per second squared) */ -DynamicsWorld::DynamicsWorld(const Vector3 &gravity) - : CollisionWorld(), - mContactSolver(mMemoryManager), - mNbVelocitySolverIterations(DEFAULT_VELOCITY_SOLVER_NB_ITERATIONS), - mNbPositionSolverIterations(DEFAULT_POSITION_SOLVER_NB_ITERATIONS), - mIsSleepingEnabled(SLEEPING_ENABLED), mRigidBodies(mMemoryManager.getPoolAllocator()), +DynamicsWorld::DynamicsWorld(const Vector3 &gravity, const WorldSettings& worldSettings) + : CollisionWorld(worldSettings), + mContactSolver(mMemoryManager, mConfig), + mNbVelocitySolverIterations(mConfig.defaultVelocitySolverNbIterations), + mNbPositionSolverIterations(mConfig.defaultPositionSolverNbIterations), + mIsSleepingEnabled(mConfig.isSleepingEnabled), mRigidBodies(mMemoryManager.getPoolAllocator()), mJoints(mMemoryManager.getPoolAllocator()), mGravity(gravity), mTimeStep(decimal(1.0f / 60.0f)), mIsGravityEnabled(true), mConstrainedLinearVelocities(nullptr), mConstrainedAngularVelocities(nullptr), mSplitLinearVelocities(nullptr), mSplitAngularVelocities(nullptr), mConstrainedPositions(nullptr), mConstrainedOrientations(nullptr), mNbIslands(0), mIslands(nullptr), - mSleepLinearVelocity(DEFAULT_SLEEP_LINEAR_VELOCITY), - mSleepAngularVelocity(DEFAULT_SLEEP_ANGULAR_VELOCITY), - mTimeBeforeSleep(DEFAULT_TIME_BEFORE_SLEEP) { + mSleepLinearVelocity(mConfig.defaultSleepLinearVelocity), + mSleepAngularVelocity(mConfig.defaultSleepAngularVelocity), + mTimeBeforeSleep(mConfig.defaultTimeBeforeSleep) { #ifdef IS_PROFILING_ACTIVE diff --git a/src/engine/DynamicsWorld.h b/src/engine/DynamicsWorld.h index af2fb659..e71c83e4 100644 --- a/src/engine/DynamicsWorld.h +++ b/src/engine/DynamicsWorld.h @@ -153,7 +153,7 @@ class DynamicsWorld : public CollisionWorld { // -------------------- Methods -------------------- // /// Constructor - DynamicsWorld(const Vector3& mGravity); + DynamicsWorld(const Vector3& mGravity, const WorldSettings& worldSettings = WorldSettings()); /// Destructor virtual ~DynamicsWorld() override; diff --git a/src/engine/Material.cpp b/src/engine/Material.cpp index f0484c96..284ae389 100644 --- a/src/engine/Material.cpp +++ b/src/engine/Material.cpp @@ -29,10 +29,10 @@ using namespace reactphysics3d; // Constructor -Material::Material() - : mFrictionCoefficient(DEFAULT_FRICTION_COEFFICIENT), - mRollingResistance(DEFAULT_ROLLING_RESISTANCE), - mBounciness(DEFAULT_BOUNCINESS) { +Material::Material(const WorldSettings& worldSettings) + : mFrictionCoefficient(worldSettings.defaultFrictionCoefficient), + mRollingResistance(worldSettings.defaultRollingRestistance), + mBounciness(worldSettings.defaultBounciness) { } diff --git a/src/engine/Material.h b/src/engine/Material.h index ca5fd532..d55724a1 100644 --- a/src/engine/Material.h +++ b/src/engine/Material.h @@ -58,7 +58,7 @@ class Material { // -------------------- Methods -------------------- // /// Constructor - Material(); + Material(const WorldSettings& worldSettings); /// Copy-constructor Material(const Material& material); diff --git a/src/engine/OverlappingPair.cpp b/src/engine/OverlappingPair.cpp index 16e077e9..882ed535 100644 --- a/src/engine/OverlappingPair.cpp +++ b/src/engine/OverlappingPair.cpp @@ -35,10 +35,11 @@ using namespace reactphysics3d; // Constructor OverlappingPair::OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, - MemoryAllocator& persistentMemoryAllocator, MemoryAllocator& temporaryMemoryAllocator) - : mContactManifoldSet(shape1, shape2, persistentMemoryAllocator), mPotentialContactManifolds(nullptr), + MemoryAllocator& persistentMemoryAllocator, MemoryAllocator& temporaryMemoryAllocator, + const WorldSettings& worldSettings) + : mContactManifoldSet(shape1, shape2, persistentMemoryAllocator, worldSettings), mPotentialContactManifolds(nullptr), mPersistentAllocator(persistentMemoryAllocator), mTempMemoryAllocator(temporaryMemoryAllocator), - mLastFrameCollisionInfos(mPersistentAllocator) { + mLastFrameCollisionInfos(mPersistentAllocator), mWorldSettings(worldSettings) { } @@ -80,7 +81,7 @@ void OverlappingPair::addPotentialContactPoints(NarrowPhaseInfo* narrowPhaseInfo // If we have found a corresponding manifold for the new contact point // (a manifold with a similar contact normal direction) - if (point->normal.dot(contactPoint->normal) >= COS_ANGLE_SIMILAR_CONTACT_MANIFOLD) { + if (point->normal.dot(contactPoint->normal) >= mWorldSettings.cosAngleSimilarContactManifold) { // Add the contact point to the manifold manifold->addContactPoint(contactPoint); diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index e93658d0..4b98c9be 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -122,13 +122,16 @@ class OverlappingPair { /// shape Ids of the two collision shapes. Map mLastFrameCollisionInfos; + /// World settings + const WorldSettings& mWorldSettings; + public: // -------------------- Methods -------------------- // /// Constructor OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, MemoryAllocator& persistentMemoryAllocator, - MemoryAllocator& temporaryMemoryAllocator); + MemoryAllocator& temporaryMemoryAllocator, const WorldSettings& worldSettings); /// Destructor ~OverlappingPair(); diff --git a/src/memory/SingleFrameAllocator.cpp b/src/memory/SingleFrameAllocator.cpp index c9d6533a..13cf23fb 100644 --- a/src/memory/SingleFrameAllocator.cpp +++ b/src/memory/SingleFrameAllocator.cpp @@ -33,7 +33,7 @@ using namespace reactphysics3d; // Constructor SingleFrameAllocator::SingleFrameAllocator() - : mTotalSizeBytes(INIT_SINGLE_FRAME_ALLOCATOR_BYTES), + : mTotalSizeBytes(INIT_SINGLE_FRAME_ALLOCATOR_NB_BYTES), mCurrentOffset(0), mNbFramesTooMuchAllocated(0), mNeedToAllocatedMore(false) { // Allocate a whole block of memory at the beginning diff --git a/src/memory/SingleFrameAllocator.h b/src/memory/SingleFrameAllocator.h index d3142908..93b75eac 100644 --- a/src/memory/SingleFrameAllocator.h +++ b/src/memory/SingleFrameAllocator.h @@ -48,6 +48,9 @@ class SingleFrameAllocator : public MemoryAllocator { /// memory if too much is allocated static const int NB_FRAMES_UNTIL_SHRINK = 120; + /// Initial size (in bytes) of the single frame allocator + size_t INIT_SINGLE_FRAME_ALLOCATOR_NB_BYTES = 1048576; // 1Mb + // -------------------- Attributes -------------------- // /// Total size (in bytes) of memory of the allocator diff --git a/testbed/src/Scene.h b/testbed/src/Scene.h index 6ccc3254..5471379e 100644 --- a/testbed/src/Scene.h +++ b/testbed/src/Scene.h @@ -72,13 +72,14 @@ struct EngineSettings { EngineSettings defaultSettings; + rp3d::WorldSettings worldSettings; defaultSettings.timeStep = 1.0f / 60.0f; - defaultSettings.nbVelocitySolverIterations = rp3d::DEFAULT_VELOCITY_SOLVER_NB_ITERATIONS; - defaultSettings.nbPositionSolverIterations = rp3d::DEFAULT_POSITION_SOLVER_NB_ITERATIONS; - defaultSettings.isSleepingEnabled = rp3d::SLEEPING_ENABLED; - defaultSettings.timeBeforeSleep = rp3d::DEFAULT_TIME_BEFORE_SLEEP; - defaultSettings.sleepLinearVelocity = rp3d::DEFAULT_SLEEP_LINEAR_VELOCITY; - defaultSettings.sleepAngularVelocity = rp3d::DEFAULT_SLEEP_ANGULAR_VELOCITY; + defaultSettings.nbVelocitySolverIterations = worldSettings.defaultVelocitySolverNbIterations; + defaultSettings.nbPositionSolverIterations = worldSettings.defaultPositionSolverNbIterations; + defaultSettings.isSleepingEnabled = worldSettings.isSleepingEnabled; + defaultSettings.timeBeforeSleep = worldSettings.defaultTimeBeforeSleep; + defaultSettings.sleepLinearVelocity = worldSettings.defaultSleepLinearVelocity; + defaultSettings.sleepAngularVelocity = worldSettings.defaultSleepAngularVelocity; defaultSettings.isGravityEnabled = true; return defaultSettings; From 7645eefa9b2efa440cfba8b5174e990fc1d88b00 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 6 Mar 2018 16:18:33 +0100 Subject: [PATCH 173/248] Update the license file --- LICENSE | 17 +++++++---------- 1 file changed, 7 insertions(+), 10 deletions(-) diff --git a/LICENSE b/LICENSE index 2fb5b4bb..02a7459f 100644 --- a/LICENSE +++ b/LICENSE @@ -1,20 +1,17 @@ -ReactPhysics3D physics library, http://code.google.com/p/reactphysics3d/ -Copyright (c) 2010-2016 Daniel Chappuis +Copyright (c) 2010-2018 Daniel Chappuis http://www.reactphysics3d.com -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. +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 +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. From b6b8ce8e53c8f3ff5abd7ace7081866801428fb5 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 6 Mar 2018 19:29:16 +0100 Subject: [PATCH 174/248] Update user manual --- .../UserManual/ReactPhysics3D-UserManual.tex | 388 ++++++++++-------- 1 file changed, 219 insertions(+), 169 deletions(-) diff --git a/documentation/UserManual/ReactPhysics3D-UserManual.tex b/documentation/UserManual/ReactPhysics3D-UserManual.tex index e1c20e5d..3da05ce1 100644 --- a/documentation/UserManual/ReactPhysics3D-UserManual.tex +++ b/documentation/UserManual/ReactPhysics3D-UserManual.tex @@ -56,19 +56,21 @@ \begin{itemize} \item Rigid body dynamics \item Discrete collision detection - \item Collision shapes (Sphere, Box, Cone, Cylinder, Capsule, Convex Mesh, Static Concave Mesh, Height Field) + \item Collision shapes (Sphere, Box, Capsule, Convex Mesh, Static Concave Mesh, Height Field) \item Multiple collision shapes per body \item Broadphase collision detection (Dynamic AABB tree) - \item Narrowphase collision detection (GJK/EPA) + \item Narrowphase collision detection (SAT/GJK) \item Collision response and friction (Sequential Impulses Solver) \item Joints (Ball and Socket, Hinge, Slider, Fixed) \item Collision filtering with categories \item Ray casting \item Sleeping technique for inactive bodies - \item Integrated Profiler \item Multi-platform (Windows, Linux, Mac OS X) + \item No external libraries (do not use STL containers) \item Documentation (User manual and Doxygen API) \item Testbed application with demos + \item Integrated Profiler + \item Logs \item Unit tests \end{itemize} @@ -100,7 +102,7 @@ xs \begin{sloppypar} where \texttt{\textless path\_to\_library\_source\textgreater} must be replaced - by the path to the \texttt{reactphysics3d-0.6.0/} folder. It is the folder that + by the path to the \texttt{reactphysics3d-0.7.0/} folder. It is the folder that contains the \texttt{CMakeLists.txt} file. Running this command will launch the CMake command line interface. Hit the 'c' key to configure the project. There, you can also change some predefined variables (see section \ref{sec:cmakevariables} for more details) and then, hit the 'c' key again. Once you have set all the values as you like, you can hit the 'g' key to generate the makefiles in the build directory @@ -117,7 +119,7 @@ xs You can also use the graphical user interface of CMake. To do this, run the \texttt{cmake-gui} program. The program will ask you for the - source folder which is the \texttt{reactphysics3d-0.6.0/} folder of + source folder which is the \texttt{reactphysics3d-0.7.0/} folder of the library. You will also have to select a folder where you want to build the library and the testbed application. Select any empty folder that is on your system. Then, you can click on \texttt{Configure}. CMake will ask you to choose an IDE that is on @@ -197,6 +199,42 @@ using namespace reactphysics3d; You can also take a look at the examples and the API documentation to get a better idea of how to use the ReactPhysics3D library. + + \subsection{Memory allocation} + + When using the ReactPhysics3D library, you will probably have to allocate new objects but the library will also allocate some objects for you. ReactPhysics3D uses a simple rule: + all the memory that is allocated by yourself (using the C++ \emph{new} operator for instance) will have to be destroyed by you (with the corresponding \emph{delete} operator). However, if you + receive a pointer to an object from a call to a ReactPhysics3D method, you have not allocated memory for this object by yourself and therefore, you are not responsible to destroy it. ReactPhysics3D + will have to destroy it. \\ + + For instance, if you create a sphere collision shape with the following code: \\ + + \begin{lstlisting} +// Here memory is allocated by yourself +rp3d::SphereShape* sphereShape = new SphereShape(radius); + \end{lstlisting} + + \vspace{0.6cm} + + In this example, you have allocated memory for the collision shape and therefore, you have to destroy this object at the end as follows: \\ + + \begin{lstlisting} +delete sphereShape; + \end{lstlisting} + + \vspace{0.6cm} + + However, when you create a RigidBody with the following code: \\ + + \begin{lstlisting} +// Here memory is allocated by the ReactPhysics3D library +RigidBody* body = dynamicsWorld.createRigidBody(transform); + \end{lstlisting} + + \vspace{0.6cm} + + Here, the ReactPhysics3D library has allocated the memory for the rigid body and has returned a pointer so that you can use it. Because you have not allocated memory by yourself here, you must not + destroy the rigid body. The library is responsible to do it. \\ \section{The Collision World} @@ -228,6 +266,20 @@ rp3d::CollisionWorld world; When the \texttt{CollisionWorld} is destroyed, all the bodies that have been added into it and that have not been destroyed already will be destroyed. Therefore, the pointers to the bodies of the world will become invalid after the existence of their \texttt{CollisionWorld}. + \subsection{Queries on the Collision World} + + Once your collision world has been created, you can add collision bodies and move them around manually. Now there are some queries that you can use on the + collision world. Here are the main methods that you can use: \\ + + TODO : FINISH THIS SECTION + + \begin{description} + \item[testOverlap()] ??? + \item[testPointInside()] ??? + \item[testCollision()] ??? + \item[testAABBOverlap()] Pointer to the Collision Body or Rigid Body that has been hit by the ray + \end{description} + \section{Collision Bodies} Once the Collision World has been created, you can create Collision Bodies into the world. A Collision Body represents an object in the Collision World. @@ -373,7 +425,7 @@ world.enableSleeping(false); \end{sloppypar} \subsection{Updating the Dynamics World} - \label{sec:updating_dynamics_world} + \label{sec:updatingdynamicsworld} The \texttt{DynamicsWorld} is used to simulate physics through time. It has to be updated each time you want to simulate a step forward in time. Most of the time, you want to update the world right before rendering a new frame in a real-time application. \\ @@ -427,6 +479,9 @@ while (accumulator >= timeStep) { \end{lstlisting} + \vspace{0.6cm} + + A nice article to read about this time interpolation is the one from Glenn Fiedler at \url{https://gafferongames.com/post/fix_your_timestep/}. \subsection{Destroying the Dynamics World} @@ -611,49 +666,92 @@ rigidBody->applyTorque(torque); \subsection{Updating a Rigid Body} - When you call the \texttt{DynamicsWorld::update()} method, the collisions between the bodies are computed and the joints are evaluated. Then, the bodies position - and orientation are updated accordingly. \\ + When you call the \texttt{DynamicsWorld::update()} method, the collisions between the bodies are computed and the joints are evaluated. Then, the bodies positions + and orientations are updated accordingly. After calling this method, you can retrieve the updated position and orientation of each body to render it. To do that, you simply need to use the + \texttt{RigidBody::getTransform()} method to get the updated transform. This transform represents the current local-to-world-space transformation + of the body. \\ - Remember that in section \ref{sec:updating_dynamics_world} we were using a time accumulator in order to always have fixed physics time steps. - Now imagine a situation where the rendering frame rate is higher than the the physics frame rate. It means that at the end of most rendering - frames there will be some time left in the accumulator for the physics time that has not been simulated yet by the physics engine. - It means that we are rendering the state of the physics simulation at a time different from the rendering time which can cause a visual stuttering effect. \\ - - To solve this, the idea is to interpolate between the previous and current physics state of the simulation based on how much time is left in the - accumulator. First we compute the interpolation factor as follows: \\ + As described in section \ref{sec:updatingdynamicsworld}, at the end of a frame, there might still be some remaining time in the time accumulator. Therefore, you should not use the updated + transform directly for rendering but you need to perform some interpolation between the updated transform and the one from the previous frame to get a smooth real-time simulation. + First, you need to compute the interpolation factor as folows : \\ \begin{lstlisting} - - // Compute the interpolation factor ("accumulator" is the time left in the accumulator and - // "dt" is the physics time step) - const float interpolationFactor = accumulator / dt; - \end{lstlisting} - - \vspace{0.6cm} - - Then we get the current transform of the rigid body and use it with the previous transform (transform at the previous frame) to - compute the interpolated transform as in the following code: \\ - - \begin{lstlisting} - - // Get the current transform of the rigid body - rp3d::Transform currentTransform = body->getTransform(); - - // Interpolate the transform between the previous one and the new one - rp3d::Transform interpolatedTransform = rp3d::Transform::interpolateTransforms(previousTransform, currentTransform, interpolationFactor); +// Compute the time interpolation factor +decimal factor = accumulator / timeStep; \end{lstlisting} \vspace{0.6cm} - If you need the array with the corresponding $4 \times 4$ OpenGL transformation matrix, you can use the \texttt{Transform::getOpenGLMatrix()} method as in the + Then, you can use the \texttt{Transform::interpolateTransforms()} method to compute the linearly interpolated transform: \\ + + \begin{lstlisting} +// Compute the interpolated transform of the rigid body +rp3d::Transform interpolatedTransform = Transform::interpolateTransforms(prevTransform, currTransform, factor); + \end{lstlisting} + + \vspace{0.6cm} + + The following code is the one from section \ref{sec:updatingdynamicsworld} for the physics simulation loop but with the update of a given rigid body. \\ + + \begin{lstlisting} + +// Constant physics time step +const float timeStep = 1.0 / 60.0; + +// Get the current system time +long double currentFrameTime = getCurrentSystemTime(); + +// Compute the time difference between the two frames +long double deltaTime = currentFrameTime - previousFrameTime; + +// Update the previous time +previousFrameTime = currentFrameTime; + +// Add the time difference in the accumulator +accumulator += mDeltaTime; + +// While there is enough accumulated time to take +// one or several physics steps +while (accumulator >= timeStep) { + + // Update the Dynamics world with a constant time step + dynamicsWorld->update(timeStep); + + // Decrease the accumulated time + accumulator -= timeStep; +} + +// Compute the time interpolation factor +decimal factor = accumulator / timeStep; + +// Get the updated transform of the body +rp3d::Transform currTransform = body->getTransform(); + +// Compute the interpolated transform of the rigid body +rp3d::Transform interpolatedTransform = Transform::interpolateTransforms(prevTransform, currTransform, factor); + +// Now you can render your body using the interpolated transform here + +// Update the previous transform +prevTransform = currTranform; + + \end{lstlisting} + + \vspace{0.6cm} + + If you need the array with the corresponding $4 \times 4$ OpenGL transformation matrix for rendering, you can use the \texttt{Transform::getOpenGLMatrix()} method as in the following code: \\ \begin{lstlisting} - // Get the OpenGL matrix array of the transform - float matrix[16]; - transform.getOpenGLMatrix(matrix); +// Get the OpenGL matrix array of the transform +float matrix[16]; +transform.getOpenGLMatrix(matrix); \end{lstlisting} + \vspace{0.6cm} + + A nice article to read about this time interpolation is the one from Glenn Fiedler at \url{https://gafferongames.com/post/fix_your_timestep/}. + \subsection{Destroying a Rigid Body} \begin{sloppypar} @@ -684,11 +782,6 @@ world.destroyRigidBody(body); those things by yourself. However, if needed, you can also specify your own center of mass or inertia tensor. Note that the inertia tensor is a $3 \times 3$ matrix describing how the mass is distributed inside the rigid body which will be used to calculate its rotation. The inertia tensor depends on the mass and the shape of the body. \\ - Every collision shapes use a \emph{collision margin} which is a small distance around the shape that is used internally in the collision detection. - Some collision shapes have their collision margin integrated into the shape that you define and therefore you do not have to worry about it. - However, for some collision shapes, the collision margin is added around the shape that you define and therefore, you might have to compensate - for this small margin when you render the object. \\ - \subsection{Box Shape} \begin{figure}[h] @@ -713,17 +806,6 @@ const rp3d::BoxShape boxShape(halfExtents); \vspace{0.6cm} - The \texttt{BoxShape} has a collision margin that is added to the box dimension you define. Therefore, the actual box shape will be a little bit larger that the one you define. - It is recommended that you use the default margin. In case, you really need to change the collision margin of your box shape (if the dimension of your box is small compared - to the default collision margin for instance), you can pass the length of the new collision margin (in meters) as a second parameter of the \texttt{BoxShape} constructor. \\ - - For instance, if you want to use a collision margin of 1 centimeter for your box shape, you can do it like this: \\ - - \begin{lstlisting} -// Create the box shape with a custom collision margin -const rp3d::BoxShape boxShape(halfExtents, 0.01); - \end{lstlisting} - \subsection{Sphere Shape} \begin{figure}[h] @@ -743,70 +825,6 @@ const rp3d::SphereShape sphereShape(2.0); \vspace{0.6cm} - The collision margin of the \texttt{SphereShape} is integrated into the sphere you define. Therefore, you do not need to worry about it and you cannot change it. - - \subsection{Cone Shape} - - \begin{figure}[h] - \centering - \includegraphics{coneshape.png} - \label{fig:coneshape} - \end{figure} - - The \texttt{ConeShape} class describes a cone collision shape centered at the origin of the shape local-space. The cone is aligned along the Y axis. - In order to create a cone shape, you need to give the radius of its base and its height (along the Y axis). \\ - - For instance, if you want to create a cone shape with a radius of 1 meter and the height of 3 meters, you need to use the following code: \\ - - \begin{lstlisting} -// Create the cone shape -const rp3d::ConeShape coneShape(1.0, 3.0); - \end{lstlisting} - - \vspace{0.6cm} - - The \texttt{ConeShape} has a collision margin that is added to the cone dimension that you define. Therefore, the actual cone shape will be a little bit larger that the size you define. - It is recommended that you use the default margin. In case you really need to change the collision margin of your cone shape (if the dimension of your cone is small compared - to the default collision margin for instance), you can pass the length of the new collision margin (in meters) as a third parameter of the \texttt{ConeShape} constructor. \\ - - For instance, if you want to use a collision margin of 1 centimeter for your cone shape, you can do it like this: \\ - - \begin{lstlisting} -// Create the cone shape with a custom collision margin -const rp3d::ConeShape coneShape(1.0, 3.0, 0.01); - \end{lstlisting} - - \subsection{Cylinder Shape} - - \begin{figure}[h] - \centering - \includegraphics{cylindershape.png} - \label{fig:cylindershape} - \end{figure} - - The \texttt{CylinderShape} class describes a cylinder collision shape centered at the origin of the shape local-space. The cylinder is aligned along the Y axis. - In order to create a cylinder shape, you need to specify the radius of its base and its height (along the Y axis). \\ - - For instance, if you want to create a cylinder shape with a radius of 1 meter and the height of 3 meters, you need to use the following code: \\ - - \begin{lstlisting} -// Create the cylinder shape -const rp3d::Cylinder cylinderShape(1.0, 3.0); - \end{lstlisting} - - \vspace{0.6cm} - - The \texttt{CylinderShape} has a collision margin that is added to the cylinder dimension that you define. Therefore, the actual cylinder shape will be a little bit larger that the one you define. - It is recommended that you use the default margin. In case you really need to change the collision margin of your cylinder shape (if the dimension of your cylinder is small compared - to the default collision margin for instance), you can pass the length of the new collision margin (in meters) as a third parameter of the \texttt{CylinderShape} constructor. \\ - - For instance, if you want to use a collision margin of 1 centimeter for your cylinder shape, you can do it like this: \\ - - \begin{lstlisting} -// Create the cylinder shape with a custom collision margin -const rp3d::CylinderShape cylinderShape(1.0, 3.0, 0.01); - \end{lstlisting} - \subsection{Capsule Shape} \begin{figure}[h] @@ -828,9 +846,6 @@ const rp3d::CapsuleShape capsuleShape(1.0, 2.0); \vspace{0.6cm} - As for the \texttt{SphereShape}, the collision margin of the \texttt{CapsuleShape} is integrated into the capsule you define. - Therefore, you do not need to worry about it and you cannot change it. - \subsection{Convex Mesh Shape} \begin{figure}[h] @@ -839,56 +854,75 @@ const rp3d::CapsuleShape capsuleShape(1.0, 2.0); \label{fig:convexshape} \end{figure} - The \texttt{ConvexMeshShape} class can be used to describe the shape of a convex mesh. In order to create a convex mesh shape, you need to supply the array with the coordinates of - the vertices of the mesh. The array is supposed to start with the three X, Y and Z coordinates of the first vertex, then the X, Y and Z coordinates of the second vertex and so on. - The first parameter of the \texttt{ConvexMeshShape} constructor is a pointer to the array of the vertices coordinates, the second parameter is the number of vertices in the array and - the third parameter is the size (in bytes) of the data needed for a single vertex in the array (data used by all the three coordinates of a single vertex). \\ + The \texttt{ConvexMeshShape} class can be used to describe the shape of a convex mesh. In order to create a convex mesh shape, you first need to create an array of \texttt{PolygonFace} to describe each face + of your mesh. You also need to have an array with the vertices coordinates and an array with the vertex indices of each face of you mesh. Then, you have to create a \texttt{PolygonVertexArray} with your + vertices coordinates and indices array. You also need to specify your array of \texttt{PolygonFace}. Then, you have to create a \texttt{PolyhedronMesh} with your \texttt{PolygonVertexArray}. + Once this is done, you can create the \texttt{ConvexMeshShape} by passing your \texttt{PolyhedronMesh} in paramater. \\ - The following example shows how to create a convex mesh shape: \\ + The following example shows how to create a convex mesh shape. In this example, we create a cube as a convex mesh shape. Of course, this is only for the example. + If you really need a cube collision shape, you should use the \texttt{BoxShape} instead. \\ \begin{lstlisting} -// Construct a convex mesh shape -rp3d::ConvexMeshShape shape(verticesArray, nbVertices, 3 * sizeof(float)); - \end{lstlisting} +// Array with the vertices coordinates of the convex mesh +float vertices[24]; +vertices[0] = -3; vertices[1] = -3; vertices[2] = 3; +vertices[3] = 3; vertices[4] = -3; vertices[5] = 3; +vertices[6] = 3; vertices[7] = -3; vertices[8] = -3; +vertices[9] = -3; vertices[10] = -3; vertices[11] = -3; +vertices[12] = -3; vertices[13] = 3; vertices[14] = 3; +vertices[15] = 3; vertices[16] = 3; vertices[17] = 3; +vertices[18] = 3; vertices[19] = 3; vertices[20] = -3; +vertices[21] = -3; vertices[22] = 3; vertices[23] = -3; - \vspace{0.6cm} +// Array with the vertices indices for each face of the mesh +int indices[24]; +indices[0]=0; indices[1]=3; indices[2]=2; indices[3]=1; +indices[4]=4; indices[5]=5; indices[6]=6; indices[7]=7; +indices[8]=0; indices[9]=1; indices[10]=5; indices[11]=4; +indices[12]=1; indices[13]=2; indices[14]=6; indices[15]=5; +indices[16]=2; indices[17]=3; indices[18]=7; indices[19]=6; +indices[20]=0; indices[21]=4; indices[22]=7; indices[23]=3; - You need to make sure that the mesh you provide is indeed convex and also that the origin of its local-space is inside the mesh. \\ +// Description of the six faces of the convex mesh +polygonFaces = new rp3d::PolygonVertexArray::PolygonFace[6]; +rp3d::PolygonVertexArray::PolygonFace* face = polygonFaces; +for (int f = 0; f < 6; f++) { - The collision detection test with a convex mesh shape runs in $O(n)$ where $n$ is the number of vertices in the mesh. Collision detection can become expensive if there are - too many vertices in the mesh. It is possible to speed up the collision detection by providing information about the edges of the convex mesh. If you provide edges information, the collision detection will run in almost constant time at the cost of a little extra memory to store the edges information. In order to provide the edges - information, you need to call the \texttt{ConvexMeshShape::addEdge()} method for each edge of the mesh. The first parameter is the index of the first vertex of the edge and the - second parameter is the index of the second vertex. Do not worry about calling this method multiple times for the same edge, the edge information will be added only - once. \\ + // First vertex of the face in the indices array + face->indexBase = f * 4; - For instance, the following code adds the edges information into a convex mesh shape: \\ + // Number of vertices in the face + face->nbVertices = 4; - \begin{lstlisting} -// Add the edges information of the mesh into the shape -for (unsigned int i=0; iraycast(ray, raycastInfo); the cubes will fall down on the floor. After falling down, the cubes will come to rest and start sleeping (become inactive). In this scene, the cubes will become red as they get inactive (sleeping). - \subsection{Joints} + \subsection{Cubes Stack Scene} + + This scene has a dynamics world and a pyramid of cubes. + + \subsection{Joints Scene} In this scene, you will learn how to create different joints (Ball and Socket, Hinge, Slider, Fixed) into the dynamics world. You can also see how to set the motor or limits of the joints. @@ -1621,11 +1664,16 @@ bool isHit = proxyShape->raycast(ray, raycastInfo); In this scene, you will see how to use the Height field collision shape of the library. Several cubes will fall down to the height field. - \subsection{Raycast Scene} + \subsection{Raycast Scene} In this scene, you will see how to use the ray casting methods of the library. Several rays are thrown against the different collision shapes. It is possible to switch from a collision shape to another using the spacebar key. + \subsection{Collision Detection Scene} + + This scene has a collision world and several collision bodies that can be move around with keyboard keys. This scene shows how to manually compute + collision detection in a collision world. + \subsection{Concave Mesh Scene} In this scene, you will see how to use the static concave mesh collision shape of the library. @@ -1710,10 +1758,12 @@ for (it = manifolds.begin(); it != manifolds.end(); ++it) { Note that this technique to retrieve the contacts, if you use it between the \texttt{DynamicsWorld::update()} calls, will only give you the contacts are the end of each frame. You will probably miss several contacts that have occured in the physics internal sub-steps. In section \ref{sec:receiving_feedback}, you will - see how to get all the contact occuring in the physis sub-steps of the engine. Also note that a contact manifold contains some persistent contact points that - have may have been there for several frames. + see how to get all the contact occuring in the physis sub-steps of the engine. \section{Receiving Feedback} + + TODO : UPDATE THIS SECTION + \label{sec:receiving_feedback} Sometimes, you want to receive notifications from the physics engine when a given event happens. The \texttt{EventListener} class can be used for that purpose. In order to use it, you need to create a new class that inherits from the \texttt{EventListener} class and overrides some methods that will be called by the ReactPhysics3D library when some events From 393bb0ed88fdd1098623a46a7a48c735bd33bd57 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 14 Mar 2018 07:33:28 +0100 Subject: [PATCH 175/248] Refactor profiler and start working on logger --- CMakeLists.txt | 11 +- src/body/Body.h | 6 +- src/body/CollisionBody.h | 2 +- src/body/RigidBody.cpp | 2 +- src/collision/CollisionDetection.cpp | 30 +- src/collision/CollisionDetection.h | 2 +- .../broadphase/BroadPhaseAlgorithm.cpp | 4 +- .../broadphase/BroadPhaseAlgorithm.h | 4 +- src/collision/broadphase/DynamicAABBTree.cpp | 6 +- .../narrowphase/GJK/GJKAlgorithm.cpp | 4 +- .../narrowphase/SAT/SATAlgorithm.cpp | 28 +- src/collision/shapes/CollisionShape.cpp | 4 +- src/collision/shapes/CollisionShape.h | 2 +- src/collision/shapes/ConcaveMeshShape.cpp | 2 +- src/collision/shapes/ConcaveMeshShape.h | 2 +- src/collision/shapes/HeightFieldShape.cpp | 2 +- src/collision/shapes/HeightFieldShape.h | 2 +- src/collision/shapes/TriangleShape.cpp | 4 +- src/constraint/BallAndSocketJoint.cpp | 4 +- src/constraint/BallAndSocketJoint.h | 2 +- src/constraint/FixedJoint.cpp | 4 +- src/constraint/FixedJoint.h | 2 +- src/constraint/HingeJoint.cpp | 4 +- src/constraint/HingeJoint.h | 2 +- src/constraint/Joint.cpp | 4 +- src/constraint/Joint.h | 19 +- src/constraint/SliderJoint.cpp | 4 +- src/constraint/SliderJoint.h | 2 +- src/containers/List.h | 1 + src/containers/Pair.h | 2 +- src/engine/CollisionWorld.cpp | 68 +++- src/engine/CollisionWorld.h | 64 +++- src/engine/ConstraintSolver.cpp | 8 +- src/engine/ContactSolver.cpp | 14 +- src/engine/DynamicsWorld.cpp | 94 +++-- src/engine/DynamicsWorld.h | 33 +- src/engine/OverlappingPair.h | 6 +- src/mathematics/Matrix2x2.h | 10 + src/mathematics/Matrix3x3.h | 11 + src/mathematics/Quaternion.h | 9 + src/mathematics/Transform.h | 8 + src/mathematics/Vector2.h | 9 + src/mathematics/Vector3.h | 9 + src/utils/Logger.cpp | 102 ++++++ src/utils/Logger.h | 332 ++++++++++++++++++ src/{engine => utils}/Profiler.cpp | 82 +++-- src/{engine => utils}/Profiler.h | 147 ++++++-- test/tests/collision/TestCollisionWorld.h | 160 ++++----- test/tests/collision/TestRaycast.h | 3 +- .../CollisionDetectionScene.cpp | 8 +- .../collisionshapes/CollisionShapesScene.cpp | 9 +- .../scenes/concavemesh/ConcaveMeshScene.cpp | 8 +- testbed/scenes/cubes/CubesScene.cpp | 8 +- testbed/scenes/cubestack/CubeStackScene.cpp | 8 +- .../scenes/heightfield/HeightFieldScene.cpp | 9 +- testbed/scenes/joints/JointsScene.cpp | 8 +- testbed/scenes/raycast/RaycastScene.cpp | 8 +- 57 files changed, 1059 insertions(+), 343 deletions(-) create mode 100644 src/utils/Logger.cpp create mode 100644 src/utils/Logger.h rename src/{engine => utils}/Profiler.cpp (85%) rename src/{engine => utils}/Profiler.h (77%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 0566a735..09a5ae73 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -21,6 +21,7 @@ ENABLE_TESTING() OPTION(COMPILE_TESTBED "Select this if you want to build the testbed application" OFF) OPTION(COMPILE_TESTS "Select this if you want to build the tests" OFF) OPTION(PROFILING_ENABLED "Select this if you want to compile with enabled profiling" OFF) +OPTION(LOGS_ENABLED "Select this if you want to compile with logs enabled during execution" OFF) OPTION(DOUBLE_PRECISION_ENABLED "Select this if you want to compile using double precision floating values" OFF) @@ -45,6 +46,10 @@ IF(PROFILING_ENABLED) ADD_DEFINITIONS(-DIS_PROFILING_ACTIVE) ENDIF(PROFILING_ENABLED) +IF(LOGS_ENABLED) + ADD_DEFINITIONS(-DIS_LOGGING_ACTIVE) +ENDIF(LOGS_ENABLED) + IF(DOUBLE_PRECISION_ENABLED) ADD_DEFINITIONS(-DIS_DOUBLE_PRECISION_ENABLED) ENDIF(DOUBLE_PRECISION_ENABLED) @@ -164,8 +169,6 @@ SET (REACTPHYSICS3D_SOURCES "src/engine/Material.cpp" "src/engine/OverlappingPair.h" "src/engine/OverlappingPair.cpp" - "src/engine/Profiler.h" - "src/engine/Profiler.cpp" "src/engine/Timer.h" "src/engine/Timer.cpp" "src/collision/CollisionCallback.h" @@ -201,6 +204,10 @@ SET (REACTPHYSICS3D_SOURCES "src/containers/Map.h" "src/containers/Set.h" "src/containers/Pair.h" + "src/utils/Profiler.h" + "src/utils/Profiler.cpp" + "src/utils/Logger.h" + "src/utils/Logger.cpp" ) # Create the library diff --git a/src/body/Body.h b/src/body/Body.h index b1b18325..4a46e83f 100644 --- a/src/body/Body.h +++ b/src/body/Body.h @@ -92,7 +92,7 @@ class Body { virtual ~Body() = default; /// Return the ID of the body - bodyindex getID() const; + bodyindex getId() const; /// Return whether or not the body is allowed to sleep bool isAllowedToSleep() const; @@ -137,9 +137,9 @@ class Body { // Return the id of the body /** - * @return The ID of the body + * @return The id of the body */ -inline bodyindex Body::getID() const { +inline bodyindex Body::getId() const { return mID; } diff --git a/src/body/CollisionBody.h b/src/body/CollisionBody.h index 9943dc86..2520cab4 100644 --- a/src/body/CollisionBody.h +++ b/src/body/CollisionBody.h @@ -36,7 +36,7 @@ #include "collision/RaycastInfo.h" #include "memory/PoolAllocator.h" #include "configuration.h" -#include "engine/Profiler.h" +#include "utils/Profiler.h" /// Namespace reactphysics3d namespace reactphysics3d { diff --git a/src/body/RigidBody.cpp b/src/body/RigidBody.cpp index 4d79f186..ab4b0c8e 100644 --- a/src/body/RigidBody.cpp +++ b/src/body/RigidBody.cpp @@ -459,7 +459,7 @@ void RigidBody::recomputeMassInformation() { // Update the broad-phase state for this body (because it has moved for instance) void RigidBody::updateBroadPhaseState() const { - PROFILE("RigidBody::updateBroadPhaseState()", mProfiler); + RP3D_PROFILE("RigidBody::updateBroadPhaseState()", mProfiler); DynamicsWorld& world = static_cast(mWorld); const Vector3 displacement = world.mTimeStep * mLinearVelocity; diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index ffbc56c7..dc2272f9 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -68,7 +68,7 @@ CollisionDetection::CollisionDetection(CollisionWorld* world, MemoryManager& mem // Compute the collision detection void CollisionDetection::computeCollisionDetection() { - PROFILE("CollisionDetection::computeCollisionDetection()", mProfiler); + RP3D_PROFILE("CollisionDetection::computeCollisionDetection()", mProfiler); // Compute the broad-phase collision detection computeBroadPhase(); @@ -86,7 +86,7 @@ void CollisionDetection::computeCollisionDetection() { // Compute the broad-phase collision detection void CollisionDetection::computeBroadPhase() { - PROFILE("CollisionDetection::computeBroadPhase()", mProfiler); + RP3D_PROFILE("CollisionDetection::computeBroadPhase()", mProfiler); // If new collision shapes have been added to bodies if (mIsCollisionShapesAdded) { @@ -101,7 +101,7 @@ void CollisionDetection::computeBroadPhase() { // Compute the middle-phase collision detection void CollisionDetection::computeMiddlePhase() { - PROFILE("CollisionDetection::computeMiddlePhase()", mProfiler); + RP3D_PROFILE("CollisionDetection::computeMiddlePhase()", mProfiler); // For each possible collision pair of bodies Map, OverlappingPair*>::Iterator it; @@ -251,7 +251,7 @@ void CollisionDetection::computeConvexVsConcaveMiddlePhase(OverlappingPair* pair // Compute the narrow-phase collision detection void CollisionDetection::computeNarrowPhase() { - PROFILE("CollisionDetection::computeNarrowPhase()", mProfiler); + RP3D_PROFILE("CollisionDetection::computeNarrowPhase()", mProfiler); NarrowPhaseInfo* currentNarrowPhaseInfo = mNarrowPhaseInfoList; while (currentNarrowPhaseInfo != nullptr) { @@ -364,7 +364,7 @@ void CollisionDetection::removeProxyCollisionShape(ProxyShape* proxyShape) { void CollisionDetection::addAllContactManifoldsToBodies() { - PROFILE("CollisionDetection::addAllContactManifoldsToBodies()", mProfiler); + RP3D_PROFILE("CollisionDetection::addAllContactManifoldsToBodies()", mProfiler); // For each overlapping pairs in contact during the narrow-phase Map, OverlappingPair*>::Iterator it; @@ -415,7 +415,7 @@ void CollisionDetection::addContactManifoldToBody(OverlappingPair* pair) { /// Convert the potential contact into actual contacts void CollisionDetection::processAllPotentialContacts() { - PROFILE("CollisionDetection::processAllPotentialContacts()", mProfiler); + RP3D_PROFILE("CollisionDetection::processAllPotentialContacts()", mProfiler); // For each overlapping pairs in contact during the narrow-phase Map, OverlappingPair*>::Iterator it; @@ -454,7 +454,7 @@ void CollisionDetection::processPotentialContacts(OverlappingPair* pair) { // Report contacts for all the colliding overlapping pairs void CollisionDetection::reportAllContacts() { - PROFILE("CollisionDetection::reportAllContacts()", mProfiler); + RP3D_PROFILE("CollisionDetection::reportAllContacts()", mProfiler); // For each overlapping pairs in contact during the narrow-phase Map, OverlappingPair*>::Iterator it; @@ -532,13 +532,13 @@ void CollisionDetection::testAABBOverlap(const AABB& aabb, OverlapCallback* over CollisionBody* overlapBody = proxyShape->getBody(); // If the proxy shape is from a body that we have not already reported collision - if (reportedBodies.find(overlapBody->getID()) == reportedBodies.end()) { + if (reportedBodies.find(overlapBody->getId()) == reportedBodies.end()) { // Check if the collision filtering allows collision between the two shapes if ((proxyShape->getCollisionCategoryBits() & categoryMaskBits) != 0) { // Add the body into the set of reported bodies - reportedBodies.add(overlapBody->getID()); + reportedBodies.add(overlapBody->getId()); // Notify the overlap to the user overlapCallback->notifyOverlap(overlapBody); @@ -646,7 +646,7 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl LinkedList overlappingNodes(mMemoryManager.getPoolAllocator()); mBroadPhaseAlgorithm.reportAllShapesOverlappingWithAABB(shapeAABB, overlappingNodes); - const bodyindex bodyId = body->getID(); + const bodyindex bodyId = body->getId(); // For each overlaping proxy shape LinkedList::ListElement* element = overlappingNodes.getListHead(); @@ -658,8 +658,8 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl // If the proxy shape is from a body that we have not already reported collision and the // two proxy collision shapes are not from the same body - if (reportedBodies.find(proxyShape->getBody()->getID()) == reportedBodies.end() && - proxyShape->getBody()->getID() != bodyId) { + if (reportedBodies.find(proxyShape->getBody()->getId()) == reportedBodies.end() && + proxyShape->getBody()->getId() != bodyId) { // Check if the collision filtering allows collision between the two shapes if ((proxyShape->getCollisionCategoryBits() & categoryMaskBits) != 0) { @@ -711,7 +711,7 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl CollisionBody* overlapBody = proxyShape->getBody(); // Add the body into the set of reported bodies - reportedBodies.add(overlapBody->getID()); + reportedBodies.add(overlapBody->getId()); // Notify the overlap to the user overlapCallback->notifyOverlap(overlapBody); @@ -826,7 +826,7 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c LinkedList overlappingNodes(mMemoryManager.getPoolAllocator()); mBroadPhaseAlgorithm.reportAllShapesOverlappingWithAABB(shapeAABB, overlappingNodes); - const bodyindex bodyId = body->getID(); + const bodyindex bodyId = body->getId(); // For each overlaping proxy shape LinkedList::ListElement* element = overlappingNodes.getListHead(); @@ -837,7 +837,7 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c ProxyShape* proxyShape = mBroadPhaseAlgorithm.getProxyShapeForBroadPhaseId(broadPhaseId); // If the two proxy collision shapes are not from the same body - if (proxyShape->getBody()->getID() != bodyId) { + if (proxyShape->getBody()->getId() != bodyId) { // Check if the collision filtering allows collision between the two shapes if ((proxyShape->getCollisionCategoryBits() & categoryMaskBits) != 0) { diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index 4dc45634..d8f5240a 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -314,7 +314,7 @@ inline void CollisionDetection::raycast(RaycastCallback* raycastCallback, const Ray& ray, unsigned short raycastWithCategoryMaskBits) const { - PROFILE("CollisionDetection::raycast()", mProfiler); + RP3D_PROFILE("CollisionDetection::raycast()", mProfiler); RaycastTest rayCastTest(raycastCallback); diff --git a/src/collision/broadphase/BroadPhaseAlgorithm.cpp b/src/collision/broadphase/BroadPhaseAlgorithm.cpp index 5f76e2c2..fbad0cfd 100644 --- a/src/collision/broadphase/BroadPhaseAlgorithm.cpp +++ b/src/collision/broadphase/BroadPhaseAlgorithm.cpp @@ -26,7 +26,7 @@ // Libraries #include "BroadPhaseAlgorithm.h" #include "collision/CollisionDetection.h" -#include "engine/Profiler.h" +#include "utils/Profiler.h" // We want to use the ReactPhysics3D namespace using namespace reactphysics3d; @@ -257,7 +257,7 @@ void BroadPhaseAlgorithm::computeOverlappingPairs(MemoryManager& memoryManager) ProxyShape* shape2 = static_cast(mDynamicAABBTree.getNodeDataPointer(pair->collisionShape2ID)); // If the two proxy collision shapes are from the same body, skip it - if (shape1->getBody()->getID() != shape2->getBody()->getID()) { + if (shape1->getBody()->getId() != shape2->getBody()->getId()) { // Notify the collision detection about the overlapping pair mCollisionDetection.broadPhaseNotifyOverlappingPair(shape1, shape2); diff --git a/src/collision/broadphase/BroadPhaseAlgorithm.h b/src/collision/broadphase/BroadPhaseAlgorithm.h index 3ae18677..df642677 100644 --- a/src/collision/broadphase/BroadPhaseAlgorithm.h +++ b/src/collision/broadphase/BroadPhaseAlgorithm.h @@ -30,7 +30,7 @@ #include "body/CollisionBody.h" #include "collision/ProxyShape.h" #include "DynamicAABBTree.h" -#include "engine/Profiler.h" +#include "utils/Profiler.h" #include "containers/LinkedList.h" /// Namespace ReactPhysics3D @@ -265,7 +265,7 @@ inline const AABB& BroadPhaseAlgorithm::getFatAABB(int broadPhaseId) const { inline void BroadPhaseAlgorithm::raycast(const Ray& ray, RaycastTest& raycastTest, unsigned short raycastWithCategoryMaskBits) const { - PROFILE("BroadPhaseAlgorithm::raycast()", mProfiler); + RP3D_PROFILE("BroadPhaseAlgorithm::raycast()", mProfiler); BroadPhaseRaycastCallback broadPhaseRaycastCallback(mDynamicAABBTree, raycastWithCategoryMaskBits, raycastTest); diff --git a/src/collision/broadphase/DynamicAABBTree.cpp b/src/collision/broadphase/DynamicAABBTree.cpp index bbc4b109..8e8bab04 100644 --- a/src/collision/broadphase/DynamicAABBTree.cpp +++ b/src/collision/broadphase/DynamicAABBTree.cpp @@ -27,7 +27,7 @@ #include "DynamicAABBTree.h" #include "BroadPhaseAlgorithm.h" #include "containers/Stack.h" -#include "engine/Profiler.h" +#include "utils/Profiler.h" using namespace reactphysics3d; @@ -173,7 +173,7 @@ void DynamicAABBTree::removeObject(int nodeID) { /// (this can be useful if the shape AABB has become much smaller than the previous one for instance). bool DynamicAABBTree::updateObject(int nodeID, const AABB& newAABB, const Vector3& displacement, bool forceReinsert) { - PROFILE("DynamicAABBTree::updateObject()", mProfiler); + RP3D_PROFILE("DynamicAABBTree::updateObject()", mProfiler); assert(nodeID >= 0 && nodeID < mNbAllocatedNodes); assert(mNodes[nodeID].isLeaf()); @@ -635,7 +635,7 @@ void DynamicAABBTree::reportAllShapesOverlappingWithAABB(const AABB& aabb, // Ray casting method void DynamicAABBTree::raycast(const Ray& ray, DynamicAABBTreeRaycastCallback &callback) const { - PROFILE("DynamicAABBTree::raycast()", mProfiler); + RP3D_PROFILE("DynamicAABBTree::raycast()", mProfiler); decimal maxFraction = ray.maxFraction; diff --git a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp index a7bc8667..a7d647ae 100644 --- a/src/collision/narrowphase/GJK/GJKAlgorithm.cpp +++ b/src/collision/narrowphase/GJK/GJKAlgorithm.cpp @@ -29,7 +29,7 @@ #include "engine/OverlappingPair.h" #include "collision/shapes/TriangleShape.h" #include "configuration.h" -#include "engine/Profiler.h" +#include "utils/Profiler.h" #include #include #include @@ -49,7 +49,7 @@ using namespace reactphysics3d; /// the correct penetration depth and contact points between the enlarged objects. GJKAlgorithm::GJKResult GJKAlgorithm::testCollision(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) { - PROFILE("GJKAlgorithm::testCollision()", mProfiler); + RP3D_PROFILE("GJKAlgorithm::testCollision()", mProfiler); Vector3 suppA; // Support point of object A Vector3 suppB; // Support point of object B diff --git a/src/collision/narrowphase/SAT/SATAlgorithm.cpp b/src/collision/narrowphase/SAT/SATAlgorithm.cpp index 66be7d06..421a4b5d 100644 --- a/src/collision/narrowphase/SAT/SATAlgorithm.cpp +++ b/src/collision/narrowphase/SAT/SATAlgorithm.cpp @@ -32,7 +32,7 @@ #include "engine/OverlappingPair.h" #include "collision/shapes/TriangleShape.h" #include "configuration.h" -#include "engine/Profiler.h" +#include "utils/Profiler.h" #include #include #include @@ -52,7 +52,7 @@ SATAlgorithm::SATAlgorithm(MemoryAllocator& memoryAllocator) : mMemoryAllocator( // Test collision between a sphere and a convex mesh bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) const { - PROFILE("SATAlgorithm::testCollisionSphereVsConvexPolyhedron()", mProfiler); + RP3D_PROFILE("SATAlgorithm::testCollisionSphereVsConvexPolyhedron()", mProfiler); bool isSphereShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::SPHERE; @@ -127,7 +127,7 @@ bool SATAlgorithm::testCollisionSphereVsConvexPolyhedron(NarrowPhaseInfo* narrow decimal SATAlgorithm::computePolyhedronFaceVsSpherePenetrationDepth(uint faceIndex, const ConvexPolyhedronShape* polyhedron, const SphereShape* sphere, const Vector3& sphereCenter) const { - PROFILE("SATAlgorithm::computePolyhedronFaceVsSpherePenetrationDepth)", mProfiler); + RP3D_PROFILE("SATAlgorithm::computePolyhedronFaceVsSpherePenetrationDepth)", mProfiler); // Get the face const HalfEdgeStructure::Face& face = polyhedron->getFace(faceIndex); @@ -144,7 +144,7 @@ decimal SATAlgorithm::computePolyhedronFaceVsSpherePenetrationDepth(uint faceInd // Test collision between a capsule and a convex mesh bool SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) const { - PROFILE("SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron()", mProfiler); + RP3D_PROFILE("SATAlgorithm::testCollisionCapsuleVsConvexPolyhedron()", mProfiler); bool isCapsuleShape1 = narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CAPSULE; @@ -304,7 +304,7 @@ decimal SATAlgorithm::computeEdgeVsCapsuleInnerSegmentPenetrationDepth(const Con const Vector3& edgeDirectionCapsuleSpace, const Transform& polyhedronToCapsuleTransform, Vector3& outAxis) const { - PROFILE("SATAlgorithm::computeEdgeVsCapsuleInnerSegmentPenetrationDepth)", mProfiler); + RP3D_PROFILE("SATAlgorithm::computeEdgeVsCapsuleInnerSegmentPenetrationDepth)", mProfiler); decimal penetrationDepth = DECIMAL_LARGEST; @@ -338,7 +338,7 @@ decimal SATAlgorithm::computePolyhedronFaceVsCapsulePenetrationDepth(uint polyhe const CapsuleShape* capsule, const Transform& polyhedronToCapsuleTransform, Vector3& outFaceNormalCapsuleSpace) const { - PROFILE("SATAlgorithm::computePolyhedronFaceVsCapsulePenetrationDepth", mProfiler); + RP3D_PROFILE("SATAlgorithm::computePolyhedronFaceVsCapsulePenetrationDepth", mProfiler); // Get the face const HalfEdgeStructure::Face& face = polyhedron->getFace(polyhedronFaceIndex); @@ -364,7 +364,7 @@ bool SATAlgorithm::computeCapsulePolyhedronFaceContactPoints(uint referenceFaceI const Vector3& capsuleSegAPolyhedronSpace, const Vector3& capsuleSegBPolyhedronSpace, NarrowPhaseInfo* narrowPhaseInfo, bool isCapsuleShape1) const { - PROFILE("SATAlgorithm::computeCapsulePolyhedronFaceContactPoints", mProfiler); + RP3D_PROFILE("SATAlgorithm::computeCapsulePolyhedronFaceContactPoints", mProfiler); const HalfEdgeStructure::Face& face = polyhedron->getFace(referenceFaceIndex); @@ -459,7 +459,7 @@ bool SATAlgorithm::isMinkowskiFaceCapsuleVsEdge(const Vector3& capsuleSegment, c // Test collision between two convex polyhedrons bool SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron(NarrowPhaseInfo* narrowPhaseInfo, bool reportContacts) const { - PROFILE("SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron()", mProfiler); + RP3D_PROFILE("SATAlgorithm::testCollisionConvexPolyhedronVsConvexPolyhedron()", mProfiler); assert(narrowPhaseInfo->collisionShape1->getType() == CollisionShapeType::CONVEX_POLYHEDRON); assert(narrowPhaseInfo->collisionShape2->getType() == CollisionShapeType::CONVEX_POLYHEDRON); @@ -804,7 +804,7 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene const Transform& polyhedron1ToPolyhedron2, const Transform& polyhedron2ToPolyhedron1, uint minFaceIndex, NarrowPhaseInfo* narrowPhaseInfo, decimal minPenetrationDepth) const { - PROFILE("SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints", mProfiler); + RP3D_PROFILE("SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints", mProfiler); const ConvexPolyhedronShape* referencePolyhedron = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron1 : polyhedron2; const ConvexPolyhedronShape* incidentPolyhedron = isMinPenetrationFaceNormalPolyhedron1 ? polyhedron2 : polyhedron1; @@ -919,7 +919,7 @@ decimal SATAlgorithm::computeDistanceBetweenEdges(const Vector3& edge1A, const V const Vector3& edge1Direction, const Vector3& edge2Direction, Vector3& outSeparatingAxisPolyhedron2Space) const { - PROFILE("SATAlgorithm::computeDistanceBetweenEdges", mProfiler); + RP3D_PROFILE("SATAlgorithm::computeDistanceBetweenEdges", mProfiler); // If the two edges are parallel if (areParallelVectors(edge1Direction, edge2Direction)) { @@ -948,7 +948,7 @@ decimal SATAlgorithm::testSingleFaceDirectionPolyhedronVsPolyhedron(const Convex const Transform& polyhedron1ToPolyhedron2, uint faceIndex) const { - PROFILE("SATAlgorithm::testSingleFaceDirectionPolyhedronVsPolyhedron", mProfiler); + RP3D_PROFILE("SATAlgorithm::testSingleFaceDirectionPolyhedronVsPolyhedron", mProfiler); const HalfEdgeStructure::Face& face = polyhedron1->getFace(faceIndex); @@ -974,7 +974,7 @@ decimal SATAlgorithm::testFacesDirectionPolyhedronVsPolyhedron(const ConvexPolyh const Transform& polyhedron1ToPolyhedron2, uint& minFaceIndex) const { - PROFILE("SATAlgorithm::testFacesDirectionPolyhedronVsPolyhedron", mProfiler); + RP3D_PROFILE("SATAlgorithm::testFacesDirectionPolyhedronVsPolyhedron", mProfiler); decimal minPenetrationDepth = DECIMAL_LARGEST; @@ -1006,7 +1006,7 @@ bool SATAlgorithm::testEdgesBuildMinkowskiFace(const ConvexPolyhedronShape* poly const ConvexPolyhedronShape* polyhedron2, const HalfEdgeStructure::Edge& edge2, const Transform& polyhedron1ToPolyhedron2) const { - PROFILE("SATAlgorithm::testEdgesBuildMinkowskiFace", mProfiler); + RP3D_PROFILE("SATAlgorithm::testEdgesBuildMinkowskiFace", mProfiler); const Vector3 a = polyhedron1ToPolyhedron2.getOrientation() * polyhedron1->getFaceNormal(edge1.faceIndex); const Vector3 b = polyhedron1ToPolyhedron2.getOrientation() * polyhedron1->getFaceNormal(polyhedron1->getHalfEdge(edge1.twinEdgeIndex).faceIndex); @@ -1039,7 +1039,7 @@ bool SATAlgorithm::testEdgesBuildMinkowskiFace(const ConvexPolyhedronShape* poly bool SATAlgorithm::testGaussMapArcsIntersect(const Vector3& a, const Vector3& b, const Vector3& c, const Vector3& d, const Vector3& bCrossA, const Vector3& dCrossC) const { - PROFILE("SATAlgorithm::testGaussMapArcsIntersect", mProfiler); + RP3D_PROFILE("SATAlgorithm::testGaussMapArcsIntersect", mProfiler); const decimal cba = c.dot(bCrossA); const decimal dba = d.dot(bCrossA); diff --git a/src/collision/shapes/CollisionShape.cpp b/src/collision/shapes/CollisionShape.cpp index 0b64190e..976c7a51 100644 --- a/src/collision/shapes/CollisionShape.cpp +++ b/src/collision/shapes/CollisionShape.cpp @@ -25,7 +25,7 @@ // Libraries #include "CollisionShape.h" -#include "engine/Profiler.h" +#include "utils/Profiler.h" #include "body/CollisionBody.h" // We want to use the ReactPhysics3D namespace @@ -48,7 +48,7 @@ CollisionShape::CollisionShape(CollisionShapeName name, CollisionShapeType type) */ void CollisionShape::computeAABB(AABB& aabb, const Transform& transform) const { - PROFILE("CollisionShape::computeAABB()", mProfiler); + RP3D_PROFILE("CollisionShape::computeAABB()", mProfiler); // Get the local bounds in x,y and z direction Vector3 minBounds; diff --git a/src/collision/shapes/CollisionShape.h b/src/collision/shapes/CollisionShape.h index 8d84ab55..3fdf4470 100644 --- a/src/collision/shapes/CollisionShape.h +++ b/src/collision/shapes/CollisionShape.h @@ -35,7 +35,7 @@ #include "AABB.h" #include "collision/RaycastInfo.h" #include "memory/PoolAllocator.h" -#include "engine/Profiler.h" +#include "utils/Profiler.h" /// ReactPhysics3D namespace namespace reactphysics3d { diff --git a/src/collision/shapes/ConcaveMeshShape.cpp b/src/collision/shapes/ConcaveMeshShape.cpp index d2046adc..768f7c2e 100644 --- a/src/collision/shapes/ConcaveMeshShape.cpp +++ b/src/collision/shapes/ConcaveMeshShape.cpp @@ -114,7 +114,7 @@ void ConcaveMeshShape::testAllTriangles(TriangleCallback& callback, const AABB& /// the ray hits many triangles. bool ConcaveMeshShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, MemoryAllocator& allocator) const { - PROFILE("ConcaveMeshShape::raycast()", mProfiler); + RP3D_PROFILE("ConcaveMeshShape::raycast()", mProfiler); // Create the callback object that will compute ray casting against triangles ConcaveMeshRaycastCallback raycastCallback(mDynamicAABBTree, *this, proxyShape, raycastInfo, ray, allocator); diff --git a/src/collision/shapes/ConcaveMeshShape.h b/src/collision/shapes/ConcaveMeshShape.h index 2ecefb94..d35c9d23 100644 --- a/src/collision/shapes/ConcaveMeshShape.h +++ b/src/collision/shapes/ConcaveMeshShape.h @@ -32,7 +32,7 @@ #include "collision/TriangleMesh.h" #include "collision/shapes/TriangleShape.h" #include "containers/List.h" -#include "engine/Profiler.h" +#include "utils/Profiler.h" namespace reactphysics3d { diff --git a/src/collision/shapes/HeightFieldShape.cpp b/src/collision/shapes/HeightFieldShape.cpp index badfb68d..df2019c0 100644 --- a/src/collision/shapes/HeightFieldShape.cpp +++ b/src/collision/shapes/HeightFieldShape.cpp @@ -217,7 +217,7 @@ bool HeightFieldShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxySh // TODO : Implement raycasting without using an AABB for the ray // but using a dynamic AABB tree or octree instead - PROFILE("HeightFieldShape::raycast()", mProfiler); + RP3D_PROFILE("HeightFieldShape::raycast()", mProfiler); TriangleOverlapCallback triangleCallback(ray, proxyShape, raycastInfo, *this, allocator); diff --git a/src/collision/shapes/HeightFieldShape.h b/src/collision/shapes/HeightFieldShape.h index fc587d4c..7b834e2b 100644 --- a/src/collision/shapes/HeightFieldShape.h +++ b/src/collision/shapes/HeightFieldShape.h @@ -29,7 +29,7 @@ // Libraries #include "ConcaveShape.h" #include "collision/shapes/TriangleShape.h" -#include "engine/Profiler.h" +#include "utils/Profiler.h" namespace reactphysics3d { diff --git a/src/collision/shapes/TriangleShape.cpp b/src/collision/shapes/TriangleShape.cpp index 2257c0e6..d3b7d753 100644 --- a/src/collision/shapes/TriangleShape.cpp +++ b/src/collision/shapes/TriangleShape.cpp @@ -27,7 +27,7 @@ #include "TriangleShape.h" #include "collision/ProxyShape.h" #include "mathematics/mathematics_functions.h" -#include "engine/Profiler.h" +#include "utils/Profiler.h" #include "configuration.h" #include @@ -213,7 +213,7 @@ Vector3 TriangleShape::computeSmoothLocalContactNormalForTriangle(const Vector3& /// Real-time Collision Detection by Christer Ericson. bool TriangleShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape, MemoryAllocator& allocator) const { - PROFILE("TriangleShape::raycast()", mProfiler); + RP3D_PROFILE("TriangleShape::raycast()", mProfiler); const Vector3 pq = ray.point2 - ray.point1; const Vector3 pa = mPoints[0] - ray.point1; diff --git a/src/constraint/BallAndSocketJoint.cpp b/src/constraint/BallAndSocketJoint.cpp index 272d922e..b1966d93 100644 --- a/src/constraint/BallAndSocketJoint.cpp +++ b/src/constraint/BallAndSocketJoint.cpp @@ -33,8 +33,8 @@ using namespace reactphysics3d; const decimal BallAndSocketJoint::BETA = decimal(0.2); // Constructor -BallAndSocketJoint::BallAndSocketJoint(const BallAndSocketJointInfo& jointInfo) - : Joint(jointInfo), mImpulse(Vector3(0, 0, 0)) { +BallAndSocketJoint::BallAndSocketJoint(uint id, const BallAndSocketJointInfo& jointInfo) + : Joint(id, jointInfo), mImpulse(Vector3(0, 0, 0)) { // Compute the local-space anchor point for each body mLocalAnchorPointBody1 = mBody1->getTransform().getInverse() * jointInfo.anchorPointWorldSpace; diff --git a/src/constraint/BallAndSocketJoint.h b/src/constraint/BallAndSocketJoint.h index c8836a23..ed66320f 100644 --- a/src/constraint/BallAndSocketJoint.h +++ b/src/constraint/BallAndSocketJoint.h @@ -125,7 +125,7 @@ class BallAndSocketJoint : public Joint { // -------------------- Methods -------------------- // /// Constructor - BallAndSocketJoint(const BallAndSocketJointInfo& jointInfo); + BallAndSocketJoint(uint id, const BallAndSocketJointInfo& jointInfo); /// Destructor virtual ~BallAndSocketJoint() override = default; diff --git a/src/constraint/FixedJoint.cpp b/src/constraint/FixedJoint.cpp index 17f9e455..94663c80 100644 --- a/src/constraint/FixedJoint.cpp +++ b/src/constraint/FixedJoint.cpp @@ -33,8 +33,8 @@ using namespace reactphysics3d; const decimal FixedJoint::BETA = decimal(0.2); // Constructor -FixedJoint::FixedJoint(const FixedJointInfo& jointInfo) - : Joint(jointInfo), mImpulseTranslation(0, 0, 0), mImpulseRotation(0, 0, 0) { +FixedJoint::FixedJoint(uint id, const FixedJointInfo& jointInfo) + : Joint(id, jointInfo), mImpulseTranslation(0, 0, 0), mImpulseRotation(0, 0, 0) { // Compute the local-space anchor point for each body const Transform& transform1 = mBody1->getTransform(); diff --git a/src/constraint/FixedJoint.h b/src/constraint/FixedJoint.h index e08b31cc..45fe1185 100644 --- a/src/constraint/FixedJoint.h +++ b/src/constraint/FixedJoint.h @@ -136,7 +136,7 @@ class FixedJoint : public Joint { // -------------------- Methods -------------------- // /// Constructor - FixedJoint(const FixedJointInfo& jointInfo); + FixedJoint(uint id, const FixedJointInfo& jointInfo); /// Destructor virtual ~FixedJoint() override = default; diff --git a/src/constraint/HingeJoint.cpp b/src/constraint/HingeJoint.cpp index 7b400a2a..990e7be1 100644 --- a/src/constraint/HingeJoint.cpp +++ b/src/constraint/HingeJoint.cpp @@ -34,8 +34,8 @@ using namespace reactphysics3d; const decimal HingeJoint::BETA = decimal(0.2); // Constructor -HingeJoint::HingeJoint(const HingeJointInfo& jointInfo) - : Joint(jointInfo), mImpulseTranslation(0, 0, 0), mImpulseRotation(0, 0), +HingeJoint::HingeJoint(uint id, const HingeJointInfo& jointInfo) + : Joint(id, jointInfo), mImpulseTranslation(0, 0, 0), mImpulseRotation(0, 0), mImpulseLowerLimit(0), mImpulseUpperLimit(0), mImpulseMotor(0), mIsLimitEnabled(jointInfo.isLimitEnabled), mIsMotorEnabled(jointInfo.isMotorEnabled), mLowerLimit(jointInfo.minAngleLimit), mUpperLimit(jointInfo.maxAngleLimit), diff --git a/src/constraint/HingeJoint.h b/src/constraint/HingeJoint.h index c553755d..fbcfeacf 100644 --- a/src/constraint/HingeJoint.h +++ b/src/constraint/HingeJoint.h @@ -287,7 +287,7 @@ class HingeJoint : public Joint { // -------------------- Methods -------------------- // /// Constructor - HingeJoint(const HingeJointInfo& jointInfo); + HingeJoint(uint id, const HingeJointInfo& jointInfo); /// Destructor virtual ~HingeJoint() override = default; diff --git a/src/constraint/Joint.cpp b/src/constraint/Joint.cpp index 2c0695ab..7582c1e0 100644 --- a/src/constraint/Joint.cpp +++ b/src/constraint/Joint.cpp @@ -29,8 +29,8 @@ using namespace reactphysics3d; // Constructor -Joint::Joint(const JointInfo& jointInfo) - :mBody1(jointInfo.body1), mBody2(jointInfo.body2), mType(jointInfo.type), +Joint::Joint(uint id, const JointInfo& jointInfo) + :mId(id), mBody1(jointInfo.body1), mBody2(jointInfo.body2), mType(jointInfo.type), mPositionCorrectionTechnique(jointInfo.positionCorrectionTechnique), mIsCollisionEnabled(jointInfo.isCollisionEnabled), mIsAlreadyInIsland(false) { diff --git a/src/constraint/Joint.h b/src/constraint/Joint.h index ead08a53..10d1680e 100644 --- a/src/constraint/Joint.h +++ b/src/constraint/Joint.h @@ -120,6 +120,9 @@ class Joint { // -------------------- Attributes -------------------- // + /// Id of the joint + uint mId; + /// Pointer to the first body of the joint RigidBody* const mBody1; @@ -144,6 +147,9 @@ class Joint { /// True if the joint has already been added into an island bool mIsAlreadyInIsland; + /// Total number of joints + static uint mNbTotalNbJoints; + // -------------------- Methods -------------------- // /// Return true if the joint has already been added into an island @@ -169,7 +175,7 @@ class Joint { // -------------------- Methods -------------------- // /// Constructor - Joint(const JointInfo& jointInfo); + Joint(uint id, const JointInfo& jointInfo); /// Destructor virtual ~Joint() = default; @@ -195,6 +201,9 @@ class Joint { /// Return true if the collision between the two bodies of the joint is enabled bool isCollisionEnabled() const; + /// Return the id of the joint + uint getId() const; + // -------------------- Friendship -------------------- // friend class DynamicsWorld; @@ -243,6 +252,14 @@ inline bool Joint::isCollisionEnabled() const { return mIsCollisionEnabled; } +// Return the id of the joint +/** + * @return The id of the joint + */ +inline uint Joint::getId() const { + return mId; +} + // Return true if the joint has already been added into an island inline bool Joint::isAlreadyInIsland() const { return mIsAlreadyInIsland; diff --git a/src/constraint/SliderJoint.cpp b/src/constraint/SliderJoint.cpp index 715bdc25..174ddb67 100644 --- a/src/constraint/SliderJoint.cpp +++ b/src/constraint/SliderJoint.cpp @@ -32,8 +32,8 @@ using namespace reactphysics3d; const decimal SliderJoint::BETA = decimal(0.2); // Constructor -SliderJoint::SliderJoint(const SliderJointInfo& jointInfo) - : Joint(jointInfo), mImpulseTranslation(0, 0), mImpulseRotation(0, 0, 0), +SliderJoint::SliderJoint(uint id, const SliderJointInfo& jointInfo) + : Joint(id, jointInfo), mImpulseTranslation(0, 0), mImpulseRotation(0, 0, 0), mImpulseLowerLimit(0), mImpulseUpperLimit(0), mImpulseMotor(0), mIsLimitEnabled(jointInfo.isLimitEnabled), mIsMotorEnabled(jointInfo.isMotorEnabled), mLowerLimit(jointInfo.minTranslationLimit), diff --git a/src/constraint/SliderJoint.h b/src/constraint/SliderJoint.h index e01a9ab4..3fd0035e 100644 --- a/src/constraint/SliderJoint.h +++ b/src/constraint/SliderJoint.h @@ -285,7 +285,7 @@ class SliderJoint : public Joint { // -------------------- Methods -------------------- // /// Constructor - SliderJoint(const SliderJointInfo& jointInfo); + SliderJoint(uint id, const SliderJointInfo& jointInfo); /// Destructor virtual ~SliderJoint() override = default; diff --git a/src/containers/List.h b/src/containers/List.h index 49bd2d21..2af3b76e 100644 --- a/src/containers/List.h +++ b/src/containers/List.h @@ -29,6 +29,7 @@ // Libraries #include "configuration.h" #include "memory/MemoryAllocator.h" +#include #include #include diff --git a/src/containers/Pair.h b/src/containers/Pair.h index 8c34b4ac..89d333b2 100644 --- a/src/containers/Pair.h +++ b/src/containers/Pair.h @@ -86,7 +86,7 @@ class Pair { } -// Hash function for struct VerticesPair +// Hash function for a reactphysics3d Pair namespace std { template struct hash> { diff --git a/src/engine/CollisionWorld.cpp b/src/engine/CollisionWorld.cpp index b91897e1..7fb223e2 100644 --- a/src/engine/CollisionWorld.cpp +++ b/src/engine/CollisionWorld.cpp @@ -26,28 +26,64 @@ // Libraries #include "CollisionWorld.h" #include +#include // Namespaces using namespace reactphysics3d; using namespace std; +// Initialization of static fields +uint CollisionWorld::mNbWorlds = 0; + // Constructor -CollisionWorld::CollisionWorld(const WorldSettings& worldSettings) - : mConfig(worldSettings), mCollisionDetection(this, mMemoryManager), mBodies(mMemoryManager.getPoolAllocator()), mCurrentBodyID(0), - mFreeBodiesIDs(mMemoryManager.getPoolAllocator()), mEventListener(nullptr) { +CollisionWorld::CollisionWorld(const string& name, const WorldSettings& worldSettings) + : mConfig(worldSettings), mCollisionDetection(this, mMemoryManager), mBodies(mMemoryManager.getPoolAllocator()), mCurrentBodyId(0), + mFreeBodiesIds(mMemoryManager.getPoolAllocator()), mEventListener(nullptr), mName(name) { + + // Automatically generate a name for the world + if (mName == "") { + + std::stringstream ss; + ss << "world"; + + if (mNbWorlds > 0) { + ss << mNbWorlds; + } + + mName = ss.str(); + } #ifdef IS_PROFILING_ACTIVE - // Set the profiler - mCollisionDetection.setProfiler(&mProfiler); + // Add a destination file for the profiling data + mProfiler.addFileDestination("rp3d_profiling_" + mName + ".txt", Profiler::Format::Text); + + // Set the profiler + mCollisionDetection.setProfiler(&mProfiler); #endif +#ifdef IS_LOGGING_ACTIVE + + // Add a log destination file + uint logLevel = static_cast(Logger::Level::Info) | static_cast(Logger::Level::Warning) | + static_cast(Logger::Level::Error); + mLogger.addFileDestination("rp3d_log_" + mName + ".html", logLevel, Logger::Format::HTML); + +#endif + + mNbWorlds++; + + RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + "Collision World: Collision world " + mName + " has been created"); } // Destructor CollisionWorld::~CollisionWorld() { + RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + "Collision World: Collision world " + mName + " has been destroyed"); + // Destroy all the collision bodies that have not been removed for (int i=mBodies.size() - 1 ; i >= 0; i--) { destroyCollisionBody(mBodies[i]); @@ -64,7 +100,7 @@ CollisionWorld::~CollisionWorld() { CollisionBody* CollisionWorld::createCollisionBody(const Transform& transform) { // Get the next available body ID - bodyindex bodyID = computeNextAvailableBodyID(); + bodyindex bodyID = computeNextAvailableBodyId(); // Largest index cannot be used (it is used for invalid index) assert(bodyID < std::numeric_limits::max()); @@ -85,6 +121,9 @@ CollisionBody* CollisionWorld::createCollisionBody(const Transform& transform) { #endif + RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::Body, + "Collision Body " + std::to_string(bodyID) + ": New collision body created"); + // Return the pointer to the rigid body return collisionBody; } @@ -95,11 +134,14 @@ CollisionBody* CollisionWorld::createCollisionBody(const Transform& transform) { */ void CollisionWorld::destroyCollisionBody(CollisionBody* collisionBody) { + RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::Body, + "Collision Body " + std::to_string(collisionBody->getId()) + ": collision body destroyed"); + // Remove all the collision shapes of the body collisionBody->removeAllCollisionShapes(); // Add the body ID to the list of free IDs - mFreeBodiesIDs.add(collisionBody->getID()); + mFreeBodiesIds.add(collisionBody->getId()); // Call the destructor of the collision body collisionBody->~CollisionBody(); @@ -112,17 +154,17 @@ void CollisionWorld::destroyCollisionBody(CollisionBody* collisionBody) { } // Return the next available body ID -bodyindex CollisionWorld::computeNextAvailableBodyID() { +bodyindex CollisionWorld::computeNextAvailableBodyId() { // Compute the body ID bodyindex bodyID; - if (mFreeBodiesIDs.size() != 0) { - bodyID = mFreeBodiesIDs[mFreeBodiesIDs.size() - 1]; - mFreeBodiesIDs.removeAt(mFreeBodiesIDs.size() - 1); + if (mFreeBodiesIds.size() != 0) { + bodyID = mFreeBodiesIds[mFreeBodiesIds.size() - 1]; + mFreeBodiesIds.removeAt(mFreeBodiesIds.size() - 1); } else { - bodyID = mCurrentBodyID; - mCurrentBodyID++; + bodyID = mCurrentBodyId; + mCurrentBodyId++; } return bodyID; diff --git a/src/engine/CollisionWorld.h b/src/engine/CollisionWorld.h index b3664ea1..f85d2fc6 100644 --- a/src/engine/CollisionWorld.h +++ b/src/engine/CollisionWorld.h @@ -30,7 +30,8 @@ #include #include "mathematics/mathematics.h" #include "containers/List.h" -#include "Profiler.h" +#include "utils/Profiler.h" +#include "utils/Logger.h" #include "body/CollisionBody.h" #include "collision/RaycastInfo.h" #include "OverlappingPair.h" @@ -71,25 +72,37 @@ class CollisionWorld { /// All the bodies (rigid and soft) of the world List mBodies; - /// Current body ID - bodyindex mCurrentBodyID; + /// Current body id + bodyindex mCurrentBodyId; - /// List of free ID for rigid bodies - List mFreeBodiesIDs; + /// List of free ids for rigid bodies + List mFreeBodiesIds; /// Pointer to an event listener object EventListener* mEventListener; + /// Name of the collision world + std::string mName; + #ifdef IS_PROFILING_ACTIVE /// Real-time hierarchical profiler Profiler mProfiler; #endif +#ifdef IS_LOGGING_ACTIVE + + /// Logger + Logger mLogger; +#endif + + /// Total number of worlds + static uint mNbWorlds; + // -------------------- Methods -------------------- // - /// Return the next available body ID - bodyindex computeNextAvailableBodyID(); + /// Return the next available body id + bodyindex computeNextAvailableBodyId(); /// Reset all the contact manifolds linked list of each body void resetContactManifoldListsOfBodies(); @@ -99,7 +112,7 @@ class CollisionWorld { // -------------------- Methods -------------------- // /// Constructor - CollisionWorld(const WorldSettings& worldSettings = WorldSettings()); + CollisionWorld(const std::string& name = "", const WorldSettings& worldSettings = WorldSettings()); /// Destructor virtual ~CollisionWorld(); @@ -147,13 +160,24 @@ class CollisionWorld { #ifdef IS_PROFILING_ACTIVE - /// Set the name of the profiler - void setProfilerName(std::string name); + /// Return a reference to the profiler + Profiler& getProfiler(); + +#endif + +#ifdef IS_LOGGING_ACTIVE + + /// Return a reference to the logger + Logger& getLogger(); + #endif /// Return the current world-space AABB of given proxy shape AABB getWorldAABB(const ProxyShape* proxyShape) const; + /// Return the name of the world + const std::string& getName() const; + // -------------------- Friendship -------------------- // friend class CollisionDetection; @@ -224,11 +248,25 @@ inline void CollisionWorld::testOverlap(CollisionBody* body, OverlapCallback* ov mCollisionDetection.testOverlap(body, overlapCallback, categoryMaskBits); } +// Return the name of the world +inline const std::string& CollisionWorld::getName() const { + return mName; +} + #ifdef IS_PROFILING_ACTIVE -// Set the name of the profiler -inline void CollisionWorld::setProfilerName(std::string name) { - mProfiler.setName(name); +// Return a reference to the profiler +inline Profiler& CollisionWorld::getProfiler() { + return mProfiler; +} + +#endif + +#ifdef IS_LOGGING_ACTIVE + +// Return a reference to the logger +inline Logger& CollisionWorld::getLogger() { + return mLogger; } #endif diff --git a/src/engine/ConstraintSolver.cpp b/src/engine/ConstraintSolver.cpp index 5345cbaf..f3b94396 100644 --- a/src/engine/ConstraintSolver.cpp +++ b/src/engine/ConstraintSolver.cpp @@ -25,7 +25,7 @@ // Libraries #include "ConstraintSolver.h" -#include "Profiler.h" +#include "utils/Profiler.h" using namespace reactphysics3d; @@ -43,7 +43,7 @@ ConstraintSolver::ConstraintSolver() : mIsWarmStartingActive(true) { // Initialize the constraint solver for a given island void ConstraintSolver::initializeForIsland(decimal dt, Island* island) { - PROFILE("ConstraintSolver::initializeForIsland()", mProfiler); + RP3D_PROFILE("ConstraintSolver::initializeForIsland()", mProfiler); assert(island != nullptr); assert(island->getNbBodies() > 0); @@ -73,7 +73,7 @@ void ConstraintSolver::initializeForIsland(decimal dt, Island* island) { // Solve the velocity constraints void ConstraintSolver::solveVelocityConstraints(Island* island) { - PROFILE("ConstraintSolver::solveVelocityConstraints()", mProfiler); + RP3D_PROFILE("ConstraintSolver::solveVelocityConstraints()", mProfiler); assert(island != nullptr); assert(island->getNbJoints() > 0); @@ -90,7 +90,7 @@ void ConstraintSolver::solveVelocityConstraints(Island* island) { // Solve the position constraints void ConstraintSolver::solvePositionConstraints(Island* island) { - PROFILE("ConstraintSolver::solvePositionConstraints()", mProfiler); + RP3D_PROFILE("ConstraintSolver::solvePositionConstraints()", mProfiler); assert(island != nullptr); assert(island->getNbJoints() > 0); diff --git a/src/engine/ContactSolver.cpp b/src/engine/ContactSolver.cpp index c6ef746e..d7539ca9 100644 --- a/src/engine/ContactSolver.cpp +++ b/src/engine/ContactSolver.cpp @@ -27,7 +27,7 @@ #include "ContactSolver.h" #include "DynamicsWorld.h" #include "body/RigidBody.h" -#include "Profiler.h" +#include "utils/Profiler.h" #include using namespace reactphysics3d; @@ -50,7 +50,7 @@ ContactSolver::ContactSolver(MemoryManager& memoryManager, const WorldSettings& // Initialize the contact constraints void ContactSolver::init(Island** islands, uint nbIslands, decimal timeStep) { - PROFILE("ContactSolver::init()", mProfiler); + RP3D_PROFILE("ContactSolver::init()", mProfiler); mTimeStep = timeStep; @@ -98,7 +98,7 @@ void ContactSolver::init(Island** islands, uint nbIslands, decimal timeStep) { // Initialize the constraint solver for a given island void ContactSolver::initializeForIsland(Island* island) { - PROFILE("ContactSolver::initializeForIsland()", mProfiler); + RP3D_PROFILE("ContactSolver::initializeForIsland()", mProfiler); assert(island != nullptr); assert(island->getNbBodies() > 0); @@ -326,7 +326,7 @@ void ContactSolver::initializeForIsland(Island* island) { /// the solution of the linear system void ContactSolver::warmStart() { - PROFILE("ContactSolver::warmStart()", mProfiler); + RP3D_PROFILE("ContactSolver::warmStart()", mProfiler); uint contactPointIndex = 0; @@ -479,7 +479,7 @@ void ContactSolver::warmStart() { // Solve the contacts void ContactSolver::solve() { - PROFILE("ContactSolver::solve()", mProfiler); + RP3D_PROFILE("ContactSolver::solve()", mProfiler); decimal deltaLambda; decimal lambdaTemp; @@ -758,7 +758,7 @@ void ContactSolver::solve() { // warm start the solver at the next iteration void ContactSolver::storeImpulses() { - PROFILE("ContactSolver::storeImpulses()", mProfiler); + RP3D_PROFILE("ContactSolver::storeImpulses()", mProfiler); uint contactPointIndex = 0; @@ -786,7 +786,7 @@ void ContactSolver::storeImpulses() { void ContactSolver::computeFrictionVectors(const Vector3& deltaVelocity, ContactManifoldSolver& contact) const { - PROFILE("ContactSolver::computeFrictionVectors()", mProfiler); + RP3D_PROFILE("ContactSolver::computeFrictionVectors()", mProfiler); assert(contact.normal.length() > decimal(0.0)); diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index 3199b775..f8ac6033 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -39,8 +39,8 @@ using namespace std; /** * @param gravity Gravity vector in the world (in meters per second squared) */ -DynamicsWorld::DynamicsWorld(const Vector3 &gravity, const WorldSettings& worldSettings) - : CollisionWorld(worldSettings), +DynamicsWorld::DynamicsWorld(const Vector3& gravity, const string& name, const WorldSettings& worldSettings) + : CollisionWorld(name, worldSettings), mContactSolver(mMemoryManager, mConfig), mNbVelocitySolverIterations(mConfig.defaultVelocitySolverNbIterations), mNbPositionSolverIterations(mConfig.defaultPositionSolverNbIterations), @@ -52,7 +52,8 @@ DynamicsWorld::DynamicsWorld(const Vector3 &gravity, const WorldSettings& worldS mConstrainedOrientations(nullptr), mNbIslands(0), mIslands(nullptr), mSleepLinearVelocity(mConfig.defaultSleepLinearVelocity), mSleepAngularVelocity(mConfig.defaultSleepAngularVelocity), - mTimeBeforeSleep(mConfig.defaultTimeBeforeSleep) { + mTimeBeforeSleep(mConfig.defaultTimeBeforeSleep), + mFreeJointsIDs(mMemoryManager.getPoolAllocator()), mCurrentJointId(0) { #ifdef IS_PROFILING_ACTIVE @@ -62,6 +63,9 @@ DynamicsWorld::DynamicsWorld(const Vector3 &gravity, const WorldSettings& worldS #endif + RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + "Dynamics world " + mName + " has been created"); + } // Destructor @@ -82,13 +86,12 @@ DynamicsWorld::~DynamicsWorld() { #ifdef IS_PROFILING_ACTIVE - // Print the profiling report - ofstream myfile; - myfile.open(mProfiler.getName() + ".txt"); - mProfiler.printReport(myfile); - myfile.close(); + // Print the profiling report into the destinations + mProfiler.printReport(); #endif + RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + "Dynamics world " + mName + " has been destroyed"); } // Update the physics simulation @@ -102,7 +105,7 @@ void DynamicsWorld::update(decimal timeStep) { mProfiler.incrementFrameCounter(); #endif - PROFILE("DynamicsWorld::update()", &mProfiler); + RP3D_PROFILE("DynamicsWorld::update()", &mProfiler); mTimeStep = timeStep; @@ -150,7 +153,7 @@ void DynamicsWorld::update(decimal timeStep) { /// the sympletic Euler time stepping scheme. void DynamicsWorld::integrateRigidBodiesPositions() { - PROFILE("DynamicsWorld::integrateRigidBodiesPositions()", &mProfiler); + RP3D_PROFILE("DynamicsWorld::integrateRigidBodiesPositions()", &mProfiler); // For each island of the world for (uint i=0; i < mNbIslands; i++) { @@ -189,7 +192,7 @@ void DynamicsWorld::integrateRigidBodiesPositions() { // Update the postion/orientation of the bodies void DynamicsWorld::updateBodiesState() { - PROFILE("DynamicsWorld::updateBodiesState()", &mProfiler); + RP3D_PROFILE("DynamicsWorld::updateBodiesState()", &mProfiler); // For each island of the world for (uint islandIndex = 0; islandIndex < mNbIslands; islandIndex++) { @@ -226,7 +229,7 @@ void DynamicsWorld::updateBodiesState() { // Initialize the bodies velocities arrays for the next simulation step. void DynamicsWorld::initVelocityArrays() { - PROFILE("DynamicsWorld::initVelocityArrays()", &mProfiler); + RP3D_PROFILE("DynamicsWorld::initVelocityArrays()", &mProfiler); // Allocate memory for the bodies velocity arrays uint nbBodies = mRigidBodies.size(); @@ -268,7 +271,7 @@ void DynamicsWorld::initVelocityArrays() { /// contact solver. void DynamicsWorld::integrateRigidBodiesVelocities() { - PROFILE("DynamicsWorld::integrateRigidBodiesVelocities()", &mProfiler); + RP3D_PROFILE("DynamicsWorld::integrateRigidBodiesVelocities()", &mProfiler); // Initialize the bodies velocity arrays initVelocityArrays(); @@ -330,7 +333,7 @@ void DynamicsWorld::integrateRigidBodiesVelocities() { // Solve the contacts and constraints void DynamicsWorld::solveContactsAndConstraints() { - PROFILE("DynamicsWorld::solveContactsAndConstraints()", &mProfiler); + RP3D_PROFILE("DynamicsWorld::solveContactsAndConstraints()", &mProfiler); // Set the velocities arrays mContactSolver.setSplitVelocitiesArrays(mSplitLinearVelocities, mSplitAngularVelocities); @@ -380,7 +383,7 @@ void DynamicsWorld::solveContactsAndConstraints() { // Solve the position error correction of the constraints void DynamicsWorld::solvePositionCorrection() { - PROFILE("DynamicsWorld::solvePositionCorrection()", &mProfiler); + RP3D_PROFILE("DynamicsWorld::solvePositionCorrection()", &mProfiler); // Do not continue if there is no constraints if (mJoints.size() == 0) return; @@ -407,7 +410,7 @@ void DynamicsWorld::solvePositionCorrection() { RigidBody* DynamicsWorld::createRigidBody(const Transform& transform) { // Compute the body ID - bodyindex bodyID = computeNextAvailableBodyID(); + bodyindex bodyID = computeNextAvailableBodyId(); // Largest index cannot be used (it is used for invalid index) assert(bodyID < std::numeric_limits::max()); @@ -427,6 +430,9 @@ RigidBody* DynamicsWorld::createRigidBody(const Transform& transform) { #endif + RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::Body, + "Rigid Body " + std::to_string(bodyID) + ": New collision body created"); + // Return the pointer to the rigid body return rigidBody; } @@ -437,11 +443,14 @@ RigidBody* DynamicsWorld::createRigidBody(const Transform& transform) { */ void DynamicsWorld::destroyRigidBody(RigidBody* rigidBody) { + RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::Body, + "Rigid Body " + std::to_string(rigidBody->getId()) + ": rigid body destroyed"); + // Remove all the collision shapes of the body rigidBody->removeAllCollisionShapes(); // Add the body ID to the list of free IDs - mFreeBodiesIDs.add(rigidBody->getID()); + mFreeBodiesIds.add(rigidBody->getId()); // Destroy all the joints in which the rigid body to be destroyed is involved JointListElement* element; @@ -472,6 +481,9 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { Joint* newJoint = nullptr; + // Get the next available joint ID + uint jointId = computeNextAvailableJointId(); + // Allocate memory to create the new joint switch(jointInfo.type) { @@ -482,7 +494,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { sizeof(BallAndSocketJoint)); const BallAndSocketJointInfo& info = static_cast( jointInfo); - newJoint = new (allocatedMemory) BallAndSocketJoint(info); + newJoint = new (allocatedMemory) BallAndSocketJoint(jointId, info); break; } @@ -492,7 +504,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { void* allocatedMemory = mMemoryManager.allocate(MemoryManager::AllocationType::Pool, sizeof(SliderJoint)); const SliderJointInfo& info = static_cast(jointInfo); - newJoint = new (allocatedMemory) SliderJoint(info); + newJoint = new (allocatedMemory) SliderJoint(jointId, info); break; } @@ -502,7 +514,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { void* allocatedMemory = mMemoryManager.allocate(MemoryManager::AllocationType::Pool, sizeof(HingeJoint)); const HingeJointInfo& info = static_cast(jointInfo); - newJoint = new (allocatedMemory) HingeJoint(info); + newJoint = new (allocatedMemory) HingeJoint(jointId, info); break; } @@ -512,7 +524,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { void* allocatedMemory = mMemoryManager.allocate(MemoryManager::AllocationType::Pool, sizeof(FixedJoint)); const FixedJointInfo& info = static_cast(jointInfo); - newJoint = new (allocatedMemory) FixedJoint(info); + newJoint = new (allocatedMemory) FixedJoint(jointId, info); break; } @@ -536,6 +548,9 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { // Add the joint into the joint list of the bodies involved in the joint addJointToBody(newJoint); + RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::Joint, + "Joint " + std::to_string(newJoint->getId()) + ": New joint created"); + // Return the pointer to the created joint return newJoint; } @@ -548,6 +563,9 @@ void DynamicsWorld::destroyJoint(Joint* joint) { assert(joint != nullptr); + RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::Joint, + "Joint " + std::to_string(joint->getId()) + ": joint destroyed"); + // If the collision between the two bodies of the constraint was disabled if (!joint->isCollisionEnabled()) { @@ -568,9 +586,15 @@ void DynamicsWorld::destroyJoint(Joint* joint) { size_t nbBytes = joint->getSizeInBytes(); + // Add the joint ID to the list of free IDs + mFreeJointsIDs.add(joint->getId()); + // Call the destructor of the joint joint->~Joint(); + // Add the joint ID to the list of free IDs + mFreeJointsIDs.add(joint->getId()); + // Release the allocated memory mMemoryManager.release(MemoryManager::AllocationType::Pool, joint, nbBytes); } @@ -595,6 +619,23 @@ void DynamicsWorld::addJointToBody(Joint* joint) { joint->mBody2->mJointsList = jointListElement2; } +// Return the next available joint Id +uint DynamicsWorld::computeNextAvailableJointId() { + + // Compute the joint ID + uint jointId; + if (mFreeJointsIDs.size() != 0) { + jointId = mFreeJointsIDs[mFreeJointsIDs.size() - 1]; + mFreeJointsIDs.removeAt(mFreeJointsIDs.size() - 1); + } + else { + jointId = mCurrentJointId; + mCurrentJointId++; + } + + return jointId; +} + // Compute the islands of awake bodies. /// An island is an isolated group of rigid bodies that have constraints (joints or contacts) /// between each other. This method computes the islands at each time step as follows: For each @@ -604,7 +645,7 @@ void DynamicsWorld::addJointToBody(Joint* joint) { /// it). Then, we create an island with this group of connected bodies. void DynamicsWorld::computeIslands() { - PROFILE("DynamicsWorld::computeIslands()", &mProfiler); + RP3D_PROFILE("DynamicsWorld::computeIslands()", &mProfiler); uint nbBodies = mRigidBodies.size(); @@ -693,7 +734,7 @@ void DynamicsWorld::computeIslands() { // Get the other body of the contact manifold RigidBody* body1 = static_cast(contactManifold->getBody1()); RigidBody* body2 = static_cast(contactManifold->getBody2()); - RigidBody* otherBody = (body1->getID() == bodyToVisit->getID()) ? body2 : body1; + RigidBody* otherBody = (body1->getId() == bodyToVisit->getId()) ? body2 : body1; // Check if the other body has already been added to the island if (otherBody->mIsAlreadyInIsland) continue; @@ -721,7 +762,7 @@ void DynamicsWorld::computeIslands() { // Get the other body of the contact manifold RigidBody* body1 = static_cast(joint->getBody1()); RigidBody* body2 = static_cast(joint->getBody2()); - RigidBody* otherBody = (body1->getID() == bodyToVisit->getID()) ? body2 : body1; + RigidBody* otherBody = (body1->getId() == bodyToVisit->getId()) ? body2 : body1; // Check if the other body has already been added to the island if (otherBody->mIsAlreadyInIsland) continue; @@ -751,7 +792,7 @@ void DynamicsWorld::computeIslands() { /// time, we put all the bodies of the island to sleep. void DynamicsWorld::updateSleepingBodies() { - PROFILE("DynamicsWorld::updateSleepingBodies()", &mProfiler); + RP3D_PROFILE("DynamicsWorld::updateSleepingBodies()", &mProfiler); const decimal sleepLinearVelocitySquare = mSleepLinearVelocity * mSleepLinearVelocity; const decimal sleepAngularVelocitySquare = mSleepAngularVelocity * mSleepAngularVelocity; @@ -820,6 +861,9 @@ void DynamicsWorld::enableSleeping(bool isSleepingEnabled) { (*it)->setIsSleeping(false); } } + + RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + "Dynamics World: isSleepingEnabled=" + (isSleepingEnabled ? std::string("true") : std::string("false")) ); } /// Return the list of all contacts of the world diff --git a/src/engine/DynamicsWorld.h b/src/engine/DynamicsWorld.h index e71c83e4..f8016fdc 100644 --- a/src/engine/DynamicsWorld.h +++ b/src/engine/DynamicsWorld.h @@ -116,6 +116,12 @@ class DynamicsWorld : public CollisionWorld { /// becomes smaller than the sleep velocity. decimal mTimeBeforeSleep; + /// List of free ID for joints + List mFreeJointsIDs; + + /// Current joint id + uint mCurrentJointId; + // -------------------- Methods -------------------- // /// Integrate the positions and orientations of rigid bodies. @@ -148,12 +154,16 @@ class DynamicsWorld : public CollisionWorld { /// Add the joint to the list of joints of the two bodies involved in the joint void addJointToBody(Joint* joint); + /// Return the next available joint id + uint computeNextAvailableJointId(); + public : // -------------------- Methods -------------------- // /// Constructor - DynamicsWorld(const Vector3& mGravity, const WorldSettings& worldSettings = WorldSettings()); + DynamicsWorld(const Vector3& mGravity, const std::string& name = "", + const WorldSettings& worldSettings = WorldSettings()); /// Destructor virtual ~DynamicsWorld() override; @@ -272,6 +282,9 @@ inline uint DynamicsWorld::getNbIterationsVelocitySolver() const { */ inline void DynamicsWorld::setNbIterationsVelocitySolver(uint nbIterations) { mNbVelocitySolverIterations = nbIterations; + + RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + "Dynamics World: Set nb iterations velocity solver to " + std::to_string(nbIterations)); } // Get the number of iterations for the position constraint solver @@ -285,6 +298,9 @@ inline uint DynamicsWorld::getNbIterationsPositionSolver() const { */ inline void DynamicsWorld::setNbIterationsPositionSolver(uint nbIterations) { mNbPositionSolverIterations = nbIterations; + + RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + "Dynamics World: Set nb iterations position solver to " + std::to_string(nbIterations)); } // Set the position correction technique used for contacts @@ -329,6 +345,9 @@ inline Vector3 DynamicsWorld::getGravity() const { */ inline void DynamicsWorld::setGravity(Vector3& gravity) { mGravity = gravity; + + RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + "Dynamics World: Set gravity vector to " + gravity.to_string()); } // Return if the gravity is enaled @@ -346,6 +365,9 @@ inline bool DynamicsWorld::isGravityEnabled() const { */ inline void DynamicsWorld::setIsGratityEnabled(bool isGravityEnabled) { mIsGravityEnabled = isGravityEnabled; + + RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + "Dynamics World: isGravityEnabled= " + (isGravityEnabled ? std::string("true") : std::string("false"))); } // Return the number of rigid bodies in the world @@ -390,6 +412,9 @@ inline decimal DynamicsWorld::getSleepLinearVelocity() const { inline void DynamicsWorld::setSleepLinearVelocity(decimal sleepLinearVelocity) { assert(sleepLinearVelocity >= decimal(0.0)); mSleepLinearVelocity = sleepLinearVelocity; + + RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + "Dynamics World: sleepLinearVelocity= " + std::to_string(sleepLinearVelocity)); } // Return the current sleep angular velocity @@ -410,6 +435,9 @@ inline decimal DynamicsWorld::getSleepAngularVelocity() const { inline void DynamicsWorld::setSleepAngularVelocity(decimal sleepAngularVelocity) { assert(sleepAngularVelocity >= decimal(0.0)); mSleepAngularVelocity = sleepAngularVelocity; + + RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + "Dynamics World: sleepAngularVelocity= " + std::to_string(sleepAngularVelocity)); } // Return the time a body is required to stay still before sleeping @@ -428,6 +456,9 @@ inline decimal DynamicsWorld::getTimeBeforeSleep() const { inline void DynamicsWorld::setTimeBeforeSleep(decimal timeBeforeSleep) { assert(timeBeforeSleep >= decimal(0.0)); mTimeBeforeSleep = timeBeforeSleep; + + RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + "Dynamics World: timeBeforeSleep= " + std::to_string(timeBeforeSleep)); } // Set an event listener object to receive events callbacks. diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index 4b98c9be..3fa083a1 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -263,9 +263,9 @@ inline bodyindexpair OverlappingPair::computeBodiesIndexPair(CollisionBody* body CollisionBody* body2) { // Construct the pair of body index - bodyindexpair indexPair = body1->getID() < body2->getID() ? - bodyindexpair(body1->getID(), body2->getID()) : - bodyindexpair(body2->getID(), body1->getID()); + bodyindexpair indexPair = body1->getId() < body2->getId() ? + bodyindexpair(body1->getId(), body2->getId()) : + bodyindexpair(body2->getId(), body1->getId()); assert(indexPair.first != indexPair.second); return indexPair; } diff --git a/src/mathematics/Matrix2x2.h b/src/mathematics/Matrix2x2.h index 8315eb99..0aeb3f5c 100644 --- a/src/mathematics/Matrix2x2.h +++ b/src/mathematics/Matrix2x2.h @@ -28,6 +28,7 @@ // Libraries #include +#include #include "Vector2.h" /// ReactPhysics3D namespace @@ -145,6 +146,9 @@ class Matrix2x2 { /// Overloaded operator to read/write element of the matrix. Vector2& operator[](int row); + + /// Return the string representation + std::string to_string() const; }; // Constructor of the class Matrix2x2 @@ -340,6 +344,12 @@ inline Vector2& Matrix2x2::operator[](int row) { return mRows[row]; } +// Get the string representation +inline std::string Matrix2x2::to_string() const { + return "Matrix2x2(" + std::to_string(mRows[0][0]) + "," + std::to_string(mRows[0][1]) + "," + + std::to_string(mRows[1][0]) + "," + std::to_string(mRows[1][1]) + ")"; +} + } #endif diff --git a/src/mathematics/Matrix3x3.h b/src/mathematics/Matrix3x3.h index 6897a2cf..fe2b053a 100644 --- a/src/mathematics/Matrix3x3.h +++ b/src/mathematics/Matrix3x3.h @@ -29,6 +29,7 @@ // Libraries #include +#include #include "Vector3.h" /// ReactPhysics3D namespace @@ -153,6 +154,9 @@ class Matrix3x3 { /// Overloaded operator to read/write element of the matrix. Vector3& operator[](int row); + + /// Return the string representation + std::string to_string() const; }; // Constructor of the class Matrix3x3 @@ -392,6 +396,13 @@ inline Vector3& Matrix3x3::operator[](int row) { return mRows[row]; } +// Get the string representation +inline std::string Matrix3x3::to_string() const { + return "Matrix3x3(" + std::to_string(mRows[0][0]) + "," + std::to_string(mRows[0][1]) + "," + std::to_string(mRows[0][2]) + "," + + std::to_string(mRows[1][0]) + "," + std::to_string(mRows[1][1]) + "," + std::to_string(mRows[1][2]) + "," + + std::to_string(mRows[2][0]) + "," + std::to_string(mRows[2][1]) + "," + std::to_string(mRows[2][2]) + ")"; +} + } #endif diff --git a/src/mathematics/Quaternion.h b/src/mathematics/Quaternion.h index dd0726dc..70f5a729 100644 --- a/src/mathematics/Quaternion.h +++ b/src/mathematics/Quaternion.h @@ -163,6 +163,9 @@ struct Quaternion { /// Overloaded operator for equality condition bool operator==(const Quaternion& quaternion) const; + /// Return the string representation + std::string to_string() const; + private: /// Initialize the quaternion using Euler angles @@ -379,6 +382,12 @@ inline bool Quaternion::operator==(const Quaternion& quaternion) const { z == quaternion.z && w == quaternion.w); } +// Get the string representation +inline std::string Quaternion::to_string() const { + return "Quaternion(" + std::to_string(x) + "," + std::to_string(y) + "," + std::to_string(z) + "," + + std::to_string(w) + ")"; +} + } #endif diff --git a/src/mathematics/Transform.h b/src/mathematics/Transform.h index aeaf4234..91dd4cb1 100644 --- a/src/mathematics/Transform.h +++ b/src/mathematics/Transform.h @@ -116,6 +116,9 @@ class Transform { /// Assignment operator Transform& operator=(const Transform& transform); + + /// Return the string representation + std::string to_string() const; }; // Constructor @@ -268,6 +271,11 @@ inline Transform& Transform::operator=(const Transform& transform) { return *this; } +// Get the string representation +inline std::string Transform::to_string() const { + return "Transform(" + mPosition.to_string() + "," + mOrientation.to_string() + ")"; +} + } #endif diff --git a/src/mathematics/Vector2.h b/src/mathematics/Vector2.h index bc5f8872..9f66ef4b 100644 --- a/src/mathematics/Vector2.h +++ b/src/mathematics/Vector2.h @@ -29,6 +29,7 @@ // Libraries #include #include +#include #include "mathematics_functions.h" #include "decimal.h" @@ -135,6 +136,9 @@ struct Vector2 { /// Overloaded less than operator for ordering to be used inside std::set for instance bool operator<(const Vector2& vector) const; + /// Return the string representation + std::string to_string() const; + /// Return a vector taking the minimum components of two vectors static Vector2 min(const Vector2& vector1, const Vector2& vector2); @@ -352,6 +356,11 @@ inline Vector2 Vector2::max(const Vector2& vector1, const Vector2& vector2) { std::max(vector1.y, vector2.y)); } +// Get the string representation +inline std::string Vector2::to_string() const { + return "Vector2(" + std::to_string(x) + "," + std::to_string(y) + ")"; +} + // Return the zero vector inline Vector2 Vector2::zero() { return Vector2(0, 0); diff --git a/src/mathematics/Vector3.h b/src/mathematics/Vector3.h index 95255fdb..27f5bcf6 100644 --- a/src/mathematics/Vector3.h +++ b/src/mathematics/Vector3.h @@ -29,6 +29,7 @@ // Libraries #include #include +#include #include "mathematics_functions.h" #include "decimal.h" @@ -147,6 +148,9 @@ struct Vector3 { /// Overloaded less than operator for ordering to be used inside std::set for instance bool operator<(const Vector3& vector) const; + /// Get the string representation + std::string to_string() const; + /// Return a vector taking the minimum components of two vectors static Vector3 min(const Vector3& vector1, const Vector3& vector2); @@ -391,6 +395,11 @@ inline decimal Vector3::getMaxValue() const { return std::max(std::max(x, y), z); } +// Get the string representation +inline std::string Vector3::to_string() const { + return "Vector3(" + std::to_string(x) + "," + std::to_string(y) + "," + std::to_string(z) + ")"; +} + // Return the zero vector inline Vector3 Vector3::zero() { return Vector3(0, 0, 0); diff --git a/src/utils/Logger.cpp b/src/utils/Logger.cpp new file mode 100644 index 00000000..89634598 --- /dev/null +++ b/src/utils/Logger.cpp @@ -0,0 +1,102 @@ +/******************************************************************************** +* 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. * +* * +********************************************************************************/ + +#ifdef IS_LOGGING_ACTIVE + +// Libraries +#include "Logger.h" +#include "memory/MemoryManager.h" + +using namespace reactphysics3d; + +// Constructor +Logger::Logger() + : mDestinations(MemoryManager::getBaseAllocator()), mFormatters(MemoryManager::getBaseAllocator()) +{ + + // Create the log formatters + mFormatters.add(Pair(Format::Text, new TextFormatter())); + mFormatters.add(Pair(Format::HTML, new HtmlFormatter())); +} + +// Destructor +Logger::~Logger() { + + removeAllDestinations(); + + // Remove all the loggers + for (auto it = mFormatters.begin(); it != mFormatters.end(); ++it) { + + delete it->second; + } +} + +// Return the corresponding formatter +Logger::Formatter* Logger::getFormatter(Format format) const { + + auto it = mFormatters.find(format); + if (it != mFormatters.end()) { + return it->second; + } + + return nullptr; +} + +// Add a log file destination to the logger +void Logger::addFileDestination(const std::string& filePath, uint logLevelFlag, Format format) { + + FileDestination* destination = new FileDestination(filePath, logLevelFlag, getFormatter(format)); + mDestinations.add(destination); +} + +/// Add a stream destination to the logger +void Logger::addStreamDestination(std::ostream& outputStream, uint logLevelFlag, Format format) { + + StreamDestination* destination = new StreamDestination(outputStream, logLevelFlag, getFormatter(format)); + mDestinations.add(destination); +} + +// Remove all logs destination previously set +void Logger::removeAllDestinations() { + + // Delete all the destinations + for (uint i=0; iwrite(message, level, category); + } +} + +#endif diff --git a/src/utils/Logger.h b/src/utils/Logger.h new file mode 100644 index 00000000..9c6421db --- /dev/null +++ b/src/utils/Logger.h @@ -0,0 +1,332 @@ +/******************************************************************************** +* 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_LOGGER_H +#define REACTPHYSICS3D_LOGGER_H + +#ifdef IS_LOGGING_ACTIVE + +// Libraries +#include "containers/List.h" +#include "containers/Map.h" +#include +#include +#include +#include + +/// ReactPhysics3D namespace +namespace reactphysics3d { + +// Class Logger +/** + * This class is used to log information, warnings or errors during the execution of the + * library code for easier debugging. + */ +class Logger { + + public: + + /// Log verbosity levels + enum class Level {Error = 1, Warning = 2, Info = 4}; + + /// Log categories + enum class Category {World, Body, Joint}; + + /// Log verbosity level + enum class Format {Text, HTML}; + + /// Log formatter + class Formatter { + + public: + + /// Constructor + Formatter() { + + } + + /// Destructor + virtual ~Formatter() { + + } + + /// Return the header to write at the beginning of the stream + virtual std::string getHeader() const { + return ""; + } + + /// Return the tail to write at the end of the stream + virtual std::string getTail() const { + return ""; + } + + /// Format a log message + virtual std::string format(const std::string& message, Level level, Category category) = 0; + }; + + class TextFormatter : public Formatter { + + public: + + /// Constructor + TextFormatter() { + + } + + /// Destructor + virtual ~TextFormatter() { + + } + + /// Format a log message + virtual std::string format(const std::string& message, Level level, + Category category) override { + return message; + } + }; + + class HtmlFormatter : public Formatter { + + private: + + /// Return the header to write at the beginning of the stream + virtual std::string getHeader() const override { + + std::stringstream ss; + + ss << "" << std::endl; + ss << "" << std::endl; + ss << "" << std::endl; + ss << "ReactPhysics3D Logs" << std::endl; + ss << "" << std::endl; + ss << "" << std::endl; + + return ss.str(); + } + + /// Return the tail to write at the end of the stream + virtual std::string getTail() const override { + + std::stringstream ss; + + ss << "" << std::endl; + ss << "" << std::endl; + + return ss.str(); + } + + public: + + /// Constructor + HtmlFormatter() { + + } + + /// Destructor + virtual ~HtmlFormatter() { + + } + + /// Format a log message + virtual std::string format(const std::string& message, Level level, + Category category) override { + + std::stringstream ss; + + ss << "

"; + ss << message; + ss << "

"; + + return ss.str(); + } + }; + + + /// Log destination + class Destination { + + public: + + /// Log level flag for this destination + uint levelFlag; + + /// Pointer to the formatter + Formatter* formatter; + + /// Constructor + Destination(uint levelFlag, Formatter* logFormatter) + : levelFlag(levelFlag), formatter(logFormatter) { + + } + + /// Destructor + virtual ~Destination() { + + } + + /// Write a message into the output stream + virtual void write(const std::string& message, Level level, Category category) = 0; + }; + + class FileDestination : public Destination { + + private: + + std::string mFilePath; + + /// Output file stream + std::ofstream mFileStream; + + public: + + /// Constructor + FileDestination(const std::string& filePath, uint levelFlag, Formatter* formatter) + :Destination(levelFlag, formatter), mFilePath(filePath), + mFileStream(filePath, std::ios::binary) { + + if(!mFileStream.is_open()) { + throw(std::runtime_error("ReactPhysics3D Logger: Unable to open an output stream to file " + mFilePath)); + } + + // Writer the head + mFileStream << formatter->getHeader() << std::endl; + } + + /// Destructor + virtual ~FileDestination() override { + + // Writer the tail + mFileStream << formatter->getTail() << std::endl; + + if (mFileStream.is_open()) { + + // Close the stream + mFileStream.close(); + } + } + + /// Write a message into the output stream + virtual void write(const std::string& message, Level level, Category category) override { + mFileStream << formatter->format(message, level, category) << std::endl; + } + }; + + /// Stream destination to output the logs into a stream + class StreamDestination : public Destination { + + private: + + /// Output stream + std::ostream& mOutputStream; + + public: + + /// Constructor + StreamDestination(std::ostream& outputStream, uint levelFlag, Formatter* formatter) + :Destination(levelFlag, formatter), mOutputStream(outputStream) { + + // Writer the head + mOutputStream << formatter->getHeader() << std::endl; + } + + /// Destructor + virtual ~StreamDestination() override { + + // Writer the tail + mOutputStream << formatter->getTail() << std::endl; + } + + /// Write a message into the output stream + virtual void write(const std::string& message, Level level, Category category) override { + mOutputStream << message << std::endl; + } + }; + + + private: + + // -------------------- Attributes -------------------- // + + /// All the log destinations + List mDestinations; + + /// Map a log format to the given formatter object + Map mFormatters; + + // -------------------- Methods -------------------- // + + /// Return the corresponding formatter + Formatter* getFormatter(Format format) const; + + public : + + // -------------------- Methods -------------------- // + + /// Constructor + Logger(); + + /// Destructor + ~Logger(); + + /// Add a file destination to the logger + void addFileDestination(const std::string& filePath, uint logLevelFlag, Format format); + + /// Add a stream destination to the logger + void addStreamDestination(std::ostream& outputStream, uint logLevelFlag, Format format); + + /// Remove all logs destination previously set + void removeAllDestinations(); + + /// Log something + void log(Level level, Category category, const std::string& message); +}; + + +// Use this macro to log something +#define RP3D_LOG(logger, level, category, message) logger.log(level, category, message) + + +} + +#else // If logger is not active + +// Empty macro in case logs are not enabled +#define RP3D_LOG(logger, level, message) + +#endif + +// Hash function for struct VerticesPair +namespace std { + + template<> struct hash { + + size_t operator()(const reactphysics3d::Logger::Format format) const { + + return static_cast(format); + } + }; +} + +#endif diff --git a/src/engine/Profiler.cpp b/src/utils/Profiler.cpp similarity index 85% rename from src/engine/Profiler.cpp rename to src/utils/Profiler.cpp index 3212e4a1..12b449f1 100644 --- a/src/engine/Profiler.cpp +++ b/src/utils/Profiler.cpp @@ -28,12 +28,10 @@ // Libraries #include "Profiler.h" #include +#include "memory/MemoryManager.h" using namespace reactphysics3d; -// Initialization of static variables -int Profiler::mNbProfilers = 0; - // Constructor ProfileNode::ProfileNode(const char* name, ProfileNode* parentNode) :mName(name), mNbTotalCalls(0), mStartingTime(0), mTotalTime(0), @@ -79,7 +77,7 @@ void ProfileNode::enterBlockOfCode() { // Get the current system time to initialize the starting time of // the profiling of the current block of code - mStartingTime = Timer::getCurrentSystemTime() * 1000.0; + mStartingTime = Timer::getCurrentSystemTime() * 1000.0L; } mRecursionCounter++; @@ -92,7 +90,7 @@ bool ProfileNode::exitBlockOfCode() { if (mRecursionCounter == 0 && mNbTotalCalls != 0) { // Get the current system time - long double currentTime = Timer::getCurrentSystemTime() * 1000.0; + long double currentTime = Timer::getCurrentSystemTime() * 1000.0L; // Increase the total elasped time in the current block of code mTotalTime += currentTime - mStartingTime; @@ -105,7 +103,7 @@ bool ProfileNode::exitBlockOfCode() { // Reset the profiling of the node void ProfileNode::reset() { mNbTotalCalls = 0; - mTotalTime = 0.0; + mTotalTime = 0.0L; // Reset the child node if (mChildNode != nullptr) { @@ -156,27 +154,11 @@ void ProfileNodeIterator::enterParent() { } // Constructor -Profiler::Profiler(std::string name) :mRootNode("Root", nullptr) { - - // Set the name of the profiler - if (name == "") { - - if (mNbProfilers == 0) { - mName = "profiler"; - } - else { - mName = std::string("profiler") + std::to_string(mNbProfilers); - } - } - else { - mName = name; - } +Profiler::Profiler() :mRootNode("Root", nullptr), mDestinations(MemoryManager::getBaseAllocator()) { mCurrentNode = &mRootNode; - mProfilingStartTime = Timer::getCurrentSystemTime() * 1000.0; + mProfilingStartTime = Timer::getCurrentSystemTime() * 1000.0L; mFrameCounter = 0; - - mNbProfilers++; } // Destructor @@ -213,18 +195,48 @@ void Profiler::reset() { mRootNode.reset(); mRootNode.enterBlockOfCode(); mFrameCounter = 0; - mProfilingStartTime = Timer::getCurrentSystemTime() * 1000.0; + mProfilingStartTime = Timer::getCurrentSystemTime() * 1000.0L; } // Print the report of the profiler in a given output stream -void Profiler::printReport(std::ostream& outputStream) { - ProfileNodeIterator* iterator = Profiler::getIterator(); +void Profiler::printReport() { - // Recursively print the report of each node of the profiler tree - printRecursiveNodeReport(iterator, 0, outputStream); + // For each destination + for (auto it = mDestinations.begin(); it != mDestinations.end(); ++it) { - // Destroy the iterator - destroyIterator(iterator); + ProfileNodeIterator* iterator = Profiler::getIterator(); + + // Recursively print the report of each node of the profiler tree + printRecursiveNodeReport(iterator, 0, (*it)->getOutputStream()); + + // Destroy the iterator + destroyIterator(iterator); + } +} + +// Remove all output profiling destinations previously set +void Profiler::removeAllDestinations() { + + // Delete all the destinations + for (size_t i=0; iisRoot() ? getElapsedTimeSinceStart() : iterator->getCurrentParentTotalTime(); - long double accumulatedTime = 0.0; + long double accumulatedTime = 0.0L; uint nbFrames = Profiler::getNbFrames(); for (int i=0; igetCurrentParentName() << " (total running time : " << parentTime << " ms) ---" << std::endl; - long double totalTime = 0.0; + long double totalTime = 0.0L; // Recurse over the children of the current node int nbChildren = 0; @@ -256,7 +268,7 @@ void Profiler::printRecursiveNodeReport(ProfileNodeIterator* iterator, long double currentTotalTime = iterator->getCurrentTotalTime(); accumulatedTime += currentTotalTime; long double fraction = parentTime > std::numeric_limits::epsilon() ? - (currentTotalTime / parentTime) * 100.0 : 0.0; + (currentTotalTime / parentTime) * 100.0L : 0.0L; for (int j=0; jgetCurrentName() << " : " << fraction << " % | " << (currentTotalTime / (long double) (nbFrames)) << @@ -270,7 +282,7 @@ void Profiler::printRecursiveNodeReport(ProfileNodeIterator* iterator, } for (int i=0; i std::numeric_limits::epsilon() ? - ((parentTime - accumulatedTime) / parentTime) * 100.0 : 0.0; + ((parentTime - accumulatedTime) / parentTime) * 100.0L : 0.0L; long double difference = parentTime - accumulatedTime; outputStream << "| Unaccounted : " << difference << " ms (" << percentage << " %)" << std::endl; diff --git a/src/engine/Profiler.h b/src/utils/Profiler.h similarity index 77% rename from src/engine/Profiler.h rename to src/utils/Profiler.h index 84b7ed59..df64dfd6 100644 --- a/src/engine/Profiler.h +++ b/src/utils/Profiler.h @@ -30,7 +30,9 @@ // Libraries #include "configuration.h" -#include "Timer.h" +#include "engine/Timer.h" +#include +#include "containers/List.h" /// ReactPhysics3D namespace namespace reactphysics3d { @@ -180,16 +182,102 @@ class ProfileNodeIterator { */ class Profiler { + public: + + /// Format of the profiling data (text, ...) + enum class Format {Text}; + + /// Profile destination + class Destination { + + public: + + /// Log format (text, ...) + Format format; + + /// Constructor + Destination(Format logFormat) : format(logFormat) { + + } + + /// Destructor + virtual ~Destination() { + + } + + /// Return the current output stream + virtual std::ostream& getOutputStream() = 0; + }; + + /// File destination to output profiling data into a file + class FileDestination : public Destination { + + private: + + std::string mFilePath; + + /// Output file stream + std::ofstream mFileStream; + + public: + + /// Constructor + FileDestination(const std::string& filePath, Format format) + :Destination(format), mFilePath(filePath), + mFileStream(filePath, std::ios::binary) { + + if(!mFileStream.is_open()) { + throw(std::runtime_error("ReactPhysics3D Logger: Unable to open an output stream to file " + mFilePath)); + } + } + + /// Destructor + virtual ~FileDestination() override { + + if (mFileStream.is_open()) { + + // Close the stream + mFileStream.close(); + } + } + + /// Return the current output stream + virtual std::ostream& getOutputStream() override { + return mFileStream; + } + }; + + /// Stream destination to output profiling data into a stream + class StreamDestination : public Destination { + + private: + + /// Output stream + std::ostream& mOutputStream; + + public: + + /// Constructor + StreamDestination(std::ostream& outputStream, Format format) + :Destination(format), mOutputStream(outputStream) { + + } + + /// Destructor + virtual ~StreamDestination() override { + + } + + /// Return the current output stream + virtual std::ostream& getOutputStream() override { + return mOutputStream; + } + }; + private : // -------------------- Attributes -------------------- // - /// Profiler name - std::string mName; - - /// Total number of profilers - static int mNbProfilers; - /// Root node of the profiler tree ProfileNode mRootNode; @@ -202,8 +290,12 @@ class Profiler { /// Starting profiling time long double mProfilingStartTime; + /// All the output destinations + List mDestinations; + /// Recursively print the report of a given node of the profiler tree - void printRecursiveNodeReport(ProfileNodeIterator* iterator, int spacing, std::ostream& outputStream); + void printRecursiveNodeReport(ProfileNodeIterator* iterator, int spacing, + std::ostream &outputStream); /// Destroy a previously allocated iterator void destroyIterator(ProfileNodeIterator* iterator); @@ -216,7 +308,7 @@ class Profiler { // -------------------- Methods -------------------- // /// Constructor - Profiler(std::string name = ""); + Profiler(); /// Destructor ~Profiler(); @@ -234,12 +326,6 @@ class Profiler { /// Return the number of frames uint getNbFrames(); - /// Get the name of the profiler - std::string getName() const; - - /// Set the name of the profiler - void setName(std::string name); - /// Return the elasped time since the start/reset of the profiling long double getElapsedTimeSinceStart(); @@ -249,8 +335,17 @@ class Profiler { /// Return an iterator over the profiler tree starting at the root ProfileNodeIterator* getIterator(); - /// Print the report of the profiler in a given output stream - void printReport(std::ostream& outputStream); + // Add a file destination to the profiler + void addFileDestination(const std::string& filePath, Format format); + + // Add a stream destination to the profiler + void addStreamDestination(std::ostream& outputStream, Format format); + + /// Remove all logs destination previously set + void removeAllDestinations(); + + /// Print the report of the profiler in every output destinations + void printReport(); }; // Class ProfileSample @@ -287,7 +382,7 @@ class ProfileSample { }; // Use this macro to start profile a block of code -#define PROFILE(name, profiler) ProfileSample profileSample(name, profiler) +#define RP3D_PROFILE(name, profiler) ProfileSample profileSample(name, profiler) // Return true if we are at the root of the profiler tree inline bool ProfileNodeIterator::isRoot() { @@ -374,19 +469,9 @@ inline uint Profiler::getNbFrames() { return mFrameCounter; } -// Get the name of the profiler -inline std::string Profiler::getName() const { - return mName; -} - -// Set the name of the profiler -inline void Profiler::setName(std::string name) { - mName = name; -} - // Return the elasped time since the start/reset of the profiling inline long double Profiler::getElapsedTimeSinceStart() { - long double currentTime = Timer::getCurrentSystemTime() * 1000.0; + long double currentTime = Timer::getCurrentSystemTime() * 1000.0L; return currentTime - mProfilingStartTime; } @@ -412,10 +497,10 @@ inline void Profiler::destroy() { } -#else // In profile is not active +#else // If profile is not active // Empty macro in case profiling is not active -#define PROFILE(name, profiler) +#define RP3D_PROFILE(name, profiler) #endif diff --git a/test/tests/collision/TestCollisionWorld.h b/test/tests/collision/TestCollisionWorld.h index 64abab25..372b9dc5 100644 --- a/test/tests/collision/TestCollisionWorld.h +++ b/test/tests/collision/TestCollisionWorld.h @@ -639,7 +639,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + bool swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points Vector3 localBody1Point(3, 0, 0); @@ -663,7 +663,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -684,7 +684,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -705,7 +705,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -759,7 +759,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + bool swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points Vector3 localBody1Point(3, 0, 0); @@ -783,7 +783,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -804,7 +804,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -825,7 +825,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -869,7 +869,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points localBody1Point = std::sqrt(4.5f) * Vector3(1, -1, 0); @@ -893,7 +893,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -914,7 +914,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -935,7 +935,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -979,7 +979,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points localBody1Point = std::sqrt(9.0f / 3.0f) * Vector3(1, -1, -1); @@ -1003,7 +1003,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1024,7 +1024,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1045,7 +1045,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1099,7 +1099,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + bool swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points Vector3 localBody1Point(0, -3, 0); @@ -1123,7 +1123,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1144,7 +1144,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1165,7 +1165,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1209,7 +1209,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points localBody1Point = Vector3(3, 0, 0); @@ -1233,7 +1233,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1254,7 +1254,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1275,7 +1275,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1329,7 +1329,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + bool swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points Vector3 localBody1Point(3, 0, 0); @@ -1353,7 +1353,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1374,7 +1374,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1395,7 +1395,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1439,7 +1439,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points localBody1Point = std::sqrt(4.5f) * Vector3(1, -1, 0); @@ -1463,7 +1463,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1484,7 +1484,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1505,7 +1505,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1549,7 +1549,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points localBody1Point = std::sqrt(9.0f / 3.0f) * Vector3(1, -1, -1); @@ -1573,7 +1573,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1594,7 +1594,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1615,7 +1615,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1669,7 +1669,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + bool swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points Vector3 localBody1Point(0, -3, 0); @@ -1693,7 +1693,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1714,7 +1714,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1735,7 +1735,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mSphereBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mSphereBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -1789,7 +1789,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 4); // True if the bodies are swapped in the collision callback response - bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + bool swappedBodiesCollisionData = collisionData->getBody1()->getId() != mBoxBody1->getId(); // Test contact points Vector3 localBody1Point1(-3, -2, -2); @@ -1831,7 +1831,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 4); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mBoxBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, @@ -1860,7 +1860,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 4); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mBoxBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, @@ -1890,7 +1890,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 4); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mBoxBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, @@ -1953,7 +1953,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 4); // True if the bodies are swapped in the collision callback response - bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + bool swappedBodiesCollisionData = collisionData->getBody1()->getId() != mBoxBody1->getId(); // Test contact points Vector3 localBody1Point1(-3, -2, -2); @@ -1995,7 +1995,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 4); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mBoxBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, @@ -2024,7 +2024,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 4); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mBoxBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, @@ -2054,7 +2054,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 4); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mBoxBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, @@ -2117,7 +2117,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 4); // True if the bodies are swapped in the collision callback response - bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + bool swappedBodiesCollisionData = collisionData->getBody1()->getId() != mConvexMeshBody1->getId(); // Test contact points Vector3 localBody1Point1(-3, -2, -2); @@ -2159,7 +2159,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 4); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mConvexMeshBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, @@ -2188,7 +2188,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 4); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mConvexMeshBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, @@ -2218,7 +2218,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 4); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mConvexMeshBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, @@ -2281,7 +2281,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + bool swappedBodiesCollisionData = collisionData->getBody1()->getId() != mBoxBody1->getId(); // Test contact points Vector3 localBody1Point1(3, 1, 0); @@ -2304,7 +2304,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mBoxBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, @@ -2325,7 +2325,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mBoxBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, @@ -2346,7 +2346,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mBoxBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, @@ -2400,7 +2400,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + bool swappedBodiesCollisionData = collisionData->getBody1()->getId() != mConvexMeshBody1->getId(); // Test contact points Vector3 localBody1Point1(3, 1, 0); @@ -2423,7 +2423,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mConvexMeshBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, @@ -2444,7 +2444,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mConvexMeshBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, @@ -2465,7 +2465,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mConvexMeshBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point1 : localBody1Point1, @@ -2519,7 +2519,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 4); // True if the bodies are swapped in the collision callback response - bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + bool swappedBodiesCollisionData = collisionData->getBody1()->getId() != mBoxBody1->getId(); for (int i=0; icontactManifolds[0].contactPoints.size(); i++) { test(approxEqual(collisionData->contactManifolds[0].contactPoints[i].penetrationDepth, 1.0f)); @@ -2539,7 +2539,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 4); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mBoxBody1->getId(); for (int i=0; icontactManifolds[0].contactPoints.size(); i++) { test(approxEqual(collisionData->contactManifolds[0].contactPoints[i].penetrationDepth, 1.0f)); @@ -2559,7 +2559,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 4); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mBoxBody1->getId(); for (int i=0; icontactManifolds[0].contactPoints.size(); i++) { test(approxEqual(collisionData->contactManifolds[0].contactPoints[i].penetrationDepth, 1.0f)); @@ -2579,7 +2579,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 4); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mBoxBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mBoxBody1->getId(); // Test contact points for (int i=0; icontactManifolds[0].contactPoints.size(); i++) { @@ -2633,7 +2633,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 4); // True if the bodies are swapped in the collision callback response - bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + bool swappedBodiesCollisionData = collisionData->getBody1()->getId() != mConvexMeshBody1->getId(); for (int i=0; icontactManifolds[0].contactPoints.size(); i++) { test(approxEqual(collisionData->contactManifolds[0].contactPoints[i].penetrationDepth, 1.0f)); @@ -2653,7 +2653,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 4); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mConvexMeshBody1->getId(); for (int i=0; icontactManifolds[0].contactPoints.size(); i++) { test(approxEqual(collisionData->contactManifolds[0].contactPoints[i].penetrationDepth, 1.0f)); @@ -2673,7 +2673,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 4); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mConvexMeshBody1->getId(); for (int i=0; icontactManifolds[0].contactPoints.size(); i++) { test(approxEqual(collisionData->contactManifolds[0].contactPoints[i].penetrationDepth, 1.0f)); @@ -2693,7 +2693,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 4); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mConvexMeshBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mConvexMeshBody1->getId(); // Test contact points for (int i=0; icontactManifolds[0].contactPoints.size(); i++) { @@ -2747,7 +2747,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + bool swappedBodiesCollisionData = collisionData->getBody1()->getId() != mCapsuleBody1->getId(); // Test contact points Vector3 localBody1Point(2, 3, 0); @@ -2771,7 +2771,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mCapsuleBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -2792,7 +2792,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mCapsuleBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -2813,7 +2813,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mCapsuleBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -2857,7 +2857,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mCapsuleBody1->getId(); // Test contact points localBody1Point = Vector3(0, 5, 0); @@ -2881,7 +2881,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mCapsuleBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -2902,7 +2902,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mCapsuleBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -2923,7 +2923,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mCapsuleBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -2977,7 +2977,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - bool swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + bool swappedBodiesCollisionData = collisionData->getBody1()->getId() != mCapsuleBody1->getId(); // Test contact points Vector3 localBody1Point(0, -5, 0); @@ -3001,7 +3001,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mCapsuleBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -3022,7 +3022,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mCapsuleBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, @@ -3043,7 +3043,7 @@ class TestCollisionWorld : public Test { test(collisionData->getTotalNbContactPoints() == 1); // True if the bodies are swapped in the collision callback response - swappedBodiesCollisionData = collisionData->getBody1()->getID() != mCapsuleBody1->getID(); + swappedBodiesCollisionData = collisionData->getBody1()->getId() != mCapsuleBody1->getId(); // Test contact points test(collisionData->hasContactPointSimilarTo(swappedBodiesCollisionData ? localBody2Point : localBody1Point, diff --git a/test/tests/collision/TestRaycast.h b/test/tests/collision/TestRaycast.h index 60d3068b..7714264a 100644 --- a/test/tests/collision/TestRaycast.h +++ b/test/tests/collision/TestRaycast.h @@ -63,7 +63,7 @@ class WorldRaycastCallback : public RaycastCallback { virtual decimal notifyRaycastHit(const RaycastInfo& info) override { - if (shapeToTest->getBody()->getID() == info.body->getID()) { + if (shapeToTest->getBody()->getId() == info.body->getId()) { raycastInfo.body = info.body; raycastInfo.hitFraction = info.hitFraction; raycastInfo.proxyShape = info.proxyShape; @@ -1310,7 +1310,6 @@ class TestRaycast : public Test { // CollisionWorld::raycast() mCallback.reset(); mWorld->raycast(ray, &mCallback); - Vector3 localTest = inverse * mCallback.raycastInfo.worldPoint; test(mCallback.isHit); test(mCallback.raycastInfo.body == mConvexMeshBody); test(mCallback.raycastInfo.proxyShape == mConvexMeshProxyShape); diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp index 02e8acc1..644b378f 100755 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp @@ -47,13 +47,7 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name, Engine setScenePosition(center, SCENE_RADIUS); // Create the dynamics world for the physics simulation - mPhysicsWorld = new rp3d::CollisionWorld(); - -#ifdef IS_PROFILING_ACTIVE - - mPhysicsWorld->setProfilerName(name + "_profiler"); - -#endif + mPhysicsWorld = new rp3d::CollisionWorld(name); // ---------- Sphere 1 ---------- // diff --git a/testbed/scenes/collisionshapes/CollisionShapesScene.cpp b/testbed/scenes/collisionshapes/CollisionShapesScene.cpp index 8efc13de..e5fb3110 100644 --- a/testbed/scenes/collisionshapes/CollisionShapesScene.cpp +++ b/testbed/scenes/collisionshapes/CollisionShapesScene.cpp @@ -46,14 +46,7 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name, EngineSettin rp3d::Vector3 gravity(0, -9.81f, 0); // Create the dynamics world for the physics simulation - mPhysicsWorld = new rp3d::DynamicsWorld(gravity); - -#ifdef IS_PROFILING_ACTIVE - - mPhysicsWorld->setProfilerName(name + "_profiler"); - -#endif - + mPhysicsWorld = new rp3d::DynamicsWorld(gravity, name); for (int i=0; isetProfilerName(name + "_profiler"); - -#endif + mPhysicsWorld = new rp3d::DynamicsWorld(gravity, name); // ---------- Create the boxes ----------- // for (int i = 0; isetProfilerName(name + "_profiler"); - -#endif + mPhysicsWorld = new rp3d::DynamicsWorld(gravity, name); // Create all the cubes of the scene for (int i=0; isetProfilerName(name + "_profiler"); - -#endif + mPhysicsWorld = new rp3d::DynamicsWorld(gravity, name); // Create all the cubes of the scene for (int i=1; i<=NB_FLOORS; i++) { diff --git a/testbed/scenes/heightfield/HeightFieldScene.cpp b/testbed/scenes/heightfield/HeightFieldScene.cpp index 0d13d40d..ed8f1313 100644 --- a/testbed/scenes/heightfield/HeightFieldScene.cpp +++ b/testbed/scenes/heightfield/HeightFieldScene.cpp @@ -46,14 +46,7 @@ HeightFieldScene::HeightFieldScene(const std::string& name, EngineSettings& sett rp3d::Vector3 gravity(0, rp3d::decimal(-9.81), 0); // Create the dynamics world for the physics simulation - mPhysicsWorld = new rp3d::DynamicsWorld(gravity); - -#ifdef IS_PROFILING_ACTIVE - - mPhysicsWorld->setProfilerName(name + "_profiler"); - -#endif - + mPhysicsWorld = new rp3d::DynamicsWorld(gravity, name); for (int i = 0; isetProfilerName(name + "_profiler"); - -#endif + mPhysicsWorld = new rp3d::DynamicsWorld(gravity, name); // Create the Ball-and-Socket joint createBallAndSocketJoints(); diff --git a/testbed/scenes/raycast/RaycastScene.cpp b/testbed/scenes/raycast/RaycastScene.cpp index 5705627d..6ef8a54c 100644 --- a/testbed/scenes/raycast/RaycastScene.cpp +++ b/testbed/scenes/raycast/RaycastScene.cpp @@ -45,13 +45,7 @@ RaycastScene::RaycastScene(const std::string& name, EngineSettings& settings) setScenePosition(center, SCENE_RADIUS); // Create the dynamics world for the physics simulation - mPhysicsWorld = new rp3d::CollisionWorld(); - -#ifdef IS_PROFILING_ACTIVE - - mPhysicsWorld->setProfilerName(name + "_profiler"); - -#endif + mPhysicsWorld = new rp3d::CollisionWorld(name); // ---------- Dumbbell ---------- // From 36568f05038a2ec02578259e078882dd80ada04e Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 15 Mar 2018 07:32:51 +0100 Subject: [PATCH 176/248] Update the compilers in travis file --- .travis.yml | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/.travis.yml b/.travis.yml index d3445273..a9a6e98b 100644 --- a/.travis.yml +++ b/.travis.yml @@ -9,27 +9,26 @@ matrix: sources: - ubuntu-toolchain-r-test packages: - - g++-4.9 + - g++-7 env: - - MATRIX_EVAL="CC=gcc-4.9 && CXX=g++-4.9" + - MATRIX_EVAL="CC=gcc-7 && CXX=g++-7" # OS X / GCC - os: osx osx_image: xcode8 env: - - MATRIX_EVAL="CC=gcc-4.9 && CXX=g++-4.9" + - MATRIX_EVAL="brew install gcc && CC=gcc-7 && CXX=g++-7" # Linux / Clang - os: linux addons: apt: sources: - - ubuntu-toolchain-r-test - - llvm-toolchain-precise-3.6 + - llvm-toolchain-trusty-5.0 packages: - - clang-3.6 + - clang-5.0 env: - - MATRIX_EVAL="CC=clang-3.6 && CXX=clang++-3.6" + - MATRIX_EVAL="CC=clang-5.0 && CXX=clang++-5.0" # OS X / Clang - os: osx @@ -56,3 +55,9 @@ script: # Build in release mode with single precision - cmake -G "Unix Makefiles" -DCMAKE_BUILD_TYPE=Release —DDOUBLE_PRECISION_ENABLED=False -DCOMPILE_TESTS=True ../ - make && make test ARGS="-V" + # Build in debug mode with logs and profiler enabled + - cmake -G "Unix Makefiles" -DCMAKE_BUILD_TYPE=Debug —DPROFILING_ENABLED=True -DLOGS_ENABLED=True + - make + # Build in release mode with logs and profiler enabled + - cmake -G "Unix Makefiles" -DCMAKE_BUILD_TYPE=Release —DPROFILING_ENABLED=True -DLOGS_ENABLED=True + - make \ No newline at end of file From 2e28b5ad8fb18c637094d11ece969f69367ce89a Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 15 Mar 2018 23:11:26 +0100 Subject: [PATCH 177/248] Refactor profiler and add logger --- src/configuration.h | 4 + src/engine/CollisionWorld.cpp | 53 +++++-- src/engine/CollisionWorld.h | 25 ++-- src/engine/DynamicsWorld.cpp | 37 ++--- src/engine/DynamicsWorld.h | 4 +- src/utils/Logger.cpp | 6 +- src/utils/Logger.h | 130 +++++++++++++++--- .../CollisionDetectionScene.cpp | 5 +- .../collisionshapes/CollisionShapesScene.cpp | 5 +- .../scenes/concavemesh/ConcaveMeshScene.cpp | 5 +- testbed/scenes/cubes/CubesScene.cpp | 5 +- testbed/scenes/cubestack/CubeStackScene.cpp | 5 +- .../scenes/heightfield/HeightFieldScene.cpp | 5 +- testbed/scenes/joints/JointsScene.cpp | 5 +- testbed/scenes/raycast/RaycastScene.cpp | 5 +- testbed/src/Gui.cpp | 8 ++ testbed/src/Scene.h | 3 + testbed/src/SceneDemo.cpp | 31 +++-- testbed/src/SceneDemo.h | 3 + testbed/src/TestbedApplication.cpp | 7 + testbed/src/TestbedApplication.h | 3 + 21 files changed, 277 insertions(+), 77 deletions(-) diff --git a/src/configuration.h b/src/configuration.h index 539f66b9..aa71e88a 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -31,6 +31,7 @@ #include #include #include +#include #include "decimal.h" #include "containers/Pair.h" @@ -110,6 +111,9 @@ constexpr decimal DYNAMIC_TREE_AABB_LIN_GAP_MULTIPLIER = decimal(1.7); */ struct WorldSettings { + /// Name of the world + std::string worldName = ""; + /// Distance threshold for two contact points for a valid persistent contact (in meters) decimal persistentContactDistanceThreshold = decimal(0.03); diff --git a/src/engine/CollisionWorld.cpp b/src/engine/CollisionWorld.cpp index 7fb223e2..1dbf1b6f 100644 --- a/src/engine/CollisionWorld.cpp +++ b/src/engine/CollisionWorld.cpp @@ -36,9 +36,11 @@ using namespace std; uint CollisionWorld::mNbWorlds = 0; // Constructor -CollisionWorld::CollisionWorld(const string& name, const WorldSettings& worldSettings) +CollisionWorld::CollisionWorld(const WorldSettings& worldSettings, Logger* logger, Profiler* profiler) : mConfig(worldSettings), mCollisionDetection(this, mMemoryManager), mBodies(mMemoryManager.getPoolAllocator()), mCurrentBodyId(0), - mFreeBodiesIds(mMemoryManager.getPoolAllocator()), mEventListener(nullptr), mName(name) { + mFreeBodiesIds(mMemoryManager.getPoolAllocator()), mEventListener(nullptr), mName(worldSettings.worldName), + mProfiler(profiler), mLogger(logger), mIsProfilerCreatedByUser(profiler != nullptr), + mIsLoggerCreatedByUser(logger != nullptr) { // Automatically generate a name for the world if (mName == "") { @@ -55,20 +57,33 @@ CollisionWorld::CollisionWorld(const string& name, const WorldSettings& worldSet #ifdef IS_PROFILING_ACTIVE - // Add a destination file for the profiling data - mProfiler.addFileDestination("rp3d_profiling_" + mName + ".txt", Profiler::Format::Text); + // If the user has not provided its own profiler, we create one + if (mProfiler == nullptr) { + + mProfiler = new Profiler(); + + // Add a destination file for the profiling data + mProfiler->addFileDestination("rp3d_profiling_" + mName + ".txt", Profiler::Format::Text); + } + // Set the profiler - mCollisionDetection.setProfiler(&mProfiler); + mCollisionDetection.setProfiler(mProfiler); #endif #ifdef IS_LOGGING_ACTIVE - // Add a log destination file - uint logLevel = static_cast(Logger::Level::Info) | static_cast(Logger::Level::Warning) | - static_cast(Logger::Level::Error); - mLogger.addFileDestination("rp3d_log_" + mName + ".html", logLevel, Logger::Format::HTML); + // If the user has not provided its own logger, we create one + if (mLogger == nullptr) { + + mLogger = new Logger(); + + // Add a log destination file + uint logLevel = static_cast(Logger::Level::Info) | static_cast(Logger::Level::Warning) | + static_cast(Logger::Level::Error); + mLogger->addFileDestination("rp3d_log_" + mName + ".html", logLevel, Logger::Format::HTML); + } #endif @@ -89,6 +104,24 @@ CollisionWorld::~CollisionWorld() { destroyCollisionBody(mBodies[i]); } +#ifdef IS_PROFILING_ACTIVE + + /// Delete the profiler + if (!mIsProfilerCreatedByUser) { + delete mProfiler; + } + +#endif + +#ifdef IS_LOGGING_ACTIVE + + /// Delete the logger + if (!mIsLoggerCreatedByUser) { + delete mLogger; + } + +#endif + assert(mBodies.size() == 0); } @@ -117,7 +150,7 @@ CollisionBody* CollisionWorld::createCollisionBody(const Transform& transform) { #ifdef IS_PROFILING_ACTIVE - collisionBody->setProfiler(&mProfiler); + collisionBody->setProfiler(mProfiler); #endif diff --git a/src/engine/CollisionWorld.h b/src/engine/CollisionWorld.h index f85d2fc6..ad3549fe 100644 --- a/src/engine/CollisionWorld.h +++ b/src/engine/CollisionWorld.h @@ -87,15 +87,21 @@ class CollisionWorld { #ifdef IS_PROFILING_ACTIVE /// Real-time hierarchical profiler - Profiler mProfiler; + Profiler* mProfiler; #endif #ifdef IS_LOGGING_ACTIVE /// Logger - Logger mLogger; + Logger* mLogger; #endif + /// True if the profiler has been created by the user + bool mIsProfilerCreatedByUser; + + /// True if the logger has been created by the user + bool mIsLoggerCreatedByUser; + /// Total number of worlds static uint mNbWorlds; @@ -112,7 +118,8 @@ class CollisionWorld { // -------------------- Methods -------------------- // /// Constructor - CollisionWorld(const std::string& name = "", const WorldSettings& worldSettings = WorldSettings()); + CollisionWorld(const WorldSettings& worldSettings = WorldSettings(), Logger* logger = nullptr, + Profiler* profiler = nullptr); /// Destructor virtual ~CollisionWorld(); @@ -161,14 +168,14 @@ class CollisionWorld { #ifdef IS_PROFILING_ACTIVE /// Return a reference to the profiler - Profiler& getProfiler(); + Profiler* getProfiler(); #endif #ifdef IS_LOGGING_ACTIVE /// Return a reference to the logger - Logger& getLogger(); + Logger* getLogger(); #endif @@ -255,8 +262,8 @@ inline const std::string& CollisionWorld::getName() const { #ifdef IS_PROFILING_ACTIVE -// Return a reference to the profiler -inline Profiler& CollisionWorld::getProfiler() { +// Return a pointer to the profiler +inline Profiler* CollisionWorld::getProfiler() { return mProfiler; } @@ -264,8 +271,8 @@ inline Profiler& CollisionWorld::getProfiler() { #ifdef IS_LOGGING_ACTIVE -// Return a reference to the logger -inline Logger& CollisionWorld::getLogger() { +// Return a pointer to the logger +inline Logger* CollisionWorld::getLogger() { return mLogger; } diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index f8ac6033..7164458d 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -39,8 +39,9 @@ using namespace std; /** * @param gravity Gravity vector in the world (in meters per second squared) */ -DynamicsWorld::DynamicsWorld(const Vector3& gravity, const string& name, const WorldSettings& worldSettings) - : CollisionWorld(name, worldSettings), +DynamicsWorld::DynamicsWorld(const Vector3& gravity, const WorldSettings& worldSettings, + Logger* logger, Profiler* profiler) + : CollisionWorld(worldSettings, logger, profiler), mContactSolver(mMemoryManager, mConfig), mNbVelocitySolverIterations(mConfig.defaultVelocitySolverNbIterations), mNbPositionSolverIterations(mConfig.defaultPositionSolverNbIterations), @@ -58,13 +59,13 @@ DynamicsWorld::DynamicsWorld(const Vector3& gravity, const string& name, const W #ifdef IS_PROFILING_ACTIVE // Set the profiler - mConstraintSolver.setProfiler(&mProfiler); - mContactSolver.setProfiler(&mProfiler); + mConstraintSolver.setProfiler(mProfiler); + mContactSolver.setProfiler(mProfiler); #endif RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, - "Dynamics world " + mName + " has been created"); + "Dynamics World: Dynamics world " + mName + " has been created"); } @@ -87,11 +88,11 @@ DynamicsWorld::~DynamicsWorld() { #ifdef IS_PROFILING_ACTIVE // Print the profiling report into the destinations - mProfiler.printReport(); + mProfiler->printReport(); #endif RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, - "Dynamics world " + mName + " has been destroyed"); + "Dynamics World: Dynamics world " + mName + " has been destroyed"); } // Update the physics simulation @@ -102,10 +103,10 @@ void DynamicsWorld::update(decimal timeStep) { #ifdef IS_PROFILING_ACTIVE // Increment the frame counter of the profiler - mProfiler.incrementFrameCounter(); + mProfiler->incrementFrameCounter(); #endif - RP3D_PROFILE("DynamicsWorld::update()", &mProfiler); + RP3D_PROFILE("DynamicsWorld::update()", mProfiler); mTimeStep = timeStep; @@ -153,7 +154,7 @@ void DynamicsWorld::update(decimal timeStep) { /// the sympletic Euler time stepping scheme. void DynamicsWorld::integrateRigidBodiesPositions() { - RP3D_PROFILE("DynamicsWorld::integrateRigidBodiesPositions()", &mProfiler); + RP3D_PROFILE("DynamicsWorld::integrateRigidBodiesPositions()", mProfiler); // For each island of the world for (uint i=0; i < mNbIslands; i++) { @@ -192,7 +193,7 @@ void DynamicsWorld::integrateRigidBodiesPositions() { // Update the postion/orientation of the bodies void DynamicsWorld::updateBodiesState() { - RP3D_PROFILE("DynamicsWorld::updateBodiesState()", &mProfiler); + RP3D_PROFILE("DynamicsWorld::updateBodiesState()", mProfiler); // For each island of the world for (uint islandIndex = 0; islandIndex < mNbIslands; islandIndex++) { @@ -229,7 +230,7 @@ void DynamicsWorld::updateBodiesState() { // Initialize the bodies velocities arrays for the next simulation step. void DynamicsWorld::initVelocityArrays() { - RP3D_PROFILE("DynamicsWorld::initVelocityArrays()", &mProfiler); + RP3D_PROFILE("DynamicsWorld::initVelocityArrays()", mProfiler); // Allocate memory for the bodies velocity arrays uint nbBodies = mRigidBodies.size(); @@ -271,7 +272,7 @@ void DynamicsWorld::initVelocityArrays() { /// contact solver. void DynamicsWorld::integrateRigidBodiesVelocities() { - RP3D_PROFILE("DynamicsWorld::integrateRigidBodiesVelocities()", &mProfiler); + RP3D_PROFILE("DynamicsWorld::integrateRigidBodiesVelocities()", mProfiler); // Initialize the bodies velocity arrays initVelocityArrays(); @@ -333,7 +334,7 @@ void DynamicsWorld::integrateRigidBodiesVelocities() { // Solve the contacts and constraints void DynamicsWorld::solveContactsAndConstraints() { - RP3D_PROFILE("DynamicsWorld::solveContactsAndConstraints()", &mProfiler); + RP3D_PROFILE("DynamicsWorld::solveContactsAndConstraints()", mProfiler); // Set the velocities arrays mContactSolver.setSplitVelocitiesArrays(mSplitLinearVelocities, mSplitAngularVelocities); @@ -383,7 +384,7 @@ void DynamicsWorld::solveContactsAndConstraints() { // Solve the position error correction of the constraints void DynamicsWorld::solvePositionCorrection() { - RP3D_PROFILE("DynamicsWorld::solvePositionCorrection()", &mProfiler); + RP3D_PROFILE("DynamicsWorld::solvePositionCorrection()", mProfiler); // Do not continue if there is no constraints if (mJoints.size() == 0) return; @@ -426,7 +427,7 @@ RigidBody* DynamicsWorld::createRigidBody(const Transform& transform) { #ifdef IS_PROFILING_ACTIVE - rigidBody->setProfiler(&mProfiler); + rigidBody->setProfiler(mProfiler); #endif @@ -645,7 +646,7 @@ uint DynamicsWorld::computeNextAvailableJointId() { /// it). Then, we create an island with this group of connected bodies. void DynamicsWorld::computeIslands() { - RP3D_PROFILE("DynamicsWorld::computeIslands()", &mProfiler); + RP3D_PROFILE("DynamicsWorld::computeIslands()", mProfiler); uint nbBodies = mRigidBodies.size(); @@ -792,7 +793,7 @@ void DynamicsWorld::computeIslands() { /// time, we put all the bodies of the island to sleep. void DynamicsWorld::updateSleepingBodies() { - RP3D_PROFILE("DynamicsWorld::updateSleepingBodies()", &mProfiler); + RP3D_PROFILE("DynamicsWorld::updateSleepingBodies()", mProfiler); const decimal sleepLinearVelocitySquare = mSleepLinearVelocity * mSleepLinearVelocity; const decimal sleepAngularVelocitySquare = mSleepAngularVelocity * mSleepAngularVelocity; diff --git a/src/engine/DynamicsWorld.h b/src/engine/DynamicsWorld.h index f8016fdc..f435f4b9 100644 --- a/src/engine/DynamicsWorld.h +++ b/src/engine/DynamicsWorld.h @@ -162,8 +162,8 @@ class DynamicsWorld : public CollisionWorld { // -------------------- Methods -------------------- // /// Constructor - DynamicsWorld(const Vector3& mGravity, const std::string& name = "", - const WorldSettings& worldSettings = WorldSettings()); + DynamicsWorld(const Vector3& mGravity, const WorldSettings& worldSettings = WorldSettings(), + Logger* logger = nullptr, Profiler* profiler = nullptr); /// Destructor virtual ~DynamicsWorld() override; diff --git a/src/utils/Logger.cpp b/src/utils/Logger.cpp index 89634598..9410cc29 100644 --- a/src/utils/Logger.cpp +++ b/src/utils/Logger.cpp @@ -92,10 +92,14 @@ void Logger::removeAllDestinations() { // Log something void Logger::log(Level level, Category category, const std::string& message) { + // Get current time + auto now = std::chrono::system_clock::now(); + auto time = std::chrono::system_clock::to_time_t(now); + // For each destination for (auto it = mDestinations.begin(); it != mDestinations.end(); ++it) { - (*it)->write(message, level, category); + (*it)->write(time, message, level, category); } } diff --git a/src/utils/Logger.h b/src/utils/Logger.h index 9c6421db..908da806 100644 --- a/src/utils/Logger.h +++ b/src/utils/Logger.h @@ -26,7 +26,6 @@ #ifndef REACTPHYSICS3D_LOGGER_H #define REACTPHYSICS3D_LOGGER_H -#ifdef IS_LOGGING_ACTIVE // Libraries #include "containers/List.h" @@ -35,6 +34,7 @@ #include #include #include +#include /// ReactPhysics3D namespace namespace reactphysics3d { @@ -57,6 +57,26 @@ class Logger { /// Log verbosity level enum class Format {Text, HTML}; + /// Return the name of a category + static std::string getCategoryName(Category category) { + + switch(category) { + case Category::World: return "World"; + case Category::Body: return "Body"; + case Category::Joint: return "Joint"; + } + } + + /// Return the name of a level + static std::string getLevelName(Level level) { + + switch(level) { + case Level::Info: return "Information"; + case Level::Warning: return "Warning"; + case Level::Error: return "Error"; + } + } + /// Log formatter class Formatter { @@ -83,7 +103,7 @@ class Logger { } /// Format a log message - virtual std::string format(const std::string& message, Level level, Category category) = 0; + virtual std::string format(const time_t& time, const std::string& message, Level level, Category category) = 0; }; class TextFormatter : public Formatter { @@ -101,8 +121,8 @@ class Logger { } /// Format a log message - virtual std::string format(const std::string& message, Level level, - Category category) override { + virtual std::string format(const time_t& time, const std::string& message, + Level level, Category category) override { return message; } }; @@ -120,6 +140,7 @@ class Logger { ss << "" << std::endl; ss << "" << std::endl; ss << "ReactPhysics3D Logs" << std::endl; + ss << "" << std::endl; ss << "" << std::endl; ss << "" << std::endl; @@ -137,6 +158,60 @@ class Logger { return ss.str(); } + std::string generateCSS() const { + return "body {" + " background-color: #f7f7f9;" + "} " + "body > div { clear:both; } " + "body > div > div { float: left; } " + ".line { " + "font-family: SFMono-Regular,Menlo,Monaco,Consolas,'Liberation Mono','Courier New',monospace; " + "font-size: 13px; " + "color: #212529; " + "margin: 0px 5px 2px 5px; " + "} " + ".time { " + "margin-right: 10px; " + "width:100px; " + "} " + ".level { " + "margin-right: 10px; " + "width: 110px; " + "}" + ".category { " + "margin-right: 10px; " + "width: 120px; " + "font-weight: bold; " + "}" + ".message { " + "color: #2e2e2e; " + "word-wrap: break-word; " + "max-width: 800px; " + "} " + ".body > .category { " + "color: #007bff; " + "} " + ".world > .category { " + "color: #4f9fcf; " + "} " + ".joint > .category { " + "color: #6c757d; " + "} " + ".warning { " + "color: #f0ad4e; " + "} " + ".error { " + "color: #d44950; " + "} "; + } + + /// Convert a string to lower case + std::string toLowerCase(const std::string& text) { + std::string textLower = text; + std::transform(textLower.begin(), textLower.end(), textLower.begin(), ::tolower); + return textLower; + } + public: /// Constructor @@ -150,14 +225,34 @@ class Logger { } /// Format a log message - virtual std::string format(const std::string& message, Level level, - Category category) override { + virtual std::string format(const time_t& time, const std::string& message, + Level level, Category category) override { std::stringstream ss; - ss << "

"; + ss << "

"; + + // Time + ss << "
"; + ss << std::put_time(std::localtime(&time), "%X"); + ss << "
"; + + // Level + ss << "
"; + ss << getLevelName(level); + ss << "
"; + + // Category + ss << "
"; + ss << getCategoryName(category); + ss << "
"; + + // Message + ss << "
"; ss << message; - ss << "

"; + ss << "
"; + + ss << "
"; return ss.str(); } @@ -187,7 +282,7 @@ class Logger { } /// Write a message into the output stream - virtual void write(const std::string& message, Level level, Category category) = 0; + virtual void write(const time_t& time, const std::string& message, Level level, Category category) = 0; }; class FileDestination : public Destination { @@ -228,8 +323,8 @@ class Logger { } /// Write a message into the output stream - virtual void write(const std::string& message, Level level, Category category) override { - mFileStream << formatter->format(message, level, category) << std::endl; + virtual void write(const time_t& time, const std::string& message, Level level, Category category) override { + mFileStream << formatter->format(time, message, level, category) << std::endl << std::flush; } }; @@ -259,8 +354,9 @@ class Logger { } /// Write a message into the output stream - virtual void write(const std::string& message, Level level, Category category) override { - mOutputStream << message << std::endl; + virtual void write(const time_t& time, const std::string& message, Level level, Category category) override { + mOutputStream << std::put_time(std::localtime(&time), "%Y-%m-%d %X") << ": "; + mOutputStream << message << std::endl << std::flush; } }; @@ -303,12 +399,12 @@ class Logger { void log(Level level, Category category, const std::string& message); }; +} + +#ifdef IS_LOGGING_ACTIVE // Use this macro to log something -#define RP3D_LOG(logger, level, category, message) logger.log(level, category, message) - - -} +#define RP3D_LOG(logger, level, category, message) logger->log(level, category, message) #else // If logger is not active diff --git a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp index 644b378f..3b4c7fc5 100755 --- a/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp +++ b/testbed/scenes/collisiondetection/CollisionDetectionScene.cpp @@ -46,8 +46,11 @@ CollisionDetectionScene::CollisionDetectionScene(const std::string& name, Engine // Set the center of the scene setScenePosition(center, SCENE_RADIUS); + rp3d::WorldSettings worldSettings; + worldSettings.worldName = name; + // Create the dynamics world for the physics simulation - mPhysicsWorld = new rp3d::CollisionWorld(name); + mPhysicsWorld = new rp3d::CollisionWorld(worldSettings); // ---------- Sphere 1 ---------- // diff --git a/testbed/scenes/collisionshapes/CollisionShapesScene.cpp b/testbed/scenes/collisionshapes/CollisionShapesScene.cpp index e5fb3110..cffe7b50 100644 --- a/testbed/scenes/collisionshapes/CollisionShapesScene.cpp +++ b/testbed/scenes/collisionshapes/CollisionShapesScene.cpp @@ -45,8 +45,11 @@ CollisionShapesScene::CollisionShapesScene(const std::string& name, EngineSettin // Gravity vector in the dynamics world rp3d::Vector3 gravity(0, -9.81f, 0); + rp3d::WorldSettings worldSettings; + worldSettings.worldName = name; + // Create the dynamics world for the physics simulation - mPhysicsWorld = new rp3d::DynamicsWorld(gravity, name); + mPhysicsWorld = new rp3d::DynamicsWorld(gravity, worldSettings); for (int i=0; isetChecked(mApp->mEngineSettings.isSleepingEnabled); checkboxSleeping->setCallback([&](bool value) { mApp->mEngineSettings.isSleepingEnabled = value; + mApp->notifyEngineSetttingsChanged(); }); // Enabled/Disable Gravity @@ -177,6 +178,7 @@ void Gui::createSettingsPanel() { checkboxGravity->setChecked(mApp->mEngineSettings.isGravityEnabled); checkboxGravity->setCallback([&](bool value) { mApp->mEngineSettings.isGravityEnabled = value; + mApp->notifyEngineSetttingsChanged(); }); // Timestep @@ -202,6 +204,7 @@ void Gui::createSettingsPanel() { if (finalValue < 1 || finalValue > 1000) return false; mApp->mEngineSettings.timeStep = finalValue / 1000.0f; + mApp->notifyEngineSetttingsChanged(); textboxTimeStep->setValue(out.str()); } catch (...) { @@ -233,6 +236,7 @@ void Gui::createSettingsPanel() { if (value < 1 || value > 1000) return false; mApp->mEngineSettings.nbVelocitySolverIterations = value; + mApp->notifyEngineSetttingsChanged(); textboxVelocityIterations->setValue(out.str()); } catch (...) { @@ -264,6 +268,7 @@ void Gui::createSettingsPanel() { if (value < 1 || value > 1000) return false; mApp->mEngineSettings.nbPositionSolverIterations = value; + mApp->notifyEngineSetttingsChanged(); textboxPositionIterations->setValue(out.str()); } catch (...) { @@ -298,6 +303,7 @@ void Gui::createSettingsPanel() { if (finalValue < 1 || finalValue > 100000) return false; mApp->mEngineSettings.timeBeforeSleep = finalValue / 1000.0f; + mApp->notifyEngineSetttingsChanged(); textboxTimeSleep->setValue(out.str()); } catch (...) { @@ -332,6 +338,7 @@ void Gui::createSettingsPanel() { if (finalValue < 0 || finalValue > 10000) return false; mApp->mEngineSettings.sleepLinearVelocity = finalValue; + mApp->notifyEngineSetttingsChanged(); textboxSleepLinearVel->setValue(out.str()); } catch (...) { @@ -366,6 +373,7 @@ void Gui::createSettingsPanel() { if (finalValue < 0 || finalValue > 10000) return false; mApp->mEngineSettings.sleepAngularVelocity = finalValue; + mApp->notifyEngineSetttingsChanged(); textboxSleepAngularVel->setValue(out.str()); } catch (...) { diff --git a/testbed/src/Scene.h b/testbed/src/Scene.h index 5471379e..8fffff2a 100644 --- a/testbed/src/Scene.h +++ b/testbed/src/Scene.h @@ -232,6 +232,9 @@ class Scene { /// Return all the contact points of the scene std::vector virtual getContactPoints(); + + /// Update the engine settings + virtual void updateEngineSettings() = 0; }; // Called when a keyboard event occurs diff --git a/testbed/src/SceneDemo.cpp b/testbed/src/SceneDemo.cpp index 8e2a92da..e4f13d99 100644 --- a/testbed/src/SceneDemo.cpp +++ b/testbed/src/SceneDemo.cpp @@ -123,18 +123,6 @@ void SceneDemo::updatePhysics() { if (getDynamicsWorld() != nullptr) { - // Update the physics engine parameters - getDynamicsWorld()->setIsGratityEnabled(mEngineSettings.isGravityEnabled); - rp3d::Vector3 gravity(mEngineSettings.gravity.x, mEngineSettings.gravity.y, - mEngineSettings.gravity.z); - getDynamicsWorld()->setGravity(gravity); - getDynamicsWorld()->enableSleeping(mEngineSettings.isSleepingEnabled); - getDynamicsWorld()->setSleepLinearVelocity(mEngineSettings.sleepLinearVelocity); - getDynamicsWorld()->setSleepAngularVelocity(mEngineSettings.sleepAngularVelocity); - getDynamicsWorld()->setNbIterationsPositionSolver(mEngineSettings.nbPositionSolverIterations); - getDynamicsWorld()->setNbIterationsVelocitySolver(mEngineSettings.nbVelocitySolverIterations); - getDynamicsWorld()->setTimeBeforeSleep(mEngineSettings.timeBeforeSleep); - // Take a simulation step getDynamicsWorld()->update(mEngineSettings.timeStep); } @@ -448,3 +436,22 @@ std::vector SceneDemo::computeContactPointsOfWorld(rp3d::DynamicsW return contactPoints; } + +// Update the engine settings +void SceneDemo::updateEngineSettings() { + + if (getDynamicsWorld() != nullptr) { + + // Update the physics engine parameters + getDynamicsWorld()->setIsGratityEnabled(mEngineSettings.isGravityEnabled); + rp3d::Vector3 gravity(mEngineSettings.gravity.x, mEngineSettings.gravity.y, + mEngineSettings.gravity.z); + getDynamicsWorld()->setGravity(gravity); + getDynamicsWorld()->enableSleeping(mEngineSettings.isSleepingEnabled); + getDynamicsWorld()->setSleepLinearVelocity(mEngineSettings.sleepLinearVelocity); + getDynamicsWorld()->setSleepAngularVelocity(mEngineSettings.sleepAngularVelocity); + getDynamicsWorld()->setNbIterationsPositionSolver(mEngineSettings.nbPositionSolverIterations); + getDynamicsWorld()->setNbIterationsVelocitySolver(mEngineSettings.nbVelocitySolverIterations); + getDynamicsWorld()->setTimeBeforeSleep(mEngineSettings.timeBeforeSleep); + } +} diff --git a/testbed/src/SceneDemo.h b/testbed/src/SceneDemo.h index 1eaa30b9..95e1ece0 100644 --- a/testbed/src/SceneDemo.h +++ b/testbed/src/SceneDemo.h @@ -151,6 +151,9 @@ class SceneDemo : public Scene { /// Render the scene (possibly in multiple passes for shadow mapping) virtual void render() override; + /// Update the engine settings + virtual void updateEngineSettings() override; + /// Render the scene in a single pass virtual void renderSinglePass(openglframework::Shader& shader, const openglframework::Matrix4& worldToCameraMatrix); diff --git a/testbed/src/TestbedApplication.cpp b/testbed/src/TestbedApplication.cpp index 63230e0c..7240ad7e 100644 --- a/testbed/src/TestbedApplication.cpp +++ b/testbed/src/TestbedApplication.cpp @@ -271,9 +271,16 @@ void TestbedApplication::switchScene(Scene* newScene) { // Reset the scene mCurrentScene->reset(); + mCurrentScene->updateEngineSettings(); + resizeEvent(Vector2i(0, 0)); } +// Notify that the engine settings have changed +void TestbedApplication::notifyEngineSetttingsChanged() { + mCurrentScene->updateEngineSettings(); +} + // Check the OpenGL errors void TestbedApplication::checkOpenGLErrorsInternal(const char* file, int line) { GLenum glError; diff --git a/testbed/src/TestbedApplication.h b/testbed/src/TestbedApplication.h index 3a9fe071..26a04bdd 100644 --- a/testbed/src/TestbedApplication.h +++ b/testbed/src/TestbedApplication.h @@ -199,6 +199,9 @@ class TestbedApplication : public Screen { /// Enable/Disable Vertical synchronization void enableVSync(bool enable); + /// Notify that the engine settings have changed + void notifyEngineSetttingsChanged(); + // -------------------- Friendship -------------------- // friend class Gui; From fc8b384d268d5ff580de71a19a9993ba200fb82b Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 15 Mar 2018 23:13:34 +0100 Subject: [PATCH 178/248] Update Readme file --- README.md | 36 +++++++++++++++++++----------------- 1 file changed, 19 insertions(+), 17 deletions(-) diff --git a/README.md b/README.md index cb305070..fb6df102 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,5 @@ [![Travis Build Status](https://travis-ci.org/DanielChappuis/reactphysics3d.svg?branch=master)](https://travis-ci.org/DanielChappuis/reactphysics3d) +[![Codacy Badge](https://api.codacy.com/project/badge/Grade/3ae24e998e304e4da78ec848eade9e3a)](https://www.codacy.com/app/chappuis.daniel/reactphysics3d?utm_source=github.com&utm_medium=referral&utm_content=DanielChappuis/reactphysics3d&utm_campaign=Badge_Grade) ## ReactPhysics3D @@ -14,23 +15,24 @@ Author : Daniel Chappuis ReactPhysics3D has the following features : -- Rigid body dynamics -- Discrete collision detection -- Collision shapes (Sphere, Box, Cone, Cylinder, Capsule, Convex Mesh, static Concave Mesh, Height Field) -- Multiple collision shapes per body -- Broadphase collision detection (Dynamic AABB tree) -- Narrowphase collision detection (GJK/EPA) -- Collision response and friction (Sequential Impulses Solver) -- Joints (Ball and Socket, Hinge, Slider, Fixed) -- Collision filtering with categories -- Ray casting -- Sleeping technique for inactive bodies -- Integrated Profiler -- Multi-platform (Windows, Linux, Mac OS X) -- No dependencies (only OpenGL for the testbed application) -- Documentation (User manual and Doxygen API) -- Testbed application with demo scenes -- Unit tests + - Rigid body dynamics + - Discrete collision detection + - Collision shapes (Sphere, Box, Capsule, Convex Mesh, Static Concave Mesh, Height Field) + - Multiple collision shapes per body + - Broadphase collision detection (Dynamic AABB tree) + - Narrowphase collision detection (SAT/GJK) + - Collision response and friction (Sequential Impulses Solver) + - Joints (Ball and Socket, Hinge, Slider, Fixed) + - Collision filtering with categories + - Ray casting + - Sleeping technique for inactive bodies + - Multi-platform (Windows, Linux, Mac OS X) + - No external libraries (do not use STL containers) + - Documentation (user manual and Doxygen API) + - Testbed application with demos + - Integrated Profiler + - Logs + - Unit tests ## License From be70a61fa7b5c1346f42165888dabb10d54e57d1 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 15 Mar 2018 23:14:54 +0100 Subject: [PATCH 179/248] Fix issue in Travis file --- .travis.yml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.travis.yml b/.travis.yml index a9a6e98b..180cb77d 100644 --- a/.travis.yml +++ b/.travis.yml @@ -56,8 +56,8 @@ script: - cmake -G "Unix Makefiles" -DCMAKE_BUILD_TYPE=Release —DDOUBLE_PRECISION_ENABLED=False -DCOMPILE_TESTS=True ../ - make && make test ARGS="-V" # Build in debug mode with logs and profiler enabled - - cmake -G "Unix Makefiles" -DCMAKE_BUILD_TYPE=Debug —DPROFILING_ENABLED=True -DLOGS_ENABLED=True + - cmake -G "Unix Makefiles" -DCMAKE_BUILD_TYPE=Debug —DPROFILING_ENABLED=True -DLOGS_ENABLED=True ../ - make # Build in release mode with logs and profiler enabled - - cmake -G "Unix Makefiles" -DCMAKE_BUILD_TYPE=Release —DPROFILING_ENABLED=True -DLOGS_ENABLED=True - - make \ No newline at end of file + - cmake -G "Unix Makefiles" -DCMAKE_BUILD_TYPE=Release —DPROFILING_ENABLED=True -DLOGS_ENABLED=True ../ + - make From 80996d617a5861aa0582c676051cce36223aacaa Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Fri, 16 Mar 2018 07:57:06 +0100 Subject: [PATCH 180/248] Fix issues in unit test for List --- test/tests/containers/TestList.h | 24 ++++++++++++------------ 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/test/tests/containers/TestList.h b/test/tests/containers/TestList.h index 750d0788..07cc5b4d 100644 --- a/test/tests/containers/TestList.h +++ b/test/tests/containers/TestList.h @@ -147,21 +147,21 @@ class TestList : public Test { test(list3.size() == 3); test(list3.capacity() == 4); test(it == list3.end()); - test(list3[0] = 1); - test(list3[1] = 2); - test(list3[2] = 3); + test(list3[0] == 1); + test(list3[1] == 2); + test(list3[2] == 3); it = list3.removeAt(1); test(list3.size() == 2); test(list3.capacity() == 4); - test(list3[0] = 1); - test(list3[1] = 3); - test(*it = 3); + test(list3[0] == 1); + test(list3[1] == 3); + test(*it == 3); list3.removeAt(0); test(list3.size() == 1); test(list3.capacity() == 4); - test(list3[0] = 3); + test(list3[0] == 3); it = list3.removeAt(0); test(list3.size() == 0); @@ -256,14 +256,14 @@ class TestList : public Test { list4 = list1; test(list4.size() == list1.size()) - test(list4[0] = list1[0]); - test(list4[1] = list1[1]); - test(list4[2] = list1[2]); + test(list4[0] == list1[0]); + test(list4[1] == list1[1]); + test(list4[2] == list1[2]); list5 = list2; test(list5.size() == list2.size()); - test(list5[0] = list2[0]); - test(list5[1] = list2[1]); + test(list5[0] == list2[0]); + test(list5[1] == list2[1]); } void testIndexing() { From 3e0c637c2bd86a1670c5e4834ea762916b77fc39 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Fri, 16 Mar 2018 07:57:28 +0100 Subject: [PATCH 181/248] Fix issue in Travis file --- .travis.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index 180cb77d..9afeb4d9 100644 --- a/.travis.yml +++ b/.travis.yml @@ -17,7 +17,7 @@ matrix: - os: osx osx_image: xcode8 env: - - MATRIX_EVAL="brew install gcc && CC=gcc-7 && CXX=g++-7" + - MATRIX_EVAL="brew update && brew install gcc && CC=gcc-7 && CXX=g++-7" # Linux / Clang - os: linux From 1bc50de2c930e1cdb8a061c5cfa6205877ed2d31 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 19 Mar 2018 23:02:13 +0100 Subject: [PATCH 182/248] Working on logger --- src/body/Body.h | 34 +++++++++ src/body/CollisionBody.cpp | 27 +++++-- src/body/CollisionBody.h | 7 ++ src/body/RigidBody.cpp | 34 ++++++++- src/body/RigidBody.h | 13 ++++ src/collision/CollisionDetection.cpp | 30 ++++---- src/collision/CollisionDetection.h | 4 +- src/collision/ProxyShape.h | 48 ++++++++++++ src/collision/TriangleVertexArray.cpp | 52 +++++++++++++ src/collision/TriangleVertexArray.h | 6 ++ .../broadphase/BroadPhaseAlgorithm.cpp | 10 +-- .../broadphase/BroadPhaseAlgorithm.h | 6 +- src/collision/shapes/BoxShape.h | 8 ++ src/collision/shapes/CapsuleShape.h | 8 ++ src/collision/shapes/CollisionShape.h | 3 + src/collision/shapes/ConcaveMeshShape.cpp | 65 ++++++++++++++++ src/collision/shapes/ConcaveMeshShape.h | 4 + src/collision/shapes/ConvexMeshShape.cpp | 44 +++++++++++ src/collision/shapes/ConvexMeshShape.h | 3 + src/collision/shapes/HeightFieldShape.cpp | 20 +++++ src/collision/shapes/HeightFieldShape.h | 3 + src/collision/shapes/SphereShape.h | 8 ++ src/collision/shapes/TriangleShape.h | 9 +++ src/configuration.h | 28 +++++++ src/engine/CollisionWorld.cpp | 22 ++++-- src/engine/DynamicsWorld.cpp | 24 +++--- src/engine/DynamicsWorld.h | 14 ++-- src/engine/Material.h | 15 ++++ src/engine/OverlappingPair.h | 8 +- src/utils/Logger.h | 75 ++++++++++++++----- 30 files changed, 551 insertions(+), 81 deletions(-) diff --git a/src/body/Body.h b/src/body/Body.h index 4a46e83f..dbacc55d 100644 --- a/src/body/Body.h +++ b/src/body/Body.h @@ -30,6 +30,7 @@ #include #include #include "configuration.h" +#include "utils/Logger.h" /// Namespace reactphysics3d namespace reactphysics3d { @@ -75,6 +76,12 @@ class Body { /// Pointer that can be used to attach user data to the body void* mUserData; +#ifdef IS_LOGGING_ACTIVE + + /// Logger + Logger* mLogger; +#endif + public : // -------------------- Methods -------------------- // @@ -118,6 +125,12 @@ class Body { /// Attach user data to this body void setUserData(void* userData); +#ifdef IS_LOGGING_ACTIVE + + /// Set the logger + void setLogger(Logger* logger); +#endif + /// Smaller than operator bool operator<(const Body& body2) const; @@ -159,6 +172,10 @@ inline void Body::setIsAllowedToSleep(bool isAllowedToSleep) { mIsAllowedToSleep = isAllowedToSleep; if (!mIsAllowedToSleep) setIsSleeping(false); + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(mID) + ": Set isAllowedToSleep=" + + (mIsAllowedToSleep ? "true" : "false")); } // Return whether or not the body is sleeping @@ -183,6 +200,10 @@ inline bool Body::isActive() const { */ inline void Body::setIsActive(bool isActive) { mIsActive = isActive; + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(mID) + ": Set isActive=" + + (mIsActive ? "true" : "false")); } // Set the variable to know whether or not the body is sleeping @@ -198,6 +219,10 @@ inline void Body::setIsSleeping(bool isSleeping) { } mIsSleeping = isSleeping; + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(mID) + ": Set isSleeping=" + + (mIsSleeping ? "true" : "false")); } // Return a pointer to the user data attached to this body @@ -216,6 +241,15 @@ inline void Body::setUserData(void* userData) { mUserData = userData; } +#ifdef IS_LOGGING_ACTIVE + +// Set the logger +inline void Body::setLogger(Logger* logger) { + mLogger = logger; +} + +#endif + // Smaller than operator inline bool Body::operator<(const Body& body2) const { return (mID < body2.mID); diff --git a/src/body/CollisionBody.cpp b/src/body/CollisionBody.cpp index bb8b0408..f7e7fe1d 100644 --- a/src/body/CollisionBody.cpp +++ b/src/body/CollisionBody.cpp @@ -79,6 +79,13 @@ ProxyShape* CollisionBody::addCollisionShape(CollisionShape* collisionShape, // Set the profiler proxyShape->setProfiler(mProfiler); +#endif + +#ifdef IS_LOGGING_ACTIVE + + // Set the logger + proxyShape->setLogger(mLogger); + #endif // Add it to the list of proxy collision shapes of the body @@ -99,6 +106,9 @@ ProxyShape* CollisionBody::addCollisionShape(CollisionShape* collisionShape, mNbCollisionShapes++; + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(mID) + ": Proxy shape " + std::to_string(proxyShape->getBroadPhaseId()) + " added to body"); + // Return a pointer to the collision shape return proxyShape; } @@ -114,11 +124,14 @@ void CollisionBody::removeCollisionShape(const ProxyShape* proxyShape) { ProxyShape* current = mProxyCollisionShapes; + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(mID) + ": Proxy shape " + std::to_string(proxyShape->getBroadPhaseId()) + " removed from body"); + // If the the first proxy shape is the one to remove if (current == proxyShape) { mProxyCollisionShapes = current->mNext; - if (mIsActive && proxyShape->mBroadPhaseID != -1) { + if (mIsActive && proxyShape->getBroadPhaseId() != -1) { mWorld.mCollisionDetection.removeProxyCollisionShape(current); } @@ -138,7 +151,7 @@ void CollisionBody::removeCollisionShape(const ProxyShape* proxyShape) { ProxyShape* elementToRemove = current->mNext; current->mNext = elementToRemove->mNext; - if (mIsActive && proxyShape->mBroadPhaseID != -1) { + if (mIsActive && proxyShape->getBroadPhaseId() != -1) { mWorld.mCollisionDetection.removeProxyCollisionShape(elementToRemove); } @@ -164,7 +177,7 @@ void CollisionBody::removeAllCollisionShapes() { // Remove the proxy collision shape ProxyShape* nextElement = current->mNext; - if (mIsActive && current->mBroadPhaseID != -1) { + if (mIsActive && current->getBroadPhaseId() != -1) { mWorld.mCollisionDetection.removeProxyCollisionShape(current); } @@ -209,7 +222,7 @@ void CollisionBody::updateBroadPhaseState() const { // Update the broad-phase state of a proxy collision shape of the body void CollisionBody::updateProxyShapeInBroadPhase(ProxyShape* proxyShape, bool forceReinsert) const { - if (proxyShape->mBroadPhaseID != -1) { + if (proxyShape->getBroadPhaseId() != -1) { // Recompute the world-space AABB of the collision shape AABB aabb; @@ -250,7 +263,7 @@ void CollisionBody::setIsActive(bool isActive) { // For each proxy shape of the body for (ProxyShape* shape = mProxyCollisionShapes; shape != nullptr; shape = shape->mNext) { - if (shape->mBroadPhaseID != -1) { + if (shape->getBroadPhaseId() != -1) { // Remove the proxy shape from the collision detection mWorld.mCollisionDetection.removeProxyCollisionShape(shape); @@ -260,6 +273,10 @@ void CollisionBody::setIsActive(bool isActive) { // Reset the contact manifold list of the body resetContactManifoldsList(); } + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(mID) + ": Set isActive=" + + (mIsActive ? "true" : "false")); } // Ask the broad-phase to test again the collision shapes of the body for collision diff --git a/src/body/CollisionBody.h b/src/body/CollisionBody.h index 2520cab4..e98b9a7d 100644 --- a/src/body/CollisionBody.h +++ b/src/body/CollisionBody.h @@ -231,6 +231,10 @@ inline void CollisionBody::setType(BodyType type) { // Update the broad-phase state of the body updateBroadPhaseState(); } + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(mID) + ": Set type=" + + (mType == BodyType::STATIC ? "Static" : (mType == BodyType::DYNAMIC ? "Dynamic" : "Kinematic"))); } // Return the current position and orientation @@ -254,6 +258,9 @@ inline void CollisionBody::setTransform(const Transform& transform) { // Update the broad-phase state of the body updateBroadPhaseState(); + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(mID) + ": Set transform=" + mTransform.to_string()); } // Return the first element of the linked list of contact manifolds involving this body diff --git a/src/body/RigidBody.cpp b/src/body/RigidBody.cpp index ab4b0c8e..3791c9d9 100644 --- a/src/body/RigidBody.cpp +++ b/src/body/RigidBody.cpp @@ -139,6 +139,9 @@ void RigidBody::setInertiaTensorLocal(const Matrix3x3& inertiaTensorLocal) { // Update the world inverse inertia tensor updateInertiaTensorInverseWorld(); + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(mID) + ": Set inertiaTensorLocal=" + inertiaTensorLocal.to_string()); } // Set the inverse local inertia tensor of the body (in local-space coordinates) @@ -160,6 +163,9 @@ void RigidBody::setInverseInertiaTensorLocal(const Matrix3x3& inverseInertiaTens // Update the world inverse inertia tensor updateInertiaTensorInverseWorld(); + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(mID) + ": Set inverseInertiaTensorLocal=" + inverseInertiaTensorLocal.to_string()); } // Set the local center of mass of the body (in local-space coordinates) @@ -183,6 +189,9 @@ void RigidBody::setCenterOfMassLocal(const Vector3& centerOfMassLocal) { // Update the linear velocity of the center of mass mLinearVelocity += mAngularVelocity.cross(mCenterOfMassWorld - oldCenterOfMass); + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(mID) + ": Set centerOfMassLocal=" + centerOfMassLocal.to_string()); } // Set the mass of the rigid body @@ -202,6 +211,9 @@ void RigidBody::setMass(decimal mass) { mInitMass = decimal(1.0); mMassInverse = decimal(1.0); } + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(mID) + ": Set mass=" + std::to_string(mass)); } // Remove a joint from the joints list @@ -264,6 +276,13 @@ ProxyShape* RigidBody::addCollisionShape(CollisionShape* collisionShape, // Set the profiler proxyShape->setProfiler(mProfiler); +#endif + +#ifdef IS_LOGGING_ACTIVE + + // Set the logger + proxyShape->setLogger(mLogger); + #endif // Add it to the list of proxy collision shapes of the body @@ -288,6 +307,9 @@ ProxyShape* RigidBody::addCollisionShape(CollisionShape* collisionShape, // collision shape recomputeMassInformation(); + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(mID) + ": Proxy shape " + std::to_string(proxyShape->getBroadPhaseId()) + " added to body"); + // Return a pointer to the proxy collision shape return proxyShape; } @@ -324,6 +346,9 @@ void RigidBody::setLinearVelocity(const Vector3& linearVelocity) { if (mLinearVelocity.lengthSquare() > decimal(0.0)) { setIsSleeping(false); } + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(mID) + ": Set linearVelocity=" + mLinearVelocity.to_string()); } // Set the angular velocity. @@ -342,6 +367,9 @@ void RigidBody::setAngularVelocity(const Vector3& angularVelocity) { if (mAngularVelocity.lengthSquare() > decimal(0.0)) { setIsSleeping(false); } + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(mID) + ": Set angularVelocity=" + mAngularVelocity.to_string()); } // Set the current position and orientation @@ -367,6 +395,9 @@ void RigidBody::setTransform(const Transform& transform) { // Update the broad-phase state of the body updateBroadPhaseState(); + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(mID) + ": Set transform=" + mTransform.to_string()); } // Recompute the center of mass, total mass and inertia tensor of the body using all @@ -469,7 +500,7 @@ void RigidBody::updateBroadPhaseState() const { // Recompute the world-space AABB of the collision shape AABB aabb; - shape->getCollisionShape()->computeAABB(aabb, mTransform *shape->getLocalToBodyTransform()); + shape->getCollisionShape()->computeAABB(aabb, mTransform * shape->getLocalToBodyTransform()); // Update the broad-phase state for the proxy collision shape mWorld.mCollisionDetection.updateProxyCollisionShape(shape, aabb, displacement); @@ -494,4 +525,3 @@ void RigidBody::setProfiler(Profiler* profiler) { } #endif - diff --git a/src/body/RigidBody.h b/src/body/RigidBody.h index 22c784ef..ad794513 100644 --- a/src/body/RigidBody.h +++ b/src/body/RigidBody.h @@ -325,6 +325,10 @@ inline bool RigidBody::isGravityEnabled() const { */ inline void RigidBody::enableGravity(bool isEnabled) { mIsGravityEnabled = isEnabled; + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(mID) + ": Set isGravityEnabled=" + + (mIsGravityEnabled ? "true" : "false")); } // Return a reference to the material properties of the rigid body @@ -341,6 +345,9 @@ inline Material& RigidBody::getMaterial() { */ inline void RigidBody::setMaterial(const Material& material) { mMaterial = material; + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(mID) + ": Set Material" + mMaterial.to_string()); } // Return the linear velocity damping factor @@ -359,6 +366,9 @@ inline decimal RigidBody::getLinearDamping() const { inline void RigidBody::setLinearDamping(decimal linearDamping) { assert(linearDamping >= decimal(0.0)); mLinearDamping = linearDamping; + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(mID) + ": Set linearDamping=" + std::to_string(mLinearDamping)); } // Return the angular velocity damping factor @@ -377,6 +387,9 @@ inline decimal RigidBody::getAngularDamping() const { inline void RigidBody::setAngularDamping(decimal angularDamping) { assert(angularDamping >= decimal(0.0)); mAngularDamping = angularDamping; + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(mID) + ": Set angularDamping=" + std::to_string(mAngularDamping)); } // Return the first element of the linked list of joints involving this body diff --git a/src/collision/CollisionDetection.cpp b/src/collision/CollisionDetection.cpp index dc2272f9..f56672ca 100644 --- a/src/collision/CollisionDetection.cpp +++ b/src/collision/CollisionDetection.cpp @@ -118,9 +118,9 @@ void CollisionDetection::computeMiddlePhase() { ProxyShape* shape1 = pair->getShape1(); ProxyShape* shape2 = pair->getShape2(); - assert(shape1->mBroadPhaseID != -1); - assert(shape2->mBroadPhaseID != -1); - assert(shape1->mBroadPhaseID != shape2->mBroadPhaseID); + assert(shape1->getBroadPhaseId() != -1); + assert(shape2->getBroadPhaseId() != -1); + assert(shape1->getBroadPhaseId() != shape2->getBroadPhaseId()); // Check if the two shapes are still overlapping. Otherwise, we destroy the // overlapping pair @@ -308,9 +308,9 @@ void CollisionDetection::computeNarrowPhase() { /// This method is called by the broad-phase collision detection algorithm void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, ProxyShape* shape2) { - assert(shape1->mBroadPhaseID != -1); - assert(shape2->mBroadPhaseID != -1); - assert(shape1->mBroadPhaseID != shape2->mBroadPhaseID); + assert(shape1->getBroadPhaseId() != -1); + assert(shape2->getBroadPhaseId() != -1); + assert(shape1->getBroadPhaseId() != shape2->getBroadPhaseId()); // Check if the collision filtering allows collision between the two shapes if ((shape1->getCollideWithMaskBits() & shape2->getCollisionCategoryBits()) == 0 || @@ -338,13 +338,13 @@ void CollisionDetection::broadPhaseNotifyOverlappingPair(ProxyShape* shape1, Pro // Remove a body from the collision detection void CollisionDetection::removeProxyCollisionShape(ProxyShape* proxyShape) { - assert(proxyShape->mBroadPhaseID != -1); + assert(proxyShape->getBroadPhaseId() != -1); // Remove all the overlapping pairs involving this proxy shape Map, OverlappingPair*>::Iterator it; for (it = mOverlappingPairs.begin(); it != mOverlappingPairs.end(); ) { - if (it->second->getShape1()->mBroadPhaseID == proxyShape->mBroadPhaseID|| - it->second->getShape2()->mBroadPhaseID == proxyShape->mBroadPhaseID) { + if (it->second->getShape1()->getBroadPhaseId() == proxyShape->getBroadPhaseId()|| + it->second->getShape2()->getBroadPhaseId() == proxyShape->getBroadPhaseId()) { // TODO : Remove all the contact manifold of the overlapping pair from the contact manifolds list of the two bodies involved @@ -637,10 +637,10 @@ void CollisionDetection::testOverlap(CollisionBody* body, OverlapCallback* overl ProxyShape* bodyProxyShape = body->getProxyShapesList(); while (bodyProxyShape != nullptr) { - if (bodyProxyShape->mBroadPhaseID != -1) { + if (bodyProxyShape->getBroadPhaseId() != -1) { // Get the AABB of the shape - const AABB& shapeAABB = mBroadPhaseAlgorithm.getFatAABB(bodyProxyShape->mBroadPhaseID); + const AABB& shapeAABB = mBroadPhaseAlgorithm.getFatAABB(bodyProxyShape->getBroadPhaseId()); // Ask the broad-phase to get all the overlapping shapes LinkedList overlappingNodes(mMemoryManager.getPoolAllocator()); @@ -817,10 +817,10 @@ void CollisionDetection::testCollision(CollisionBody* body, CollisionCallback* c ProxyShape* bodyProxyShape = body->getProxyShapesList(); while (bodyProxyShape != nullptr) { - if (bodyProxyShape->mBroadPhaseID != -1) { + if (bodyProxyShape->getBroadPhaseId() != -1) { // Get the AABB of the shape - const AABB& shapeAABB = mBroadPhaseAlgorithm.getFatAABB(bodyProxyShape->mBroadPhaseID); + const AABB& shapeAABB = mBroadPhaseAlgorithm.getFatAABB(bodyProxyShape->getBroadPhaseId()); // Ask the broad-phase to get all the overlapping shapes LinkedList overlappingNodes(mMemoryManager.getPoolAllocator()); @@ -996,6 +996,6 @@ EventListener* CollisionDetection::getWorldEventListener() { // Return the world-space AABB of a given proxy shape const AABB CollisionDetection::getWorldAABB(const ProxyShape* proxyShape) const { - assert(proxyShape->mBroadPhaseID > -1); - return mBroadPhaseAlgorithm.getFatAABB(proxyShape->mBroadPhaseID); + assert(proxyShape->getBroadPhaseId() > -1); + return mBroadPhaseAlgorithm.getFatAABB(proxyShape->getBroadPhaseId()); } diff --git a/src/collision/CollisionDetection.h b/src/collision/CollisionDetection.h index d8f5240a..ecfa766d 100644 --- a/src/collision/CollisionDetection.h +++ b/src/collision/CollisionDetection.h @@ -279,8 +279,8 @@ inline void CollisionDetection::removeNoCollisionPair(CollisionBody* body1, /// previous frame so that it is tested for collision again in the broad-phase. inline void CollisionDetection::askForBroadPhaseCollisionCheck(ProxyShape* shape) { - if (shape->mBroadPhaseID != -1) { - mBroadPhaseAlgorithm.addMovedCollisionShape(shape->mBroadPhaseID); + if (shape->getBroadPhaseId() != -1) { + mBroadPhaseAlgorithm.addMovedCollisionShape(shape->getBroadPhaseId()); } } diff --git a/src/collision/ProxyShape.h b/src/collision/ProxyShape.h index 0da79e28..61118d45 100644 --- a/src/collision/ProxyShape.h +++ b/src/collision/ProxyShape.h @@ -93,6 +93,12 @@ class ProxyShape { #endif +#ifdef IS_LOGGING_ACTIVE + + /// Logger + Logger* mLogger; +#endif + // -------------------- Methods -------------------- // /// Return the collision shape @@ -175,6 +181,9 @@ class ProxyShape { /// Set the local scaling vector of the collision shape virtual void setLocalScaling(const Vector3& scaling); + /// Return the broad-phase id + int getBroadPhaseId() const; + #ifdef IS_PROFILING_ACTIVE /// Set the profiler @@ -182,6 +191,12 @@ class ProxyShape { #endif +#ifdef IS_LOGGING_ACTIVE + + /// Set the logger + void setLogger(Logger* logger); +#endif + // -------------------- Friendship -------------------- // friend class OverlappingPair; @@ -265,6 +280,10 @@ inline void ProxyShape::setLocalToBodyTransform(const Transform& transform) { // Notify the body that the proxy shape has to be updated in the broad-phase mBody->updateProxyShapeInBroadPhase(this, true); + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::ProxyShape, + "ProxyShape " + std::to_string(mBroadPhaseID) + ": Set localToBodyTransform=" + + mLocalToBodyTransform.to_string()); } // Return the local to world transform @@ -316,6 +335,10 @@ inline unsigned short ProxyShape::getCollisionCategoryBits() const { */ inline void ProxyShape::setCollisionCategoryBits(unsigned short collisionCategoryBits) { mCollisionCategoryBits = collisionCategoryBits; + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::ProxyShape, + "ProxyShape " + std::to_string(mBroadPhaseID) + ": Set collisionCategoryBits=" + + std::to_string(mCollisionCategoryBits)); } // Return the collision bits mask @@ -332,6 +355,10 @@ inline unsigned short ProxyShape::getCollideWithMaskBits() const { */ inline void ProxyShape::setCollideWithMaskBits(unsigned short collideWithMaskBits) { mCollideWithMaskBits = collideWithMaskBits; + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::ProxyShape, + "ProxyShape " + std::to_string(mBroadPhaseID) + ": Set collideWithMaskBits=" + + std::to_string(mCollideWithMaskBits)); } // Return the local scaling vector of the collision shape @@ -348,6 +375,8 @@ inline Vector3 ProxyShape::getLocalScaling() const { */ inline void ProxyShape::setLocalScaling(const Vector3& scaling) { + // TODO : Do not use a local of the collision shape in case of shared collision shapes + // Set the local scaling of the collision shape mCollisionShape->setLocalScaling(scaling); @@ -355,6 +384,15 @@ inline void ProxyShape::setLocalScaling(const Vector3& scaling) { // Notify the body that the proxy shape has to be updated in the broad-phase mBody->updateProxyShapeInBroadPhase(this, true); + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::ProxyShape, + "ProxyShape " + std::to_string(mBroadPhaseID) + ": Set localScaling=" + + mCollisionShape->getLocalScaling().to_string()); +} + +// Return the broad-phase id +inline int ProxyShape::getBroadPhaseId() const { + return mBroadPhaseID; } /// Test if the proxy shape overlaps with a given AABB @@ -378,6 +416,16 @@ inline void ProxyShape::setProfiler(Profiler* profiler) { #endif +#ifdef IS_LOGGING_ACTIVE + +// Set the logger +inline void ProxyShape::setLogger(Logger* logger) { + + mLogger = logger; +} + +#endif + } #endif diff --git a/src/collision/TriangleVertexArray.cpp b/src/collision/TriangleVertexArray.cpp index 7cfb2076..a54ad425 100644 --- a/src/collision/TriangleVertexArray.cpp +++ b/src/collision/TriangleVertexArray.cpp @@ -280,3 +280,55 @@ void TriangleVertexArray::getTriangleVerticesNormals(uint triangleIndex, Vector3 } } } + +// Return a vertex of the array +void TriangleVertexArray::getVertex(uint vertexIndex, Vector3* outVertex) { + + assert(vertexIndex < mNbVertices); + + const uchar* vertexPointerChar = mVerticesStart + vertexIndex * mVerticesStride; + const void* vertexPointer = static_cast(vertexPointerChar); + + // Get the vertices components of the triangle + if (mVertexDataType == TriangleVertexArray::VertexDataType::VERTEX_FLOAT_TYPE) { + const float* vertices = static_cast(vertexPointer); + (*outVertex)[0] = decimal(vertices[0]); + (*outVertex)[1] = decimal(vertices[1]); + (*outVertex)[2] = decimal(vertices[2]); + } + else if (mVertexDataType == TriangleVertexArray::VertexDataType::VERTEX_DOUBLE_TYPE) { + const double* vertices = static_cast(vertexPointer); + (*outVertex)[0] = decimal(vertices[0]); + (*outVertex)[1] = decimal(vertices[1]); + (*outVertex)[2] = decimal(vertices[2]); + } + else { + assert(false); + } +} + +// Return a vertex normal of the array +void TriangleVertexArray::getNormal(uint vertexIndex, Vector3* outNormal) { + + assert(vertexIndex < mNbVertices); + + const uchar* vertexNormalPointerChar = mVerticesNormalsStart + vertexIndex * mVerticesNormalsStride; + const void* vertexNormalPointer = static_cast(vertexNormalPointerChar); + + // Get the normals from the array + if (mVertexNormaldDataType == TriangleVertexArray::NormalDataType::NORMAL_FLOAT_TYPE) { + const float* normal = static_cast(vertexNormalPointer); + (*outNormal)[0] = decimal(normal[0]); + (*outNormal)[1] = decimal(normal[1]); + (*outNormal)[2] = decimal(normal[2]); + } + else if (mVertexNormaldDataType == TriangleVertexArray::NormalDataType::NORMAL_DOUBLE_TYPE) { + const double* normal = static_cast(vertexNormalPointer); + (*outNormal)[0] = decimal(normal[0]); + (*outNormal)[1] = decimal(normal[1]); + (*outNormal)[2] = decimal(normal[2]); + } + else { + assert(false); + } +} diff --git a/src/collision/TriangleVertexArray.h b/src/collision/TriangleVertexArray.h index 3a48c2e3..4fe2fe07 100644 --- a/src/collision/TriangleVertexArray.h +++ b/src/collision/TriangleVertexArray.h @@ -169,6 +169,12 @@ class TriangleVertexArray { /// Return the indices of the three vertices of a given triangle in the array void getTriangleVerticesIndices(uint triangleIndex, uint* outVerticesIndices) const; + + /// Return a vertex of the array + void getVertex(uint vertexIndex, Vector3* outVertex); + + /// Return a vertex normal of the array + void getNormal(uint vertexIndex, Vector3* outNormal); }; // Return the vertex data type diff --git a/src/collision/broadphase/BroadPhaseAlgorithm.cpp b/src/collision/broadphase/BroadPhaseAlgorithm.cpp index fbad0cfd..0d722a0a 100644 --- a/src/collision/broadphase/BroadPhaseAlgorithm.cpp +++ b/src/collision/broadphase/BroadPhaseAlgorithm.cpp @@ -140,7 +140,7 @@ void BroadPhaseAlgorithm::removeMovedCollisionShape(int broadPhaseID) { // Add a proxy collision shape into the broad-phase collision detection void BroadPhaseAlgorithm::addProxyCollisionShape(ProxyShape* proxyShape, const AABB& aabb) { - assert(proxyShape->mBroadPhaseID == -1); + assert(proxyShape->getBroadPhaseId() == -1); // Add the collision shape into the dynamic AABB tree and get its broad-phase ID int nodeId = mDynamicAABBTree.addObject(aabb, proxyShape); @@ -150,15 +150,15 @@ void BroadPhaseAlgorithm::addProxyCollisionShape(ProxyShape* proxyShape, const A // Add the collision shape into the array of bodies that have moved (or have been created) // during the last simulation step - addMovedCollisionShape(proxyShape->mBroadPhaseID); + addMovedCollisionShape(proxyShape->getBroadPhaseId()); } // Remove a proxy collision shape from the broad-phase collision detection void BroadPhaseAlgorithm::removeProxyCollisionShape(ProxyShape* proxyShape) { - assert(proxyShape->mBroadPhaseID != -1); + assert(proxyShape->getBroadPhaseId() != -1); - int broadPhaseID = proxyShape->mBroadPhaseID; + int broadPhaseID = proxyShape->getBroadPhaseId(); proxyShape->mBroadPhaseID = -1; @@ -174,7 +174,7 @@ void BroadPhaseAlgorithm::removeProxyCollisionShape(ProxyShape* proxyShape) { void BroadPhaseAlgorithm::updateProxyCollisionShape(ProxyShape* proxyShape, const AABB& aabb, const Vector3& displacement, bool forceReinsert) { - int broadPhaseID = proxyShape->mBroadPhaseID; + int broadPhaseID = proxyShape->getBroadPhaseId(); assert(broadPhaseID >= 0); diff --git a/src/collision/broadphase/BroadPhaseAlgorithm.h b/src/collision/broadphase/BroadPhaseAlgorithm.h index df642677..4e8360b9 100644 --- a/src/collision/broadphase/BroadPhaseAlgorithm.h +++ b/src/collision/broadphase/BroadPhaseAlgorithm.h @@ -246,11 +246,11 @@ inline bool BroadPhasePair::smallerThan(const BroadPhasePair& pair1, const Broad inline bool BroadPhaseAlgorithm::testOverlappingShapes(const ProxyShape* shape1, const ProxyShape* shape2) const { - if (shape1->mBroadPhaseID == -1 || shape2->mBroadPhaseID == -1) return false; + if (shape1->getBroadPhaseId() == -1 || shape2->getBroadPhaseId() == -1) return false; // Get the two AABBs of the collision shapes - const AABB& aabb1 = mDynamicAABBTree.getFatAABB(shape1->mBroadPhaseID); - const AABB& aabb2 = mDynamicAABBTree.getFatAABB(shape2->mBroadPhaseID); + const AABB& aabb1 = mDynamicAABBTree.getFatAABB(shape1->getBroadPhaseId()); + const AABB& aabb2 = mDynamicAABBTree.getFatAABB(shape2->getBroadPhaseId()); // Check if the two AABBs are overlapping return aabb1.testCollision(aabb2); diff --git a/src/collision/shapes/BoxShape.h b/src/collision/shapes/BoxShape.h index 2ebcdce1..0c261a6f 100644 --- a/src/collision/shapes/BoxShape.h +++ b/src/collision/shapes/BoxShape.h @@ -123,6 +123,9 @@ class BoxShape : public ConvexPolyhedronShape { /// Return the centroid of the polyhedron virtual Vector3 getCentroid() const override; + + /// Return the string representation of the shape + virtual std::string to_string() const override; }; // Return the extents of the box @@ -237,6 +240,11 @@ inline Vector3 BoxShape::getCentroid() const { return Vector3::zero(); } +// Return the string representation of the shape +inline std::string BoxShape::to_string() const { + return "BoxShape {extents=" + mExtent.to_string() + "}"; +} + // Return the number of half-edges of the polyhedron inline uint BoxShape::getNbHalfEdges() const { return 24; diff --git a/src/collision/shapes/CapsuleShape.h b/src/collision/shapes/CapsuleShape.h index 7843f139..6a58f115 100644 --- a/src/collision/shapes/CapsuleShape.h +++ b/src/collision/shapes/CapsuleShape.h @@ -105,6 +105,9 @@ class CapsuleShape : public ConvexShape { /// Return the local inertia tensor of the collision shape virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; + + /// Return the string representation of the shape + virtual std::string to_string() const override; }; // Get the radius of the capsule @@ -185,6 +188,11 @@ inline Vector3 CapsuleShape::getLocalSupportPointWithoutMargin(const Vector3& di } } +// Return the string representation of the shape +inline std::string CapsuleShape::to_string() const { + return "CapsuleShape {halfHeight=" + std::to_string(mHalfHeight) + ", radius=" + std::to_string(getRadius()) + "}"; +} + } #endif diff --git a/src/collision/shapes/CollisionShape.h b/src/collision/shapes/CollisionShape.h index 3fdf4470..a7b07fc3 100644 --- a/src/collision/shapes/CollisionShape.h +++ b/src/collision/shapes/CollisionShape.h @@ -138,6 +138,9 @@ class CollisionShape { /// Compute the world-space AABB of the collision shape given a transform virtual void computeAABB(AABB& aabb, const Transform& transform) const; + /// Return the string representation of the shape + virtual std::string to_string() const=0; + #ifdef IS_PROFILING_ACTIVE /// Set the profiler diff --git a/src/collision/shapes/ConcaveMeshShape.cpp b/src/collision/shapes/ConcaveMeshShape.cpp index 768f7c2e..bde756e4 100644 --- a/src/collision/shapes/ConcaveMeshShape.cpp +++ b/src/collision/shapes/ConcaveMeshShape.cpp @@ -214,3 +214,68 @@ void ConcaveMeshRaycastCallback::raycastTriangles() { } } + +// Return the string representation of the shape +std::string ConcaveMeshShape::to_string() const { + + std::stringstream ss; + + ss << "ConcaveMeshShape {" << std::endl; + ss << "nbSubparts=" << mTriangleMesh->getNbSubparts() << std::endl; + + // Vertices array + for (uint subPart=0; subPartgetNbSubparts(); subPart++) { + + // Get the triangle vertex array of the current sub-part + TriangleVertexArray* triangleVertexArray = mTriangleMesh->getSubpart(subPart); + + ss << "subpart" << subPart << "={" << std::endl; + ss << "nbVertices=" << triangleVertexArray->getNbVertices() << std::endl; + ss << "nbTriangles=" << triangleVertexArray->getNbTriangles() << std::endl; + + ss << "vertices=["; + + // For each triangle of the concave mesh + for (uint v=0; vgetNbVertices(); v++) { + + Vector3 vertex; + triangleVertexArray->getVertex(v, &vertex); + + ss << vertex.to_string() << ", "; + } + + ss << "], " << std::endl; + + ss << "normals=["; + + // For each triangle of the concave mesh + for (uint v=0; vgetNbVertices(); v++) { + + Vector3 normal; + triangleVertexArray->getNormal(v, &normal); + + ss << normal.to_string() << ", "; + } + + ss << "], " << std::endl; + + ss << "triangles=["; + + // For each triangle of the concave mesh + // For each triangle of the concave mesh + for (uint triangleIndex=0; triangleIndexgetNbTriangles(); triangleIndex++) { + + uint indices[3]; + + triangleVertexArray->getTriangleVerticesIndices(triangleIndex, indices); + + ss << "(" << indices[0] << "," << indices[1] << "," << indices[2] << "), "; + } + + ss << "], " << std::endl; + + ss << "}" << std::endl; + } + + return ss.str(); +} diff --git a/src/collision/shapes/ConcaveMeshShape.h b/src/collision/shapes/ConcaveMeshShape.h index d35c9d23..ccafbba9 100644 --- a/src/collision/shapes/ConcaveMeshShape.h +++ b/src/collision/shapes/ConcaveMeshShape.h @@ -186,6 +186,9 @@ class ConcaveMeshShape : public ConcaveShape { /// Use a callback method on all triangles of the concave shape inside a given AABB virtual void testAllTriangles(TriangleCallback& callback, const AABB& localAABB) const override; + /// Return the string representation of the shape + virtual std::string to_string() const override; + #ifdef IS_PROFILING_ACTIVE /// Set the profiler @@ -277,6 +280,7 @@ inline void ConcaveMeshShape::setProfiler(Profiler* profiler) { mDynamicAABBTree.setProfiler(profiler); } + #endif } diff --git a/src/collision/shapes/ConvexMeshShape.cpp b/src/collision/shapes/ConvexMeshShape.cpp index d4037a8c..1c47b4d9 100644 --- a/src/collision/shapes/ConvexMeshShape.cpp +++ b/src/collision/shapes/ConvexMeshShape.cpp @@ -201,3 +201,47 @@ bool ConvexMeshShape::testPointInside(const Vector3& localPoint, ProxyShape* pro return true; } +// Return the string representation of the shape +std::string ConvexMeshShape::to_string() const { + + std::stringstream ss; + ss << "ConvexMeshShape {" << std::endl; + ss << "nbVertices=" << mPolyhedronMesh->getNbVertices() << std::endl; + ss << "nbFaces=" << mPolyhedronMesh->getNbFaces() << std::endl; + + ss << "vertices=["; + + for (uint v=0; v < mPolyhedronMesh->getNbVertices(); v++) { + + Vector3 vertex = mPolyhedronMesh->getVertex(v); + ss << vertex.to_string(); + if (v != mPolyhedronMesh->getNbVertices() - 1) { + ss << ", "; + } + } + + ss << "], faces=["; + + HalfEdgeStructure halfEdgeStruct = mPolyhedronMesh->getHalfEdgeStructure(); + for (uint f=0; f < mPolyhedronMesh->getNbFaces(); f++) { + + const HalfEdgeStructure::Face& face = halfEdgeStruct.getFace(f); + + ss << "["; + + for (uint v=0; v < face.faceVertices.size(); v++) { + + ss << face.faceVertices[v]; + if (v != face.faceVertices.size() - 1) { + ss << ","; + } + } + + ss << "]"; + } + + ss << "]}"; + + return ss.str(); +} + diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index 49d3f773..ebec6a09 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -130,6 +130,9 @@ class ConvexMeshShape : public ConvexPolyhedronShape { /// Return the centroid of the polyhedron virtual Vector3 getCentroid() const override; + + /// Return the string representation of the shape + virtual std::string to_string() const override; }; /// Set the scaling vector of the collision shape diff --git a/src/collision/shapes/HeightFieldShape.cpp b/src/collision/shapes/HeightFieldShape.cpp index df2019c0..0b3a4044 100644 --- a/src/collision/shapes/HeightFieldShape.cpp +++ b/src/collision/shapes/HeightFieldShape.cpp @@ -297,3 +297,23 @@ void TriangleOverlapCallback::testTriangle(const Vector3* trianglePoints, const mIsHit = true; } } + +// Return the string representation of the shape +std::string HeightFieldShape::to_string() const { + + std::stringstream ss; + + ss << "HeightFieldShape {" << std::endl; + + ss << "nbColumns=" << mNbColumns << std::endl; + ss << "nbRows=" << mNbRows << std::endl; + ss << "width=" << mWidth << std::endl; + ss << "length=" << mLength << std::endl; + ss << "minHeight=" << mMinHeight << std::endl; + ss << "maxHeight=" << mMaxHeight << std::endl; + ss << "upAxis=" << mUpAxis << std::endl; + ss << "integerHeightScale=" << mIntegerHeightScale << std::endl; + ss << "}"; + + return ss.str(); +} diff --git a/src/collision/shapes/HeightFieldShape.h b/src/collision/shapes/HeightFieldShape.h index 7b834e2b..e796e208 100644 --- a/src/collision/shapes/HeightFieldShape.h +++ b/src/collision/shapes/HeightFieldShape.h @@ -209,6 +209,9 @@ class HeightFieldShape : public ConcaveShape { /// Use a callback method on all triangles of the concave shape inside a given AABB virtual void testAllTriangles(TriangleCallback& callback, const AABB& localAABB) const override; + /// Return the string representation of the shape + virtual std::string to_string() const override; + // ---------- Friendship ----------- // friend class ConvexTriangleAABBOverlapCallback; diff --git a/src/collision/shapes/SphereShape.h b/src/collision/shapes/SphereShape.h index 90b20d2d..a0010b06 100644 --- a/src/collision/shapes/SphereShape.h +++ b/src/collision/shapes/SphereShape.h @@ -93,6 +93,9 @@ class SphereShape : public ConvexShape { /// Update the AABB of a body using its collision shape virtual void computeAABB(AABB& aabb, const Transform& transform) const override; + + /// Return the string representation of the shape + virtual std::string to_string() const override; }; // Get the radius of the sphere @@ -181,6 +184,11 @@ inline bool SphereShape::testPointInside(const Vector3& localPoint, ProxyShape* return (localPoint.lengthSquare() < mMargin * mMargin); } +// Return the string representation of the shape +inline std::string SphereShape::to_string() const { + return "SphereShape { radius=" + std::to_string(getRadius()) + "}"; +} + } #endif diff --git a/src/collision/shapes/TriangleShape.h b/src/collision/shapes/TriangleShape.h index 23f26adc..5a5a49b2 100644 --- a/src/collision/shapes/TriangleShape.h +++ b/src/collision/shapes/TriangleShape.h @@ -175,6 +175,9 @@ class TriangleShape : public ConvexPolyhedronShape { const Transform& shape1ToWorld, const Transform& shape2ToWorld, decimal penetrationDepth, Vector3& outSmoothVertexNormal); + /// Return the string representation of the shape + virtual std::string to_string() const override; + // ---------- Friendship ---------- // friend class ConcaveMeshRaycastCallback; @@ -325,6 +328,12 @@ inline void TriangleShape::setRaycastTestType(TriangleRaycastSide testType) { mRaycastTestType = testType; } +// Return the string representation of the shape +inline std::string TriangleShape::to_string() const { + return "TriangleShape {v1=" + mPoints[0].to_string() + ", v2=" + mPoints[1].to_string() + "," + + "v3=" + mPoints[2].to_string() + "}"; +} + } #endif diff --git a/src/configuration.h b/src/configuration.h index aa71e88a..aa8a0535 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -31,6 +31,7 @@ #include #include #include +#include #include #include "decimal.h" #include "containers/Pair.h" @@ -105,6 +106,9 @@ constexpr decimal DYNAMIC_TREE_AABB_GAP = decimal(0.1); /// followin constant with the linear velocity and the elapsed time between two frames. constexpr decimal DYNAMIC_TREE_AABB_LIN_GAP_MULTIPLIER = decimal(1.7); +/// Current version of ReactPhysics3D +const std::string RP3D_VERSION = std::string("0.7.0"); + /// Structure WorldSettings /** * This class is used to describe some settings of a physics world. @@ -161,6 +165,30 @@ struct WorldSettings { /// merge them. If the cosine of the angle between the normals of the two manifold are larger /// than the value bellow, the manifold are considered to be similar. decimal cosAngleSimilarContactManifold = decimal(0.95); + + /// Return a string with the world settings + std::string to_string() const { + + std::stringstream ss; + + ss << "worldName=" << worldName << std::endl; + ss << "persistentContactDistanceThreshold=" << persistentContactDistanceThreshold << std::endl; + ss << "defaultFrictionCoefficient=" << defaultFrictionCoefficient << std::endl; + ss << "defaultBounciness=" << defaultBounciness << std::endl; + ss << "restitutionVelocityThreshold=" << restitutionVelocityThreshold << std::endl; + ss << "defaultRollingRestistance=" << defaultRollingRestistance << std::endl; + ss << "isSleepingEnabled=" << isSleepingEnabled << std::endl; + ss << "defaultVelocitySolverNbIterations=" << defaultVelocitySolverNbIterations << std::endl; + ss << "defaultPositionSolverNbIterations=" << defaultPositionSolverNbIterations << std::endl; + ss << "defaultTimeBeforeSleep=" << defaultTimeBeforeSleep << std::endl; + ss << "defaultSleepLinearVelocity=" << defaultSleepLinearVelocity << std::endl; + ss << "defaultSleepAngularVelocity=" << defaultSleepAngularVelocity << std::endl; + ss << "nbMaxContactManifoldsConvexShape=" << nbMaxContactManifoldsConvexShape << std::endl; + ss << "nbMaxContactManifoldsConcaveShape=" << nbMaxContactManifoldsConcaveShape << std::endl; + ss << "cosAngleSimilarContactManifold=" << cosAngleSimilarContactManifold << std::endl; + + return ss.str(); + } }; } diff --git a/src/engine/CollisionWorld.cpp b/src/engine/CollisionWorld.cpp index 1dbf1b6f..d9b5f258 100644 --- a/src/engine/CollisionWorld.cpp +++ b/src/engine/CollisionWorld.cpp @@ -80,7 +80,7 @@ CollisionWorld::CollisionWorld(const WorldSettings& worldSettings, Logger* logge mLogger = new Logger(); // Add a log destination file - uint logLevel = static_cast(Logger::Level::Info) | static_cast(Logger::Level::Warning) | + uint logLevel = static_cast(Logger::Level::Information) | static_cast(Logger::Level::Warning) | static_cast(Logger::Level::Error); mLogger->addFileDestination("rp3d_log_" + mName + ".html", logLevel, Logger::Format::HTML); } @@ -89,14 +89,16 @@ CollisionWorld::CollisionWorld(const WorldSettings& worldSettings, Logger* logge mNbWorlds++; - RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World, "Collision World: Collision world " + mName + " has been created"); + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World, + "Collision World: Initial world settings: " + worldSettings.to_string()); } // Destructor CollisionWorld::~CollisionWorld() { - RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World, "Collision World: Collision world " + mName + " has been destroyed"); // Destroy all the collision bodies that have not been removed @@ -154,8 +156,12 @@ CollisionBody* CollisionWorld::createCollisionBody(const Transform& transform) { #endif - RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::Body, - "Collision Body " + std::to_string(bodyID) + ": New collision body created"); +#ifdef IS_LOGGING_ACTIVE + collisionBody->setLogger(mLogger); +#endif + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(bodyID) + ": New collision body created"); // Return the pointer to the rigid body return collisionBody; @@ -167,8 +173,8 @@ CollisionBody* CollisionWorld::createCollisionBody(const Transform& transform) { */ void CollisionWorld::destroyCollisionBody(CollisionBody* collisionBody) { - RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::Body, - "Collision Body " + std::to_string(collisionBody->getId()) + ": collision body destroyed"); + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(collisionBody->getId()) + ": collision body destroyed"); // Remove all the collision shapes of the body collisionBody->removeAllCollisionShapes(); @@ -253,7 +259,7 @@ bool CollisionWorld::testOverlap(CollisionBody* body1, CollisionBody* body2) { // Return the current world-space AABB of given proxy shape AABB CollisionWorld::getWorldAABB(const ProxyShape* proxyShape) const { - if (proxyShape->mBroadPhaseID == -1) { + if (proxyShape->getBroadPhaseId() == -1) { return AABB(); } diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index 7164458d..8fb71e08 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -64,7 +64,7 @@ DynamicsWorld::DynamicsWorld(const Vector3& gravity, const WorldSettings& worldS #endif - RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World, "Dynamics World: Dynamics world " + mName + " has been created"); } @@ -91,7 +91,7 @@ DynamicsWorld::~DynamicsWorld() { mProfiler->printReport(); #endif - RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World, "Dynamics World: Dynamics world " + mName + " has been destroyed"); } @@ -426,13 +426,15 @@ RigidBody* DynamicsWorld::createRigidBody(const Transform& transform) { mRigidBodies.add(rigidBody); #ifdef IS_PROFILING_ACTIVE - rigidBody->setProfiler(mProfiler); - #endif - RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::Body, - "Rigid Body " + std::to_string(bodyID) + ": New collision body created"); +#ifdef IS_LOGGING_ACTIVE + rigidBody->setLogger(mLogger); +#endif + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(bodyID) + ": New collision body created"); // Return the pointer to the rigid body return rigidBody; @@ -444,8 +446,8 @@ RigidBody* DynamicsWorld::createRigidBody(const Transform& transform) { */ void DynamicsWorld::destroyRigidBody(RigidBody* rigidBody) { - RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::Body, - "Rigid Body " + std::to_string(rigidBody->getId()) + ": rigid body destroyed"); + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(rigidBody->getId()) + ": rigid body destroyed"); // Remove all the collision shapes of the body rigidBody->removeAllCollisionShapes(); @@ -549,7 +551,7 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { // Add the joint into the joint list of the bodies involved in the joint addJointToBody(newJoint); - RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::Joint, + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Joint, "Joint " + std::to_string(newJoint->getId()) + ": New joint created"); // Return the pointer to the created joint @@ -564,7 +566,7 @@ void DynamicsWorld::destroyJoint(Joint* joint) { assert(joint != nullptr); - RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::Joint, + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Joint, "Joint " + std::to_string(joint->getId()) + ": joint destroyed"); // If the collision between the two bodies of the constraint was disabled @@ -863,7 +865,7 @@ void DynamicsWorld::enableSleeping(bool isSleepingEnabled) { } } - RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World, "Dynamics World: isSleepingEnabled=" + (isSleepingEnabled ? std::string("true") : std::string("false")) ); } diff --git a/src/engine/DynamicsWorld.h b/src/engine/DynamicsWorld.h index f435f4b9..53ef8d9e 100644 --- a/src/engine/DynamicsWorld.h +++ b/src/engine/DynamicsWorld.h @@ -283,7 +283,7 @@ inline uint DynamicsWorld::getNbIterationsVelocitySolver() const { inline void DynamicsWorld::setNbIterationsVelocitySolver(uint nbIterations) { mNbVelocitySolverIterations = nbIterations; - RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World, "Dynamics World: Set nb iterations velocity solver to " + std::to_string(nbIterations)); } @@ -299,7 +299,7 @@ inline uint DynamicsWorld::getNbIterationsPositionSolver() const { inline void DynamicsWorld::setNbIterationsPositionSolver(uint nbIterations) { mNbPositionSolverIterations = nbIterations; - RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World, "Dynamics World: Set nb iterations position solver to " + std::to_string(nbIterations)); } @@ -346,7 +346,7 @@ inline Vector3 DynamicsWorld::getGravity() const { inline void DynamicsWorld::setGravity(Vector3& gravity) { mGravity = gravity; - RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World, "Dynamics World: Set gravity vector to " + gravity.to_string()); } @@ -366,7 +366,7 @@ inline bool DynamicsWorld::isGravityEnabled() const { inline void DynamicsWorld::setIsGratityEnabled(bool isGravityEnabled) { mIsGravityEnabled = isGravityEnabled; - RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World, "Dynamics World: isGravityEnabled= " + (isGravityEnabled ? std::string("true") : std::string("false"))); } @@ -413,7 +413,7 @@ inline void DynamicsWorld::setSleepLinearVelocity(decimal sleepLinearVelocity) { assert(sleepLinearVelocity >= decimal(0.0)); mSleepLinearVelocity = sleepLinearVelocity; - RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World, "Dynamics World: sleepLinearVelocity= " + std::to_string(sleepLinearVelocity)); } @@ -436,7 +436,7 @@ inline void DynamicsWorld::setSleepAngularVelocity(decimal sleepAngularVelocity) assert(sleepAngularVelocity >= decimal(0.0)); mSleepAngularVelocity = sleepAngularVelocity; - RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World, "Dynamics World: sleepAngularVelocity= " + std::to_string(sleepAngularVelocity)); } @@ -457,7 +457,7 @@ inline void DynamicsWorld::setTimeBeforeSleep(decimal timeBeforeSleep) { assert(timeBeforeSleep >= decimal(0.0)); mTimeBeforeSleep = timeBeforeSleep; - RP3D_LOG(mLogger, Logger::Level::Info, Logger::Category::World, + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::World, "Dynamics World: timeBeforeSleep= " + std::to_string(timeBeforeSleep)); } diff --git a/src/engine/Material.h b/src/engine/Material.h index d55724a1..ffe6b1e9 100644 --- a/src/engine/Material.h +++ b/src/engine/Material.h @@ -84,6 +84,9 @@ class Material { /// Set the rolling resistance factor void setRollingResistance(decimal rollingResistance); + /// Return a string representation for the material + std::string to_string() const; + /// Overloaded assignment operator Material& operator=(const Material& material); }; @@ -147,6 +150,18 @@ inline void Material::setRollingResistance(decimal rollingResistance) { mRollingResistance = rollingResistance; } +// Return a string representation for the material +inline std::string Material::to_string() const { + + std::stringstream ss; + + ss << "frictionCoefficient=" << mFrictionCoefficient << std::endl; + ss << "rollingResistance=" << mRollingResistance << std::endl; + ss << "bounciness=" << mBounciness << std::endl; + + return ss.str(); +} + // Overloaded assignment operator inline Material& Material::operator=(const Material& material) { diff --git a/src/engine/OverlappingPair.h b/src/engine/OverlappingPair.h index 3fa083a1..a16ea84e 100644 --- a/src/engine/OverlappingPair.h +++ b/src/engine/OverlappingPair.h @@ -248,12 +248,12 @@ inline void OverlappingPair::makeContactsObsolete() { // Return the pair of bodies index inline OverlappingPair::OverlappingPairId OverlappingPair::computeID(ProxyShape* shape1, ProxyShape* shape2) { - assert(shape1->mBroadPhaseID >= 0 && shape2->mBroadPhaseID >= 0); + assert(shape1->getBroadPhaseId() >= 0 && shape2->getBroadPhaseId() >= 0); // Construct the pair of body index - OverlappingPairId pairID = shape1->mBroadPhaseID < shape2->mBroadPhaseID ? - OverlappingPairId(shape1->mBroadPhaseID, shape2->mBroadPhaseID) : - OverlappingPairId(shape2->mBroadPhaseID, shape1->mBroadPhaseID); + OverlappingPairId pairID = shape1->getBroadPhaseId() < shape2->getBroadPhaseId() ? + OverlappingPairId(shape1->getBroadPhaseId(), shape2->getBroadPhaseId()) : + OverlappingPairId(shape2->getBroadPhaseId(), shape1->getBroadPhaseId()); assert(pairID.first != pairID.second); return pairID; } diff --git a/src/utils/Logger.h b/src/utils/Logger.h index 908da806..8ce51fb3 100644 --- a/src/utils/Logger.h +++ b/src/utils/Logger.h @@ -49,10 +49,10 @@ class Logger { public: /// Log verbosity levels - enum class Level {Error = 1, Warning = 2, Info = 4}; + enum class Level {Error = 1, Warning = 2, Information = 4}; /// Log categories - enum class Category {World, Body, Joint}; + enum class Category {World, Body, Joint, ProxyShape}; /// Log verbosity level enum class Format {Text, HTML}; @@ -64,6 +64,7 @@ class Logger { case Category::World: return "World"; case Category::Body: return "Body"; case Category::Joint: return "Joint"; + case Category::ProxyShape: return "ProxyShape"; } } @@ -71,7 +72,7 @@ class Logger { static std::string getLevelName(Level level) { switch(level) { - case Level::Info: return "Information"; + case Level::Information: return "Information"; case Level::Warning: return "Warning"; case Level::Error: return "Error"; } @@ -120,6 +121,22 @@ class Logger { } + /// Return the header to write at the beginning of the stream + virtual std::string getHeader() const override { + + // Get current date + auto now = std::chrono::system_clock::now(); + auto time = std::chrono::system_clock::to_time_t(now); + + std::stringstream ss; + ss << "ReactPhysics3D Logs" << std::endl; + ss << "ReactPhysics3D Version: " << RP3D_VERSION << std::endl; + ss << "Date: " << std::put_time(std::localtime(&time), "%Y-%m-%d") << std::endl; + ss << "---------------------------------------------------------" << std::endl; + + return ss.str(); + } + /// Format a log message virtual std::string format(const time_t& time, const std::string& message, Level level, Category category) override { @@ -134,8 +151,11 @@ class Logger { /// Return the header to write at the beginning of the stream virtual std::string getHeader() const override { - std::stringstream ss; + // Get current date + auto now = std::chrono::system_clock::now(); + auto time = std::chrono::system_clock::to_time_t(now); + std::stringstream ss; ss << "" << std::endl; ss << "" << std::endl; ss << "" << std::endl; @@ -143,6 +163,12 @@ class Logger { ss << "" << std::endl; ss << "" << std::endl; ss << "" << std::endl; + ss << "

ReactPhysics3D Logs

" << std::endl; + ss << "
" << std::endl; + ss << "

ReactPhysics3D version: " << RP3D_VERSION << "

" << std::endl; + ss << "

Date: " << std::put_time(std::localtime(&time), "%Y-%m-%d") << "

" << std::endl; + ss << "
" << std::endl; + ss << "
"; return ss.str(); } @@ -161,26 +187,33 @@ class Logger { std::string generateCSS() const { return "body {" " background-color: #f7f7f9;" + " font-family: SFMono-Regular,Menlo,Monaco,Consolas,'Liberation Mono','Courier New',monospace; " "} " "body > div { clear:both; } " "body > div > div { float: left; } " + "h1 {" + " margin: 5px 5px 5px 5px;" + "} " + ".general_info > p {" + "margin: 5px;" + "font-weight: bold;" + "} " ".line { " - "font-family: SFMono-Regular,Menlo,Monaco,Consolas,'Liberation Mono','Courier New',monospace; " "font-size: 13px; " "color: #212529; " "margin: 0px 5px 2px 5px; " "} " ".time { " - "margin-right: 10px; " - "width:100px; " + "margin-right: 20px; " + "width:80px; " "} " ".level { " - "margin-right: 10px; " - "width: 110px; " + "margin-right: 20px; " + "width: 90px; " "}" ".category { " - "margin-right: 10px; " - "width: 120px; " + "margin-right: 20px; " + "width: 100px; " "font-weight: bold; " "}" ".message { " @@ -188,20 +221,23 @@ class Logger { "word-wrap: break-word; " "max-width: 800px; " "} " - ".body > .category { " - "color: #007bff; " + ".body > .category, .body > .message { " + "color: #8bc34a;" "} " - ".world > .category { " + ".world > .category, .world > .message { " "color: #4f9fcf; " "} " - ".joint > .category { " - "color: #6c757d; " + ".joint .category, .joint > .message { " + "color: #aa00ff; " + "} " + ".proxyshape .category, .proxyshape > .message { " + "color: #009933; " "} " ".warning { " - "color: #f0ad4e; " + "color: #ff9900 !important; " "} " ".error { " - "color: #d44950; " + "color: red !important; " "} "; } @@ -248,7 +284,8 @@ class Logger { ss << ""; // Message - ss << "
"; + ss << "
" << std::endl; ss << message; ss << "
"; From 2567d25afd972629467dc420b2ed87c55268777c Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 19 Mar 2018 23:07:09 +0100 Subject: [PATCH 183/248] Update user manual --- .../UserManual/ReactPhysics3D-UserManual.tex | 277 +++++++++++------- documentation/UserManual/title.tex | 2 +- 2 files changed, 173 insertions(+), 106 deletions(-) diff --git a/documentation/UserManual/ReactPhysics3D-UserManual.tex b/documentation/UserManual/ReactPhysics3D-UserManual.tex index 3da05ce1..b5e46c49 100644 --- a/documentation/UserManual/ReactPhysics3D-UserManual.tex +++ b/documentation/UserManual/ReactPhysics3D-UserManual.tex @@ -9,9 +9,19 @@ \usepackage{graphicx} \usepackage{listings} \usepackage{url} +\usepackage{hyperref} \usepackage[usenames]{xcolor} +\hypersetup{ + colorlinks, + linkcolor={blue!70!black}, + citecolor={blue!200!black}, + urlcolor={blue!80!black} +} \usepackage[top=3cm, bottom=3cm, left=3cm, right=3cm]{geometry} +\usepackage[scaled]{helvet} +\renewcommand\familydefault{\sfdefault} + % Path to the pictures \graphicspath{ {images/} } @@ -20,11 +30,11 @@ backgroundcolor=\color{gray!15}, belowcaptionskip=1\baselineskip, breaklines=true, - frame=L, + frame=single, xleftmargin=\parindent, language=C++, showstringspaces=false, - basicstyle=\footnotesize\ttfamily, + basicstyle=\ttfamily\footnotesize, keywordstyle=\bfseries\color{green!40!black}, commentstyle=\itshape\color{purple!40!black}, identifierstyle=\color{blue}, @@ -67,7 +77,7 @@ \item Sleeping technique for inactive bodies \item Multi-platform (Windows, Linux, Mac OS X) \item No external libraries (do not use STL containers) - \item Documentation (User manual and Doxygen API) + \item Documentation (user manual and Doxygen API) \item Testbed application with demos \item Integrated Profiler \item Logs @@ -89,9 +99,9 @@ If you have never used cmake before, you should read the page \url{http://www.cmake.org/cmake/help/runningcmake.html} as it contains a lot of useful information. \\ - It is also possible to compile the testbed application using CMake. The testbed application contains different - demo scenes using the ReactPhysics3D library. -xs + It is also possible to compile the testbed application using CMake. This application contains different + physics demo scenes. + \subsection{CMake using the command line (Linux and Mac OS X)} Now, we will see how to build the ReactPhysics3D library using the CMake tool with the command line. @@ -108,13 +118,15 @@ xs and then, hit the 'c' key again. Once you have set all the values as you like, you can hit the 'g' key to generate the makefiles in the build directory that you have created before and exit. \\ - Now that you have generated the makefiles with the CMake software, you can compile the code to build the static library in the + Now that you have generated the makefiles, you can compile the code to build the static library in the \texttt{/lib} folder with the following command in your build directory: \\ \end{sloppypar} \texttt{make} + TODO : Add "make install" information here + \subsection{CMake using the graphical interface (Linux, Mac OS X and Windows)} You can also use the graphical user interface of CMake. To do this, @@ -125,7 +137,7 @@ xs is on your system. Then, you can click on \texttt{Configure}. CMake will ask you to choose an IDE that is on your system. For instance, you can select Visual Studio, Qt Creator, XCode, ... Then, you can change the compilation options. See section \ref{sec:cmakevariables} to see what are the possible options. - Once this is done, you can click on \texttt{Configure} again and finally on \texttt{Generate}. \\ + Once this is done, click on \texttt{Configure} again and finally on \texttt{Generate}. \\ Now, if you go into the folder you have chosen to build the library, you should be able to open the project file that corresponds to your IDE and compile @@ -151,12 +163,15 @@ xs \item[COMPILE\_TESTS] If this variable is \texttt{ON}, the unit tests of the library will be compiled. You will then be able to launch the tests to make sure that they are running fine on your system. + TODO : Edit the profiling info bellow \item[PROFILING\_ENABLED] If this variable is \texttt{ON}, the integrated profiler will collect data while the application is running and the profiling report will be displayed in the console at the end of the application (in the destructor of the \texttt{DynamicsWorld} class). This might be useful to see what part of the reactphysics3d library takes time during its execution. This variable must be set to \texttt{OFF} when you compile the final release of your application. + TODO : Add info to enable logs here + \item[DOUBLE\_PRECISION\_ENABLED] If this variable is \texttt{ON}, the library will be compiled with double floating point precision. Otherwise, the library will be compiled with single precision. \end{description} @@ -164,8 +179,10 @@ xs \section{Using ReactPhysics3D in your application} - In order to use the library in your own application, first build - the static library of ReactPhysics3d as described above to get the + TODO : Update this section with "make install" way + + In order to use ReactPhysics3D in your own application, first build + the static library as described above to get the static library file in the \texttt{lib/} folder. Then, in your code, you have to include the ReactPhysics3D header file with the line: \\ @@ -237,26 +254,39 @@ RigidBody* body = dynamicsWorld.createRigidBody(transform); destroy the rigid body. The library is responsible to do it. \\ \section{The Collision World} + \label{sec:collisionworld} There are two main ways to use ReactPhysics3D. The first one is to create bodies that you have to manually move so that you can test collision between them. To do this, - you need to create a Collision World with several Collision Bodies in it. The second way is to create bodies and let ReactPhysics3D simulate their motions automatically using the - physics. This is done by creating Rigid Bodies in a Dynamics World instead. In summary, a Collision World is used to simply test collision between bodies that you have to manually move - and a Dynamics World is used to create bodies that will be automatically moved using collisions, joints and forces. \\ + you need to create a collision world with several collision bodies in it. The second way is to create bodies and let ReactPhysics3D simulate their motions automatically using the + physics. This is done by creating rigid bodies in a dynamics world instead. In summary, a collision world is used to simply test collision between bodies that you have to manually move + and a dynamics world is used to create bodies that will be automatically moved using collisions, joints and forces. \\ - The \texttt{CollisionWorld} class represents a Collision World in the ReactPhysics3D library. + The \texttt{CollisionWorld} class represents a collision world in the ReactPhysics3D library. \subsection{Creating the Collision World} If you only have to test collision between bodies, the first thing to do is to create an instance of the \texttt{CollisionWorld} class. \\ - Here is how to create a Collision World: \\ + Here is how to create a collision world: \\ \begin{lstlisting} - // Create the collision world rp3d::CollisionWorld world; \end{lstlisting} + \subsubsection{World settings} + + When you create a world as in the previous example, it will have default settings. If you want to customize some settings, you need to create + a \texttt{WorldSettings} object and give it in paramater when you create your world as in the following example: \\ + + \begin{lstlisting} + TODO: ADD CODE HERE + \end{lstlisting} + + \vspace{0.6cm} + + Take a look at the API documentation to see which world settings you can change. + \subsection{Destroying the Collision World} Do not forget to destroy the \texttt{CollisionWorld} instance at the end of your program in order to release the allocated memory. If the object has been created @@ -268,41 +298,44 @@ rp3d::CollisionWorld world; \subsection{Queries on the Collision World} - Once your collision world has been created, you can add collision bodies and move them around manually. Now there are some queries that you can use on the - collision world. Here are the main methods that you can use: \\ - - TODO : FINISH THIS SECTION + Once your collision world has been created, you can add collision bodies and move them around manually. Now there are some queries that you can perform on the + collision world. Here are the main methods that you can use: \begin{description} - \item[testOverlap()] ??? - \item[testPointInside()] ??? - \item[testCollision()] ??? - \item[testAABBOverlap()] Pointer to the Collision Body or Rigid Body that has been hit by the ray + \item[testOverlap()] Those methods can be used to test whether the collision shapes of two bodies overlap or not. You can use this if you just want to + know if bodies are colliding but your are not interested in the contact information. This method can be called on a \texttt{CollisionWorld}. + \item[testCollision()] Those methods will give you the collision information (contact points, normals, ...) for colliding bodies. + This method can be called on a \texttt{CollisionWorld}. + \item[testAABBOverlap()] Those methods will test whether AABBs of bodies overlap. This is faster than \texttt{testOverlap()} but less precise because it only + use the AABBs and not the actual collision shapes of the bodies. This method can be called on a \texttt{CollisionWorld}. + \item[testPointInside()] This method will tell if you if a 3D point is inside a given \texttt{CollisionBody} or \texttt{ProxyShape}. \end{description} + Take a look at the API documentation for more information about those methods. + \section{Collision Bodies} - Once the Collision World has been created, you can create Collision Bodies into the world. A Collision Body represents an object in the Collision World. - It has a position, an orientation and one or more collision shapes. It has to be moved manually in the Collision World. You can then - test collisions between the Collision Bodies of the world. In ReactPhysics3D, the \texttt{CollisionBody} class is used to describe a Collision Body. \\ + Once the collision world has been created, you can create collision bodies into the world. A collision body represents an object in the collision world. + It has a position, an orientation and one or more collision shapes. It has to be moved manually in the collision world. You can then + test collisions between the collision bodies of the world. In ReactPhysics3D, the \texttt{CollisionBody} class is used to describe a collision body. \\ - If you do not want to simply test collision between your bodies but want them to move automatically according to the physics, you should use Rigid Bodies in a - Dynamics World instead. See section \ref{sec:dynamicsworld} for more information about the Dynamics World and section \ref{sec:rigidbody} if you would like to know more - about the Rigid Bodies. + If you do not want to simply test collision between your bodies but want them to move automatically according to the physics, you should use rigid bodies in a + dynamics world instead. See section \ref{sec:dynamicsworld} for more information about the dynamics world and section \ref{sec:rigidbody} if you would like to know more + about the rigid bodies. \subsection{Creating a Collision Body} - In order to create a Collision Body, you need to specify its transform. The transform describes the initial + In order to create a collision body, you need to specify its transform. The transform describes the initial position and orientation of the body in the world. You need to create an instance of the \texttt{Transform} class with a vector describing the initial position and a quaternion for the initial orientation of the body. \\ In order to test collision between your body and other bodies in the world, you need to add one or several collision shapes to your body. Take a look at section \ref{sec:collisionshapes} to learn about the different collision shapes and how to create them. \\ - You need to call the \texttt{CollisionWorld::createCollisionBody()} method to create a Collision Body in the world previously created. This method will return a pointer to the instance + You need to call the \texttt{CollisionWorld::createCollisionBody()} method to create a collision body in the world previously created. This method will return a pointer to the instance of the \texttt{CollisionBody} class that has been created internally. You will then be able to use that pointer to get or set values of the body. \\ - You can see in the following code how to create a Collision Body in the world. \\ + You can see in the following code how to create a collision body in the world. \\ \begin{lstlisting} @@ -318,8 +351,8 @@ body = world.createCollisionBody(transform); \subsection{Moving a Collision Body} - A Collision Body has to be moved manually in the world. To do that, you need to use the \texttt{CollisionBody::setTransform()} method to set a new position and new - orientation to the body. + A collision body has to be moved manually in the world. To do that, you need to use the \texttt{CollisionBody::setTransform()} method to set a new position and new + orientation to the body. \\ \begin{lstlisting} @@ -335,11 +368,11 @@ body->setTransform(newTransform); \subsection{Destroying a Collision Body} \begin{sloppypar} - In order to destroy a Collision Body from the world, you need to use the \texttt{CollisionWorld::destroyCollisionBody()} method. You need to use the pointer to the body you + In order to destroy a collision body from the world, you need to use the \texttt{CollisionWorld::destroyCollisionBody()} method. You need to use the pointer to the body you want to destroy in argument. Note that after calling that method, the pointer will not be valid anymore and therefore, you should not use it. \\ \end{sloppypar} - Here is how to destroy a Collision Body: \\ + Here is how to destroy a collision body: \\ \begin{lstlisting} // Here, world is an instance of the CollisionWorld class @@ -352,10 +385,10 @@ world.destroyCollisionBody(body); \section{The Dynamics World} \label{sec:dynamicsworld} - The Collision World of the previous section is used to manually move the bodies and check for collision between them. On the other side, the Dynamics World + The collision world of the previous section is used to manually move the bodies and check for collision between them. On the other side, a dynamics world is used to automatically simulate the motion of your bodies using the physics. You do not have to move the bodies manually (but you still can if needed). - The Dynamics World will contain the bodies and joints that you create. You will then be able to run your simulation across time by updating the world at each frame. - The \texttt{DynamicsWorld} class (which inherits from the \texttt{CollisionWorld} class) represents a Dynamics World in the ReactPhysics3D library. + The dynamics world will contain the bodies and joints that you create. You will then be able to run your simulation across time by updating the world at each frame. + The \texttt{DynamicsWorld} class (which inherits from the \texttt{CollisionWorld} class) represents a dynamics world in the ReactPhysics3D library. \subsection{Creating the Dynamics World} @@ -363,7 +396,9 @@ world.destroyCollisionBody(body); of the \texttt{DynamicsWorld}. You need to specify the gravity acceleration vector (in $m / s^2$) in the world as parameter. Note that gravity is activated by default when you create the world. \\ - Here is how to create the Dynamics World: \\ + Here is how to create the dynamics world: \\ + + TODO : Update this example with new constructor for CollisionWorld \begin{lstlisting} // Gravity vector @@ -377,7 +412,7 @@ rp3d::DynamicsWorld world(gravity); \subsubsection{Solver parameters} - ReactPhysics3D uses an iterative solver to compute the contacts and joints. For contacts, there is a unique velocity solver and for joints there are a velocity and a + ReactPhysics3D uses an iterative solver to simulate the contacts and joints. For contacts, there is a unique velocity solver and for joints there is a velocity and a position solver. By default, the number of iterations of the velocity solver is 10 and the number of iterations for the position solver is 5. It is possible to change the number of iterations for both solvers. \\ @@ -416,8 +451,7 @@ world.enableSleeping(false); \begin{sloppypar} A body is put to sleep when its linear and angular velocity stay under a given velocity threshold for a certain amount of time (one second by default). It is possible to - change the two - linear and angular velocity thresholds using the two methods \texttt{DynamicsWorld::setSleepLinearVelocity()} and \texttt{DynamicsWorld::setSleepAngularVelocity()}. + change the linear and angular velocity thresholds using the two methods \texttt{DynamicsWorld::setSleepLinearVelocity()} and \texttt{DynamicsWorld::setSleepAngularVelocity()}. Note that the velocities must be specified in meters per second. You can also change the amount of time (in seconds) the velocity of a body needs to stay under the threshold to be considered sleeping. To do this, use the @@ -481,7 +515,7 @@ while (accumulator >= timeStep) { \vspace{0.6cm} - A nice article to read about this time interpolation is the one from Glenn Fiedler at \url{https://gafferongames.com/post/fix_your_timestep/}. + A nice article to read about this is the one from Glenn Fiedler at \url{https://gafferongames.com/post/fix_your_timestep/}. \subsection{Destroying the Dynamics World} @@ -495,21 +529,21 @@ while (accumulator >= timeStep) { \section{Rigid Bodies} \label{sec:rigidbody} - Once the Dynamics World has been created, you can create rigid bodies into the world. A Rigid Body represents an object that you want to simulate in the world. - It has a mass, a position, an orientation and one or several collision shapes. The Dynamics World will compute collisions between the bodies and will update their position + Once the dynamics world has been created, you can create rigid bodies into the world. A rigid body represents an object that you want to simulate in the world. + It has a mass, a position, an orientation and one or several collision shapes. The dynamics world will compute collisions between the bodies and will update its position and orientation accordingly at each time step. You can also create joints between the bodies in the world. In ReactPhysics3D, the \texttt{RigidBody} class - (which inherits from the \texttt{CollisionBody} class) is used to describe a Rigid Body. + (which inherits from the \texttt{CollisionBody} class) is used to describe a rigid body. \subsection{Creating a Rigid Body} - In order to create a Rigid Body, you need to specify its transform. The transform describes the initial + In order to create a rigid body, you need to specify its transform. The transform describes the initial position and orientation of the body in the world. You need to create an instance of the \texttt{Transform} class with a vector describing the initial position and a quaternion for the initial orientation of the body. \\ - You need to call the \texttt{DynamicsWorld::createRigidBody()} method to create a Rigid Body in the world previously created. This method will return a pointer to the + You have to call the \texttt{DynamicsWorld::createRigidBody()} method to create a rigid body in the world previously created. This method will return a pointer to the instance of the \texttt{RigidBody} object that has been created internally. You will then be able to use that pointer to get or set values of the body. \\ - You can see in the following code how to create a Rigid Body in your world: \\ + You can see in the following code how to create a rigid body in your world: \\ \begin{lstlisting} // Initial position and orientation of the rigid body @@ -524,12 +558,12 @@ body = dynamicsWorld.createRigidBody(transform); \vspace{0.6cm} - Once your Rigid Body has been created in the world, you need to add one or several collision shapes to it. Take a look at section \ref{sec:collisionshapes} to learn + Once your rigid body has been created in the world, you need to add one or several collision shapes to it. Take a look at section \ref{sec:collisionshapes} to learn about the different collision shapes and how to create them. \\ \subsection{Customizing a Rigid Body} - Once a Rigid Body has been created, you can change some of its properties. + Once a rigid body has been created, you can change some of its properties. \subsubsection{Type of a Rigid Body (static, kinematic or dynamic)} @@ -552,7 +586,7 @@ body->setType(KINEMATIC); \subsubsection{Gravity} By default, all the rigid bodies with react to the gravity force of the world. If you do not want the gravity to be applied to a given body, you can disable - it using the \texttt{RigidBody::enableGravity()} method as in the following example : \\ + it using the \texttt{RigidBody::enableGravity()} method as in the following example: \\ \begin{lstlisting} // Disable gravity for this body @@ -561,7 +595,7 @@ rigidBody->enableGravity(false); \subsubsection{Material of a Rigid Body} - The material of a rigid body is used to describe the physical properties it is made of. The \texttt{Material} class represents the material of a body. Each body that + The material of a rigid body is used to describe the physical properties it is made of. This is represented by the \texttt{Material} class. Each body that you create will have a default material. You can get the material of the rigid body using the \texttt{RigidBody::getMaterial()} method. Then, you will be able to change some properties. \\ @@ -573,11 +607,11 @@ rigidBody->enableGravity(false); \texttt{Material::setFrictionCoefficient()} method. \\ You can use the material to add rolling resistance to a rigid body. Rolling resistance can be used to stop - a rolling object on a flat surface for instance. You should use this only with SphereShape, - CapsuleShape, CylinderShape or ConeShape collision shapes. By default, rolling resistance is zero but you can + a rolling object on a flat surface for instance. You should use this only with SphereShape or + CapsuleShape collision shapes. By default, rolling resistance is zero but you can set a positive value using the \texttt{Material::setRollingResistance()} method to increase resistance. \\ - Here is how to get the material of a rigid body and how to modify some of its properties : \\ + Here is how to get the material of a rigid body and how to modify some of its properties: \\ \begin{lstlisting} // Get the current material of the body @@ -603,7 +637,7 @@ material.setFrictionCoefficient(rp3d::decimal(0.2)); \label{sec:rigidbodysleeping} As described in section \ref{sec:sleeping}, the sleeping technique is used to disable the simulation of resting bodies. By default, the bodies are allowed to sleep - when they come to rest. However, if you do not want a given body to be put to sleep, you can use the \texttt{Body::setIsAllowedToSleep()} method as in the next example : \\ + when they come to rest. However, if you do not want a given body to be put to sleep, you can use the \texttt{Body::setIsAllowedToSleep()} method as in the next example: \\ \begin{lstlisting} // This rigid body cannot sleep @@ -612,7 +646,7 @@ rigidBody->setIsAllowedToSleep(false); \subsubsection{Applying Force or Torque to a Rigid Body} - During the simulation, you can apply a force or a torque to a given rigid body. First, you can apply a force to the center of mass of the rigid body using the + During the simulation, you can apply a force or a torque to a given rigid body. This force can be applied to the center of mass of the rigid body by using the \texttt{RigidBody::applyForceToCenter()} method. You need to specify the force vector (in Newton) as a parameter. If the force is applied to the center of mass, no torque will be created and only the linear motion of the body will be affected. \\ @@ -673,7 +707,7 @@ rigidBody->applyTorque(torque); As described in section \ref{sec:updatingdynamicsworld}, at the end of a frame, there might still be some remaining time in the time accumulator. Therefore, you should not use the updated transform directly for rendering but you need to perform some interpolation between the updated transform and the one from the previous frame to get a smooth real-time simulation. - First, you need to compute the interpolation factor as folows : \\ + First, you need to compute the interpolation factor as folows: \\ \begin{lstlisting} // Compute the time interpolation factor @@ -774,11 +808,11 @@ world.destroyRigidBody(body); \section{Collision Shapes} \label{sec:collisionshapes} - Once you have created a Collision Body or a Rigid Body in the world, you need to add one or more collision shapes into it so that it is able to collide with other bodies. + Once you have created a collision body or a rigid body in the world, you need to add one or more collision shapes into it so that it is able to collide with other bodies. This section describes all the collision shapes available in the ReactPhysics3D library and how to use them. \\ - The Collision Shapes are also the way to represent the mass of a Rigid Body. Whenever you add a collision shape to a Rigid Body, you need to specify the mass of the shape. - Then the Rigid Body will recompute its total mass, its center of mass and its inertia tensor taking into account all its collision shapes. Therefore, you do not have to compute + The collision shapes are also the way to represent the mass of a Rigid Body. Whenever you add a collision shape to a rigid body, you need to specify the mass of the shape. + Then the rigid body will recompute its total mass, its center of mass and its inertia tensor taking into account all its collision shapes. Therefore, you do not have to compute those things by yourself. However, if needed, you can also specify your own center of mass or inertia tensor. Note that the inertia tensor is a $3 \times 3$ matrix describing how the mass is distributed inside the rigid body which will be used to calculate its rotation. The inertia tensor depends on the mass and the shape of the body. \\ @@ -790,7 +824,7 @@ world.destroyRigidBody(body); \label{fig:boxshape} \end{figure} - The \texttt{BoxShape} class describes a box collision. The box is aligned with the shape local X, Y and Z axis. + The \texttt{BoxShape} class describes a box collision shape. The box is aligned with the shape local X, Y and Z axis. In order to create a box shape, you only need to specify the three half extents dimensions of the box in the three X, Y and Z directions. \\ For instance, if you want to create a box shape with dimensions of 4 meters, 6 meters and 10 meters along the X, Y and Z axis respectively, you need to use the @@ -833,7 +867,7 @@ const rp3d::SphereShape sphereShape(2.0); \label{fig:capsuleshape} \end{figure} - The \texttt{CapsuleShape} class describes a capsule collision shape around the Y axis and centered at the origin of the shape local-space. It is the convex hull of two + The \texttt{CapsuleShape} class describes a capsule collision shape around the local Y axis and centered at the origin of the shape local-space. It is the convex hull of two spheres. It can also be seen as an elongated sphere. In order to create it, you only need to specify the radius of the two spheres and the height of the capsule (distance between the centers of the two spheres). \\ @@ -916,7 +950,7 @@ convexMeshShape = new rp3d::ConvexMeshShape(polyhedronMesh); the all the \texttt{PolygonFace}, the \texttt{PolygonVertexArray} and the \texttt{PolyhedronMesh}. \\ You need to make sure that the mesh you provide is indeed convex. Secondly, you should provide the simplest possible convex mesh. It means that you need to avoid - coplanar faces in your convex mesh shape. Coplanar faces need to merge together. Remember that convex meshes are not limited to triangular faces, you can + coplanar faces in your convex mesh shape. Coplanar faces have to be merged together. Remember that convex meshes are not limited to triangular faces, you can create faces with more than three vertices. \\ When you specify the vertices for each face of your convex mesh, be careful with their order. The vertices of a face must be specified in counter clockwise order @@ -939,7 +973,7 @@ convexMeshShape = new rp3d::ConvexMeshShape(polyhedronMesh); In order to create a concave mesh shape, you need to supply a pointer to a \texttt{TriangleMesh}. A \texttt{TriangleMesh} class describes a mesh made of triangles. It may contain several parts (submeshes). Each part is a set of - triangles represented by a \texttt{TriangleVertexArray} object. First, you need to create a \texttt{TriangleVertexArray}. A \texttt{TriangleVertexArray} represents + triangles represented by a \texttt{TriangleVertexArray} object. A \texttt{TriangleVertexArray} represents a continuous array of vertices and indexes for a triangular mesh. When you create a \texttt{TriangleVertexArray}, no data is copied into the array. It only stores a pointer to the data. The idea is to allow the user to share vertices data between the physics engine and the rendering part. Therefore, make sure that the data pointed by a \texttt{TriangleVertexArray} remains valid during the whole \texttt{TriangleVertexArray} life. @@ -999,7 +1033,7 @@ ConcaveMeshShape* concaveMesh = new rp3d::ConcaveMeshShape(&triangleMesh); In order to create a \texttt{HeightFieldShape}, you need to have an array with all the height values of your field. You can have height values of type int, float or double. You need to give the number of rows and columns of your two dimensional grid. Note that the height values in your array must be organized such that the value at row - \texttt{indexRow} and column \texttt{indexColumn} is located at the following position in the array: + \texttt{indexRow} and column \texttt{indexColumn} is located at the following position in the array: \\ \begin{lstlisting} heighFieldValues[indexRow * nbColumns + indexColumn] @@ -1027,8 +1061,8 @@ maxHeight, heightValues, rp3d::HeightFieldShape::HEIGHT_FLOAT_TYPE); \vspace{0.6cm} - Note that the array of height values is not copied into the \texttt{HeightFieldShape}. Therefore, you need to make sure - it exists during the lifetime of the \texttt{HeightFieldShape} and you must not forget to release its memory when you + Note that the array of height values are not copied into the \texttt{HeightFieldShape}. Therefore, you need to make sure + they exist during the lifetime of the \texttt{HeightFieldShape} and you must not forget to release their memory when you destroy the collision shape or at the end of your application. \\ When creating a \texttt{HeightFieldShape}, the origin of the shape will be at the center of its bounding volume. @@ -1045,14 +1079,14 @@ maxHeight, heightValues, rp3d::HeightFieldShape::HEIGHT_FLOAT_TYPE); create a collision shape and reuse it for multiple bodies. You are also responsible to destroy the shape at the end when the bodies are not used anymore. \\ - In order to add a collision shape to a body, you need to use the \texttt{CollisionBody::addCollisionShape()} method for a Collision Body and the - \texttt{RigidBody::addCollisionShape()} method for a Rigid Body. You will have to provide the collision shape transform in parameter. This is the - transformation mapping the local-space of the collision shape to the local-space of the body. For a Rigid Body, you will also have to provide the + In order to add a collision shape to a body, you need to use the \texttt{CollisionBody::addCollisionShape()} method for a collision body and the + \texttt{RigidBody::addCollisionShape()} method for a rigid body. You will have to provide the collision shape transform in parameter. This is the + transformation mapping the local-space of the collision shape to the local-space of the body. For a rigid body, you will also have to provide the mass of the shape you want to add. As explained before, this is used to automatically compute the center of mass, total mass and inertia tensor of the body. \\ - The \texttt{addCollisionShape()} method returns a pointer to a Proxy Shape. A Proxy Shape is what links a given collision shape to the body it has been added. - You can use the returned Proxy Shape to get or set parameters of the given collision shape in that particular body. This concept is also called \emph{fixture} in some - other physics engines. In ReactPhysics3D, a Proxy Shape is represented by the \texttt{ProxyShape} class. \\ + The \texttt{addCollisionShape()} method returns a pointer to a proxy shape. A proxy shape is what links a given collision shape to the body it has been added. + You can use the returned proxy shape to get or set parameters of the given collision shape in that particular body. This concept is also called \emph{fixture} in some + other physics engines. In ReactPhysics3D, a proxy shape is represented by the \texttt{ProxyShape} class. \\ The following example shows how to add a sphere collision shape with a given mass to a rigid body and also how to remove it from the body using the Proxy Shape pointer. \\ \end{sloppypar} @@ -1080,8 +1114,8 @@ body->removeCollisionShape(proxyShape); \vspace{0.6cm} - As you can see, you can use the \texttt{removeCollisionShape()} method to remove a collision shape from a body by using the Proxy Shape. Note that - after removing a collision shape, the corresponding Proxy Shape pointer will not be valid anymore. It is not necessary to manually remove all the collision shapes from + As you can see, you can use the \texttt{removeCollisionShape()} method to remove a collision shape from a body by using the proxy shape. Note that + after removing a collision shape, the corresponding proxy shape pointer will not be valid anymore. It is not necessary to manually remove all the collision shapes from a body at the end of your application. They will automatically be removed when you destroy the body. \subsection{Collision filtering} @@ -1092,7 +1126,7 @@ body->removeCollisionShape(proxyShape); for each collision shape against which categories it will be able to collide. \\ ReactPhysics3D uses bits mask to represent categories. The first thing to do is to assign a category to the collision shapes of your body. To do this, you need to - call the \texttt{ProxyShape::setCollisionCategoryBits()} method on the corresponding Proxy Shape as in the following example. Here we consider that we have four bodies + call the \texttt{ProxyShape::setCollisionCategoryBits()} method on the corresponding proxy shape as in the following example. Here we consider that we have four bodies where each one has a single collision shape. \\ \begin{lstlisting} @@ -1119,7 +1153,7 @@ proxyShapeBody4->setCollisionCategoryBits(CATEGORY3); \begin{sloppypar} Now, for each collision shape, we need to specify with which categories the shape is allowed to collide with. To do this, you need to use the \texttt{ProxyShape::setCollideWithMaskBits()} - method of the Proxy Shape. Note that you can specify one or more categories using the bitwise OR operator. The following example shows how to specify with which categories the + method of the proxy shape. Note that you can specify one or more categories using the bitwise OR operator. The following example shows how to specify with which categories the shapes can collide. \\ \end{sloppypar} @@ -1147,7 +1181,7 @@ proxyShapeBody4->setCollideWithMaskBits(CATEGORY2); \section{Joints} - Joints are used to constraint the motion of the rigid bodies between each other. A single joint represents a constraint between two rigid bodies. + Joints are used to constrain the motion of the rigid bodies between each other. A single joint represents a constraint between two rigid bodies. When the motion of the first body of the joint is known, the relative motion of the second body has at most six degrees of freedom (three for the translation and three for the rotation). The different joints can reduce the number of degrees of freedom between two rigid bodies. \\ @@ -1427,7 +1461,7 @@ joint = dynamic_cast(world.createJoint(jointInfo)); \subsection{Collision between the bodies of a Joint} - By default the two bodies involved in a joint are able to collide with each other. However, it is possible to disable the collision between the two bodies that are part + By default, the two bodies involved in a joint are able to collide with each other. However, it is possible to disable the collision between the two bodies that are part of the joint. To do it, you simply need to set the variable \texttt{isCollisionEnabled} of the joint info object to \emph{false} when you create the joint. \\ For instance, when you create a \texttt{HingeJointInfo} object in order to construct a hinge joint, you can disable the collision between the two bodies of the joint as in the @@ -1492,8 +1526,8 @@ rp3d::Ray ray(startPoint, endPoint); \item[worldNormal] Surface normal of the proxy shape at the hit point in world-space coordinates \item[hitFraction] Fraction distance of the hit point between \emph{startPoint} and \emph{endPoint} of the ray. The hit point \emph{p} is such that $p = startPoint + hitFraction \cdot (endPoint - startPoint)$ - \item[body] Pointer to the Collision Body or Rigid Body that has been hit by the ray - \item[proxyShape] Pointer to the Proxy Shape that has been hit by the ray + \item[body] Pointer to the collision body or rigid body that has been hit by the ray + \item[proxyShape] Pointer to the proxy shape that has been hit by the ray \end{description} Note that you can also use collision filtering with ray casting in order to only test ray intersection with specific proxy shapes. @@ -1501,7 +1535,7 @@ rp3d::Ray ray(startPoint, endPoint); \subsection{Ray casting against multiple bodies} - This ray casting query will return all the proxy shapes of all bodies in the world that are intersected by a given ray. + This section describes how to get all the proxy shapes of all bodies in the world that are intersected by a given ray. \subsubsection{The RaycastCallback class} @@ -1543,7 +1577,7 @@ public: \subsubsection{Raycast query in the world} Now that you have your own raycast callback class, you can use the \texttt{raycast()} method to perform a ray casting test - on a Collision World or a Dynamics World. \\ + on a collision world or a dynamics world. \\ The first parameter of this method is a reference to the \texttt{Ray} object representing the ray you need to test intersection with. The second parameter is a pointer to the object of your raycast callback object. You can specify an optional third parameter which is the bit mask for collision filtering. @@ -1568,7 +1602,7 @@ world->raycast(ray, &callbackObject); \begin{sloppypar} - You can also perform ray casting against a single specific Collision Body or Rigid Body of the world. To do this, you need to use the + You can also perform ray casting against a single specific collision body or rigid body of the world. To do this, you need to use the \texttt{CollisionBody::raycast()} method. This method takes two parameters. The first one is a reference to the \texttt{Ray} object and the second one is a reference to the \texttt{RaycastInfo} object that will contain hit information if the ray hits the body. This method returns true if the ray hits the body. The \texttt{RaycastInfo} object will only be valid if the returned value is \emph{true} (a hit occured). \\ @@ -1595,12 +1629,12 @@ bool isHit = body->raycast(ray, raycastInfo); \subsection{Ray casting against the proxy shape of a body} - You can also perform ray casting against a single specific Proxy Shape of a Collision Body or Rigid Body of the world. To do this, you need to use the - \texttt{ProxyShape::raycast()} method of the given Proxy Shape. This method takes two parameters. The first one is a reference to the \texttt{Ray} + You can also perform ray casting against a single specific proxy shape of a collision body or rigid body of the world. To do this, you need to use the + \texttt{ProxyShape::raycast()} method of the given proxy shape. This method takes two parameters. The first one is a reference to the \texttt{Ray} object and the second one is a reference to the \texttt{RaycastInfo} object that will contain hit information if the ray hits the body. This method returns true if the ray hits the body. The \texttt{RaycastInfo} object will only be valid if the returned value is \emph{true} (a hit occured). \\ - The following example shows how to test ray intersection with a given Proxy Shape: \\ + The following example shows how to test ray intersection with a given proxy shape: \\ \begin{lstlisting} // Create the ray @@ -1621,6 +1655,8 @@ bool isHit = proxyShape->raycast(ray, raycastInfo); \section{Testbed application} \label{sec:testbed} + TODO : Update screenshot here + \begin{figure}[h] \centering \includegraphics{testbed.png} @@ -1651,17 +1687,17 @@ bool isHit = proxyShape->raycast(ray, raycastInfo); \subsection{Joints Scene} - In this scene, you will learn how to create different joints (Ball and Socket, Hinge, Slider, Fixed) into the dynamics world. You can also see how + In this scene, you will learn how to create different joints (ball and socket, hinge, slider, fixed) into the dynamics world. You can also see how to set the motor or limits of the joints. \subsection{Collision Shapes Scene} In this scene, you will see how to create a floor (using the Box Shape) and some other bodies using the different collision shapes available - in the ReactPhysics3D library like Cylinders, Capsules, Spheres, Convex Meshes and Cones. Those bodies will fall down to the floor. + in the ReactPhysics3D library like capsules, spheres, boxes and convex meshes. Those bodies will fall down to the floor. \subsection{Heightfield Scene} - In this scene, you will see how to use the Height field collision shape of the library. Several cubes will fall + In this scene, you will see how to use the Height field collision shape of the library. Several bodies will fall down to the height field. \subsection{Raycast Scene} @@ -1716,18 +1752,19 @@ for (; listElem != NULL; listElem = listElem->next) { \vspace{0.6cm} - Note that this technique to retrieve the contacts, if you use it between the \texttt{DynamicsWorld::update()} calls, will only give you the contacts are the end of + Note that this technique to retrieve the contacts, if you use it between the \texttt{DynamicsWorld::update()} calls, will only give you the contacts at the end of each frame. You will probably miss several contacts that have occured in the physics internal sub-steps. In section \ref{sec:receiving_feedback}, you will - see how to get all the contact occuring in the physis sub-steps of the engine. Also note that a contact manifold contains some persistent contact points that - have may have been there for several frames. + see how to get all the contact occuring in the physis sub-steps of the engine. \subsection{All the contacts of the world} If you want to retrieve all the contacts of any rigid body in the world, you can use the \texttt{DynamicsWorld::getContactsList()} method. This method will - a \texttt{std::vector} with the list of all the current contact manifolds of the world. A contact manifold may contain several contact points. \\ + a \texttt{List} with the all the current contact manifolds of the world. A contact manifold may contain several contact points. \\ The following example shows how to get all the contacts of the world using this method: \\ + TODO : Refactor return type of getContactsList() + \begin{lstlisting} std::vector manifolds; @@ -1762,10 +1799,8 @@ for (it = manifolds.begin(); it != manifolds.end(); ++it) { \section{Receiving Feedback} - TODO : UPDATE THIS SECTION - \label{sec:receiving_feedback} - Sometimes, you want to receive notifications from the physics engine when a given event happens. The \texttt{EventListener} class can be used for that purpose. In order to use + Sometimes, you want to receive notifications from the physics engine when a given event occurs. The \texttt{EventListener} class can be used for that purpose. In order to use it, you need to create a new class that inherits from the \texttt{EventListener} class and overrides some methods that will be called by the ReactPhysics3D library when some events occur. You also need to register your class in the physics world using the \texttt{DynamicsWorld::setEventListener()} as in the following code: \\ @@ -1788,22 +1823,54 @@ world.setEventListener(&listener); \section{Profiler} + TODO : Update this section + If you build the library with the \texttt{PROFILING\_ENABLED} variable enabled (see section \ref{sec:cmakevariables}), a real-time profiler will collect information while the application is running. Then, at the end of your application, when the destructor of the \texttt{DynamicsWorld} class is called, information about the running time of the library will be displayed in the standard output. This can be useful to know where time is spent in the different parts of the ReactPhysics3D library in case your application is too slow. + \section{Logger} + + TODO : Update this section + + ReactPhysics3D has an internal logger that can be used to output logs while running the application. This can be useful for debugging for instance. + To enable the logger, you need to build the library with the ????. + + Each collision or dynamics world has its own logger. By default, logs wil be written in an HTML file next to the executable. + If you have multiple worlds in your application, there will be one log file for each world. The logs files will be named after the + name of the worlds. By defaults worlds will have names: world, world1, world2, world3, \dots You can change the name of the world by + setting it into the \texttt{WorldSettings} object when you create the world (see section \ref{sec:collisionworld}). \\ + + It is also possible to output the logs at another destination. To do this, + you have to create your own logger object before the creation of the physics world. You will then be able to add one or more logs destination + to the logger. A destination can be either a file or an output stream (\texttt{std::ostream}) of your choice. For each destination, you also + have to select the output format of the logs (text or HTML). When this is done, you have to give the pointer to your logger object in paramater + when you create the world. \\ + + The following example shows how to create your own logger object and add a file destination (custom_log.html) and a stream destination (std::cout): \\ + + \begin{lstlisting} + + TODO: CREATE CODE HERE + \end{lstlisting} + + \vspace{0.6cm} + + Do not forget to build the ReactPhysics3D library without the logs when you release your final application. + \section{API Documentation} Some documentation about the API of the code has been generated using Doxygen. You will be able to find this documentation in the library archive in the folder \texttt{/documentation/API/html/}. You just need to open the \texttt{index.html} file with your favorite web browser. - \section{Bugs} - If you find some bugs, do not hesitate to report them on our issue tracker here: \\ + \section{Bugs} - \url{https://github.com/DanielChappuis/reactphysics3d/issues} \\ + If you find some bugs, do not hesitate to report them on our issue tracker here: \\ - Thanks a lot for reporting the issues that you find. It will help us to correct and improve the library. + \url{https://github.com/DanielChappuis/reactphysics3d/issues} \\ + + Thanks a lot for reporting the issues that you find. It will help us to correct and improve the library. \end{document} diff --git a/documentation/UserManual/title.tex b/documentation/UserManual/title.tex index 385abfe4..d0b6a9a0 100644 --- a/documentation/UserManual/title.tex +++ b/documentation/UserManual/title.tex @@ -10,7 +10,7 @@ \vskip 1.3cm {\Huge \@title\par}% \vskip 0.3cm - {\Large Version: 0.6.0\par}% + {\Large Version: 0.7.0\par}% \vskip 0.3cm {\Large \@author\par}% \vskip 2cm From f45f32dcb791a8d0abdef783dd8679746098e02e Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 19 Mar 2018 23:07:43 +0100 Subject: [PATCH 184/248] Add changelog file --- CHANGELOG.md | 157 +++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 157 insertions(+) create mode 100644 CHANGELOG.md diff --git a/CHANGELOG.md b/CHANGELOG.md new file mode 100644 index 00000000..9a3f4cd0 --- /dev/null +++ b/CHANGELOG.md @@ -0,0 +1,157 @@ +#Changelog + +## Version 0.7.0 (March, 2018) + +### Added + + - Dedicated Sphere vs Capsule collision detection algorithm. + - Dedicated Capsule vs Capsule collision detection algorithm. + - Allow a Rigid Body to have zero mass (for static bodies for instance). + - Add single frame memory allocator for faster memory allocation in a frame. + - Make possible to have a profiler per DynamicsWorld instead of a unique one. + - Make possible to use your own allocation/deallocation methods instead of default malloc/free + - Make possible to display the AABB of the bodies in the testbed application. + - Add RigidBody::setInverseLocalInertiaTensor() method to directly set the inverse inertia tensor of a rigid body. + - More unit tests have been added + +### Changed + + - Use single-shot contact manifold computation instead of incremental across several frames. + - Replace the EPA narrow-phase collision detection with SAT algorithm. + - The collision detection is now faster and more robust. + - Code has been refactored such that we do not use STL containers anymore. + - The way to create a ConvexMeshShape has changed (see the user manual) + - The vertex indices stride has changed in the TriangleVertexArray for ConvexMeshShape (see the API documentation) + - The raycasting of a ConvexMeshShape does not use GJK algorithm anymore. + - The test do detect if a point is inside of a ConvexMeshShape does not use GJK algorithm anymore. + - A lot of optimizations have been performed and the library is now faster. + - Documentation has been updated + +### Removed + + - Quaternion constructor with Euler angles has been removed. The Quaternion::fromEulerAngles() method should be used instead. + - Cylinder and Cone collision shapes have been removed. The ConvexMeshShape collision shape should be used instead. + +### Fixed + + - Issues with checkboxes in testbed application were fixed. + - Fix issue with wrong AABB computation that can cause missing collision in broad-phase + - Bug [#26](https://github.com/DanielChappuis/reactphysics3d/issues/26) has been fixed. + - Bug [#30](https://github.com/DanielChappuis/reactphysics3d/issues/30) has been fixed. + - Bug [#32](https://github.com/DanielChappuis/reactphysics3d/issues/32) has been fixed. + - Issue [#31](https://github.com/DanielChappuis/reactphysics3d/issues/31) has been fixed. + - Issue [#34](https://github.com/DanielChappuis/reactphysics3d/issues/34) has been fixed. + - Issue [#37](https://github.com/DanielChappuis/reactphysics3d/issues/37) has been fixed. + +## Version 0.6.0 (April 15, 2016) + +### Added + + - Support for static concave triangular mesh collision shape. + - Support for height field collision shape. + - Support for rolling resistance. + - It is now possible to change the local scaling of a collision shape. + - Add new constructor of ConvexMeshShape that accepts a triangular mesh. + - It is now easier to use your own narrow-phase collision detection algorithm. + - The CollisionWorld and DynamicsWorld now automatically destroys bodies and joints that have not been destroyed at the end. + - New testbed application with demo scenes. + +### Changed + + - The DynamicsWorld::update() method now takes the time step for the next simulation step in parameter. + +## Version 0.5.0 (March 4, 2015) + +### Added + + - It is now possible to use multiple collision shapes per body. + - Ray casting support. + - Add methods to check if a point is inside a body or a proxy shape. + - Add collision filtering using collision categories (with bit masks). + - It is possible to attach user data to a body or a proxy shape. + - It is now possible to create a quaternion using Euler angles. + - It now possible to activate of deactivate a body. + - Differentiation between dynamic, kinematic and static bodies. + - Gravity can now be changed after the creation of the world. + - The center of mass and inertia tensor of a body can be set manually (center of mass can be different from body origin). + - Add a simulation step callback in the EventListener class that is called at each internal physics tick. + - Add methods to transform points/vectors from/into local-space/world-space coordinates of a body. + - Add CollisionWorld::testAABBOverlap() method to test overlap between two bodies or two proxy shapes. + - Add a ray casting example. + - Add unit tests for ray casting and collision detection. + +### Changed + + - Replace the Sweep-And-Prune algorithm by a Dynamic AABB Tree for the broad-phase collision detection. + - The center of mass of a body is now automatically computed from its collision shapes. + - Use GLFW instead of GLUT/Freeglut for the examples. + +### Fixed + + - Fix two issues in the EPA algorithm. + +## Version 0.4.0 (October 7, 2013) + +### Added + + - Add collision shapes (Capsule, Convex Mesh). + - Add joints (Ball and Socket, Hinge, Slider, Fixed). + - Add sleeping technique for inactive bodies. + - Add velocity damping. + - It is now easier to apply force and torque to a rigid body. + - Add the EventListener class to allow the user to be notified when some events occur (contacts, …). + - Add examples for the joints and collision shapes. + - Make possible to modify the collision margin of some collision shapes. + - Add a Material class to keep track of the properties of a rigid body (friction coefficient, bounciness, …). + - Add a hierarchical real-time profiler. + +### Changed + + - Collision shapes now use the internal memory allocator. + - New internal memory allocator. + +### Removed + + - Remove the world gravity force from the external force of rigid bodies and allow the user to disable the gravity on a given body. + - Reduce the allocated memory of the broad-phase when several bodies are removed from the world. + +### Fixed + + - Fix issue in the Sweep-And-Prune broad-phase collision detection (thanks to Aleksi Sapon). + - Fix issue in the contact solver resulting in less jittering. + + +## Version 0.3.0 + +### Added + + - Implementation of a dedicated collision detection algorithm for spheres against spheres instead of using GJK/EPA algorithm. + - Make possible to use a unique instance of a collision shape for multiple rigid bodies. + - Create the API documentation using Doxygen. + - Add Unit tests + +### Changed + + - The Sweep-and-Prune broad-phase collision detection algorithm has been rewritten according to the technique described by Pierre Terdiman at http://www.codercorner.com/SAP.pdf to be much more efficient than the previous naive implementation. + - The contact solver has been rewritten to use the Sequential Impulses technique from Erin Catto which is mathematically equivalent to the Projected Gauss Seidel technique that was used before. The Sequential Impulses technique is more intuitive. + - Make GJK/EPA algorithm more robust for spheres. + - Change the structure of the code for a better separation between the collision detection and the dynamics simulation code. + +## Version 0.2.0 + +### Added + + - Add the GJK/EPA algorithm for convex shapes collision detection + - Persistent contacts storing between frames + - Add Sphere, Cylinder and Cone collision shapes + - Add the Transform class for better handling of position and orientation of rigid bodies + - It is now possible to approximate the inertia tensor of rigid bodies using the collision shape inertia tensor. + - The AABB is now computed automatically using the collision shape + - Add the MemoryPool class to avoid intense dynamic allocation during the simulation + +### Changed + + - Simplification of the mathematics library + - Optimization of the constraint solver + - ReactPhysics3D is now under the zlib license + From 71bfa6afce00c41164c05eab21e4ac3687158ff8 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 26 Mar 2018 22:00:52 +0200 Subject: [PATCH 185/248] Remove setLocalScaling() method from CollisionShape and ProxyShape and use scaling only for HeightFieldShape, ConvexMeshShape and ConcaveMeshShape --- src/collision/ProxyShape.h | 35 ----------------------- src/collision/shapes/BoxShape.h | 11 ------- src/collision/shapes/CapsuleShape.h | 12 -------- src/collision/shapes/CollisionShape.cpp | 2 +- src/collision/shapes/CollisionShape.h | 16 ----------- src/collision/shapes/ConcaveMeshShape.cpp | 5 ++-- src/collision/shapes/ConcaveMeshShape.h | 28 ++++++++---------- src/collision/shapes/ConvexMeshShape.cpp | 5 ++-- src/collision/shapes/ConvexMeshShape.h | 22 +++++++------- src/collision/shapes/HeightFieldShape.cpp | 4 +-- src/collision/shapes/HeightFieldShape.h | 22 ++++++++------ src/collision/shapes/SphereShape.h | 11 ------- src/collision/shapes/TriangleShape.h | 13 --------- test/tests/collision/TestRaycast.h | 1 - testbed/common/Box.cpp | 13 --------- testbed/common/Box.h | 3 -- testbed/common/Capsule.cpp | 13 --------- testbed/common/Capsule.h | 3 -- testbed/common/ConcaveMesh.cpp | 14 --------- testbed/common/ConcaveMesh.h | 3 -- testbed/common/ConvexMesh.cpp | 13 --------- testbed/common/ConvexMesh.h | 3 -- testbed/common/Dumbbell.cpp | 27 ----------------- testbed/common/Dumbbell.h | 3 -- testbed/common/HeightField.cpp | 13 --------- testbed/common/HeightField.h | 3 -- testbed/common/PhysicsObject.h | 3 -- testbed/common/Sphere.cpp | 13 --------- testbed/common/Sphere.h | 3 -- 29 files changed, 46 insertions(+), 271 deletions(-) diff --git a/src/collision/ProxyShape.h b/src/collision/ProxyShape.h index 61118d45..9e4ea298 100644 --- a/src/collision/ProxyShape.h +++ b/src/collision/ProxyShape.h @@ -175,12 +175,6 @@ class ProxyShape { /// Return the next proxy shape in the linked list of proxy shapes const ProxyShape* getNext() const; - /// Return the local scaling vector of the collision shape - Vector3 getLocalScaling() const; - - /// Set the local scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling); - /// Return the broad-phase id int getBroadPhaseId() const; @@ -361,35 +355,6 @@ inline void ProxyShape::setCollideWithMaskBits(unsigned short collideWithMaskBit std::to_string(mCollideWithMaskBits)); } -// Return the local scaling vector of the collision shape -/** - * @return The local scaling vector - */ -inline Vector3 ProxyShape::getLocalScaling() const { - return mCollisionShape->getLocalScaling(); -} - -// Set the local scaling vector of the collision shape -/** - * @param scaling The new local scaling vector - */ -inline void ProxyShape::setLocalScaling(const Vector3& scaling) { - - // TODO : Do not use a local of the collision shape in case of shared collision shapes - - // Set the local scaling of the collision shape - mCollisionShape->setLocalScaling(scaling); - - mBody->setIsSleeping(false); - - // Notify the body that the proxy shape has to be updated in the broad-phase - mBody->updateProxyShapeInBroadPhase(this, true); - - RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::ProxyShape, - "ProxyShape " + std::to_string(mBroadPhaseID) + ": Set localScaling=" + - mCollisionShape->getLocalScaling().to_string()); -} - // Return the broad-phase id inline int ProxyShape::getBroadPhaseId() const { return mBroadPhaseID; diff --git a/src/collision/shapes/BoxShape.h b/src/collision/shapes/BoxShape.h index 0c261a6f..b1128582 100644 --- a/src/collision/shapes/BoxShape.h +++ b/src/collision/shapes/BoxShape.h @@ -88,9 +88,6 @@ class BoxShape : public ConvexPolyhedronShape { /// Return the extents of the box Vector3 getExtent() const; - /// Set the scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling) override; - /// Return the local bounds of the shape in x, y and z directions virtual void getLocalBounds(Vector3& min, Vector3& max) const override; @@ -136,14 +133,6 @@ inline Vector3 BoxShape::getExtent() const { return mExtent; } -// Set the scaling vector of the collision shape -inline void BoxShape::setLocalScaling(const Vector3& scaling) { - - mExtent = (mExtent / mScaling) * scaling; - - CollisionShape::setLocalScaling(scaling); -} - // Return the local bounds of the shape in x, y and z directions /// This method is used to compute the AABB of the box /** diff --git a/src/collision/shapes/CapsuleShape.h b/src/collision/shapes/CapsuleShape.h index 6a58f115..decf6474 100644 --- a/src/collision/shapes/CapsuleShape.h +++ b/src/collision/shapes/CapsuleShape.h @@ -94,9 +94,6 @@ class CapsuleShape : public ConvexShape { /// Return the height of the capsule decimal getHeight() const; - /// Set the scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling) override; - /// Return the local bounds of the shape in x, y and z directions virtual void getLocalBounds(Vector3& min, Vector3& max) const override; @@ -126,15 +123,6 @@ inline decimal CapsuleShape::getHeight() const { return mHalfHeight + mHalfHeight; } -// Set the scaling vector of the collision shape -inline void CapsuleShape::setLocalScaling(const Vector3& scaling) { - - mHalfHeight = (mHalfHeight / mScaling.y) * scaling.y; - mMargin = (mMargin / mScaling.x) * scaling.x; - - CollisionShape::setLocalScaling(scaling); -} - // Return the number of bytes used by the collision shape inline size_t CapsuleShape::getSizeInBytes() const { return sizeof(CapsuleShape); diff --git a/src/collision/shapes/CollisionShape.cpp b/src/collision/shapes/CollisionShape.cpp index 976c7a51..4e6e4b9b 100644 --- a/src/collision/shapes/CollisionShape.cpp +++ b/src/collision/shapes/CollisionShape.cpp @@ -33,7 +33,7 @@ using namespace reactphysics3d; // Constructor CollisionShape::CollisionShape(CollisionShapeName name, CollisionShapeType type) - : mType(type), mName(name), mScaling(1.0, 1.0, 1.0), mId(0) { + : mType(type), mName(name), mId(0) { } diff --git a/src/collision/shapes/CollisionShape.h b/src/collision/shapes/CollisionShape.h index a7b07fc3..990ef33f 100644 --- a/src/collision/shapes/CollisionShape.h +++ b/src/collision/shapes/CollisionShape.h @@ -68,9 +68,6 @@ class CollisionShape { /// Name of the colision shape CollisionShapeName mName; - /// Scaling vector of the collision shape - Vector3 mScaling; - /// Unique identifier of the shape inside an overlapping pair uint mId; @@ -126,9 +123,6 @@ class CollisionShape { /// Return the scaling vector of the collision shape Vector3 getLocalScaling() const; - /// Set the local scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling); - /// Return the id of the shape uint getId() const; @@ -170,16 +164,6 @@ inline CollisionShapeType CollisionShape::getType() const { return mType; } -// Return the scaling vector of the collision shape -inline Vector3 CollisionShape::getLocalScaling() const { - return mScaling; -} - -// Set the scaling vector of the collision shape -inline void CollisionShape::setLocalScaling(const Vector3& scaling) { - mScaling = scaling; -} - // Return the id of the shape inline uint CollisionShape::getId() const { return mId; diff --git a/src/collision/shapes/ConcaveMeshShape.cpp b/src/collision/shapes/ConcaveMeshShape.cpp index bde756e4..a6cfcb9c 100644 --- a/src/collision/shapes/ConcaveMeshShape.cpp +++ b/src/collision/shapes/ConcaveMeshShape.cpp @@ -30,8 +30,9 @@ using namespace reactphysics3d; // Constructor -ConcaveMeshShape::ConcaveMeshShape(TriangleMesh* triangleMesh) - : ConcaveShape(CollisionShapeName::TRIANGLE_MESH), mDynamicAABBTree(MemoryManager::getBaseAllocator()) { +ConcaveMeshShape::ConcaveMeshShape(TriangleMesh* triangleMesh, const Vector3& scaling) + : ConcaveShape(CollisionShapeName::TRIANGLE_MESH), mDynamicAABBTree(MemoryManager::getBaseAllocator()), + mScaling(scaling) { mTriangleMesh = triangleMesh; mRaycastTestType = TriangleRaycastSide::FRONT; diff --git a/src/collision/shapes/ConcaveMeshShape.h b/src/collision/shapes/ConcaveMeshShape.h index ccafbba9..e8ad78e5 100644 --- a/src/collision/shapes/ConcaveMeshShape.h +++ b/src/collision/shapes/ConcaveMeshShape.h @@ -140,6 +140,9 @@ class ConcaveMeshShape : public ConcaveShape { /// if the user did not provide its own vertices normals) Vector3** mComputedVerticesNormals; + /// Scaling + const Vector3 mScaling; + // -------------------- Methods -------------------- // /// Raycast method with feedback information @@ -163,7 +166,7 @@ class ConcaveMeshShape : public ConcaveShape { public: /// Constructor - ConcaveMeshShape(TriangleMesh* triangleMesh); + ConcaveMeshShape(TriangleMesh* triangleMesh, const Vector3& scaling = Vector3(1, 1, 1)); /// Destructor virtual ~ConcaveMeshShape() = default; @@ -174,12 +177,12 @@ class ConcaveMeshShape : public ConcaveShape { /// Deleted assignment operator ConcaveMeshShape& operator=(const ConcaveMeshShape& shape) = delete; + /// Return the scaling vector + const Vector3& getScaling() const; + /// Return the local bounds of the shape in x, y and z directions. virtual void getLocalBounds(Vector3& min, Vector3& max) const override; - /// Set the local scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling) override; - /// Return the local inertia tensor of the collision shape virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; @@ -207,6 +210,11 @@ inline size_t ConcaveMeshShape::getSizeInBytes() const { return sizeof(ConcaveMeshShape); } +// Return the scaling vector +inline const Vector3& ConcaveMeshShape::getScaling() const { + return mScaling; +} + // Return the local bounds of the shape in x, y and z directions. // This method is used to compute the AABB of the box /** @@ -222,18 +230,6 @@ inline void ConcaveMeshShape::getLocalBounds(Vector3& min, Vector3& max) const { max = treeAABB.getMax(); } -// Set the local scaling vector of the collision shape -inline void ConcaveMeshShape::setLocalScaling(const Vector3& scaling) { - - CollisionShape::setLocalScaling(scaling); - - // Reset the Dynamic AABB Tree - mDynamicAABBTree.reset(); - - // Rebuild Dynamic AABB Tree here - initBVHTree(); -} - // Return the local inertia tensor of the shape /** * @param[out] tensor The 3x3 inertia tensor matrix of the shape in local-space diff --git a/src/collision/shapes/ConvexMeshShape.cpp b/src/collision/shapes/ConvexMeshShape.cpp index 1c47b4d9..3dadfee4 100644 --- a/src/collision/shapes/ConvexMeshShape.cpp +++ b/src/collision/shapes/ConvexMeshShape.cpp @@ -38,8 +38,9 @@ using namespace reactphysics3d; * @param stride Stride between the beginning of two elements in the vertices array * @param margin Collision margin (in meters) around the collision shape */ -ConvexMeshShape::ConvexMeshShape(PolyhedronMesh* polyhedronMesh) - : ConvexPolyhedronShape(CollisionShapeName::CONVEX_MESH), mPolyhedronMesh(polyhedronMesh), mMinBounds(0, 0, 0), mMaxBounds(0, 0, 0) { +ConvexMeshShape::ConvexMeshShape(PolyhedronMesh* polyhedronMesh, const Vector3& scaling) + : ConvexPolyhedronShape(CollisionShapeName::CONVEX_MESH), mPolyhedronMesh(polyhedronMesh), + mMinBounds(0, 0, 0), mMaxBounds(0, 0, 0), mScaling(scaling) { // Recalculate the bounds of the mesh recalculateBounds(); diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index ebec6a09..5ce02b19 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -30,7 +30,7 @@ #include "ConvexPolyhedronShape.h" #include "engine/CollisionWorld.h" #include "mathematics/mathematics.h" -#include "collision/TriangleMesh.h" + #include "collision/PolyhedronMesh.h" #include "collision/narrowphase/GJK/GJKAlgorithm.h" @@ -62,6 +62,9 @@ class ConvexMeshShape : public ConvexPolyhedronShape { /// Mesh maximum bounds in the three local x, y and z directions Vector3 mMaxBounds; + /// Local scaling + const Vector3 mScaling; + // -------------------- Methods -------------------- // /// Recompute the bounds of the mesh @@ -84,7 +87,7 @@ class ConvexMeshShape : public ConvexPolyhedronShape { // -------------------- Methods -------------------- // /// Constructor - ConvexMeshShape(PolyhedronMesh* polyhedronMesh); + ConvexMeshShape(PolyhedronMesh* polyhedronMesh, const Vector3& scaling = Vector3(1,1,1)); /// Destructor virtual ~ConvexMeshShape() override = default; @@ -95,8 +98,8 @@ class ConvexMeshShape : public ConvexPolyhedronShape { /// Deleted assignment operator ConvexMeshShape& operator=(const ConvexMeshShape& shape) = delete; - /// Set the scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling) override; + /// Return the scaling vector + const Vector3& getScaling() const; /// Return the local bounds of the shape in x, y and z directions virtual void getLocalBounds(Vector3& min, Vector3& max) const override; @@ -135,17 +138,16 @@ class ConvexMeshShape : public ConvexPolyhedronShape { virtual std::string to_string() const override; }; -/// Set the scaling vector of the collision shape -inline void ConvexMeshShape::setLocalScaling(const Vector3& scaling) { - ConvexShape::setLocalScaling(scaling); - recalculateBounds(); -} - // Return the number of bytes used by the collision shape inline size_t ConvexMeshShape::getSizeInBytes() const { return sizeof(ConvexMeshShape); } +// Return the scaling vector +inline const Vector3& ConvexMeshShape::getScaling() const { + return mScaling; +} + // Return the local bounds of the shape in x, y and z directions /** * @param min The minimum bounds of the shape in local-space coordinates diff --git a/src/collision/shapes/HeightFieldShape.cpp b/src/collision/shapes/HeightFieldShape.cpp index 0b3a4044..0136c881 100644 --- a/src/collision/shapes/HeightFieldShape.cpp +++ b/src/collision/shapes/HeightFieldShape.cpp @@ -41,11 +41,11 @@ using namespace reactphysics3d; */ HeightFieldShape::HeightFieldShape(int nbGridColumns, int nbGridRows, decimal minHeight, decimal maxHeight, const void* heightFieldData, HeightDataType dataType, int upAxis, - decimal integerHeightScale) + decimal integerHeightScale, const Vector3& scaling) : ConcaveShape(CollisionShapeName::HEIGHTFIELD), mNbColumns(nbGridColumns), mNbRows(nbGridRows), mWidth(nbGridColumns - 1), mLength(nbGridRows - 1), mMinHeight(minHeight), mMaxHeight(maxHeight), mUpAxis(upAxis), mIntegerHeightScale(integerHeightScale), - mHeightDataType(dataType) { + mHeightDataType(dataType), mScaling(scaling) { assert(nbGridColumns >= 2); assert(nbGridRows >= 2); diff --git a/src/collision/shapes/HeightFieldShape.h b/src/collision/shapes/HeightFieldShape.h index e796e208..8d4574d2 100644 --- a/src/collision/shapes/HeightFieldShape.h +++ b/src/collision/shapes/HeightFieldShape.h @@ -141,6 +141,9 @@ class HeightFieldShape : public ConcaveShape { /// Local AABB of the height field (without scaling) AABB mAABB; + /// Scaling vector + const Vector3 mScaling; + // -------------------- Methods -------------------- // /// Raycast method with feedback information @@ -177,7 +180,8 @@ class HeightFieldShape : public ConcaveShape { /// Constructor HeightFieldShape(int nbGridColumns, int nbGridRows, decimal minHeight, decimal maxHeight, const void* heightFieldData, HeightDataType dataType, - int upAxis = 1, decimal integerHeightScale = 1.0f); + int upAxis = 1, decimal integerHeightScale = 1.0f, + const Vector3& scaling = Vector3(1,1,1)); /// Destructor virtual ~HeightFieldShape() override = default; @@ -188,6 +192,9 @@ class HeightFieldShape : public ConcaveShape { /// Deleted assignment operator HeightFieldShape& operator=(const HeightFieldShape& shape) = delete; + /// Return the scaling factor + const Vector3& getScaling() const; + /// Return the number of rows in the height field int getNbRows() const; @@ -200,9 +207,6 @@ class HeightFieldShape : public ConcaveShape { /// Return the local bounds of the shape in x, y and z directions. virtual void getLocalBounds(Vector3& min, Vector3& max) const override; - /// Set the local scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling) override; - /// Return the local inertia tensor of the collision shape virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; @@ -218,6 +222,11 @@ class HeightFieldShape : public ConcaveShape { friend class ConcaveMeshRaycastCallback; }; +// Return the scaling factor +inline const Vector3& HeightFieldShape::getScaling() const { + return mScaling; +} + // Return the number of rows in the height field inline int HeightFieldShape::getNbRows() const { return mNbRows; @@ -238,11 +247,6 @@ inline size_t HeightFieldShape::getSizeInBytes() const { return sizeof(HeightFieldShape); } -// Set the local scaling vector of the collision shape -inline void HeightFieldShape::setLocalScaling(const Vector3& scaling) { - CollisionShape::setLocalScaling(scaling); -} - // Return the height of a given (x,y) point in the height field inline decimal HeightFieldShape::getHeightAt(int x, int y) const { diff --git a/src/collision/shapes/SphereShape.h b/src/collision/shapes/SphereShape.h index a0010b06..01e2001e 100644 --- a/src/collision/shapes/SphereShape.h +++ b/src/collision/shapes/SphereShape.h @@ -82,9 +82,6 @@ class SphereShape : public ConvexShape { /// Return true if the collision shape is a polyhedron virtual bool isPolyhedron() const override; - /// Set the scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling) override; - /// Return the local bounds of the shape in x, y and z directions. virtual void getLocalBounds(Vector3& min, Vector3& max) const override; @@ -111,14 +108,6 @@ inline bool SphereShape::isPolyhedron() const { return false; } -// Set the scaling vector of the collision shape -inline void SphereShape::setLocalScaling(const Vector3& scaling) { - - mMargin = (mMargin / mScaling.x) * scaling.x; - - CollisionShape::setLocalScaling(scaling); -} - // Return the number of bytes used by the collision shape inline size_t SphereShape::getSizeInBytes() const { return sizeof(SphereShape); diff --git a/src/collision/shapes/TriangleShape.h b/src/collision/shapes/TriangleShape.h index 5a5a49b2..23a55c38 100644 --- a/src/collision/shapes/TriangleShape.h +++ b/src/collision/shapes/TriangleShape.h @@ -127,9 +127,6 @@ class TriangleShape : public ConvexPolyhedronShape { /// Return the local bounds of the shape in x, y and z directions. virtual void getLocalBounds(Vector3& min, Vector3& max) const override; - /// Set the local scaling vector of the collision shape - virtual void setLocalScaling(const Vector3& scaling) override; - /// Return the local inertia tensor of the collision shape virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const override; @@ -214,16 +211,6 @@ inline void TriangleShape::getLocalBounds(Vector3& min, Vector3& max) const { max += Vector3(mMargin, mMargin, mMargin); } -// Set the local scaling vector of the collision shape -inline void TriangleShape::setLocalScaling(const Vector3& scaling) { - - mPoints[0] = (mPoints[0] / mScaling) * scaling; - mPoints[1] = (mPoints[1] / mScaling) * scaling; - mPoints[2] = (mPoints[2] / mScaling) * scaling; - - CollisionShape::setLocalScaling(scaling); -} - // Return the local inertia tensor of the triangle shape /** * @param[out] tensor The 3x3 inertia tensor matrix of the shape in local-space diff --git a/test/tests/collision/TestRaycast.h b/test/tests/collision/TestRaycast.h index 7714264a..70397ed0 100644 --- a/test/tests/collision/TestRaycast.h +++ b/test/tests/collision/TestRaycast.h @@ -1303,7 +1303,6 @@ class TestRaycast : public Test { Vector3 point2 = mLocalShapeToWorld * Vector3(1, 2, -4); Ray ray(point1, point2); Vector3 hitPoint = mLocalShapeToWorld * Vector3(1, 2, 4); - Transform inverse = mLocalShapeToWorld.getInverse(); mCallback.shapeToTest = mConvexMeshProxyShape; diff --git a/testbed/common/Box.cpp b/testbed/common/Box.cpp index 508fa516..6d685086 100644 --- a/testbed/common/Box.cpp +++ b/testbed/common/Box.cpp @@ -255,16 +255,3 @@ void Box::createVBOAndVAO() { // Unbind the VAO mVAO.unbind(); } - -// Set the scaling of the object -void Box::setScaling(const openglframework::Vector3& scaling) { - - // Scale the collision shape - mProxyShape->setLocalScaling(rp3d::Vector3(scaling.x, scaling.y, scaling.z)); - - // Scale the graphics object - mScalingMatrix = openglframework::Matrix4(mSize[0] * scaling.x, 0, 0, 0, - 0, mSize[1] * scaling.y, 0, 0, - 0, 0, mSize[2] * scaling.z, 0, - 0, 0, 0, 1); -} diff --git a/testbed/common/Box.h b/testbed/common/Box.h index 42d234f9..21fe0ed1 100644 --- a/testbed/common/Box.h +++ b/testbed/common/Box.h @@ -88,9 +88,6 @@ class Box : public PhysicsObject { /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; - - /// Set the scaling of the object - void setScaling(const openglframework::Vector3& scaling) override; }; // Update the transform matrix of the object diff --git a/testbed/common/Capsule.cpp b/testbed/common/Capsule.cpp index b48baf69..160030b7 100644 --- a/testbed/common/Capsule.cpp +++ b/testbed/common/Capsule.cpp @@ -235,16 +235,3 @@ void Capsule::createVBOAndVAO() { // Unbind the VAO mVAO.unbind(); } - -// Set the scaling of the object -void Capsule::setScaling(const openglframework::Vector3& scaling) { - - // Scale the collision shape - mProxyShape->setLocalScaling(rp3d::Vector3(scaling.x, scaling.y, scaling.z)); - - // Scale the graphics object - mScalingMatrix = openglframework::Matrix4(mRadius * scaling.x, 0, 0, 0, - 0, (mHeight * scaling.y + 2.0f * mRadius * scaling.x) / 3, 0,0, - 0, 0, mRadius * scaling.x, 0, - 0, 0, 0, 1.0f); -} diff --git a/testbed/common/Capsule.h b/testbed/common/Capsule.h index d0e74436..1591f247 100644 --- a/testbed/common/Capsule.h +++ b/testbed/common/Capsule.h @@ -96,9 +96,6 @@ class Capsule : public PhysicsObject { /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; - - /// Set the scaling of the object - void setScaling(const openglframework::Vector3& scaling) override; }; // Update the transform matrix of the object diff --git a/testbed/common/ConcaveMesh.cpp b/testbed/common/ConcaveMesh.cpp index f6b04b9c..553a83ca 100644 --- a/testbed/common/ConcaveMesh.cpp +++ b/testbed/common/ConcaveMesh.cpp @@ -244,17 +244,3 @@ void ConcaveMesh::createVBOAndVAO() { // Unbind the VAO mVAO.unbind(); } - -// Set the scaling of the object -void ConcaveMesh::setScaling(const openglframework::Vector3& scaling) { - - // Scale the collision shape - mProxyShape->setLocalScaling(rp3d::Vector3(scaling.x, scaling.y, scaling.z)); - - // Scale the graphics object - mScalingMatrix = openglframework::Matrix4(scaling.x, 0, 0, 0, - 0, scaling.y, 0,0, - 0, 0, scaling.z, 0, - 0, 0, 0, 1.0f); -} - diff --git a/testbed/common/ConcaveMesh.h b/testbed/common/ConcaveMesh.h index 17755352..21d40082 100644 --- a/testbed/common/ConcaveMesh.h +++ b/testbed/common/ConcaveMesh.h @@ -90,9 +90,6 @@ class ConcaveMesh : public PhysicsObject { /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; - - /// Set the scaling of the object - void setScaling(const openglframework::Vector3& scaling) override; }; // Update the transform matrix of the object diff --git a/testbed/common/ConvexMesh.cpp b/testbed/common/ConvexMesh.cpp index a59c2f3d..95e41dd1 100644 --- a/testbed/common/ConvexMesh.cpp +++ b/testbed/common/ConvexMesh.cpp @@ -254,16 +254,3 @@ void ConvexMesh::createVBOAndVAO() { // Unbind the VAO mVAO.unbind(); } - -// Set the scaling of the object -void ConvexMesh::setScaling(const openglframework::Vector3& scaling) { - - // Scale the collision shape - mProxyShape->setLocalScaling(rp3d::Vector3(scaling.x, scaling.y, scaling.z)); - - // Scale the graphics object - mScalingMatrix = openglframework::Matrix4(scaling.x, 0, 0, 0, - 0, scaling.y, 0, 0, - 0, 0, scaling.z, 0, - 0, 0, 0, 1); -} diff --git a/testbed/common/ConvexMesh.h b/testbed/common/ConvexMesh.h index 865921ca..cc8c1599 100644 --- a/testbed/common/ConvexMesh.h +++ b/testbed/common/ConvexMesh.h @@ -92,9 +92,6 @@ class ConvexMesh : public PhysicsObject { /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; - - /// Set the scaling of the object - void setScaling(const openglframework::Vector3& scaling) override; }; // Update the transform matrix of the object diff --git a/testbed/common/Dumbbell.cpp b/testbed/common/Dumbbell.cpp index f90f0cc9..866c35b1 100644 --- a/testbed/common/Dumbbell.cpp +++ b/testbed/common/Dumbbell.cpp @@ -272,30 +272,3 @@ void Dumbbell::createVBOAndVAO() { // Unbind the VAO mVAO.unbind(); } - -// Set the scaling of the object -void Dumbbell::setScaling(const openglframework::Vector3& scaling) { - - // Scale the collision shape - rp3d::Vector3 newScaling(scaling.x, scaling.y, scaling.z); - mProxyShapeCapsule->setLocalScaling(newScaling); - mProxyShapeSphere1->setLocalScaling(newScaling); - mProxyShapeSphere2->setLocalScaling(newScaling); - - mDistanceBetweenSphere = (mDistanceBetweenSphere / mScalingMatrix.getValue(1, 1)) * scaling.y; - - // Initial transform of the first sphere collision shape of the dumbbell (in local-space) - rp3d::Transform transformSphereShape1(rp3d::Vector3(0, mDistanceBetweenSphere / 2.0f, 0), rp3d::Quaternion::identity()); - - // Initial transform of the second sphere collision shape of the dumbell (in local-space) - rp3d::Transform transformSphereShape2(rp3d::Vector3(0, -mDistanceBetweenSphere / 2.0f, 0), rp3d::Quaternion::identity()); - - mProxyShapeSphere1->setLocalToBodyTransform(transformSphereShape1); - mProxyShapeSphere2->setLocalToBodyTransform(transformSphereShape2); - - // Scale the graphics object - mScalingMatrix = openglframework::Matrix4(scaling.x, 0, 0, 0, - 0, scaling.y, 0, 0, - 0, 0, scaling.z, 0, - 0, 0, 0, 1); -} diff --git a/testbed/common/Dumbbell.h b/testbed/common/Dumbbell.h index 135beabc..8044e434 100644 --- a/testbed/common/Dumbbell.h +++ b/testbed/common/Dumbbell.h @@ -95,9 +95,6 @@ class Dumbbell : public PhysicsObject { /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; - - /// Set the scaling of the object - void setScaling(const openglframework::Vector3& scaling) override; }; // Update the transform matrix of the object diff --git a/testbed/common/HeightField.cpp b/testbed/common/HeightField.cpp index e979936d..b1077fad 100644 --- a/testbed/common/HeightField.cpp +++ b/testbed/common/HeightField.cpp @@ -303,16 +303,3 @@ void HeightField::createVBOAndVAO() { // Unbind the VAO mVAO.unbind(); } - -// Set the scaling of the object -void HeightField::setScaling(const openglframework::Vector3& scaling) { - - // Scale the collision shape - mProxyShape->setLocalScaling(rp3d::Vector3(scaling.x, scaling.y, scaling.z)); - - // Scale the graphics object - mScalingMatrix = openglframework::Matrix4(scaling.x, 0, 0, 0, - 0, scaling.y, 0,0, - 0, 0, scaling.z, 0, - 0, 0, 0, 1.0f); -} diff --git a/testbed/common/HeightField.h b/testbed/common/HeightField.h index 1ff390ee..e68c8388 100644 --- a/testbed/common/HeightField.h +++ b/testbed/common/HeightField.h @@ -103,9 +103,6 @@ class HeightField : public PhysicsObject { /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; - - /// Set the scaling of the object - void setScaling(const openglframework::Vector3& scaling) override; }; // Update the transform matrix of the object diff --git a/testbed/common/PhysicsObject.h b/testbed/common/PhysicsObject.h index e1714048..31e01c4f 100644 --- a/testbed/common/PhysicsObject.h +++ b/testbed/common/PhysicsObject.h @@ -82,9 +82,6 @@ class PhysicsObject : public openglframework::Mesh { /// Return a pointer to the rigid body of the box reactphysics3d::RigidBody* getRigidBody(); - - /// Set the scaling of the object - virtual void setScaling(const openglframework::Vector3& scaling)=0; }; // Set the color of the box diff --git a/testbed/common/Sphere.cpp b/testbed/common/Sphere.cpp index f7c53579..15375e05 100644 --- a/testbed/common/Sphere.cpp +++ b/testbed/common/Sphere.cpp @@ -234,16 +234,3 @@ void Sphere::createVBOAndVAO() { // Unbind the VAO mVAO.unbind(); } - -// Set the scaling of the object -void Sphere::setScaling(const openglframework::Vector3& scaling) { - - // Scale the collision shape - mProxyShape->setLocalScaling(rp3d::Vector3(scaling.x, scaling.y, scaling.z)); - - // Scale the graphics object - mScalingMatrix = openglframework::Matrix4(mRadius * scaling.x, 0, 0, 0, - 0, mRadius * scaling.y, 0, 0, - 0, 0, mRadius * scaling.z, 0, - 0, 0, 0, 1); -} diff --git a/testbed/common/Sphere.h b/testbed/common/Sphere.h index fe2b3f83..e1ba6ed6 100644 --- a/testbed/common/Sphere.h +++ b/testbed/common/Sphere.h @@ -92,9 +92,6 @@ class Sphere : public PhysicsObject { /// Update the transform matrix of the object virtual void updateTransform(float interpolationFactor) override; - - /// Set the scaling of the object - void setScaling(const openglframework::Vector3& scaling) override; }; // Update the transform matrix of the object From 66df1e87e90bd7630d15e10941ba42954357ddbe Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Mon, 26 Mar 2018 22:10:39 +0200 Subject: [PATCH 186/248] Update of the user manual --- .../UserManual/ReactPhysics3D-UserManual.tex | 116 ++++++++++++------ 1 file changed, 78 insertions(+), 38 deletions(-) diff --git a/documentation/UserManual/ReactPhysics3D-UserManual.tex b/documentation/UserManual/ReactPhysics3D-UserManual.tex index b5e46c49..c3096c47 100644 --- a/documentation/UserManual/ReactPhysics3D-UserManual.tex +++ b/documentation/UserManual/ReactPhysics3D-UserManual.tex @@ -154,7 +154,7 @@ In debugging mode, the library might run a bit slow due to all the debugging information. However, if this variable is set to \texttt{Release}, no debugging information is stored and therefore, it will run much faster. This mode must be used when you compile the final - release of you application. + release of your application. \item[COMPILE\_TESTBED] If this variable is \texttt{ON}, the tesbed application of the library will be compiled. The testbed application uses OpenGL for rendering. @@ -163,14 +163,13 @@ \item[COMPILE\_TESTS] If this variable is \texttt{ON}, the unit tests of the library will be compiled. You will then be able to launch the tests to make sure that they are running fine on your system. - TODO : Edit the profiling info bellow - \item[PROFILING\_ENABLED] If this variable is \texttt{ON}, the integrated profiler will collect data while the application is running - and the profiling report will be displayed in the console at the end of the application (in the - destructor of the \texttt{DynamicsWorld} class). This might be useful to see what part of the reactphysics3d + \item[PROFILING\_ENABLED] If this variable is \texttt{ON}, the integrated profiler will collect data during the execution of the application. + This might be useful to see which part of the ReactPhysics3D library takes time during its execution. This variable must be set to \texttt{OFF} when you compile - the final release of your application. + the final release of your application. You can find more information about the profiler in section \ref{sec:profiler}. - TODO : Add info to enable logs here + \item[LOGS\_ENABLED] Set this variable to \texttt{ON} if you want to enable the internal logger of ReactPhysics3D. Logs can be useful for debugging the application. + You can find more information about the logger in section \ref{sec:logger}. \item[DOUBLE\_PRECISION\_ENABLED] If this variable is \texttt{ON}, the library will be compiled with double floating point precision. Otherwise, the library will be compiled with single precision. @@ -280,12 +279,20 @@ rp3d::CollisionWorld world; a \texttt{WorldSettings} object and give it in paramater when you create your world as in the following example: \\ \begin{lstlisting} - TODO: ADD CODE HERE + // Create the world settings + rp3d::WorldSettings settings; + settings.nbVelocitySolverIterations = 20; + settings.isSleepingEnabled = false; + + // Create the world with your settings + rp3d::CollisionWorld world(settings); \end{lstlisting} \vspace{0.6cm} - Take a look at the API documentation to see which world settings you can change. + The settings are copied into the world at its creation. Therefore, changing the values of your \texttt{WorldSettings} instance after the world constructor call + will not have any effects. However, some methods are available to change settings after the world creation. You can take a look at the API documentation to see what + world settings can be changed. \subsection{Destroying the Collision World} @@ -398,8 +405,6 @@ world.destroyCollisionBody(body); Here is how to create the dynamics world: \\ - TODO : Update this example with new constructor for CollisionWorld - \begin{lstlisting} // Gravity vector rp3d::Vector3 gravity(0.0, -9.81, 0.0); @@ -1763,31 +1768,28 @@ for (; listElem != NULL; listElem = listElem->next) { The following example shows how to get all the contacts of the world using this method: \\ - TODO : Refactor return type of getContactsList() - \begin{lstlisting} -std::vector manifolds; +rp3d::List manifolds; // Get all the contacts of the world manifolds = dynamicsWorld->getContactsList(); -std::vector::iterator it; +rp3d::List::iterator it; -// For each contact manifold of the body +// For each contact manifold for (it = manifolds.begin(); it != manifolds.end(); ++it) { - ContactManifold* manifold = *it; + const rp3d::ContactManifold* manifold = *it; - // For each contact point of the manifold - for (int i=0; igetNbContactPoints(); i++) { + // For each contact point of the manifold + rp3d::ContactPoint* contactPoint = manifold->getContactPoints(); + while (contactPoint != nullptr) { - // Get the contact point - ContactPoint* point = manifold->getContactPoint(i); + // Retrieve the world contact point and normal + rp3d::Vector3 worldPoint = manifold->getShape1()->getLocalToWorldTransform() * contactPoint->getLocalPointOnShape1(); + rp3d::Vector3 worldNormal = contactPoint->getNormal(); - // Get the world-space contact point on body 1 - Vector3 pos = point->getWorldPointOnBody1(); - - // Get the world-space contact normal - Vector3 normal = point->getNormal(); - } + // Move to the next contact point + contactPoint = contactPoint->getNext(); + } } \end{lstlisting} @@ -1822,36 +1824,74 @@ world.setEventListener(&listener); method will be called when a new contact is found. \section{Profiler} - - TODO : Update this section + \label{sec:profiler} If you build the library with the \texttt{PROFILING\_ENABLED} variable enabled (see section \ref{sec:cmakevariables}), a real-time profiler will collect information while the application is running. Then, at the end of your application, when the destructor of the \texttt{DynamicsWorld} class is called, information about the running time of the library will be displayed in the - standard output. This can be useful to know where time is spent in the different parts of the ReactPhysics3D library in case your application is too slow. + standard output. This can be useful to know where time is spent in the different parts of the ReactPhysics3D library in case your application is too slow. \\ + + Each collision or dynamics world has its own profiler. By default, the profiling report wil be written in a text file next to the executable. + If you have multiple worlds in your application, there will be one profile file for each world. The profile files will be named after the + name of the worlds. By defaults worlds will have names: world, world1, world2, world3, \dots You can change the name of the world by + setting it into the \texttt{WorldSettings} object when you create the world (see section \ref{sec:collisionworld}). \\ + + It is also possible to output the profiling report to another destination. To do this, + you have to create your own profiler object before the creation of the physics world. You will then be able to add one or more profile destinations + to the profiler. A destination can be either a file or an output stream (\texttt{std::ostream}) of your choice. For each destination, you also + have to select the output format of the profiling report. When this is done, you have to give the pointer to your profiler object in paramater + when you create the world. \\ + + The following example shows how to create your own profiler object and add a file destination (custom\_profile.txt) and a stream destination (std::cout): \\ + + \begin{lstlisting} +// Create the profiler +rp3d::Profiler* profiler = new rp3d::Profiler(); + +// Add a log destination file +profiler->addFileDestination("custom\_profile.txt", Profiler::Format::Text); + +// Add an output stream destination +profiler->addStreamDestination(std::cout, Profiler::Format::Text); + +// Create the physics world with your profiler +rp3d::CollisionWorld world(rp3d::WorldSettings(), nullptr, profiler); + \end{lstlisting} \section{Logger} - - TODO : Update this section + \label{sec:logger} ReactPhysics3D has an internal logger that can be used to output logs while running the application. This can be useful for debugging for instance. - To enable the logger, you need to build the library with the ????. + To enable the logger, you need to build the library with the \texttt{LOGS\_ENABLED} variable enabled (see section \ref{sec:cmakevariables}). \\ Each collision or dynamics world has its own logger. By default, logs wil be written in an HTML file next to the executable. If you have multiple worlds in your application, there will be one log file for each world. The logs files will be named after the name of the worlds. By defaults worlds will have names: world, world1, world2, world3, \dots You can change the name of the world by setting it into the \texttt{WorldSettings} object when you create the world (see section \ref{sec:collisionworld}). \\ - It is also possible to output the logs at another destination. To do this, - you have to create your own logger object before the creation of the physics world. You will then be able to add one or more logs destination + It is also possible to output the logs to another destination. To do this, + you have to create your own logger object before the creation of the physics world. You will then be able to add one or more logs destinations to the logger. A destination can be either a file or an output stream (\texttt{std::ostream}) of your choice. For each destination, you also have to select the output format of the logs (text or HTML). When this is done, you have to give the pointer to your logger object in paramater when you create the world. \\ - The following example shows how to create your own logger object and add a file destination (custom_log.html) and a stream destination (std::cout): \\ + The following example shows how to create your own logger object and add a file destination (custom\_log.html) and a stream destination (std::cout): \\ \begin{lstlisting} - - TODO: CREATE CODE HERE +// Create the logger +rp3d::Logger* logger = new rp3d::Logger(); + +// Log level (infor, warning and error +uint logLevel = static\_cast(Logger::Level::Info) | static\_cast(Logger::Level::Warning) | +static\_cast(Logger::Level::Error); + +// Add a log destination file +logger->addFileDestination("custom\_log.html", logLevel, Logger::Format::HTML); + +// Add an output stream destination +logger->addStreamDestination(std::cout, logLevel, Logger::Format::Text); + +// Create the physics world with your logger +rp3d::CollisionWorld world(rp3d::WorldSettings(), logger); \end{lstlisting} \vspace{0.6cm} From 100cdbc64a14ef855b4f6a890caee8267ae4b016 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 28 Mar 2018 22:55:02 +0200 Subject: [PATCH 187/248] Working on logger --- src/body/Body.h | 7 +++-- src/body/CollisionBody.cpp | 4 +++ src/body/RigidBody.cpp | 4 +++ src/collision/shapes/BoxShape.h | 2 +- src/collision/shapes/CapsuleShape.h | 2 +- src/collision/shapes/ConcaveMeshShape.cpp | 2 +- src/collision/shapes/ConvexMeshShape.cpp | 2 +- src/collision/shapes/HeightFieldShape.cpp | 16 +++++------ src/collision/shapes/SphereShape.h | 2 +- src/collision/shapes/TriangleShape.h | 2 +- src/constraint/BallAndSocketJoint.h | 9 +++++++ src/constraint/FixedJoint.h | 11 ++++++++ src/constraint/HingeJoint.cpp | 4 +-- src/constraint/HingeJoint.h | 14 ++++++++++ src/constraint/Joint.h | 3 +++ src/constraint/SliderJoint.cpp | 6 ++--- src/constraint/SliderJoint.h | 14 ++++++++++ src/engine/DynamicsWorld.cpp | 16 ++++++++--- src/utils/Logger.cpp | 4 +++ src/utils/Logger.h | 33 +++++++++++++++++------ 20 files changed, 125 insertions(+), 32 deletions(-) diff --git a/src/body/Body.h b/src/body/Body.h index dbacc55d..337b9df1 100644 --- a/src/body/Body.h +++ b/src/body/Body.h @@ -218,11 +218,14 @@ inline void Body::setIsSleeping(bool isSleeping) { } } - mIsSleeping = isSleeping; + if (mIsSleeping != isSleeping) { - RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + mIsSleeping = isSleeping; + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, "Body " + std::to_string(mID) + ": Set isSleeping=" + (mIsSleeping ? "true" : "false")); + } } // Return a pointer to the user data attached to this body diff --git a/src/body/CollisionBody.cpp b/src/body/CollisionBody.cpp index f7e7fe1d..62c035ff 100644 --- a/src/body/CollisionBody.cpp +++ b/src/body/CollisionBody.cpp @@ -109,6 +109,10 @@ ProxyShape* CollisionBody::addCollisionShape(CollisionShape* collisionShape, RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, "Body " + std::to_string(mID) + ": Proxy shape " + std::to_string(proxyShape->getBroadPhaseId()) + " added to body"); + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::ProxyShape, + "ProxyShape " + std::to_string(proxyShape->getBroadPhaseId()) + ": collisionShape=" + + proxyShape->getCollisionShape()->to_string()); + // Return a pointer to the collision shape return proxyShape; } diff --git a/src/body/RigidBody.cpp b/src/body/RigidBody.cpp index 3791c9d9..4a05010b 100644 --- a/src/body/RigidBody.cpp +++ b/src/body/RigidBody.cpp @@ -310,6 +310,10 @@ ProxyShape* RigidBody::addCollisionShape(CollisionShape* collisionShape, RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, "Body " + std::to_string(mID) + ": Proxy shape " + std::to_string(proxyShape->getBroadPhaseId()) + " added to body"); + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::ProxyShape, + "ProxyShape " + std::to_string(proxyShape->getBroadPhaseId()) + ": collisionShape=" + + proxyShape->getCollisionShape()->to_string()); + // Return a pointer to the proxy collision shape return proxyShape; } diff --git a/src/collision/shapes/BoxShape.h b/src/collision/shapes/BoxShape.h index b1128582..7e5fba31 100644 --- a/src/collision/shapes/BoxShape.h +++ b/src/collision/shapes/BoxShape.h @@ -231,7 +231,7 @@ inline Vector3 BoxShape::getCentroid() const { // Return the string representation of the shape inline std::string BoxShape::to_string() const { - return "BoxShape {extents=" + mExtent.to_string() + "}"; + return "BoxShape{extents=" + mExtent.to_string() + "}"; } // Return the number of half-edges of the polyhedron diff --git a/src/collision/shapes/CapsuleShape.h b/src/collision/shapes/CapsuleShape.h index decf6474..c595da77 100644 --- a/src/collision/shapes/CapsuleShape.h +++ b/src/collision/shapes/CapsuleShape.h @@ -178,7 +178,7 @@ inline Vector3 CapsuleShape::getLocalSupportPointWithoutMargin(const Vector3& di // Return the string representation of the shape inline std::string CapsuleShape::to_string() const { - return "CapsuleShape {halfHeight=" + std::to_string(mHalfHeight) + ", radius=" + std::to_string(getRadius()) + "}"; + return "CapsuleShape{halfHeight=" + std::to_string(mHalfHeight) + ", radius=" + std::to_string(getRadius()) + "}"; } } diff --git a/src/collision/shapes/ConcaveMeshShape.cpp b/src/collision/shapes/ConcaveMeshShape.cpp index a6cfcb9c..21677154 100644 --- a/src/collision/shapes/ConcaveMeshShape.cpp +++ b/src/collision/shapes/ConcaveMeshShape.cpp @@ -221,7 +221,7 @@ std::string ConcaveMeshShape::to_string() const { std::stringstream ss; - ss << "ConcaveMeshShape {" << std::endl; + ss << "ConcaveMeshShape{" << std::endl; ss << "nbSubparts=" << mTriangleMesh->getNbSubparts() << std::endl; // Vertices array diff --git a/src/collision/shapes/ConvexMeshShape.cpp b/src/collision/shapes/ConvexMeshShape.cpp index 3dadfee4..01cb9dc6 100644 --- a/src/collision/shapes/ConvexMeshShape.cpp +++ b/src/collision/shapes/ConvexMeshShape.cpp @@ -206,7 +206,7 @@ bool ConvexMeshShape::testPointInside(const Vector3& localPoint, ProxyShape* pro std::string ConvexMeshShape::to_string() const { std::stringstream ss; - ss << "ConvexMeshShape {" << std::endl; + ss << "ConvexMeshShape{" << std::endl; ss << "nbVertices=" << mPolyhedronMesh->getNbVertices() << std::endl; ss << "nbFaces=" << mPolyhedronMesh->getNbFaces() << std::endl; diff --git a/src/collision/shapes/HeightFieldShape.cpp b/src/collision/shapes/HeightFieldShape.cpp index 0136c881..37d73005 100644 --- a/src/collision/shapes/HeightFieldShape.cpp +++ b/src/collision/shapes/HeightFieldShape.cpp @@ -303,16 +303,16 @@ std::string HeightFieldShape::to_string() const { std::stringstream ss; - ss << "HeightFieldShape {" << std::endl; + ss << "HeightFieldShape{" << std::endl; ss << "nbColumns=" << mNbColumns << std::endl; - ss << "nbRows=" << mNbRows << std::endl; - ss << "width=" << mWidth << std::endl; - ss << "length=" << mLength << std::endl; - ss << "minHeight=" << mMinHeight << std::endl; - ss << "maxHeight=" << mMaxHeight << std::endl; - ss << "upAxis=" << mUpAxis << std::endl; - ss << "integerHeightScale=" << mIntegerHeightScale << std::endl; + ss << ", nbRows=" << mNbRows << std::endl; + ss << ", width=" << mWidth << std::endl; + ss << ", length=" << mLength << std::endl; + ss << ", minHeight=" << mMinHeight << std::endl; + ss << ", maxHeight=" << mMaxHeight << std::endl; + ss << ", upAxis=" << mUpAxis << std::endl; + ss << ", integerHeightScale=" << mIntegerHeightScale << std::endl; ss << "}"; return ss.str(); diff --git a/src/collision/shapes/SphereShape.h b/src/collision/shapes/SphereShape.h index 01e2001e..baebf6e1 100644 --- a/src/collision/shapes/SphereShape.h +++ b/src/collision/shapes/SphereShape.h @@ -175,7 +175,7 @@ inline bool SphereShape::testPointInside(const Vector3& localPoint, ProxyShape* // Return the string representation of the shape inline std::string SphereShape::to_string() const { - return "SphereShape { radius=" + std::to_string(getRadius()) + "}"; + return "SphereShape{radius=" + std::to_string(getRadius()) + "}"; } } diff --git a/src/collision/shapes/TriangleShape.h b/src/collision/shapes/TriangleShape.h index 23a55c38..87ae5398 100644 --- a/src/collision/shapes/TriangleShape.h +++ b/src/collision/shapes/TriangleShape.h @@ -317,7 +317,7 @@ inline void TriangleShape::setRaycastTestType(TriangleRaycastSide testType) { // Return the string representation of the shape inline std::string TriangleShape::to_string() const { - return "TriangleShape {v1=" + mPoints[0].to_string() + ", v2=" + mPoints[1].to_string() + "," + + return "TriangleShape{v1=" + mPoints[0].to_string() + ", v2=" + mPoints[1].to_string() + "," + "v3=" + mPoints[2].to_string() + "}"; } diff --git a/src/constraint/BallAndSocketJoint.h b/src/constraint/BallAndSocketJoint.h index ed66320f..33260bfb 100644 --- a/src/constraint/BallAndSocketJoint.h +++ b/src/constraint/BallAndSocketJoint.h @@ -133,6 +133,9 @@ class BallAndSocketJoint : public Joint { /// Deleted copy-constructor BallAndSocketJoint(const BallAndSocketJoint& constraint) = delete; + /// Return a string representation + virtual std::string to_string() const override; + /// Deleted assignment operator BallAndSocketJoint& operator=(const BallAndSocketJoint& constraint) = delete; }; @@ -142,6 +145,12 @@ inline size_t BallAndSocketJoint::getSizeInBytes() const { return sizeof(BallAndSocketJoint); } +// Return a string representation +inline std::string BallAndSocketJoint::to_string() const { + return "BallAndSocketJoint{ localAnchorPointBody1=" + mLocalAnchorPointBody1.to_string() + + ", localAnchorPointBody2=" + mLocalAnchorPointBody2.to_string() + "}"; +} + } #endif diff --git a/src/constraint/FixedJoint.h b/src/constraint/FixedJoint.h index 45fe1185..bc472cfa 100644 --- a/src/constraint/FixedJoint.h +++ b/src/constraint/FixedJoint.h @@ -144,6 +144,9 @@ class FixedJoint : public Joint { /// Deleted copy-constructor FixedJoint(const FixedJoint& constraint) = delete; + /// Return a string representation + virtual std::string to_string() const override; + /// Deleted assignment operator FixedJoint& operator=(const FixedJoint& constraint) = delete; }; @@ -153,6 +156,14 @@ inline size_t FixedJoint::getSizeInBytes() const { return sizeof(FixedJoint); } +// Return a string representation +inline std::string FixedJoint::to_string() const { + return "FixedJoint{ localAnchorPointBody1=" + mLocalAnchorPointBody1.to_string() + + ", localAnchorPointBody2=" + mLocalAnchorPointBody2.to_string() + + ", initOrientationDifferenceInv=" + mInitOrientationDifferenceInv.to_string() + + "}"; +} + } #endif diff --git a/src/constraint/HingeJoint.cpp b/src/constraint/HingeJoint.cpp index 990e7be1..bccd0cb1 100644 --- a/src/constraint/HingeJoint.cpp +++ b/src/constraint/HingeJoint.cpp @@ -42,8 +42,8 @@ HingeJoint::HingeJoint(uint id, const HingeJointInfo& jointInfo) mIsLowerLimitViolated(false), mIsUpperLimitViolated(false), mMotorSpeed(jointInfo.motorSpeed), mMaxMotorTorque(jointInfo.maxMotorTorque) { - assert(mLowerLimit <= 0 && mLowerLimit >= -2.0 * PI); - assert(mUpperLimit >= 0 && mUpperLimit <= 2.0 * PI); + assert(mLowerLimit <= decimal(0) && mLowerLimit >= decimal(-2.0) * PI); + assert(mUpperLimit >= decimal(0) && mUpperLimit <= decimal(2.0) * PI); // Compute the local-space anchor point for each body Transform transform1 = mBody1->getTransform(); diff --git a/src/constraint/HingeJoint.h b/src/constraint/HingeJoint.h index fbcfeacf..435064d2 100644 --- a/src/constraint/HingeJoint.h +++ b/src/constraint/HingeJoint.h @@ -336,6 +336,9 @@ class HingeJoint : public Joint { /// Return the intensity of the current torque applied for the joint motor decimal getMotorTorque(decimal timeStep) const; + + /// Return a string representation + virtual std::string to_string() const override; }; // Return true if the limits of the joint are enabled @@ -400,6 +403,17 @@ inline size_t HingeJoint::getSizeInBytes() const { return sizeof(HingeJoint); } +// Return a string representation +inline std::string HingeJoint::to_string() const { + return "HingeJoint{ lowerLimit=" + std::to_string(mLowerLimit) + ", upperLimit=" + std::to_string(mUpperLimit) + + "localAnchorPointBody1=" + mLocalAnchorPointBody1.to_string() + ", localAnchorPointBody2=" + + mLocalAnchorPointBody2.to_string() + ", hingeLocalAxisBody1=" + mHingeLocalAxisBody1.to_string() + + ", hingeLocalAxisBody2=" + mHingeLocalAxisBody2.to_string() + ", initOrientationDifferenceInv=" + + mInitOrientationDifferenceInv.to_string() + ", motorSpeed=" + std::to_string(mMotorSpeed) + + ", maxMotorTorque=" + std::to_string(mMaxMotorTorque) + ", isLimitEnabled=" + + (mIsLimitEnabled ? "true" : "false") + ", isMotorEnabled=" + (mIsMotorEnabled ? "true" : "false") + "}"; +} + } diff --git a/src/constraint/Joint.h b/src/constraint/Joint.h index 10d1680e..92c413da 100644 --- a/src/constraint/Joint.h +++ b/src/constraint/Joint.h @@ -204,6 +204,9 @@ class Joint { /// Return the id of the joint uint getId() const; + /// Return a string representation + virtual std::string to_string() const=0; + // -------------------- Friendship -------------------- // friend class DynamicsWorld; diff --git a/src/constraint/SliderJoint.cpp b/src/constraint/SliderJoint.cpp index 174ddb67..839cc4dc 100644 --- a/src/constraint/SliderJoint.cpp +++ b/src/constraint/SliderJoint.cpp @@ -41,9 +41,9 @@ SliderJoint::SliderJoint(uint id, const SliderJointInfo& jointInfo) mIsUpperLimitViolated(false), mMotorSpeed(jointInfo.motorSpeed), mMaxMotorForce(jointInfo.maxMotorForce){ - assert(mUpperLimit >= 0.0); - assert(mLowerLimit <= 0.0); - assert(mMaxMotorForce >= 0.0); + assert(mUpperLimit >= decimal(0.0)); + assert(mLowerLimit <= decimal(0.0)); + assert(mMaxMotorForce >= decimal(0.0)); // Compute the local-space anchor point for each body const Transform& transform1 = mBody1->getTransform(); diff --git a/src/constraint/SliderJoint.h b/src/constraint/SliderJoint.h index 3fd0035e..e6ae05dd 100644 --- a/src/constraint/SliderJoint.h +++ b/src/constraint/SliderJoint.h @@ -337,6 +337,9 @@ class SliderJoint : public Joint { /// Return the intensity of the current force applied for the joint motor decimal getMotorForce(decimal timeStep) const; + + /// Return a string representation + virtual std::string to_string() const override; }; // Return true if the limits or the joint are enabled @@ -401,6 +404,17 @@ inline size_t SliderJoint::getSizeInBytes() const { return sizeof(SliderJoint); } +// Return a string representation +inline std::string SliderJoint::to_string() const { + return "SliderJoint{ lowerLimit=" + std::to_string(mLowerLimit) + ", upperLimit=" + std::to_string(mUpperLimit) + + "localAnchorPointBody1=" + mLocalAnchorPointBody1.to_string() + ", localAnchorPointBody2=" + + mLocalAnchorPointBody2.to_string() + ", sliderAxisBody1=" + mSliderAxisBody1.to_string() + + ", initOrientationDifferenceInv=" + + mInitOrientationDifferenceInv.to_string() + ", motorSpeed=" + std::to_string(mMotorSpeed) + + ", maxMotorForce=" + std::to_string(mMaxMotorForce) + ", isLimitEnabled=" + + (mIsLimitEnabled ? "true" : "false") + ", isMotorEnabled=" + (mIsMotorEnabled ? "true" : "false") + "}"; +} + } #endif diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index 8fb71e08..8f06ca74 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -548,11 +548,13 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { // Add the joint into the world mJoints.add(newJoint); - // Add the joint into the joint list of the bodies involved in the joint - addJointToBody(newJoint); - RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Joint, "Joint " + std::to_string(newJoint->getId()) + ": New joint created"); + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Joint, + "Joint " + std::to_string(newJoint->getId()) + ": " + newJoint->to_string()); + + // Add the joint into the joint list of the bodies involved in the joint + addJointToBody(newJoint); // Return the pointer to the created joint return newJoint; @@ -614,12 +616,20 @@ void DynamicsWorld::addJointToBody(Joint* joint) { joint->mBody1->mJointsList); joint->mBody1->mJointsList = jointListElement1; + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(joint->mBody1->getId()) + ": Joint " + std::to_string(joint->getId()) + + " added to body"); + // Add the joint at the beginning of the linked list of joints of the second body void* allocatedMemory2 = mMemoryManager.allocate(MemoryManager::AllocationType::Pool, sizeof(JointListElement)); JointListElement* jointListElement2 = new (allocatedMemory2) JointListElement(joint, joint->mBody2->mJointsList); joint->mBody2->mJointsList = jointListElement2; + + RP3D_LOG(mLogger, Logger::Level::Information, Logger::Category::Body, + "Body " + std::to_string(joint->mBody2->getId()) + ": Joint " + std::to_string(joint->getId()) + + " added to body"); } // Return the next available joint Id diff --git a/src/utils/Logger.cpp b/src/utils/Logger.cpp index 9410cc29..2b213020 100644 --- a/src/utils/Logger.cpp +++ b/src/utils/Logger.cpp @@ -96,11 +96,15 @@ void Logger::log(Level level, Category category, const std::string& message) { auto now = std::chrono::system_clock::now(); auto time = std::chrono::system_clock::to_time_t(now); + mMutex.lock(); + // For each destination for (auto it = mDestinations.begin(); it != mDestinations.end(); ++it) { (*it)->write(time, message, level, category); } + + mMutex.unlock(); } #endif diff --git a/src/utils/Logger.h b/src/utils/Logger.h index 8ce51fb3..879909c7 100644 --- a/src/utils/Logger.h +++ b/src/utils/Logger.h @@ -35,6 +35,7 @@ #include #include #include +#include /// ReactPhysics3D namespace namespace reactphysics3d { @@ -140,7 +141,21 @@ class Logger { /// Format a log message virtual std::string format(const time_t& time, const std::string& message, Level level, Category category) override { - return message; + std::stringstream ss; + + // Time + ss << std::put_time(std::localtime(&time), "%X") << " "; + + // Level + ss << getLevelName(level) << " "; + + // Category + ss << getCategoryName(category) << " "; + + // Message + ss << message << std::endl; + + return ss.str(); } }; @@ -186,7 +201,7 @@ class Logger { std::string generateCSS() const { return "body {" - " background-color: #f7f7f9;" + " background-color: #e6e6e6;" " font-family: SFMono-Regular,Menlo,Monaco,Consolas,'Liberation Mono','Courier New',monospace; " "} " "body > div { clear:both; } " @@ -222,16 +237,16 @@ class Logger { "max-width: 800px; " "} " ".body > .category, .body > .message { " - "color: #8bc34a;" + "color: #00994d;" "} " ".world > .category, .world > .message { " - "color: #4f9fcf; " + "color: #3477DB; " "} " ".joint .category, .joint > .message { " - "color: #aa00ff; " + "color: #bf8040; " "} " ".proxyshape .category, .proxyshape > .message { " - "color: #009933; " + "color: #9933ff; " "} " ".warning { " "color: #ff9900 !important; " @@ -392,8 +407,7 @@ class Logger { /// Write a message into the output stream virtual void write(const time_t& time, const std::string& message, Level level, Category category) override { - mOutputStream << std::put_time(std::localtime(&time), "%Y-%m-%d %X") << ": "; - mOutputStream << message << std::endl << std::flush; + mOutputStream << formatter->format(time, message, level, category) << std::endl << std::flush; } }; @@ -408,6 +422,9 @@ class Logger { /// Map a log format to the given formatter object Map mFormatters; + /// Mutex + std::mutex mMutex; + // -------------------- Methods -------------------- // /// Return the corresponding formatter From cd897f1151321a9dc388d8c887fd9e38abab7c87 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 29 Mar 2018 07:16:50 +0200 Subject: [PATCH 188/248] Fix compilation errors when logs or profiling is disabled --- src/engine/CollisionWorld.cpp | 6 +++++- src/utils/Logger.h | 2 +- src/utils/Profiler.h | 17 +++++++++-------- 3 files changed, 15 insertions(+), 10 deletions(-) diff --git a/src/engine/CollisionWorld.cpp b/src/engine/CollisionWorld.cpp index d9b5f258..04cf252f 100644 --- a/src/engine/CollisionWorld.cpp +++ b/src/engine/CollisionWorld.cpp @@ -39,7 +39,7 @@ uint CollisionWorld::mNbWorlds = 0; CollisionWorld::CollisionWorld(const WorldSettings& worldSettings, Logger* logger, Profiler* profiler) : mConfig(worldSettings), mCollisionDetection(this, mMemoryManager), mBodies(mMemoryManager.getPoolAllocator()), mCurrentBodyId(0), mFreeBodiesIds(mMemoryManager.getPoolAllocator()), mEventListener(nullptr), mName(worldSettings.worldName), - mProfiler(profiler), mLogger(logger), mIsProfilerCreatedByUser(profiler != nullptr), + mIsProfilerCreatedByUser(profiler != nullptr), mIsLoggerCreatedByUser(logger != nullptr) { // Automatically generate a name for the world @@ -57,6 +57,8 @@ CollisionWorld::CollisionWorld(const WorldSettings& worldSettings, Logger* logge #ifdef IS_PROFILING_ACTIVE + mProfiler = profiler; + // If the user has not provided its own profiler, we create one if (mProfiler == nullptr) { @@ -74,6 +76,8 @@ CollisionWorld::CollisionWorld(const WorldSettings& worldSettings, Logger* logge #ifdef IS_LOGGING_ACTIVE + mLogger = logger; + // If the user has not provided its own logger, we create one if (mLogger == nullptr) { diff --git a/src/utils/Logger.h b/src/utils/Logger.h index 879909c7..0e7bb27d 100644 --- a/src/utils/Logger.h +++ b/src/utils/Logger.h @@ -463,7 +463,7 @@ class Logger { #else // If logger is not active // Empty macro in case logs are not enabled -#define RP3D_LOG(logger, level, message) +#define RP3D_LOG(logger, level, category, message) #endif diff --git a/src/utils/Profiler.h b/src/utils/Profiler.h index df64dfd6..57fbc84b 100644 --- a/src/utils/Profiler.h +++ b/src/utils/Profiler.h @@ -26,8 +26,6 @@ #ifndef REACTPHYSICS3D_PROFILER_H #define REACTPHYSICS3D_PROFILER_H -#ifdef IS_PROFILING_ACTIVE - // Libraries #include "configuration.h" #include "engine/Timer.h" @@ -381,9 +379,18 @@ class ProfileSample { } }; +#ifdef IS_PROFILING_ACTIVE + // Use this macro to start profile a block of code #define RP3D_PROFILE(name, profiler) ProfileSample profileSample(name, profiler) +#else // If profile is not active + +// Empty macro in case profiling is not active +#define RP3D_PROFILE(name, profiler) + +#endif + // Return true if we are at the root of the profiler tree inline bool ProfileNodeIterator::isRoot() { return (mCurrentParentNode->getParentNode() == nullptr); @@ -497,11 +504,5 @@ inline void Profiler::destroy() { } -#else // If profile is not active - -// Empty macro in case profiling is not active -#define RP3D_PROFILE(name, profiler) - -#endif #endif From d55c7e3b9118db8d25da748b7dc8b63c7f8d94e0 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Thu, 29 Mar 2018 07:40:24 +0200 Subject: [PATCH 189/248] Fix memory leaks in tests --- test/tests/collision/TestCollisionWorld.h | 2 +- test/tests/collision/TestPointInside.h | 3 ++- test/tests/collision/TestRaycast.h | 1 + 3 files changed, 4 insertions(+), 2 deletions(-) diff --git a/test/tests/collision/TestCollisionWorld.h b/test/tests/collision/TestCollisionWorld.h index 372b9dc5..3538c418 100644 --- a/test/tests/collision/TestCollisionWorld.h +++ b/test/tests/collision/TestCollisionWorld.h @@ -462,7 +462,7 @@ class TestCollisionWorld : public Test { delete mConvexMesh2PolyhedronMesh; delete mConvexMesh1PolygonVertexArray; delete mConvexMesh2PolygonVertexArray; - delete mConvexMeshPolygonFaces; + delete[] mConvexMeshPolygonFaces; delete mConcaveMeshShape; delete mConcaveTriangleMesh; diff --git a/test/tests/collision/TestPointInside.h b/test/tests/collision/TestPointInside.h index 540f9f03..6a7fe5b8 100644 --- a/test/tests/collision/TestPointInside.h +++ b/test/tests/collision/TestPointInside.h @@ -170,11 +170,12 @@ class TestPointInside : public Test { /// Destructor virtual ~TestPointInside() { + delete mWorld; delete mBoxShape; delete mSphereShape; delete mCapsuleShape; delete mConvexMeshShape; - delete mConvexMeshPolygonFaces; + delete[] mConvexMeshPolygonFaces; delete mConvexMeshPolygonVertexArray; delete mConvexMeshPolyhedronMesh; } diff --git a/test/tests/collision/TestRaycast.h b/test/tests/collision/TestRaycast.h index 70397ed0..916997bf 100644 --- a/test/tests/collision/TestRaycast.h +++ b/test/tests/collision/TestRaycast.h @@ -308,6 +308,7 @@ class TestRaycast : public Test { /// Destructor virtual ~TestRaycast() { + delete mWorld; delete mBoxShape; delete mSphereShape; delete mCapsuleShape; From 235b36ac478f269e75249faeeeb70e3353a1e8c2 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Tue, 3 Apr 2018 07:08:19 +0200 Subject: [PATCH 190/248] Fix issue with logger --- src/utils/Profiler.cpp | 25 ++++++++++++++----------- 1 file changed, 14 insertions(+), 11 deletions(-) diff --git a/src/utils/Profiler.cpp b/src/utils/Profiler.cpp index 12b449f1..96db0066 100644 --- a/src/utils/Profiler.cpp +++ b/src/utils/Profiler.cpp @@ -163,9 +163,23 @@ Profiler::Profiler() :mRootNode("Root", nullptr), mDestinations(MemoryManager::g // Destructor Profiler::~Profiler() { + + removeAllDestinations(); + destroy(); } +// Remove all logs destination previously set +void Profiler::removeAllDestinations() { + + // Delete all the destinations + for (uint i=0; i Date: Tue, 3 Apr 2018 22:45:20 +0200 Subject: [PATCH 191/248] Fix issue in List --- src/containers/List.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/containers/List.h b/src/containers/List.h index 2af3b76e..410e1746 100644 --- a/src/containers/List.h +++ b/src/containers/List.h @@ -273,7 +273,7 @@ class List { // Move the elements to fill in the empty slot char* dest = static_cast(mBuffer) + index * sizeof(T); char* src = dest + sizeof(T); - std::memcpy(static_cast(dest), static_cast(src), (mSize - index) * sizeof(T)); + std::memmove(static_cast(dest), static_cast(src), (mSize - index) * sizeof(T)); } // Return an iterator pointing to the element after the removed one From 1aebf7703adb5f933386a85e0ad91f2ab59f02e9 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 4 Apr 2018 07:14:58 +0200 Subject: [PATCH 192/248] Update the nanogui library that is used for the GUI of the testbed application --- testbed/nanogui/CMakeLists.txt | 436 +- testbed/nanogui/CONTRIBUTING.rst | 48 + testbed/nanogui/LICENSE.txt | 2 +- testbed/nanogui/README.rst | 217 + testbed/nanogui/ext/coro/LICENSE | 26 + testbed/nanogui/ext/coro/README | 6 + testbed/nanogui/ext/coro/coro.c | 803 + testbed/nanogui/ext/coro/coro.h | 425 + testbed/nanogui/ext/eigen/CMakeLists.txt | 299 +- testbed/nanogui/ext/eigen/COPYING.MINPACK | 104 +- testbed/nanogui/ext/eigen/CTestConfig.cmake | 8 +- testbed/nanogui/ext/eigen/Eigen/Array | 11 - .../nanogui/ext/eigen/Eigen/CMakeLists.txt | 2 +- testbed/nanogui/ext/eigen/Eigen/Cholesky | 17 +- .../nanogui/ext/eigen/Eigen/CholmodSupport | 13 +- testbed/nanogui/ext/eigen/Eigen/Core | 310 +- testbed/nanogui/ext/eigen/Eigen/Eigen | 2 +- testbed/nanogui/ext/eigen/Eigen/Eigen2Support | 95 - testbed/nanogui/ext/eigen/Eigen/Eigenvalues | 15 +- testbed/nanogui/ext/eigen/Eigen/Geometry | 60 +- testbed/nanogui/ext/eigen/Eigen/Householder | 7 + .../ext/eigen/Eigen/IterativeLinearSolvers | 24 +- testbed/nanogui/ext/eigen/Eigen/Jacobi | 7 + testbed/nanogui/ext/eigen/Eigen/LU | 21 +- testbed/nanogui/ext/eigen/Eigen/LeastSquares | 32 - testbed/nanogui/ext/eigen/Eigen/MetisSupport | 7 + .../nanogui/ext/eigen/Eigen/OrderingMethods | 7 + testbed/nanogui/ext/eigen/Eigen/PaStiXSupport | 12 +- .../nanogui/ext/eigen/Eigen/PardisoSupport | 9 +- testbed/nanogui/ext/eigen/Eigen/QR | 26 +- .../nanogui/ext/eigen/Eigen/QtAlignedMalloc | 10 +- testbed/nanogui/ext/eigen/Eigen/SPQRSupport | 11 +- testbed/nanogui/ext/eigen/Eigen/SVD | 28 +- testbed/nanogui/ext/eigen/Eigen/Sparse | 15 +- .../nanogui/ext/eigen/Eigen/SparseCholesky | 2 - testbed/nanogui/ext/eigen/Eigen/SparseCore | 35 +- testbed/nanogui/ext/eigen/Eigen/SparseLU | 3 - testbed/nanogui/ext/eigen/Eigen/SparseQR | 10 +- testbed/nanogui/ext/eigen/Eigen/StdDeque | 2 +- testbed/nanogui/ext/eigen/Eigen/StdList | 2 +- testbed/nanogui/ext/eigen/Eigen/StdVector | 2 +- .../nanogui/ext/eigen/Eigen/SuperLUSupport | 13 +- .../nanogui/ext/eigen/Eigen/UmfPackSupport | 12 +- .../ext/eigen/Eigen/src/CMakeLists.txt | 7 - .../eigen/Eigen/src/Cholesky/CMakeLists.txt | 6 - .../ext/eigen/Eigen/src/Cholesky/LDLT.h | 272 +- .../ext/eigen/Eigen/src/Cholesky/LLT.h | 171 +- .../src/Cholesky/{LLT_MKL.h => LLT_LAPACKE.h} | 47 +- .../Eigen/src/CholmodSupport/CMakeLists.txt | 6 - .../Eigen/src/CholmodSupport/CholmodSupport.h | 351 +- .../eigen/Eigen/src/Core/ArithmeticSequence.h | 350 + .../nanogui/ext/eigen/Eigen/src/Core/Array.h | 153 +- .../ext/eigen/Eigen/src/Core/ArrayBase.h | 80 +- .../ext/eigen/Eigen/src/Core/ArrayWrapper.h | 145 +- .../nanogui/ext/eigen/Eigen/src/Core/Assign.h | 535 +- .../eigen/Eigen/src/Core/AssignEvaluator.h | 935 + .../ext/eigen/Eigen/src/Core/Assign_MKL.h | 256 +- .../ext/eigen/Eigen/src/Core/BandMatrix.h | 61 +- .../nanogui/ext/eigen/Eigen/src/Core/Block.h | 279 +- .../ext/eigen/Eigen/src/Core/BooleanRedux.h | 68 +- .../ext/eigen/Eigen/src/Core/CMakeLists.txt | 10 - .../eigen/Eigen/src/Core/CommaInitializer.h | 44 +- .../eigen/Eigen/src/Core/ConditionEstimator.h | 175 + .../ext/eigen/Eigen/src/Core/CoreEvaluators.h | 1728 ++ .../ext/eigen/Eigen/src/Core/CoreIterators.h | 145 +- .../ext/eigen/Eigen/src/Core/CwiseBinaryOp.h | 168 +- .../ext/eigen/Eigen/src/Core/CwiseNullaryOp.h | 324 +- .../ext/eigen/Eigen/src/Core/CwiseTernaryOp.h | 197 + .../ext/eigen/Eigen/src/Core/CwiseUnaryOp.h | 111 +- .../ext/eigen/Eigen/src/Core/CwiseUnaryView.h | 81 +- .../ext/eigen/Eigen/src/Core/DenseBase.h | 390 +- .../eigen/Eigen/src/Core/DenseCoeffsBase.h | 281 +- .../ext/eigen/Eigen/src/Core/DenseStorage.h | 477 +- .../ext/eigen/Eigen/src/Core/Diagonal.h | 76 +- .../ext/eigen/Eigen/src/Core/DiagonalMatrix.h | 140 +- .../eigen/Eigen/src/Core/DiagonalProduct.h | 106 +- .../nanogui/ext/eigen/Eigen/src/Core/Dot.h | 170 +- .../ext/eigen/Eigen/src/Core/EigenBase.h | 49 +- .../ext/eigen/Eigen/src/Core/Flagged.h | 140 - .../eigen/Eigen/src/Core/ForceAlignedAccess.h | 24 +- .../ext/eigen/Eigen/src/Core/Functors.h | 985 - .../nanogui/ext/eigen/Eigen/src/Core/Fuzzy.h | 19 +- .../ext/eigen/Eigen/src/Core/GeneralProduct.h | 511 +- .../eigen/Eigen/src/Core/GenericPacketMath.h | 358 +- .../eigen/Eigen/src/Core/GlobalFunctions.h | 164 +- testbed/nanogui/ext/eigen/Eigen/src/Core/IO.h | 57 +- .../ext/eigen/Eigen/src/Core/IndexedView.h | 207 + .../ext/eigen/Eigen/src/Core/Inverse.h | 118 + .../nanogui/ext/eigen/Eigen/src/Core/Map.h | 110 +- .../ext/eigen/Eigen/src/Core/MapBase.h | 104 +- .../ext/eigen/Eigen/src/Core/MathFunctions.h | 1121 +- .../eigen/Eigen/src/Core/MathFunctionsImpl.h | 73 + .../nanogui/ext/eigen/Eigen/src/Core/Matrix.h | 248 +- .../ext/eigen/Eigen/src/Core/MatrixBase.h | 330 +- .../ext/eigen/Eigen/src/Core/NestByValue.h | 55 +- .../ext/eigen/Eigen/src/Core/NoAlias.h | 82 +- .../ext/eigen/Eigen/src/Core/NumTraits.h | 138 +- .../eigen/Eigen/src/Core/PermutationMatrix.h | 393 +- .../eigen/Eigen/src/Core/PlainObjectBase.h | 441 +- .../ext/eigen/Eigen/src/Core/Product.h | 186 + .../ext/eigen/Eigen/src/Core/ProductBase.h | 290 - .../eigen/Eigen/src/Core/ProductEvaluators.h | 1099 + .../nanogui/ext/eigen/Eigen/src/Core/Random.h | 60 +- .../nanogui/ext/eigen/Eigen/src/Core/Redux.h | 227 +- .../nanogui/ext/eigen/Eigen/src/Core/Ref.h | 204 +- .../ext/eigen/Eigen/src/Core/Replicate.h | 99 +- .../ext/eigen/Eigen/src/Core/ReturnByValue.h | 49 +- .../ext/eigen/Eigen/src/Core/Reverse.h | 213 +- .../nanogui/ext/eigen/Eigen/src/Core/Select.h | 22 +- .../eigen/Eigen/src/Core/SelfAdjointView.h | 300 +- .../eigen/Eigen/src/Core/SelfCwiseBinaryOp.h | 188 +- .../nanogui/ext/eigen/Eigen/src/Core/Solve.h | 188 + .../eigen/Eigen/src/Core/SolveTriangular.h | 76 +- .../ext/eigen/Eigen/src/Core/SolverBase.h | 130 + .../ext/eigen/Eigen/src/Core/StableNorm.h | 54 +- .../nanogui/ext/eigen/Eigen/src/Core/Stride.h | 25 +- .../nanogui/ext/eigen/Eigen/src/Core/Swap.h | 149 +- .../ext/eigen/Eigen/src/Core/Transpose.h | 194 +- .../ext/eigen/Eigen/src/Core/Transpositions.h | 245 +- .../eigen/Eigen/src/Core/TriangularMatrix.h | 1173 +- .../ext/eigen/Eigen/src/Core/VectorBlock.h | 27 +- .../ext/eigen/Eigen/src/Core/VectorwiseOp.h | 343 +- .../ext/eigen/Eigen/src/Core/Visitor.h | 74 +- .../eigen/Eigen/src/Core/arch/AVX/Complex.h | 483 + .../Eigen/src/Core/arch/AVX/MathFunctions.h | 439 + .../Eigen/src/Core/arch/AVX/PacketMath.h | 643 + .../Eigen/src/Core/arch/AVX/TypeCasting.h | 51 + .../src/Core/arch/AVX512/MathFunctions.h | 396 + .../Eigen/src/Core/arch/AVX512/PacketMath.h | 1286 + .../src/Core/arch/AltiVec/CMakeLists.txt | 6 - .../Eigen/src/Core/arch/AltiVec/Complex.h | 354 +- .../src/Core/arch/AltiVec/MathFunctions.h | 322 + .../Eigen/src/Core/arch/AltiVec/PacketMath.h | 798 +- .../eigen/Eigen/src/Core/arch/CMakeLists.txt | 4 - .../eigen/Eigen/src/Core/arch/CUDA/Complex.h | 103 + .../ext/eigen/Eigen/src/Core/arch/CUDA/Half.h | 604 + .../Eigen/src/Core/arch/CUDA/MathFunctions.h | 103 + .../Eigen/src/Core/arch/CUDA/PacketMath.h | 333 + .../Eigen/src/Core/arch/CUDA/PacketMathHalf.h | 1132 + .../Eigen/src/Core/arch/CUDA/TypeCasting.h | 212 + .../src/Core/arch/Default/CMakeLists.txt | 6 - .../Eigen/src/Core/arch/NEON/CMakeLists.txt | 6 - .../eigen/Eigen/src/Core/arch/NEON/Complex.h | 251 +- .../Eigen/src/Core/arch/NEON/MathFunctions.h | 91 + .../Eigen/src/Core/arch/NEON/PacketMath.h | 416 +- .../Eigen/src/Core/arch/SSE/CMakeLists.txt | 6 - .../eigen/Eigen/src/Core/arch/SSE/Complex.h | 99 +- .../Eigen/src/Core/arch/SSE/MathFunctions.h | 121 +- .../Eigen/src/Core/arch/SSE/PacketMath.h | 522 +- .../Eigen/src/Core/arch/SSE/TypeCasting.h | 77 + .../Eigen/src/Core/arch/ZVector/Complex.h | 394 + .../src/Core/arch/ZVector/MathFunctions.h | 137 + .../Eigen/src/Core/arch/ZVector/PacketMath.h | 945 + .../src/Core/functors/AssignmentFunctors.h | 168 + .../Eigen/src/Core/functors/BinaryFunctors.h | 482 + .../Eigen/src/Core/functors/NullaryFunctors.h | 189 + .../Eigen/src/Core/functors/StlFunctors.h | 132 + .../Eigen/src/Core/functors/TernaryFunctors.h | 25 + .../Eigen/src/Core/functors/UnaryFunctors.h | 830 + .../Eigen/src/Core/products/CMakeLists.txt | 6 - .../src/Core/products/CoeffBasedProduct.h | 439 - .../Core/products/GeneralBlockPanelKernel.h | 2314 +- .../src/Core/products/GeneralMatrixMatrix.h | 357 +- .../products/GeneralMatrixMatrixTriangular.h | 140 +- ...h => GeneralMatrixMatrixTriangular_BLAS.h} | 65 +- ...atrix_MKL.h => GeneralMatrixMatrix_BLAS.h} | 47 +- .../src/Core/products/GeneralMatrixVector.h | 715 +- ...ector_MKL.h => GeneralMatrixVector_BLAS.h} | 68 +- .../Eigen/src/Core/products/Parallelizer.h | 82 +- .../Core/products/SelfadjointMatrixMatrix.h | 341 +- ...x_MKL.h => SelfadjointMatrixMatrix_BLAS.h} | 136 +- .../Core/products/SelfadjointMatrixVector.h | 123 +- ...r_MKL.h => SelfadjointMatrixVector_BLAS.h} | 49 +- .../src/Core/products/SelfadjointProduct.h | 28 +- .../Core/products/SelfadjointRank2Update.h | 10 +- .../Core/products/TriangularMatrixMatrix.h | 138 +- ...ix_MKL.h => TriangularMatrixMatrix_BLAS.h} | 111 +- .../Core/products/TriangularMatrixVector.h | 174 +- ...or_MKL.h => TriangularMatrixVector_BLAS.h} | 96 +- .../Core/products/TriangularSolverMatrix.h | 82 +- ...ix_MKL.h => TriangularSolverMatrix_BLAS.h} | 56 +- .../Core/products/TriangularSolverVector.h | 24 +- .../ext/eigen/Eigen/src/Core/util/BlasUtil.h | 211 +- .../eigen/Eigen/src/Core/util/CMakeLists.txt | 6 - .../ext/eigen/Eigen/src/Core/util/Constants.h | 169 +- .../src/Core/util/DisableStupidWarnings.h | 43 +- .../Eigen/src/Core/util/ForwardDeclarations.h | 132 +- .../Eigen/src/Core/util/IndexedViewHelper.h | 187 + .../Eigen/src/Core/util/IntegralConstant.h | 270 + .../eigen/Eigen/src/Core/util/MKL_support.h | 82 +- .../ext/eigen/Eigen/src/Core/util/Macros.h | 865 +- .../ext/eigen/Eigen/src/Core/util/Memory.h | 568 +- .../ext/eigen/Eigen/src/Core/util/Meta.h | 415 +- .../src/Core/util/ReenableStupidWarnings.h | 13 + .../eigen/Eigen/src/Core/util/StaticAssert.h | 40 +- .../eigen/Eigen/src/Core/util/SymbolicIndex.h | 300 + .../ext/eigen/Eigen/src/Core/util/XprHelper.h | 584 +- .../ext/eigen/Eigen/src/Eigen2Support/Block.h | 126 - .../Eigen/src/Eigen2Support/CMakeLists.txt | 8 - .../ext/eigen/Eigen/src/Eigen2Support/Cwise.h | 192 - .../Eigen/src/Eigen2Support/CwiseOperators.h | 298 - .../src/Eigen2Support/Geometry/AlignedBox.h | 159 - .../Eigen/src/Eigen2Support/Geometry/All.h | 115 - .../src/Eigen2Support/Geometry/AngleAxis.h | 214 - .../src/Eigen2Support/Geometry/CMakeLists.txt | 6 - .../src/Eigen2Support/Geometry/Hyperplane.h | 254 - .../Eigen2Support/Geometry/ParametrizedLine.h | 141 - .../src/Eigen2Support/Geometry/Quaternion.h | 495 - .../src/Eigen2Support/Geometry/Rotation2D.h | 145 - .../src/Eigen2Support/Geometry/RotationBase.h | 123 - .../src/Eigen2Support/Geometry/Scaling.h | 167 - .../src/Eigen2Support/Geometry/Transform.h | 786 - .../src/Eigen2Support/Geometry/Translation.h | 184 - .../ext/eigen/Eigen/src/Eigen2Support/LU.h | 120 - .../ext/eigen/Eigen/src/Eigen2Support/Lazy.h | 71 - .../Eigen/src/Eigen2Support/LeastSquares.h | 169 - .../eigen/Eigen/src/Eigen2Support/Macros.h | 20 - .../Eigen/src/Eigen2Support/MathFunctions.h | 57 - .../eigen/Eigen/src/Eigen2Support/Memory.h | 45 - .../ext/eigen/Eigen/src/Eigen2Support/Meta.h | 75 - .../ext/eigen/Eigen/src/Eigen2Support/Minor.h | 117 - .../ext/eigen/Eigen/src/Eigen2Support/QR.h | 67 - .../ext/eigen/Eigen/src/Eigen2Support/SVD.h | 637 - .../src/Eigen2Support/TriangularSolver.h | 42 - .../Eigen/src/Eigen2Support/VectorBlock.h | 94 - .../Eigen/src/Eigenvalues/CMakeLists.txt | 6 - .../src/Eigenvalues/ComplexEigenSolver.h | 33 +- .../Eigen/src/Eigenvalues/ComplexSchur.h | 19 +- ...plexSchur_MKL.h => ComplexSchur_LAPACKE.h} | 41 +- .../eigen/Eigen/src/Eigenvalues/EigenSolver.h | 122 +- .../src/Eigenvalues/GeneralizedEigenSolver.h | 206 +- .../GeneralizedSelfAdjointEigenSolver.h | 3 +- .../src/Eigenvalues/HessenbergDecomposition.h | 15 +- .../src/Eigenvalues/MatrixBaseEigenvalues.h | 4 +- .../ext/eigen/Eigen/src/Eigenvalues/RealQZ.h | 58 +- .../eigen/Eigen/src/Eigenvalues/RealSchur.h | 51 +- .../{RealSchur_MKL.h => RealSchur_LAPACKE.h} | 42 +- .../src/Eigenvalues/SelfAdjointEigenSolver.h | 536 +- ...MKL.h => SelfAdjointEigenSolver_LAPACKE.h} | 42 +- .../src/Eigenvalues/Tridiagonalization.h | 39 +- .../ext/eigen/Eigen/src/Geometry/AlignedBox.h | 169 +- .../ext/eigen/Eigen/src/Geometry/AngleAxis.h | 92 +- .../eigen/Eigen/src/Geometry/CMakeLists.txt | 8 - .../eigen/Eigen/src/Geometry/EulerAngles.h | 22 +- .../eigen/Eigen/src/Geometry/Homogeneous.h | 290 +- .../ext/eigen/Eigen/src/Geometry/Hyperplane.h | 64 +- .../eigen/Eigen/src/Geometry/OrthoMethods.h | 58 +- .../Eigen/src/Geometry/ParametrizedLine.h | 99 +- .../ext/eigen/Eigen/src/Geometry/Quaternion.h | 243 +- .../ext/eigen/Eigen/src/Geometry/Rotation2D.h | 85 +- .../eigen/Eigen/src/Geometry/RotationBase.h | 48 +- .../ext/eigen/Eigen/src/Geometry/Scaling.h | 38 +- .../ext/eigen/Eigen/src/Geometry/Transform.h | 321 +- .../eigen/Eigen/src/Geometry/Translation.h | 60 +- .../ext/eigen/Eigen/src/Geometry/Umeyama.h | 19 +- .../Eigen/src/Geometry/arch/CMakeLists.txt | 6 - .../Eigen/src/Geometry/arch/Geometry_SSE.h | 56 +- .../Eigen/src/Householder/BlockHouseholder.h | 77 +- .../Eigen/src/Householder/CMakeLists.txt | 6 - .../eigen/Eigen/src/Householder/Householder.h | 7 +- .../src/Householder/HouseholderSequence.h | 55 +- .../BasicPreconditioners.h | 118 +- .../src/IterativeLinearSolvers/BiCGSTAB.h | 115 +- .../src/IterativeLinearSolvers/CMakeLists.txt | 6 - .../ConjugateGradient.h | 162 +- .../IncompleteCholesky.h | 400 + .../IterativeLinearSolvers/IncompleteLUT.h | 153 +- .../IterativeSolverBase.h | 314 +- .../LeastSquareConjugateGradient.h | 216 + .../IterativeLinearSolvers/SolveWithGuess.h | 115 + .../ext/eigen/Eigen/src/Jacobi/CMakeLists.txt | 6 - .../ext/eigen/Eigen/src/Jacobi/Jacobi.h | 34 +- .../ext/eigen/Eigen/src/LU/CMakeLists.txt | 8 - .../ext/eigen/Eigen/src/LU/Determinant.h | 2 +- .../ext/eigen/Eigen/src/LU/FullPivLU.h | 316 +- .../Eigen/src/LU/{Inverse.h => InverseImpl.h} | 81 +- .../ext/eigen/Eigen/src/LU/PartialPivLU.h | 256 +- ...tialPivLU_MKL.h => PartialPivLU_LAPACKE.h} | 26 +- .../eigen/Eigen/src/LU/arch/CMakeLists.txt | 6 - .../ext/eigen/Eigen/src/LU/arch/Inverse_SSE.h | 47 +- .../Eigen/src/MetisSupport/CMakeLists.txt | 6 - .../Eigen/src/MetisSupport/MetisSupport.h | 18 +- .../ext/eigen/Eigen/src/OrderingMethods/Amd.h | 104 +- .../Eigen/src/OrderingMethods/CMakeLists.txt | 6 - .../Eigen/src/OrderingMethods/Eigen_Colamd.h | 423 +- .../Eigen/src/OrderingMethods/Ordering.h | 51 +- .../Eigen/src/PaStiXSupport/CMakeLists.txt | 6 - .../Eigen/src/PaStiXSupport/PaStiXSupport.h | 155 +- .../Eigen/src/PardisoSupport/CMakeLists.txt | 6 - .../Eigen/src/PardisoSupport/PardisoSupport.h | 249 +- .../ext/eigen/Eigen/src/QR/CMakeLists.txt | 6 - .../eigen/Eigen/src/QR/ColPivHouseholderQR.h | 318 +- ...QR_MKL.h => ColPivHouseholderQR_LAPACKE.h} | 48 +- .../src/QR/CompleteOrthogonalDecomposition.h | 562 + .../eigen/Eigen/src/QR/FullPivHouseholderQR.h | 197 +- .../ext/eigen/Eigen/src/QR/HouseholderQR.h | 204 +- ...holderQR_MKL.h => HouseholderQR_LAPACKE.h} | 45 +- .../Eigen/src/SPQRSupport/CMakeLists.txt | 6 - .../src/SPQRSupport/SuiteSparseQRSupport.h | 169 +- .../nanogui/ext/eigen/Eigen/src/SVD/BDCSVD.h | 1230 + .../ext/eigen/Eigen/src/SVD/CMakeLists.txt | 6 - .../ext/eigen/Eigen/src/SVD/JacobiSVD.h | 381 +- .../{JacobiSVD_MKL.h => JacobiSVD_LAPACKE.h} | 52 +- .../{unsupported => }/Eigen/src/SVD/SVDBase.h | 198 +- .../Eigen/src/SVD/UpperBidiagonalization.h | 328 +- .../Eigen/src/SparseCholesky/CMakeLists.txt | 6 - .../src/SparseCholesky/SimplicialCholesky.h | 272 +- .../SparseCholesky/SimplicialCholesky_impl.h | 34 +- .../eigen/Eigen/src/SparseCore/AmbiVector.h | 98 +- .../eigen/Eigen/src/SparseCore/CMakeLists.txt | 6 - .../Eigen/src/SparseCore/CompressedStorage.h | 139 +- .../ConservativeSparseSparseProduct.h | 214 +- .../Eigen/src/SparseCore/MappedSparseMatrix.h | 164 +- .../eigen/Eigen/src/SparseCore/SparseAssign.h | 216 + .../eigen/Eigen/src/SparseCore/SparseBlock.h | 664 +- .../Eigen/src/SparseCore/SparseColEtree.h | 44 +- .../src/SparseCore/SparseCompressedBase.h | 357 + .../src/SparseCore/SparseCwiseBinaryOp.h | 689 +- .../Eigen/src/SparseCore/SparseCwiseUnaryOp.h | 155 +- .../Eigen/src/SparseCore/SparseDenseProduct.h | 429 +- .../src/SparseCore/SparseDiagonalProduct.h | 234 +- .../eigen/Eigen/src/SparseCore/SparseDot.h | 17 +- .../eigen/Eigen/src/SparseCore/SparseFuzzy.h | 29 +- .../eigen/Eigen/src/SparseCore/SparseMap.h | 305 + .../eigen/Eigen/src/SparseCore/SparseMatrix.h | 646 +- .../Eigen/src/SparseCore/SparseMatrixBase.h | 291 +- .../Eigen/src/SparseCore/SparsePermutation.h | 170 +- .../Eigen/src/SparseCore/SparseProduct.h | 291 +- .../eigen/Eigen/src/SparseCore/SparseRedux.h | 12 +- .../eigen/Eigen/src/SparseCore/SparseRef.h | 397 + .../src/SparseCore/SparseSelfAdjointView.h | 568 +- .../Eigen/src/SparseCore/SparseSolverBase.h | 124 + .../SparseSparseProductWithPruning.h | 88 +- .../Eigen/src/SparseCore/SparseTranspose.h | 99 +- .../src/SparseCore/SparseTriangularView.h | 268 +- .../eigen/Eigen/src/SparseCore/SparseUtil.h | 105 +- .../eigen/Eigen/src/SparseCore/SparseVector.h | 219 +- .../eigen/Eigen/src/SparseCore/SparseView.h | 240 +- .../Eigen/src/SparseCore/TriangularSolver.h | 119 +- .../eigen/Eigen/src/SparseLU/CMakeLists.txt | 6 - .../ext/eigen/Eigen/src/SparseLU/SparseLU.h | 300 +- .../eigen/Eigen/src/SparseLU/SparseLUImpl.h | 12 +- .../Eigen/src/SparseLU/SparseLU_Memory.h | 19 +- .../Eigen/src/SparseLU/SparseLU_Structs.h | 3 +- .../src/SparseLU/SparseLU_SupernodalMatrix.h | 73 +- .../eigen/Eigen/src/SparseLU/SparseLU_Utils.h | 10 +- .../Eigen/src/SparseLU/SparseLU_column_bmod.h | 11 +- .../Eigen/src/SparseLU/SparseLU_column_dfs.h | 38 +- .../src/SparseLU/SparseLU_copy_to_ucol.h | 7 +- .../Eigen/src/SparseLU/SparseLU_gemm_kernel.h | 93 +- .../src/SparseLU/SparseLU_heap_relax_snode.h | 21 +- .../Eigen/src/SparseLU/SparseLU_kernel_bmod.h | 56 +- .../Eigen/src/SparseLU/SparseLU_panel_bmod.h | 14 +- .../Eigen/src/SparseLU/SparseLU_panel_dfs.h | 44 +- .../Eigen/src/SparseLU/SparseLU_pivotL.h | 25 +- .../Eigen/src/SparseLU/SparseLU_pruneL.h | 7 +- .../Eigen/src/SparseLU/SparseLU_relax_snode.h | 12 +- .../eigen/Eigen/src/SparseQR/CMakeLists.txt | 6 - .../ext/eigen/Eigen/src/SparseQR/SparseQR.h | 187 +- .../eigen/Eigen/src/StlSupport/CMakeLists.txt | 6 - .../ext/eigen/Eigen/src/StlSupport/StdDeque.h | 20 +- .../ext/eigen/Eigen/src/StlSupport/StdList.h | 22 +- .../eigen/Eigen/src/StlSupport/StdVector.h | 5 + .../ext/eigen/Eigen/src/StlSupport/details.h | 16 +- .../Eigen/src/SuperLUSupport/CMakeLists.txt | 6 - .../Eigen/src/SuperLUSupport/SuperLUSupport.h | 209 +- .../Eigen/src/UmfPackSupport/CMakeLists.txt | 6 - .../Eigen/src/UmfPackSupport/UmfPackSupport.h | 318 +- .../ext/eigen/Eigen/src/misc/CMakeLists.txt | 6 - .../nanogui/ext/eigen/Eigen/src/misc/Image.h | 2 - .../nanogui/ext/eigen/Eigen/src/misc/Kernel.h | 4 +- .../ext/eigen/Eigen/src/misc/RealSvd2x2.h | 55 + .../nanogui/ext/eigen/Eigen/src/misc/Solve.h | 76 - .../ext/eigen/Eigen/src/misc/SparseSolve.h | 128 - .../nanogui/ext/eigen/Eigen/src/misc/blas.h | 404 +- .../nanogui/ext/eigen/Eigen/src/misc/lapack.h | 152 + .../ext/eigen/Eigen/src/misc/lapacke.h | 16292 +++++++++++++ .../eigen/Eigen/src/misc/lapacke_mangling.h | 17 + .../Eigen/src/plugins/ArrayCwiseBinaryOps.h | 241 +- .../Eigen/src/plugins/ArrayCwiseUnaryOps.h | 522 +- .../eigen/Eigen/src/plugins/BlockMethods.h | 1575 +- .../eigen/Eigen/src/plugins/CMakeLists.txt | 6 - .../Eigen/src/plugins/CommonCwiseBinaryOps.h | 75 +- .../Eigen/src/plugins/CommonCwiseUnaryOps.h | 193 +- .../Eigen/src/plugins/IndexedViewMethods.h | 267 + .../Eigen/src/plugins/MatrixCwiseBinaryOps.h | 42 +- .../Eigen/src/plugins/MatrixCwiseUnaryOps.h | 122 +- testbed/nanogui/ext/eigen/README.md | 3 + testbed/nanogui/ext/eigen/bench/BenchTimer.h | 10 +- .../eigen/bench/analyze-blocking-sizes.cpp | 876 + .../nanogui/ext/eigen/bench/benchCholesky.cpp | 16 +- .../nanogui/ext/eigen/bench/bench_gemm.cpp | 117 +- .../nanogui/ext/eigen/bench/bench_norm.cpp | 117 +- .../eigen/bench/benchmark-blocking-sizes.cpp | 677 + .../ext/eigen/bench/btl/CMakeLists.txt | 31 +- .../eigen/bench/btl/actions/action_axpby.hh | 2 +- .../eigen/bench/btl/actions/action_axpy.hh | 2 +- .../eigen/bench/btl/actions/basic_actions.hh | 2 +- .../ext/eigen/bench/btl/cmake/FindACML.cmake | 2 + .../ext/eigen/bench/btl/cmake/FindATLAS.cmake | 26 +- .../ext/eigen/bench/btl/cmake/FindBLAZE.cmake | 31 + .../ext/eigen/bench/btl/cmake/FindCBLAS.cmake | 1 + .../ext/eigen/bench/btl/cmake/FindGOTO.cmake | 15 - .../ext/eigen/bench/btl/cmake/FindGOTO2.cmake | 25 - .../eigen/bench/btl/cmake/FindOPENBLAS.cmake | 17 + .../eigen/bench/btl/data/action_settings.txt | 34 +- .../bench/btl/data/perlib_plot_settings.txt | 4 +- .../eigen/bench/btl/generic_bench/bench.hh | 4 +- .../btl/generic_bench/bench_parameter.hh | 4 +- .../ext/eigen/bench/btl/generic_bench/btl.hh | 17 +- .../btl/generic_bench/init/init_function.hh | 8 +- .../btl/generic_bench/init/init_matrix.hh | 10 +- .../btl/generic_bench/init/init_vector.hh | 2 +- .../timers/portable_perf_analyzer.hh | 2 +- .../generic_bench/timers/portable_timer.hh | 46 +- .../btl/generic_bench/utils/size_lin_log.hh | 2 +- .../eigen/bench/btl/libs/BLAS/CMakeLists.txt | 29 +- .../btl/libs/BLAS/blas_interface_impl.hh | 12 +- .../bench/btl/libs/BLAS/c_interface_base.h | 6 +- .../ext/eigen/bench/btl/libs/BLAS/main.cpp | 12 +- .../eigen/bench/btl/libs/STL/STL_interface.hh | 28 +- .../eigen/bench/btl/libs/blaze/CMakeLists.txt | 13 + .../bench/btl/libs/blaze/blaze_interface.hh | 141 + .../ext/eigen/bench/btl/libs/blaze/main.cpp | 40 + .../bench/btl/libs/eigen2/eigen2_interface.hh | 2 +- .../bench/btl/libs/eigen3/eigen3_interface.hh | 64 +- .../eigen/bench/btl/libs/eigen3/main_adv.cpp | 14 +- .../bench/btl/libs/eigen3/main_matmat.cpp | 2 +- .../bench/btl/libs/tensors/CMakeLists.txt | 44 + .../bench/btl/libs/tensors/main_linear.cpp | 23 + .../bench/btl/libs/tensors/main_matmat.cpp | 21 + .../bench/btl/libs/tensors/main_vecmat.cpp | 21 + .../btl/libs/tensors/tensor_interface.hh | 105 + .../nanogui/ext/eigen/bench/dense_solvers.cpp | 186 + testbed/nanogui/ext/eigen/bench/eig33.cpp | 57 +- .../bench/perf_monitoring/changesets.txt | 71 + .../ext/eigen/bench/perf_monitoring/gemm.cpp | 12 + .../eigen/bench/perf_monitoring/gemm_common.h | 67 + .../bench/perf_monitoring/gemm_settings.txt | 15 + .../perf_monitoring/gemm_square_settings.txt | 11 + .../ext/eigen/bench/perf_monitoring/gemv.cpp | 12 + .../eigen/bench/perf_monitoring/gemv_common.h | 69 + .../bench/perf_monitoring/gemv_settings.txt | 11 + .../perf_monitoring/gemv_square_settings.txt | 13 + .../ext/eigen/bench/perf_monitoring/gemvt.cpp | 12 + .../eigen/bench/perf_monitoring/lazy_gemm.cpp | 101 + .../perf_monitoring/lazy_gemm_settings.txt | 15 + .../ext/eigen/bench/perf_monitoring/llt.cpp | 15 + .../eigen/bench/perf_monitoring/make_plot.sh | 98 + .../resources/chart_footer.html | 37 + .../resources/chart_header.html | 46 + .../perf_monitoring/resources/footer.html | 3 + .../perf_monitoring/resources/header.html | 42 + .../bench/perf_monitoring/resources/s1.js | 1 + .../bench/perf_monitoring/resources/s2.js | 1 + .../ext/eigen/bench/perf_monitoring/run.sh | 172 + .../ext/eigen/bench/perf_monitoring/runall.sh | 63 + .../eigen/bench/perf_monitoring/trmv_lo.cpp | 12 + .../eigen/bench/perf_monitoring/trmv_lot.cpp | 12 + .../eigen/bench/perf_monitoring/trmv_up.cpp | 12 + .../eigen/bench/perf_monitoring/trmv_upt.cpp | 12 + .../ext/eigen/bench/spbench/CMakeLists.txt | 2 +- .../ext/eigen/bench/spbench/spbenchstyle.h | 3 +- .../nanogui/ext/eigen/bench/tensors/README | 21 + .../ext/eigen/bench/tensors/benchmark.h | 49 + .../ext/eigen/bench/tensors/benchmark_main.cc | 237 + .../tensors/contraction_benchmarks_cpu.cc | 39 + .../eigen/bench/tensors/tensor_benchmarks.h | 478 + .../bench/tensors/tensor_benchmarks_cpu.cc | 168 + .../tensors/tensor_benchmarks_fp16_gpu.cu | 77 + .../bench/tensors/tensor_benchmarks_gpu.cu | 75 + .../bench/tensors/tensor_benchmarks_sycl.cc | 20 + testbed/nanogui/ext/eigen/blas/CMakeLists.txt | 35 +- .../eigen/blas/PackedTriangularMatrixVector.h | 4 +- testbed/nanogui/ext/eigen/blas/chbmv.f | 310 - testbed/nanogui/ext/eigen/blas/chpmv.f | 272 - testbed/nanogui/ext/eigen/blas/common.h | 44 +- testbed/nanogui/ext/eigen/blas/ctbmv.f | 366 - testbed/nanogui/ext/eigen/blas/double.cpp | 11 +- testbed/nanogui/ext/eigen/blas/drotm.f | 147 - testbed/nanogui/ext/eigen/blas/drotmg.f | 206 - testbed/nanogui/ext/eigen/blas/dsbmv.f | 304 - testbed/nanogui/ext/eigen/blas/dspmv.f | 265 - testbed/nanogui/ext/eigen/blas/dtbmv.f | 335 - testbed/nanogui/ext/eigen/blas/f2c/chbmv.c | 487 + testbed/nanogui/ext/eigen/blas/f2c/chpmv.c | 438 + .../nanogui/ext/eigen/blas/f2c/complexdots.c | 84 + testbed/nanogui/ext/eigen/blas/f2c/ctbmv.c | 647 + testbed/nanogui/ext/eigen/blas/f2c/d_cnjg.c | 6 + .../nanogui/ext/eigen/blas/f2c/datatypes.h | 24 + testbed/nanogui/ext/eigen/blas/f2c/drotm.c | 215 + testbed/nanogui/ext/eigen/blas/f2c/drotmg.c | 293 + testbed/nanogui/ext/eigen/blas/f2c/dsbmv.c | 366 + testbed/nanogui/ext/eigen/blas/f2c/dspmv.c | 316 + testbed/nanogui/ext/eigen/blas/f2c/dtbmv.c | 428 + testbed/nanogui/ext/eigen/blas/f2c/lsame.c | 117 + testbed/nanogui/ext/eigen/blas/f2c/r_cnjg.c | 6 + testbed/nanogui/ext/eigen/blas/f2c/srotm.c | 216 + testbed/nanogui/ext/eigen/blas/f2c/srotmg.c | 295 + testbed/nanogui/ext/eigen/blas/f2c/ssbmv.c | 368 + testbed/nanogui/ext/eigen/blas/f2c/sspmv.c | 316 + testbed/nanogui/ext/eigen/blas/f2c/stbmv.c | 428 + testbed/nanogui/ext/eigen/blas/f2c/zhbmv.c | 488 + testbed/nanogui/ext/eigen/blas/f2c/zhpmv.c | 438 + testbed/nanogui/ext/eigen/blas/f2c/ztbmv.c | 647 + .../eigen/blas/{ => fortran}/complexdots.f | 0 .../nanogui/ext/eigen/blas/level1_cplx_impl.h | 54 +- testbed/nanogui/ext/eigen/blas/level1_impl.h | 49 +- .../nanogui/ext/eigen/blas/level1_real_impl.h | 22 +- .../nanogui/ext/eigen/blas/level2_cplx_impl.h | 116 +- testbed/nanogui/ext/eigen/blas/level2_impl.h | 427 +- .../nanogui/ext/eigen/blas/level2_real_impl.h | 168 +- testbed/nanogui/ext/eigen/blas/level3_impl.h | 458 +- testbed/nanogui/ext/eigen/blas/lsame.f | 85 - testbed/nanogui/ext/eigen/blas/single.cpp | 2 +- testbed/nanogui/ext/eigen/blas/srotm.f | 148 - testbed/nanogui/ext/eigen/blas/srotmg.f | 208 - testbed/nanogui/ext/eigen/blas/ssbmv.f | 306 - testbed/nanogui/ext/eigen/blas/sspmv.f | 265 - testbed/nanogui/ext/eigen/blas/stbmv.f | 335 - .../nanogui/ext/eigen/blas/testing/cblat1.f | 83 +- .../nanogui/ext/eigen/blas/testing/cblat2.f | 188 +- .../nanogui/ext/eigen/blas/testing/cblat3.f | 185 +- .../nanogui/ext/eigen/blas/testing/dblat2.f | 186 +- .../nanogui/ext/eigen/blas/testing/dblat3.f | 168 +- .../nanogui/ext/eigen/blas/testing/sblat2.f | 186 +- .../nanogui/ext/eigen/blas/testing/sblat3.f | 168 +- .../nanogui/ext/eigen/blas/testing/zblat1.f | 83 +- .../nanogui/ext/eigen/blas/testing/zblat2.f | 188 +- .../nanogui/ext/eigen/blas/testing/zblat3.f | 189 +- testbed/nanogui/ext/eigen/blas/xerbla.cpp | 6 +- testbed/nanogui/ext/eigen/blas/zhbmv.f | 310 - testbed/nanogui/ext/eigen/blas/zhpmv.f | 272 - testbed/nanogui/ext/eigen/blas/ztbmv.f | 366 - .../ext/eigen/cmake/Eigen3Config.cmake.in | 21 + .../eigen/cmake/Eigen3ConfigLegacy.cmake.in | 30 + .../eigen/cmake/EigenConfigureTesting.cmake | 62 +- .../eigen/cmake/EigenDetermineOSVersion.cmake | 2 +- .../cmake/EigenDetermineVSServicePack.cmake | 18 +- .../ext/eigen/cmake/EigenTesting.cmake | 357 +- .../ext/eigen/cmake/EigenUninstall.cmake | 40 + .../nanogui/ext/eigen/cmake/FindAdolc.cmake | 2 +- .../ext/eigen/cmake/FindComputeCpp.cmake | 245 + .../nanogui/ext/eigen/cmake/FindEigen3.cmake | 28 +- .../nanogui/ext/eigen/cmake/FindMetis.cmake | 2 +- .../nanogui/ext/eigen/cmake/FindSPQR.cmake | 7 +- .../nanogui/ext/eigen/cmake/FindSuperLU.cmake | 79 +- .../nanogui/ext/eigen/cmake/FindUmfpack.cmake | 21 +- .../nanogui/ext/eigen/cmake/FindXsmm.cmake | 25 + .../nanogui/ext/eigen/cmake/UseEigen3.cmake | 6 + .../ext/eigen/cmake/language_support.cmake | 3 +- .../nanogui/ext/eigen/debug/gdb/printers.py | 174 +- .../nanogui/ext/eigen/debug/msvc/eigen.natvis | 470 +- .../eigen/debug/msvc/eigen_autoexp_part.dat | 590 +- .../nanogui/ext/eigen/demos/CMakeLists.txt | 13 + .../ext/eigen/demos/mandelbrot/CMakeLists.txt | 21 + .../nanogui/ext/eigen/demos/mandelbrot/README | 10 + .../ext/eigen/demos/mandelbrot/mandelbrot.cpp | 213 + .../ext/eigen/demos/mandelbrot/mandelbrot.h | 71 + .../ext/eigen/demos/mix_eigen_and_c/README | 9 + .../demos/mix_eigen_and_c/binary_library.cpp | 185 + .../demos/mix_eigen_and_c/binary_library.h | 71 + .../ext/eigen/demos/mix_eigen_and_c/example.c | 65 + .../ext/eigen/demos/opengl/CMakeLists.txt | 28 + testbed/nanogui/ext/eigen/demos/opengl/README | 13 + .../nanogui/ext/eigen/demos/opengl/camera.cpp | 264 + .../nanogui/ext/eigen/demos/opengl/camera.h | 118 + .../ext/eigen/demos/opengl/gpuhelper.cpp | 126 + .../ext/eigen/demos/opengl/gpuhelper.h | 207 + .../ext/eigen/demos/opengl/icosphere.cpp | 120 + .../ext/eigen/demos/opengl/icosphere.h | 30 + .../eigen/demos/opengl/quaternion_demo.cpp | 656 + .../ext/eigen/demos/opengl/quaternion_demo.h | 114 + .../ext/eigen/demos/opengl/trackball.cpp | 59 + .../ext/eigen/demos/opengl/trackball.h | 42 + .../ext/eigen/doc/A05_PortingFrom2To3.dox | 299 + .../ext/eigen/doc/AsciiQuickReference.txt | 215 + .../ext/eigen/doc/B01_Experimental.dox | 52 + testbed/nanogui/ext/eigen/doc/CMakeLists.txt | 112 + .../nanogui/ext/eigen/doc/ClassHierarchy.dox | 129 + .../eigen/doc/CoeffwiseMathFunctionsTable.dox | 525 + .../doc/CustomizingEigen_CustomScalar.dox | 120 + .../doc/CustomizingEigen_InheritingMatrix.dox | 34 + .../doc/CustomizingEigen_NullaryExpr.dox | 86 + .../eigen/doc/CustomizingEigen_Plugins.dox | 69 + .../eigen/doc/DenseDecompositionBenchmark.dox | 42 + testbed/nanogui/ext/eigen/doc/Doxyfile.in | 1898 ++ .../eigen/doc/Eigen_Silly_Professor_64x64.png | Bin 0 -> 8355 bytes .../ext/eigen/doc/FixedSizeVectorizable.dox | 38 + .../eigen/doc/FunctionsTakingEigenTypes.dox | 217 + .../nanogui/ext/eigen/doc/HiPerformance.dox | 128 + .../ext/eigen/doc/InplaceDecomposition.dox | 115 + .../ext/eigen/doc/InsideEigenExample.dox | 495 + .../nanogui/ext/eigen/doc/LeastSquares.dox | 70 + testbed/nanogui/ext/eigen/doc/Manual.dox | 189 + .../ext/eigen/doc/MatrixfreeSolverExample.dox | 20 + .../ext/eigen/doc/NewExpressionType.dox | 143 + testbed/nanogui/ext/eigen/doc/Overview.dox | 30 + .../nanogui/ext/eigen/doc/PassingByValue.dox | 40 + testbed/nanogui/ext/eigen/doc/Pitfalls.dox | 38 + .../ext/eigen/doc/PreprocessorDirectives.dox | 170 + .../nanogui/ext/eigen/doc/QuickReference.dox | 785 + .../nanogui/ext/eigen/doc/QuickStartGuide.dox | 100 + .../ext/eigen/doc/SparseLinearSystems.dox | 229 + .../ext/eigen/doc/SparseQuickReference.dox | 272 + .../nanogui/ext/eigen/doc/StlContainers.dox | 62 + .../nanogui/ext/eigen/doc/StorageOrders.dox | 86 + .../eigen/doc/StructHavingEigenMembers.dox | 190 + .../nanogui/ext/eigen/doc/TemplateKeyword.dox | 133 + .../nanogui/ext/eigen/doc/TopicAliasing.dox | 237 + .../nanogui/ext/eigen/doc/TopicAssertions.dox | 108 + .../nanogui/ext/eigen/doc/TopicCMakeGuide.dox | 56 + .../doc/TopicEigenExpressionTemplates.dox | 12 + .../ext/eigen/doc/TopicLazyEvaluation.dox | 65 + .../doc/TopicLinearAlgebraDecompositions.dox | 263 + .../ext/eigen/doc/TopicMultithreading.dox | 54 + .../nanogui/ext/eigen/doc/TopicResizing.dox | 11 + .../ext/eigen/doc/TopicScalarTypes.dox | 12 + .../ext/eigen/doc/TopicVectorization.dox | 9 + .../doc/TutorialAdvancedInitialization.dox | 162 + .../ext/eigen/doc/TutorialArrayClass.dox | 192 + .../ext/eigen/doc/TutorialBlockOperations.dox | 228 + .../ext/eigen/doc/TutorialGeometry.dox | 242 + .../ext/eigen/doc/TutorialLinearAlgebra.dox | 272 + .../ext/eigen/doc/TutorialMapClass.dox | 86 + .../eigen/doc/TutorialMatrixArithmetic.dox | 214 + .../ext/eigen/doc/TutorialMatrixClass.dox | 265 + ...TutorialReductionsVisitorsBroadcasting.dox | 266 + .../ext/eigen/doc/TutorialReshapeSlicing.dox | 65 + .../nanogui/ext/eigen/doc/TutorialSparse.dox | 365 + .../doc/TutorialSparse_example_details.dox | 4 + .../ext/eigen/doc/UnalignedArrayAssert.dox | 129 + .../ext/eigen/doc/UsingBlasLapackBackends.dox | 133 + .../nanogui/ext/eigen/doc/UsingIntelMKL.dox | 107 + testbed/nanogui/ext/eigen/doc/UsingNVCC.dox | 32 + .../ext/eigen/doc/WrongStackAlignment.dox | 56 + .../ext/eigen/doc/eigen_navtree_hacks.js | 240 + testbed/nanogui/ext/eigen/doc/eigendoxy.css | 221 + .../ext/eigen/doc/eigendoxy_footer.html.in | 36 + .../ext/eigen/doc/eigendoxy_header.html.in | 61 + .../ext/eigen/doc/eigendoxy_layout.xml.in | 178 + .../nanogui/ext/eigen/doc/eigendoxy_tabs.css | 59 + testbed/nanogui/ext/eigen/doc/examples/.krazy | 2 + .../ext/eigen/doc/examples/CMakeLists.txt | 21 + .../examples/CustomizingEigen_Inheritance.cpp | 30 + .../ext/eigen/doc/examples/Cwise_erf.cpp | 9 + .../ext/eigen/doc/examples/Cwise_erfc.cpp | 9 + .../ext/eigen/doc/examples/Cwise_lgamma.cpp | 9 + .../doc/examples/DenseBase_middleCols_int.cpp | 15 + .../doc/examples/DenseBase_middleRows_int.cpp | 15 + .../DenseBase_template_int_middleCols.cpp | 15 + .../DenseBase_template_int_middleRows.cpp | 15 + .../eigen/doc/examples/QuickStart_example.cpp | 14 + .../examples/QuickStart_example2_dynamic.cpp | 15 + .../examples/QuickStart_example2_fixed.cpp | 15 + .../doc/examples/TemplateKeyword_flexible.cpp | 22 + .../doc/examples/TemplateKeyword_simple.cpp | 20 + .../eigen/doc/examples/TutorialInplaceLU.cpp | 61 + .../examples/TutorialLinAlgComputeTwice.cpp | 23 + .../TutorialLinAlgExComputeSolveError.cpp | 14 + ...torialLinAlgExSolveColPivHouseholderQR.cpp | 17 + .../examples/TutorialLinAlgExSolveLDLT.cpp | 16 + .../TutorialLinAlgInverseDeterminant.cpp | 16 + .../examples/TutorialLinAlgRankRevealing.cpp | 20 + .../doc/examples/TutorialLinAlgSVDSolve.cpp | 15 + .../TutorialLinAlgSelfAdjointEigenSolver.cpp | 18 + .../examples/TutorialLinAlgSetThreshold.cpp | 16 + .../Tutorial_ArrayClass_accessors.cpp | 24 + .../examples/Tutorial_ArrayClass_addition.cpp | 23 + .../Tutorial_ArrayClass_cwise_other.cpp | 19 + .../examples/Tutorial_ArrayClass_interop.cpp | 22 + .../Tutorial_ArrayClass_interop_matrix.cpp | 26 + .../doc/examples/Tutorial_ArrayClass_mult.cpp | 16 + ...orial_BlockOperations_block_assignment.cpp | 18 + .../Tutorial_BlockOperations_colrow.cpp | 17 + .../Tutorial_BlockOperations_corner.cpp | 17 + .../Tutorial_BlockOperations_print_block.cpp | 20 + .../Tutorial_BlockOperations_vector.cpp | 14 + .../doc/examples/Tutorial_PartialLU_solve.cpp | 18 + ...ionsVisitorsBroadcasting_broadcast_1nn.cpp | 24 + ...sVisitorsBroadcasting_broadcast_simple.cpp | 21 + ...sBroadcasting_broadcast_simple_rowwise.cpp | 20 + ...ReductionsVisitorsBroadcasting_colwise.cpp | 13 + ...ReductionsVisitorsBroadcasting_maxnorm.cpp | 20 + ...nsVisitorsBroadcasting_reductions_bool.cpp | 21 + ...nsVisitorsBroadcasting_reductions_norm.cpp | 28 + ...rsBroadcasting_reductions_operatornorm.cpp | 18 + ...ReductionsVisitorsBroadcasting_rowwise.cpp | 13 + ...eductionsVisitorsBroadcasting_visitors.cpp | 26 + .../Tutorial_simple_example_dynamic_size.cpp | 22 + .../Tutorial_simple_example_fixed_size.cpp | 15 + .../ext/eigen/doc/examples/class_Block.cpp | 27 + .../doc/examples/class_CwiseBinaryOp.cpp | 18 + .../eigen/doc/examples/class_CwiseUnaryOp.cpp | 19 + .../examples/class_CwiseUnaryOp_ptrfun.cpp | 20 + .../eigen/doc/examples/class_FixedBlock.cpp | 27 + .../doc/examples/class_FixedVectorBlock.cpp | 27 + .../eigen/doc/examples/class_VectorBlock.cpp | 27 + .../examples/function_taking_eigenbase.cpp | 18 + .../doc/examples/function_taking_ref.cpp | 19 + .../ext/eigen/doc/examples/make_circulant.cpp | 11 + .../doc/examples/make_circulant.cpp.entry | 5 + .../doc/examples/make_circulant.cpp.evaluator | 32 + .../examples/make_circulant.cpp.expression | 20 + .../doc/examples/make_circulant.cpp.main | 8 + .../doc/examples/make_circulant.cpp.preamble | 4 + .../doc/examples/make_circulant.cpp.traits | 19 + .../eigen/doc/examples/make_circulant2.cpp | 52 + .../ext/eigen/doc/examples/matrixfree_cg.cpp | 128 + .../eigen/doc/examples/nullary_indexing.cpp | 66 + .../doc/examples/tut_arithmetic_add_sub.cpp | 22 + .../doc/examples/tut_arithmetic_dot_cross.cpp | 15 + .../examples/tut_arithmetic_matrix_mul.cpp | 19 + .../examples/tut_arithmetic_redux_basic.cpp | 16 + .../tut_arithmetic_scalar_mul_div.cpp | 17 + .../tut_matrix_coefficient_accessors.cpp | 18 + .../eigen/doc/examples/tut_matrix_resize.cpp | 18 + .../examples/tut_matrix_resize_fixed_size.cpp | 12 + testbed/nanogui/ext/eigen/doc/ftv2node.png | Bin 0 -> 86 bytes testbed/nanogui/ext/eigen/doc/ftv2pnode.png | Bin 0 -> 229 bytes testbed/nanogui/ext/eigen/doc/snippets/.krazy | 2 + .../doc/snippets/AngleAxis_mimic_euler.cpp | 5 + .../eigen/doc/snippets/BiCGSTAB_simple.cpp | 11 + .../doc/snippets/BiCGSTAB_step_by_step.cpp | 14 + .../ext/eigen/doc/snippets/CMakeLists.txt | 26 + .../snippets/ColPivHouseholderQR_solve.cpp | 8 + .../snippets/ComplexEigenSolver_compute.cpp | 16 + .../ComplexEigenSolver_eigenvalues.cpp | 4 + .../ComplexEigenSolver_eigenvectors.cpp | 4 + .../doc/snippets/ComplexSchur_compute.cpp | 6 + .../doc/snippets/ComplexSchur_matrixT.cpp | 4 + .../doc/snippets/ComplexSchur_matrixU.cpp | 4 + .../ext/eigen/doc/snippets/Cwise_abs.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_abs2.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_acos.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_arg.cpp | 3 + .../doc/snippets/Cwise_array_power_array.cpp | 4 + .../ext/eigen/doc/snippets/Cwise_asin.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_atan.cpp | 2 + .../eigen/doc/snippets/Cwise_boolean_and.cpp | 2 + .../eigen/doc/snippets/Cwise_boolean_not.cpp | 5 + .../eigen/doc/snippets/Cwise_boolean_or.cpp | 2 + .../eigen/doc/snippets/Cwise_boolean_xor.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_ceil.cpp | 3 + .../ext/eigen/doc/snippets/Cwise_cos.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_cosh.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_cube.cpp | 2 + .../eigen/doc/snippets/Cwise_equal_equal.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_exp.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_floor.cpp | 3 + .../ext/eigen/doc/snippets/Cwise_greater.cpp | 2 + .../doc/snippets/Cwise_greater_equal.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_inverse.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_isFinite.cpp | 5 + .../ext/eigen/doc/snippets/Cwise_isInf.cpp | 5 + .../ext/eigen/doc/snippets/Cwise_isNaN.cpp | 5 + .../ext/eigen/doc/snippets/Cwise_less.cpp | 2 + .../eigen/doc/snippets/Cwise_less_equal.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_log.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_log10.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_max.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_min.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_minus.cpp | 2 + .../eigen/doc/snippets/Cwise_minus_equal.cpp | 3 + .../eigen/doc/snippets/Cwise_not_equal.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_plus.cpp | 2 + .../eigen/doc/snippets/Cwise_plus_equal.cpp | 3 + .../ext/eigen/doc/snippets/Cwise_pow.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_product.cpp | 4 + .../ext/eigen/doc/snippets/Cwise_quotient.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_round.cpp | 3 + .../doc/snippets/Cwise_scalar_power_array.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_sign.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_sin.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_sinh.cpp | 2 + .../eigen/doc/snippets/Cwise_slash_equal.cpp | 3 + .../ext/eigen/doc/snippets/Cwise_sqrt.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_square.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_tan.cpp | 2 + .../ext/eigen/doc/snippets/Cwise_tanh.cpp | 2 + .../eigen/doc/snippets/Cwise_times_equal.cpp | 3 + .../doc/snippets/DenseBase_LinSpaced.cpp | 2 + .../doc/snippets/DenseBase_LinSpacedInt.cpp | 8 + .../doc/snippets/DenseBase_LinSpaced_seq.cpp | 2 + .../doc/snippets/DenseBase_setLinSpaced.cpp | 3 + .../snippets/DirectionWise_hnormalized.cpp | 7 + .../doc/snippets/DirectionWise_replicate.cpp | 4 + .../snippets/DirectionWise_replicate_int.cpp | 4 + .../EigenSolver_EigenSolver_MatrixType.cpp | 16 + .../doc/snippets/EigenSolver_compute.cpp | 6 + .../doc/snippets/EigenSolver_eigenvalues.cpp | 4 + .../doc/snippets/EigenSolver_eigenvectors.cpp | 4 + .../EigenSolver_pseudoEigenvectors.cpp | 9 + .../snippets/FullPivHouseholderQR_solve.cpp | 8 + .../eigen/doc/snippets/FullPivLU_image.cpp | 9 + .../eigen/doc/snippets/FullPivLU_kernel.cpp | 7 + .../eigen/doc/snippets/FullPivLU_solve.cpp | 11 + .../doc/snippets/GeneralizedEigenSolver.cpp | 7 + .../HessenbergDecomposition_compute.cpp | 6 + .../HessenbergDecomposition_matrixH.cpp | 8 + .../HessenbergDecomposition_packedMatrix.cpp | 9 + .../snippets/HouseholderQR_householderQ.cpp | 7 + .../doc/snippets/HouseholderQR_solve.cpp | 9 + ...ouseholderSequence_HouseholderSequence.cpp | 31 + .../ext/eigen/doc/snippets/IOFormat.cpp | 14 + .../eigen/doc/snippets/JacobiSVD_basic.cpp | 9 + .../eigen/doc/snippets/Jacobi_makeGivens.cpp | 6 + .../eigen/doc/snippets/Jacobi_makeJacobi.cpp | 8 + .../ext/eigen/doc/snippets/LLT_example.cpp | 12 + .../ext/eigen/doc/snippets/LLT_solve.cpp | 8 + .../snippets/LeastSquaresNormalEquations.cpp | 4 + .../ext/eigen/doc/snippets/LeastSquaresQR.cpp | 4 + .../eigen/doc/snippets/Map_general_stride.cpp | 5 + .../eigen/doc/snippets/Map_inner_stride.cpp | 5 + .../eigen/doc/snippets/Map_outer_stride.cpp | 3 + .../eigen/doc/snippets/Map_placement_new.cpp | 5 + .../ext/eigen/doc/snippets/Map_simple.cpp | 3 + .../eigen/doc/snippets/MatrixBase_adjoint.cpp | 3 + .../ext/eigen/doc/snippets/MatrixBase_all.cpp | 7 + .../snippets/MatrixBase_applyOnTheLeft.cpp | 7 + .../snippets/MatrixBase_applyOnTheRight.cpp | 9 + .../eigen/doc/snippets/MatrixBase_array.cpp | 4 + .../doc/snippets/MatrixBase_array_const.cpp | 4 + .../doc/snippets/MatrixBase_asDiagonal.cpp | 1 + .../doc/snippets/MatrixBase_block_int_int.cpp | 5 + .../MatrixBase_block_int_int_int_int.cpp | 5 + .../MatrixBase_bottomLeftCorner_int_int.cpp | 6 + .../MatrixBase_bottomRightCorner_int_int.cpp | 6 + .../snippets/MatrixBase_bottomRows_int.cpp | 6 + .../eigen/doc/snippets/MatrixBase_cast.cpp | 3 + .../ext/eigen/doc/snippets/MatrixBase_col.cpp | 3 + .../eigen/doc/snippets/MatrixBase_colwise.cpp | 5 + ...trixBase_computeInverseAndDetWithCheck.cpp | 13 + .../MatrixBase_computeInverseWithCheck.cpp | 11 + .../doc/snippets/MatrixBase_cwiseAbs.cpp | 4 + .../doc/snippets/MatrixBase_cwiseAbs2.cpp | 4 + .../doc/snippets/MatrixBase_cwiseEqual.cpp | 7 + .../doc/snippets/MatrixBase_cwiseInverse.cpp | 4 + .../doc/snippets/MatrixBase_cwiseMax.cpp | 2 + .../doc/snippets/MatrixBase_cwiseMin.cpp | 2 + .../doc/snippets/MatrixBase_cwiseNotEqual.cpp | 7 + .../doc/snippets/MatrixBase_cwiseProduct.cpp | 4 + .../doc/snippets/MatrixBase_cwiseQuotient.cpp | 2 + .../doc/snippets/MatrixBase_cwiseSign.cpp | 4 + .../doc/snippets/MatrixBase_cwiseSqrt.cpp | 2 + .../doc/snippets/MatrixBase_diagonal.cpp | 4 + .../doc/snippets/MatrixBase_diagonal_int.cpp | 5 + .../MatrixBase_diagonal_template_int.cpp | 5 + .../doc/snippets/MatrixBase_eigenvalues.cpp | 3 + .../eigen/doc/snippets/MatrixBase_end_int.cpp | 5 + .../eigen/doc/snippets/MatrixBase_eval.cpp | 12 + .../MatrixBase_fixedBlock_int_int.cpp | 5 + .../doc/snippets/MatrixBase_hnormalized.cpp | 6 + .../doc/snippets/MatrixBase_homogeneous.cpp | 6 + .../doc/snippets/MatrixBase_identity.cpp | 1 + .../snippets/MatrixBase_identity_int_int.cpp | 1 + .../eigen/doc/snippets/MatrixBase_inverse.cpp | 3 + .../doc/snippets/MatrixBase_isDiagonal.cpp | 6 + .../doc/snippets/MatrixBase_isIdentity.cpp | 5 + .../eigen/doc/snippets/MatrixBase_isOnes.cpp | 5 + .../doc/snippets/MatrixBase_isOrthogonal.cpp | 6 + .../doc/snippets/MatrixBase_isUnitary.cpp | 5 + .../eigen/doc/snippets/MatrixBase_isZero.cpp | 5 + .../doc/snippets/MatrixBase_leftCols_int.cpp | 6 + .../eigen/doc/snippets/MatrixBase_noalias.cpp | 3 + .../eigen/doc/snippets/MatrixBase_ones.cpp | 2 + .../doc/snippets/MatrixBase_ones_int.cpp | 2 + .../doc/snippets/MatrixBase_ones_int_int.cpp | 1 + .../doc/snippets/MatrixBase_operatorNorm.cpp | 3 + .../eigen/doc/snippets/MatrixBase_prod.cpp | 3 + .../eigen/doc/snippets/MatrixBase_random.cpp | 1 + .../doc/snippets/MatrixBase_random_int.cpp | 1 + .../snippets/MatrixBase_random_int_int.cpp | 1 + .../doc/snippets/MatrixBase_replicate.cpp | 4 + .../snippets/MatrixBase_replicate_int_int.cpp | 4 + .../eigen/doc/snippets/MatrixBase_reverse.cpp | 8 + .../doc/snippets/MatrixBase_rightCols_int.cpp | 6 + .../ext/eigen/doc/snippets/MatrixBase_row.cpp | 3 + .../eigen/doc/snippets/MatrixBase_rowwise.cpp | 5 + .../snippets/MatrixBase_segment_int_int.cpp | 5 + .../eigen/doc/snippets/MatrixBase_select.cpp | 6 + .../snippets/MatrixBase_selfadjointView.cpp | 6 + .../ext/eigen/doc/snippets/MatrixBase_set.cpp | 13 + .../doc/snippets/MatrixBase_setIdentity.cpp | 3 + .../eigen/doc/snippets/MatrixBase_setOnes.cpp | 3 + .../doc/snippets/MatrixBase_setRandom.cpp | 3 + .../eigen/doc/snippets/MatrixBase_setZero.cpp | 3 + .../doc/snippets/MatrixBase_start_int.cpp | 5 + .../MatrixBase_template_int_bottomRows.cpp | 6 + .../snippets/MatrixBase_template_int_end.cpp | 5 + ...template_int_int_block_int_int_int_int.cpp | 5 + ...Base_template_int_int_bottomLeftCorner.cpp | 6 + ...plate_int_int_bottomLeftCorner_int_int.cpp | 6 + ...ase_template_int_int_bottomRightCorner.cpp | 6 + ...late_int_int_bottomRightCorner_int_int.cpp | 6 + ...rixBase_template_int_int_topLeftCorner.cpp | 6 + ...template_int_int_topLeftCorner_int_int.cpp | 6 + ...ixBase_template_int_int_topRightCorner.cpp | 6 + ...emplate_int_int_topRightCorner_int_int.cpp | 6 + .../MatrixBase_template_int_leftCols.cpp | 6 + .../MatrixBase_template_int_rightCols.cpp | 6 + .../MatrixBase_template_int_segment.cpp | 5 + .../MatrixBase_template_int_start.cpp | 5 + .../MatrixBase_template_int_topRows.cpp | 6 + .../MatrixBase_topLeftCorner_int_int.cpp | 6 + .../MatrixBase_topRightCorner_int_int.cpp | 6 + .../doc/snippets/MatrixBase_topRows_int.cpp | 6 + .../doc/snippets/MatrixBase_transpose.cpp | 8 + .../snippets/MatrixBase_triangularView.cpp | 9 + .../eigen/doc/snippets/MatrixBase_zero.cpp | 2 + .../doc/snippets/MatrixBase_zero_int.cpp | 2 + .../doc/snippets/MatrixBase_zero_int_int.cpp | 1 + .../snippets/Matrix_resize_NoChange_int.cpp | 3 + .../eigen/doc/snippets/Matrix_resize_int.cpp | 6 + .../snippets/Matrix_resize_int_NoChange.cpp | 3 + .../doc/snippets/Matrix_resize_int_int.cpp | 9 + .../doc/snippets/Matrix_setConstant_int.cpp | 3 + .../snippets/Matrix_setConstant_int_int.cpp | 3 + .../snippets/Matrix_setIdentity_int_int.cpp | 3 + .../eigen/doc/snippets/Matrix_setOnes_int.cpp | 3 + .../doc/snippets/Matrix_setOnes_int_int.cpp | 3 + .../doc/snippets/Matrix_setRandom_int.cpp | 3 + .../doc/snippets/Matrix_setRandom_int_int.cpp | 3 + .../eigen/doc/snippets/Matrix_setZero_int.cpp | 3 + .../doc/snippets/Matrix_setZero_int_int.cpp | 3 + .../eigen/doc/snippets/PartialPivLU_solve.cpp | 7 + .../eigen/doc/snippets/PartialRedux_count.cpp | 5 + .../doc/snippets/PartialRedux_maxCoeff.cpp | 3 + .../doc/snippets/PartialRedux_minCoeff.cpp | 3 + .../eigen/doc/snippets/PartialRedux_norm.cpp | 3 + .../eigen/doc/snippets/PartialRedux_prod.cpp | 3 + .../doc/snippets/PartialRedux_squaredNorm.cpp | 3 + .../eigen/doc/snippets/PartialRedux_sum.cpp | 3 + .../ext/eigen/doc/snippets/RealQZ_compute.cpp | 17 + .../RealSchur_RealSchur_MatrixType.cpp | 10 + .../eigen/doc/snippets/RealSchur_compute.cpp | 6 + ...ointEigenSolver_SelfAdjointEigenSolver.cpp | 7 + ...lver_SelfAdjointEigenSolver_MatrixType.cpp | 17 + ...ver_SelfAdjointEigenSolver_MatrixType2.cpp | 16 + ...fAdjointEigenSolver_compute_MatrixType.cpp | 7 + ...AdjointEigenSolver_compute_MatrixType2.cpp | 9 + .../SelfAdjointEigenSolver_eigenvalues.cpp | 4 + .../SelfAdjointEigenSolver_eigenvectors.cpp | 4 + ...AdjointEigenSolver_operatorInverseSqrt.cpp | 9 + .../SelfAdjointEigenSolver_operatorSqrt.cpp | 8 + .../snippets/SelfAdjointView_eigenvalues.cpp | 3 + .../snippets/SelfAdjointView_operatorNorm.cpp | 3 + .../doc/snippets/SparseMatrix_coeffs.cpp | 9 + .../doc/snippets/TopicAliasing_block.cpp | 7 + .../snippets/TopicAliasing_block_correct.cpp | 7 + .../doc/snippets/TopicAliasing_cwise.cpp | 20 + .../doc/snippets/TopicAliasing_mult1.cpp | 4 + .../doc/snippets/TopicAliasing_mult2.cpp | 10 + .../doc/snippets/TopicAliasing_mult3.cpp | 4 + .../doc/snippets/TopicAliasing_mult4.cpp | 5 + .../doc/snippets/TopicAliasing_mult5.cpp | 5 + .../snippets/TopicStorageOrders_example.cpp | 18 + .../eigen/doc/snippets/Triangular_solve.cpp | 11 + ...lization_Tridiagonalization_MatrixType.cpp | 9 + .../snippets/Tridiagonalization_compute.cpp | 9 + .../Tridiagonalization_decomposeInPlace.cpp | 10 + .../snippets/Tridiagonalization_diagonal.cpp | 13 + ...iagonalization_householderCoefficients.cpp | 6 + .../Tridiagonalization_packedMatrix.cpp | 8 + .../Tutorial_AdvancedInitialization_Block.cpp | 5 + ..._AdvancedInitialization_CommaTemporary.cpp | 4 + .../Tutorial_AdvancedInitialization_Join.cpp | 11 + ...orial_AdvancedInitialization_LinSpaced.cpp | 7 + ...orial_AdvancedInitialization_ThreeWays.cpp | 20 + .../Tutorial_AdvancedInitialization_Zero.cpp | 13 + .../doc/snippets/Tutorial_Map_rowmajor.cpp | 7 + .../eigen/doc/snippets/Tutorial_Map_using.cpp | 21 + .../doc/snippets/Tutorial_ReshapeMat2Mat.cpp | 6 + .../doc/snippets/Tutorial_ReshapeMat2Vec.cpp | 11 + .../doc/snippets/Tutorial_SlicingCol.cpp | 11 + .../doc/snippets/Tutorial_SlicingVec.cpp | 4 + .../doc/snippets/Tutorial_commainit_01.cpp | 5 + .../doc/snippets/Tutorial_commainit_01b.cpp | 5 + .../doc/snippets/Tutorial_commainit_02.cpp | 7 + .../Tutorial_solve_matrix_inverse.cpp | 6 + .../snippets/Tutorial_solve_multiple_rhs.cpp | 10 + .../Tutorial_solve_reuse_decomposition.cpp | 13 + .../doc/snippets/Tutorial_solve_singular.cpp | 9 + .../snippets/Tutorial_solve_triangular.cpp | 8 + .../Tutorial_solve_triangular_inplace.cpp | 6 + .../doc/snippets/VectorwiseOp_homogeneous.cpp | 7 + .../eigen/doc/snippets/Vectorwise_reverse.cpp | 10 + .../eigen/doc/snippets/class_FullPivLU.cpp | 16 + .../eigen/doc/snippets/compile_snippet.cpp.in | 20 + .../snippets/tut_arithmetic_redux_minmax.cpp | 12 + .../tut_arithmetic_transpose_aliasing.cpp | 5 + .../tut_arithmetic_transpose_conjugate.cpp | 12 + .../tut_arithmetic_transpose_inplace.cpp | 6 + .../tut_matrix_assignment_resizing.cpp | 5 + .../eigen/doc/special_examples/CMakeLists.txt | 35 + .../Tutorial_sparse_example.cpp | 34 + .../Tutorial_sparse_example_details.cpp | 44 + .../doc/special_examples/random_cpp11.cpp | 14 + testbed/nanogui/ext/eigen/doc/tutorial.cpp | 62 + testbed/nanogui/ext/eigen/eigen3.pc.in | 7 +- .../nanogui/ext/eigen/failtest/CMakeLists.txt | 32 + .../nanogui/ext/eigen/failtest/bdcsvd_int.cpp | 14 + .../ext/eigen/failtest/colpivqr_int.cpp | 14 + ...seunaryview_nonconst_ctor_on_const_xpr.cpp | 15 + ...unaryview_on_const_type_actually_const.cpp | 16 + .../ext/eigen/failtest/eigensolver_cplx.cpp | 14 + .../ext/eigen/failtest/eigensolver_int.cpp | 14 + .../ext/eigen/failtest/fullpivlu_int.cpp | 14 + .../ext/eigen/failtest/fullpivqr_int.cpp | 14 + .../ext/eigen/failtest/jacobisvd_int.cpp | 14 + .../nanogui/ext/eigen/failtest/ldlt_int.cpp | 14 + .../nanogui/ext/eigen/failtest/llt_int.cpp | 14 + .../ext/eigen/failtest/partialpivlu_int.cpp | 14 + testbed/nanogui/ext/eigen/failtest/qr_int.cpp | 14 + ...adjointview_nonconst_ctor_on_const_xpr.cpp | 15 + ...jointview_on_const_type_actually_const.cpp | 16 + .../ext/eigen/failtest/sparse_ref_1.cpp | 18 + .../ext/eigen/failtest/sparse_ref_2.cpp | 15 + .../ext/eigen/failtest/sparse_ref_3.cpp | 15 + .../ext/eigen/failtest/sparse_ref_4.cpp | 15 + .../ext/eigen/failtest/sparse_ref_5.cpp | 16 + .../failtest/sparse_storage_mismatch.cpp | 16 + testbed/nanogui/ext/eigen/failtest/swap_1.cpp | 14 + testbed/nanogui/ext/eigen/failtest/swap_2.cpp | 14 + .../nanogui/ext/eigen/failtest/ternary_1.cpp | 13 + .../nanogui/ext/eigen/failtest/ternary_2.cpp | 13 + ...angularview_nonconst_ctor_on_const_xpr.cpp | 15 + ...gularview_on_const_type_actually_const.cpp | 16 + .../ext/eigen/lapack/complex_double.cpp | 3 +- .../ext/eigen/lapack/complex_single.cpp | 3 +- testbed/nanogui/ext/eigen/lapack/double.cpp | 3 +- .../nanogui/ext/eigen/lapack/eigenvalues.cpp | 27 +- .../nanogui/ext/eigen/lapack/lapack_common.h | 8 +- testbed/nanogui/ext/eigen/lapack/single.cpp | 3 +- testbed/nanogui/ext/eigen/lapack/svd.cpp | 138 + .../nanogui/ext/eigen/scripts/buildtests.in | 6 +- testbed/nanogui/ext/eigen/scripts/check.in | 2 +- .../nanogui/ext/eigen/scripts/eigen_gen_docs | 2 +- .../ext/eigen/scripts/eigen_monitor_perf.sh | 25 + testbed/nanogui/ext/eigen/test/CMakeLists.txt | 225 +- testbed/nanogui/ext/eigen/test/adjoint.cpp | 42 +- testbed/nanogui/ext/eigen/test/array.cpp | 262 +- .../ext/eigen/test/array_for_matrix.cpp | 35 +- .../ext/eigen/test/array_of_string.cpp | 32 + .../ext/eigen/test/array_replicate.cpp | 13 + .../nanogui/ext/eigen/test/array_reverse.cpp | 32 +- testbed/nanogui/ext/eigen/test/bandmatrix.cpp | 3 - testbed/nanogui/ext/eigen/test/basicstuff.cpp | 102 +- testbed/nanogui/ext/eigen/test/bdcsvd.cpp | 111 + testbed/nanogui/ext/eigen/test/bicgstab.cpp | 16 +- testbed/nanogui/ext/eigen/test/block.cpp | 50 +- .../nanogui/ext/eigen/test/boostmultiprec.cpp | 201 + testbed/nanogui/ext/eigen/test/bug1213.cpp | 13 + testbed/nanogui/ext/eigen/test/bug1213.h | 8 + .../nanogui/ext/eigen/test/bug1213_main.cpp | 18 + testbed/nanogui/ext/eigen/test/cholesky.cpp | 157 +- .../ext/eigen/test/cholmod_support.cpp | 57 +- .../ext/eigen/test/commainitializer.cpp | 60 + .../ext/eigen/test/conjugate_gradient.cpp | 18 +- .../nanogui/ext/eigen/test/constructor.cpp | 84 + testbed/nanogui/ext/eigen/test/ctorleak.cpp | 69 + testbed/nanogui/ext/eigen/test/cuda_basic.cu | 173 + testbed/nanogui/ext/eigen/test/cuda_common.h | 101 + testbed/nanogui/ext/eigen/test/cwiseop.cpp | 184 - .../nanogui/ext/eigen/test/dense_storage.cpp | 76 + testbed/nanogui/ext/eigen/test/diagonal.cpp | 24 + .../ext/eigen/test/diagonalmatrices.cpp | 27 + testbed/nanogui/ext/eigen/test/dynalloc.cpp | 89 +- .../ext/eigen/test/eigen2/CMakeLists.txt | 61 - .../ext/eigen/test/eigen2/eigen2_adjoint.cpp | 99 - .../eigen/test/eigen2/eigen2_alignedbox.cpp | 60 - .../ext/eigen/test/eigen2/eigen2_array.cpp | 142 - .../eigen/test/eigen2/eigen2_basicstuff.cpp | 105 - .../ext/eigen/test/eigen2/eigen2_bug_132.cpp | 26 - .../ext/eigen/test/eigen2/eigen2_cholesky.cpp | 113 - .../test/eigen2/eigen2_commainitializer.cpp | 46 - .../ext/eigen/test/eigen2/eigen2_cwiseop.cpp | 155 - .../eigen/test/eigen2/eigen2_determinant.cpp | 61 - .../ext/eigen/test/eigen2/eigen2_dynalloc.cpp | 131 - .../eigen/test/eigen2/eigen2_eigensolver.cpp | 146 - .../test/eigen2/eigen2_first_aligned.cpp | 49 - .../ext/eigen/test/eigen2/eigen2_geometry.cpp | 432 - .../eigen2_geometry_with_eigen2_prefix.cpp | 435 - .../eigen/test/eigen2/eigen2_hyperplane.cpp | 126 - .../ext/eigen/test/eigen2/eigen2_inverse.cpp | 62 - .../test/eigen2/eigen2_linearstructure.cpp | 83 - .../ext/eigen/test/eigen2/eigen2_lu.cpp | 122 - .../ext/eigen/test/eigen2/eigen2_map.cpp | 114 - .../ext/eigen/test/eigen2/eigen2_meta.cpp | 60 - .../eigen/test/eigen2/eigen2_miscmatrices.cpp | 48 - .../eigen/test/eigen2/eigen2_mixingtypes.cpp | 77 - .../ext/eigen/test/eigen2/eigen2_nomalloc.cpp | 53 - .../eigen/test/eigen2/eigen2_packetmath.cpp | 132 - .../test/eigen2/eigen2_parametrizedline.cpp | 62 - .../test/eigen2/eigen2_prec_inverse_4x4.cpp | 84 - .../test/eigen2/eigen2_product_large.cpp | 45 - .../test/eigen2/eigen2_product_small.cpp | 22 - .../ext/eigen/test/eigen2/eigen2_qr.cpp | 69 - .../ext/eigen/test/eigen2/eigen2_qtvector.cpp | 158 - .../eigen/test/eigen2/eigen2_regression.cpp | 136 - .../ext/eigen/test/eigen2/eigen2_sizeof.cpp | 31 - .../eigen/test/eigen2/eigen2_smallvectors.cpp | 42 - .../eigen/test/eigen2/eigen2_sparse_basic.cpp | 317 - .../test/eigen2/eigen2_sparse_product.cpp | 115 - .../test/eigen2/eigen2_sparse_solvers.cpp | 200 - .../test/eigen2/eigen2_sparse_vector.cpp | 84 - .../eigen/test/eigen2/eigen2_stdvector.cpp | 148 - .../eigen/test/eigen2/eigen2_submatrices.cpp | 142 - .../ext/eigen/test/eigen2/eigen2_sum.cpp | 71 - .../ext/eigen/test/eigen2/eigen2_svd.cpp | 87 - .../ext/eigen/test/eigen2/eigen2_swap.cpp | 83 - .../eigen/test/eigen2/eigen2_triangular.cpp | 148 - .../test/eigen2/eigen2_unalignedassert.cpp | 116 - .../ext/eigen/test/eigen2/eigen2_visitor.cpp | 116 - .../ext/eigen/test/eigen2/gsl_helper.h | 175 - testbed/nanogui/ext/eigen/test/eigen2/main.h | 399 - .../nanogui/ext/eigen/test/eigen2/product.h | 129 - .../nanogui/ext/eigen/test/eigen2/runtest.sh | 28 - .../nanogui/ext/eigen/test/eigen2/sparse.h | 154 - .../ext/eigen/test/eigen2/testsuite.cmake | 197 - .../nanogui/ext/eigen/test/eigen2support.cpp | 1 - .../ext/eigen/test/eigensolver_complex.cpp | 71 +- .../test/eigensolver_generalized_real.cpp | 54 +- .../ext/eigen/test/eigensolver_generic.cpp | 49 +- .../eigen/test/eigensolver_selfadjoint.cpp | 184 +- .../nanogui/ext/eigen/test/evaluator_common.h | 0 testbed/nanogui/ext/eigen/test/evaluators.cpp | 499 + testbed/nanogui/ext/eigen/test/fastmath.cpp | 99 + .../nanogui/ext/eigen/test/first_aligned.cpp | 6 +- .../nanogui/ext/eigen/test/geo_alignedbox.cpp | 22 +- .../ext/eigen/test/geo_eulerangles.cpp | 20 +- .../ext/eigen/test/geo_homogeneous.cpp | 26 +- .../nanogui/ext/eigen/test/geo_hyperplane.cpp | 39 +- .../ext/eigen/test/geo_orthomethods.cpp | 14 +- .../ext/eigen/test/geo_parametrizedline.cpp | 37 +- .../nanogui/ext/eigen/test/geo_quaternion.cpp | 51 +- .../ext/eigen/test/geo_transformations.cpp | 170 +- testbed/nanogui/ext/eigen/test/half_float.cpp | 257 + .../ext/eigen/test/incomplete_cholesky.cpp | 65 + .../nanogui/ext/eigen/test/indexed_view.cpp | 378 + .../ext/eigen/test/inplace_decomposition.cpp | 110 + .../nanogui/ext/eigen/test/integer_types.cpp | 8 + testbed/nanogui/ext/eigen/test/inverse.cpp | 15 +- .../nanogui/ext/eigen/test/is_same_dense.cpp | 33 + testbed/nanogui/ext/eigen/test/jacobisvd.cpp | 386 +- .../ext/eigen/test/linearstructure.cpp | 67 +- testbed/nanogui/ext/eigen/test/lscg.cpp | 29 + testbed/nanogui/ext/eigen/test/lu.cpp | 88 +- testbed/nanogui/ext/eigen/test/main.h | 284 +- .../nanogui/ext/eigen/test/mapped_matrix.cpp | 110 +- .../ext/eigen/test/mapstaticmethods.cpp | 6 +- testbed/nanogui/ext/eigen/test/mapstride.cpp | 43 +- testbed/nanogui/ext/eigen/test/meta.cpp | 24 + .../nanogui/ext/eigen/test/metis_support.cpp | 22 +- .../nanogui/ext/eigen/test/mixingtypes.cpp | 202 +- testbed/nanogui/ext/eigen/test/mpl2only.cpp | 22 + .../nanogui/ext/eigen/test/nesting_ops.cpp | 86 +- testbed/nanogui/ext/eigen/test/nomalloc.cpp | 59 +- testbed/nanogui/ext/eigen/test/nullary.cpp | 225 +- testbed/nanogui/ext/eigen/test/packetmath.cpp | 425 +- .../nanogui/ext/eigen/test/pastix_support.cpp | 10 + .../ext/eigen/test/permutationmatrices.cpp | 62 +- .../ext/eigen/test/prec_inverse_4x4.cpp | 15 + testbed/nanogui/ext/eigen/test/product.h | 101 +- .../nanogui/ext/eigen/test/product_extra.cpp | 204 +- .../nanogui/ext/eigen/test/product_large.cpp | 49 +- .../nanogui/ext/eigen/test/product_mmtr.cpp | 32 +- .../ext/eigen/test/product_notemporary.cpp | 60 +- .../ext/eigen/test/product_selfadjoint.cpp | 9 +- .../nanogui/ext/eigen/test/product_small.cpp | 247 +- .../nanogui/ext/eigen/test/product_symm.cpp | 18 + .../nanogui/ext/eigen/test/product_syrk.cpp | 5 +- .../nanogui/ext/eigen/test/product_trmm.cpp | 22 +- .../nanogui/ext/eigen/test/product_trmv.cpp | 6 +- .../ext/eigen/test/product_trsolve.cpp | 18 +- testbed/nanogui/ext/eigen/test/qr.cpp | 9 +- .../nanogui/ext/eigen/test/qr_colpivoting.cpp | 206 +- .../ext/eigen/test/qr_fullpivoting.cpp | 34 +- testbed/nanogui/ext/eigen/test/rand.cpp | 118 + testbed/nanogui/ext/eigen/test/real_qz.cpp | 32 +- testbed/nanogui/ext/eigen/test/redux.cpp | 21 +- testbed/nanogui/ext/eigen/test/ref.cpp | 64 +- testbed/nanogui/ext/eigen/test/runtest.sh | 20 - .../nanogui/ext/eigen/test/rvalue_types.cpp | 64 + .../nanogui/ext/eigen/test/schur_complex.cpp | 4 +- testbed/nanogui/ext/eigen/test/schur_real.cpp | 4 +- .../nanogui/ext/eigen/test/selfadjoint.cpp | 15 +- .../ext/eigen/test/simplicial_cholesky.cpp | 28 +- testbed/nanogui/ext/eigen/test/sizeof.cpp | 17 +- .../nanogui/ext/eigen/test/sizeoverflow.cpp | 2 - testbed/nanogui/ext/eigen/test/sparse.h | 23 +- .../nanogui/ext/eigen/test/sparse_basic.cpp | 637 +- .../nanogui/ext/eigen/test/sparse_block.cpp | 317 + .../ext/eigen/test/sparse_permutations.cpp | 95 +- .../nanogui/ext/eigen/test/sparse_product.cpp | 201 +- testbed/nanogui/ext/eigen/test/sparse_ref.cpp | 139 + .../nanogui/ext/eigen/test/sparse_solver.h | 412 +- .../nanogui/ext/eigen/test/sparse_vector.cpp | 75 +- testbed/nanogui/ext/eigen/test/sparselu.cpp | 31 +- testbed/nanogui/ext/eigen/test/sparseqr.cpp | 12 +- .../nanogui/ext/eigen/test/spqr_support.cpp | 8 +- .../nanogui/ext/eigen/test/stable_norm.cpp | 105 +- ...newstdvector.cpp => stddeque_overload.cpp} | 77 +- .../ext/eigen/test/stdlist_overload.cpp | 192 + testbed/nanogui/ext/eigen/test/stdvector.cpp | 6 +- .../ext/eigen/test/stdvector_overload.cpp | 6 +- .../ext/eigen/test/superlu_support.cpp | 1 + testbed/nanogui/ext/eigen/test/svd_common.h | 483 + testbed/nanogui/ext/eigen/test/svd_fill.h | 119 + testbed/nanogui/ext/eigen/test/swap.cpp | 23 +- .../nanogui/ext/eigen/test/symbolic_index.cpp | 104 + .../nanogui/ext/eigen/test/testsuite.cmake | 229 - testbed/nanogui/ext/eigen/test/triangular.cpp | 19 +- .../ext/eigen/test/umfpack_support.cpp | 1 + .../ext/eigen/test/unalignedassert.cpp | 93 +- .../nanogui/ext/eigen/test/unalignedcount.cpp | 9 +- .../ext/eigen/test/upperbidiagonalization.cpp | 2 +- .../ext/eigen/test/vectorization_logic.cpp | 340 +- .../nanogui/ext/eigen/test/vectorwiseop.cpp | 87 +- testbed/nanogui/ext/eigen/test/visitor.cpp | 5 + testbed/nanogui/ext/eigen/test/zerosized.cpp | 20 +- .../ext/eigen/unsupported/CMakeLists.txt | 10 +- .../ext/eigen/unsupported/Eigen/AdolcForward | 2 +- .../eigen/unsupported/Eigen/AlignedVector3 | 40 +- .../eigen/unsupported/Eigen/CMakeLists.txt | 31 +- .../unsupported/Eigen/CXX11/CMakeLists.txt | 8 + .../ext/eigen/unsupported/Eigen/CXX11/Tensor | 159 + .../unsupported/Eigen/CXX11/TensorSymmetry | 42 + .../eigen/unsupported/Eigen/CXX11/ThreadPool | 78 + .../Eigen/CXX11/src/Tensor/README.md | 1755 ++ .../Eigen/CXX11/src/Tensor/Tensor.h | 527 + .../Eigen/CXX11/src/Tensor/TensorArgMax.h | 299 + .../Eigen/CXX11/src/Tensor/TensorAssign.h | 181 + .../Eigen/CXX11/src/Tensor/TensorBase.h | 1016 + .../CXX11/src/Tensor/TensorBroadcasting.h | 392 + .../Eigen/CXX11/src/Tensor/TensorChipping.h | 400 + .../CXX11/src/Tensor/TensorConcatenation.h | 367 + .../CXX11/src/Tensor/TensorContraction.h | 909 + .../src/Tensor/TensorContractionBlocking.h | 190 + .../CXX11/src/Tensor/TensorContractionCuda.h | 1386 ++ .../src/Tensor/TensorContractionMapper.h | 493 + .../CXX11/src/Tensor/TensorContractionSycl.h | 400 + .../src/Tensor/TensorContractionThreadPool.h | 1252 + .../Eigen/CXX11/src/Tensor/TensorConversion.h | 282 + .../CXX11/src/Tensor/TensorConvolution.h | 1104 + .../CXX11/src/Tensor/TensorConvolutionSycl.h | 476 + .../Eigen/CXX11/src/Tensor/TensorCostModel.h | 212 + .../Eigen/CXX11/src/Tensor/TensorCustomOp.h | 313 + .../Eigen/CXX11/src/Tensor/TensorDevice.h | 68 + .../Eigen/CXX11/src/Tensor/TensorDeviceCuda.h | 340 + .../CXX11/src/Tensor/TensorDeviceDefault.h | 81 + .../Eigen/CXX11/src/Tensor/TensorDeviceSycl.h | 415 + .../CXX11/src/Tensor/TensorDeviceThreadPool.h | 268 + .../CXX11/src/Tensor/TensorDimensionList.h | 236 + .../Eigen/CXX11/src/Tensor/TensorDimensions.h | 430 + .../Eigen/CXX11/src/Tensor/TensorEvalTo.h | 184 + .../Eigen/CXX11/src/Tensor/TensorEvaluator.h | 640 + .../Eigen/CXX11/src/Tensor/TensorExecutor.h | 288 + .../Eigen/CXX11/src/Tensor/TensorExpr.h | 371 + .../Eigen/CXX11/src/Tensor/TensorFFT.h | 651 + .../Eigen/CXX11/src/Tensor/TensorFixedSize.h | 389 + .../Eigen/CXX11/src/Tensor/TensorForcedEval.h | 162 + .../src/Tensor/TensorForwardDeclarations.h | 121 + .../Eigen/CXX11/src/Tensor/TensorFunctors.h | 489 + .../Eigen/CXX11/src/Tensor/TensorGenerator.h | 185 + .../CXX11/src/Tensor/TensorGlobalFunctions.h | 33 + .../Eigen/CXX11/src/Tensor/TensorIO.h | 79 + .../Eigen/CXX11/src/Tensor/TensorImagePatch.h | 509 + .../Eigen/CXX11/src/Tensor/TensorIndexList.h | 725 + .../Eigen/CXX11/src/Tensor/TensorInflation.h | 229 + .../CXX11/src/Tensor/TensorInitializer.h | 82 + .../Eigen/CXX11/src/Tensor/TensorIntDiv.h | 263 + .../Eigen/CXX11/src/Tensor/TensorLayoutSwap.h | 209 + .../Eigen/CXX11/src/Tensor/TensorMacros.h | 62 + .../Eigen/CXX11/src/Tensor/TensorMap.h | 321 + .../Eigen/CXX11/src/Tensor/TensorMeta.h | 219 + .../Eigen/CXX11/src/Tensor/TensorMorphing.h | 921 + .../Eigen/CXX11/src/Tensor/TensorPadding.h | 404 + .../Eigen/CXX11/src/Tensor/TensorPatch.h | 269 + .../Eigen/CXX11/src/Tensor/TensorRandom.h | 276 + .../Eigen/CXX11/src/Tensor/TensorReduction.h | 799 + .../CXX11/src/Tensor/TensorReductionCuda.h | 749 + .../CXX11/src/Tensor/TensorReductionSycl.h | 175 + .../Eigen/CXX11/src/Tensor/TensorRef.h | 429 + .../Eigen/CXX11/src/Tensor/TensorReverse.h | 293 + .../Eigen/CXX11/src/Tensor/TensorScan.h | 287 + .../Eigen/CXX11/src/Tensor/TensorShuffling.h | 270 + .../Eigen/CXX11/src/Tensor/TensorStorage.h | 146 + .../Eigen/CXX11/src/Tensor/TensorStriding.h | 348 + .../Eigen/CXX11/src/Tensor/TensorSycl.h | 94 + .../TensorSyclConvertToDeviceExpression.h | 165 + .../src/Tensor/TensorSyclExprConstructor.h | 401 + .../src/Tensor/TensorSyclExtractAccessor.h | 239 + .../src/Tensor/TensorSyclExtractFunctors.h | 319 + .../CXX11/src/Tensor/TensorSyclFunctors.h | 245 + .../CXX11/src/Tensor/TensorSyclLeafCount.h | 166 + .../src/Tensor/TensorSyclPlaceHolderExpr.h | 232 + .../Eigen/CXX11/src/Tensor/TensorSyclRun.h | 97 + .../Eigen/CXX11/src/Tensor/TensorSyclTuple.h | 236 + .../Eigen/CXX11/src/Tensor/TensorTraits.h | 278 + .../Eigen/CXX11/src/Tensor/TensorUInt128.h | 249 + .../CXX11/src/Tensor/TensorVolumePatch.h | 608 + .../src/TensorSymmetry/DynamicSymmetry.h | 293 + .../CXX11/src/TensorSymmetry/StaticSymmetry.h | 236 + .../Eigen/CXX11/src/TensorSymmetry/Symmetry.h | 338 + .../TensorSymmetry/util/TemplateGroupTheory.h | 666 + .../Eigen/CXX11/src/ThreadPool/EventCount.h | 233 + .../src/ThreadPool/NonBlockingThreadPool.h | 344 + .../Eigen/CXX11/src/ThreadPool/RunQueue.h | 217 + .../CXX11/src/ThreadPool/SimpleThreadPool.h | 162 + .../Eigen/CXX11/src/ThreadPool/ThreadCancel.h | 23 + .../CXX11/src/ThreadPool/ThreadEnvironment.h | 40 + .../Eigen/CXX11/src/ThreadPool/ThreadLocal.h | 22 + .../src/ThreadPool/ThreadPoolInterface.h | 39 + .../Eigen/CXX11/src/ThreadPool/ThreadYield.h | 20 + .../Eigen/CXX11/src/util/CXX11Meta.h | 546 + .../Eigen/CXX11/src/util/CXX11Workarounds.h | 88 + .../Eigen/CXX11/src/util/EmulateArray.h | 256 + .../Eigen/CXX11/src/util/EmulateCXX11Meta.h | 311 + .../Eigen/CXX11/src/util/MaxSizeVector.h | 141 + .../ext/eigen/unsupported/Eigen/EulerAngles | 43 + .../eigen/unsupported/Eigen/IterativeSolvers | 5 +- .../eigen/unsupported/Eigen/KroneckerProduct | 2 + .../ext/eigen/unsupported/Eigen/MPRealSupport | 100 +- .../eigen/unsupported/Eigen/MatrixFunctions | 76 +- .../ext/eigen/unsupported/Eigen/OpenGLSupport | 20 +- .../nanogui/ext/eigen/unsupported/Eigen/SVD | 39 - .../ext/eigen/unsupported/Eigen/SparseExtra | 3 - .../eigen/unsupported/Eigen/SpecialFunctions | 63 + .../Eigen/src/AutoDiff/AutoDiffJacobian.h | 51 +- .../Eigen/src/AutoDiff/AutoDiffScalar.h | 242 +- .../Eigen/src/AutoDiff/CMakeLists.txt | 6 - .../unsupported/Eigen/src/BVH/CMakeLists.txt | 6 - .../unsupported/Eigen/src/CMakeLists.txt | 13 - .../ArpackSelfAdjointEigenSolver.h | 14 +- .../Eigen/src/EulerAngles/CMakeLists.txt | 6 + .../Eigen/src/EulerAngles/EulerAngles.h | 355 + .../Eigen/src/EulerAngles/EulerSystem.h | 306 + .../unsupported/Eigen/src/FFT/CMakeLists.txt | 6 - .../Eigen/src/IterativeSolvers/CMakeLists.txt | 6 - .../Eigen/src/IterativeSolvers/DGMRES.h | 61 +- .../Eigen/src/IterativeSolvers/GMRES.h | 408 +- .../src/IterativeSolvers/IncompleteCholesky.h | 278 - .../Eigen/src/IterativeSolvers/IncompleteLU.h | 39 +- .../Eigen/src/IterativeSolvers/MINRES.h | 147 +- .../Eigen/src/IterativeSolvers/Scaling.h | 6 +- .../Eigen/src/KroneckerProduct/CMakeLists.txt | 6 - .../KroneckerProduct/KroneckerTensorProduct.h | 183 +- .../src/LevenbergMarquardt/CMakeLists.txt | 6 - .../Eigen/src/LevenbergMarquardt/LMcovar.h | 1 - .../Eigen/src/LevenbergMarquardt/LMpar.h | 2 +- .../Eigen/src/LevenbergMarquardt/LMqrsolv.h | 9 +- .../LevenbergMarquardt/LevenbergMarquardt.h | 31 +- .../Eigen/src/MatrixFunctions/CMakeLists.txt | 6 - .../src/MatrixFunctions/MatrixExponential.h | 711 +- .../src/MatrixFunctions/MatrixFunction.h | 714 +- .../MatrixFunctions/MatrixFunctionAtomic.h | 131 - .../src/MatrixFunctions/MatrixLogarithm.h | 517 +- .../Eigen/src/MatrixFunctions/MatrixPower.h | 397 +- .../src/MatrixFunctions/MatrixSquareRoot.h | 452 +- .../Eigen/src/MatrixFunctions/StemFunction.h | 172 +- .../src/MoreVectorization/CMakeLists.txt | 6 - .../src/NonLinearOptimization/CMakeLists.txt | 6 - .../HybridNonLinearSolver.h | 4 +- .../LevenbergMarquardt.h | 25 +- .../Eigen/src/NumericalDiff/CMakeLists.txt | 6 - .../Eigen/src/Polynomials/CMakeLists.txt | 6 - .../Eigen/src/Polynomials/Companion.h | 50 +- .../Eigen/src/Polynomials/PolynomialSolver.h | 51 +- .../Eigen/src/Polynomials/PolynomialUtils.h | 2 +- .../eigen/unsupported/Eigen/src/SVD/BDCSVD.h | 748 - .../unsupported/Eigen/src/SVD/CMakeLists.txt | 6 - .../unsupported/Eigen/src/SVD/JacobiSVD.h | 782 - .../unsupported/Eigen/src/SVD/TODOBdcsvd.txt | 29 - .../Eigen/src/SVD/doneInBDCSVD.txt | 21 - .../Eigen/src/Skyline/CMakeLists.txt | 6 - .../Eigen/src/Skyline/SkylineProduct.h | 6 +- .../Eigen/src/SparseExtra/BlockSparseMatrix.h | 1079 + .../Eigen/src/SparseExtra/CMakeLists.txt | 6 - .../src/SparseExtra/DynamicSparseMatrix.h | 71 +- .../Eigen/src/SparseExtra/MarketIO.h | 96 +- .../src/SparseExtra/MatrixMarketIterator.h | 43 +- .../Eigen/src/SparseExtra/RandomSetter.h | 10 +- .../SpecialFunctionsArrayAPI.h | 124 + .../SpecialFunctionsFunctors.h | 236 + .../SpecialFunctions/SpecialFunctionsHalf.h | 47 + .../SpecialFunctions/SpecialFunctionsImpl.h | 1565 ++ .../SpecialFunctionsPacketMath.h | 58 + .../arch/CUDA/CudaSpecialFunctions.h | 165 + .../Eigen/src/Splines/CMakeLists.txt | 6 - .../unsupported/Eigen/src/Splines/Spline.h | 74 +- .../Eigen/src/Splines/SplineFitting.h | 274 + .../unsupported/Eigen/src/Splines/SplineFwd.h | 11 +- .../ext/eigen/unsupported/doc/Overview.dox | 11 +- .../unsupported/doc/examples/BVH_Example.cpp | 4 +- .../unsupported/doc/examples/EulerAngles.cpp | 46 + .../ext/eigen/unsupported/test/CMakeLists.txt | 198 +- .../eigen/unsupported/test/EulerAngles.cpp | 292 + .../ext/eigen/unsupported/test/FFTW.cpp | 32 +- .../test/NonLinearOptimization.cpp | 46 +- .../eigen/unsupported/test/alignedvector3.cpp | 29 +- .../ext/eigen/unsupported/test/autodiff.cpp | 206 +- .../unsupported/test/autodiff_scalar.cpp | 83 + .../ext/eigen/unsupported/test/bdcsvd.cpp | 213 - .../unsupported/test/cxx11_eventcount.cpp | 142 + .../ext/eigen/unsupported/test/cxx11_meta.cpp | 357 + .../test/cxx11_non_blocking_thread_pool.cpp | 125 + .../eigen/unsupported/test/cxx11_runqueue.cpp | 235 + .../unsupported/test/cxx11_tensor_argmax.cpp | 294 + .../test/cxx11_tensor_argmax_cuda.cu | 254 + .../unsupported/test/cxx11_tensor_assign.cpp | 370 + .../test/cxx11_tensor_broadcast_sycl.cpp | 144 + .../test/cxx11_tensor_broadcasting.cpp | 194 + .../test/cxx11_tensor_builtins_sycl.cpp | 267 + .../test/cxx11_tensor_cast_float16_cuda.cu | 82 + .../unsupported/test/cxx11_tensor_casts.cpp | 115 + .../test/cxx11_tensor_chipping.cpp | 425 + .../test/cxx11_tensor_chipping_sycl.cpp | 622 + .../test/cxx11_tensor_comparisons.cpp | 84 + .../test/cxx11_tensor_complex_cuda.cu | 153 + .../cxx11_tensor_complex_cwise_ops_cuda.cu | 97 + .../test/cxx11_tensor_concatenation.cpp | 137 + .../test/cxx11_tensor_concatenation_sycl.cpp | 180 + .../unsupported/test/cxx11_tensor_const.cpp | 62 + .../test/cxx11_tensor_contract_cuda.cu | 216 + .../test/cxx11_tensor_contract_sycl.cpp | 290 + .../test/cxx11_tensor_contraction.cpp | 545 + .../test/cxx11_tensor_convolution.cpp | 149 + .../test/cxx11_tensor_convolution_sycl.cpp | 469 + .../unsupported/test/cxx11_tensor_cuda.cu | 1287 + .../test/cxx11_tensor_custom_index.cpp | 100 + .../test/cxx11_tensor_custom_op.cpp | 111 + .../unsupported/test/cxx11_tensor_device.cu | 390 + .../test/cxx11_tensor_device_sycl.cpp | 77 + .../test/cxx11_tensor_dimension.cpp | 69 + .../unsupported/test/cxx11_tensor_empty.cpp | 40 + .../unsupported/test/cxx11_tensor_expr.cpp | 360 + .../unsupported/test/cxx11_tensor_fft.cpp | 273 + .../test/cxx11_tensor_fixed_size.cpp | 261 + .../test/cxx11_tensor_forced_eval.cpp | 79 + .../test/cxx11_tensor_forced_eval_sycl.cpp | 76 + .../test/cxx11_tensor_generator.cpp | 91 + .../unsupported/test/cxx11_tensor_ifft.cpp | 154 + .../test/cxx11_tensor_image_patch.cpp | 757 + .../test/cxx11_tensor_index_list.cpp | 386 + .../test/cxx11_tensor_inflation.cpp | 81 + .../unsupported/test/cxx11_tensor_intdiv.cpp | 147 + .../unsupported/test/cxx11_tensor_io.cpp | 136 + .../test/cxx11_tensor_layout_swap.cpp | 61 + .../unsupported/test/cxx11_tensor_lvalue.cpp | 42 + .../unsupported/test/cxx11_tensor_map.cpp | 277 + .../unsupported/test/cxx11_tensor_math.cpp | 46 + .../test/cxx11_tensor_mixed_indices.cpp | 53 + .../test/cxx11_tensor_morphing.cpp | 485 + .../test/cxx11_tensor_morphing_sycl.cpp | 248 + .../test/cxx11_tensor_notification.cpp | 72 + .../test/cxx11_tensor_of_complex.cpp | 103 + .../test/cxx11_tensor_of_const_values.cpp | 105 + .../test/cxx11_tensor_of_float16_cuda.cu | 500 + .../test/cxx11_tensor_of_strings.cpp | 152 + .../unsupported/test/cxx11_tensor_padding.cpp | 93 + .../test/cxx11_tensor_padding_sycl.cpp | 157 + .../unsupported/test/cxx11_tensor_patch.cpp | 172 + .../unsupported/test/cxx11_tensor_random.cpp | 78 + .../test/cxx11_tensor_random_cuda.cu | 88 + .../test/cxx11_tensor_reduction.cpp | 508 + .../test/cxx11_tensor_reduction_cuda.cu | 157 + .../test/cxx11_tensor_reduction_sycl.cpp | 181 + .../unsupported/test/cxx11_tensor_ref.cpp | 248 + .../unsupported/test/cxx11_tensor_reverse.cpp | 190 + .../test/cxx11_tensor_reverse_sycl.cpp | 221 + .../test/cxx11_tensor_roundings.cpp | 62 + .../unsupported/test/cxx11_tensor_scan.cpp | 110 + .../test/cxx11_tensor_scan_cuda.cu | 79 + .../test/cxx11_tensor_shuffling.cpp | 228 + .../test/cxx11_tensor_shuffling_sycl.cpp | 119 + .../unsupported/test/cxx11_tensor_simple.cpp | 327 + .../test/cxx11_tensor_striding.cpp | 119 + .../test/cxx11_tensor_striding_sycl.cpp | 203 + .../unsupported/test/cxx11_tensor_sugar.cpp | 81 + .../unsupported/test/cxx11_tensor_sycl.cpp | 276 + .../test/cxx11_tensor_symmetry.cpp | 818 + .../test/cxx11_tensor_thread_pool.cpp | 373 + .../unsupported/test/cxx11_tensor_uint128.cpp | 160 + .../test/cxx11_tensor_volume_patch.cpp | 112 + .../eigen/unsupported/test/forward_adolc.cpp | 4 +- .../ext/eigen/unsupported/test/jacobisvd.cpp | 198 - .../unsupported/test/kronecker_product.cpp | 89 +- .../unsupported/test/levenberg_marquardt.cpp | 93 +- .../unsupported/test/matrix_function.cpp | 6 +- .../eigen/unsupported/test/matrix_functions.h | 42 +- .../eigen/unsupported/test/matrix_power.cpp | 169 +- .../ext/eigen/unsupported/test/minres.cpp | 32 +- .../eigen/unsupported/test/mpreal/mpreal.h | 6177 ++--- .../eigen/unsupported/test/mpreal_support.cpp | 10 +- .../unsupported/test/polynomialsolver.cpp | 39 +- .../eigen/unsupported/test/sparse_extra.cpp | 24 +- .../unsupported/test/special_functions.cpp | 345 + .../ext/eigen/unsupported/test/splines.cpp | 73 +- .../ext/eigen/unsupported/test/svd_common.h | 261 - .../ext/glad/include/KHR/khrplatform.h | 285 + testbed/nanogui/ext/glad/include/glad/glad.h | 2155 ++ testbed/nanogui/ext/glad/src/glad.c | 993 + testbed/nanogui/ext/glew/CMakeLists.txt | 13 - testbed/nanogui/ext/glew/include/GL/glew.h | 19367 --------------- testbed/nanogui/ext/glew/include/GL/glxew.h | 1771 -- testbed/nanogui/ext/glew/include/GL/wglew.h | 1452 -- testbed/nanogui/ext/glew/src/glew.c | 19630 ---------------- testbed/nanogui/ext/glfw/.appveyor.yml | 22 + .../nanogui/ext/glfw/.github/CONTRIBUTING.md | 106 + testbed/nanogui/ext/glfw/.gitignore | 86 + testbed/nanogui/ext/glfw/.travis.yml | 30 + ...leInfo.plist => MacOSXBundleInfo.plist.in} | 22 +- .../ext/glfw/CMake/modules/FindEGL.cmake | 16 - .../ext/glfw/CMake/modules/FindGLESv1.cmake | 16 - .../ext/glfw/CMake/modules/FindGLESv2.cmake | 16 - .../ext/glfw/CMake/modules/FindVulkan.cmake | 31 + .../ext/glfw/CMake/modules/FindWayland.cmake | 66 - .../CMake/modules/FindWaylandProtocols.cmake | 26 + testbed/nanogui/ext/glfw/CMakeLists.txt | 351 +- testbed/nanogui/ext/glfw/COPYING.txt | 2 +- testbed/nanogui/ext/glfw/README.md | 150 +- testbed/nanogui/ext/glfw/deps/EGL/eglext.h | 565 - testbed/nanogui/ext/glfw/deps/GL/glext.h | 11626 --------- testbed/nanogui/ext/glfw/deps/GL/glxext.h | 906 - testbed/nanogui/ext/glfw/deps/GL/wglext.h | 840 - testbed/nanogui/ext/glfw/deps/glad.c | 1328 +- testbed/nanogui/ext/glfw/deps/glad/glad.h | 2214 +- testbed/nanogui/ext/glfw/deps/linmath.h | 571 + .../ext/glfw/deps/mingw/_mingw_dxhelper.h | 117 + testbed/nanogui/ext/glfw/deps/mingw/dinput.h | 2467 ++ testbed/nanogui/ext/glfw/deps/mingw/xinput.h | 239 + testbed/nanogui/ext/glfw/deps/tinycthread.c | 9 +- testbed/nanogui/ext/glfw/deps/tinycthread.h | 1 + .../ext/glfw/deps/vulkan/vk_platform.h | 120 + testbed/nanogui/ext/glfw/deps/vulkan/vulkan.h | 3835 +++ testbed/nanogui/ext/glfw/docs/CMakeLists.txt | 32 + testbed/nanogui/ext/glfw/docs/Doxyfile.in | 1859 ++ .../nanogui/ext/glfw/docs/DoxygenLayout.xml | 188 + testbed/nanogui/ext/glfw/docs/build.dox | 323 + testbed/nanogui/ext/glfw/docs/compat.dox | 224 + testbed/nanogui/ext/glfw/docs/compile.dox | 279 + testbed/nanogui/ext/glfw/docs/context.dox | 346 + testbed/nanogui/ext/glfw/docs/extra.css | 1 + testbed/nanogui/ext/glfw/docs/extra.less | 370 + testbed/nanogui/ext/glfw/docs/footer.html | 7 + testbed/nanogui/ext/glfw/docs/header.html | 34 + testbed/nanogui/ext/glfw/docs/input.dox | 664 + testbed/nanogui/ext/glfw/docs/internal.dox | 116 + testbed/nanogui/ext/glfw/docs/intro.dox | 369 + testbed/nanogui/ext/glfw/docs/main.dox | 47 + testbed/nanogui/ext/glfw/docs/monitor.dox | 215 + testbed/nanogui/ext/glfw/docs/moving.dox | 506 + testbed/nanogui/ext/glfw/docs/news.dox | 376 + testbed/nanogui/ext/glfw/docs/quick.dox | 364 + testbed/nanogui/ext/glfw/docs/spaces.svg | 872 + testbed/nanogui/ext/glfw/docs/vulkan.dox | 212 + testbed/nanogui/ext/glfw/docs/window.dox | 1002 + .../nanogui/ext/glfw/examples/CMakeLists.txt | 67 + testbed/nanogui/ext/glfw/examples/boing.c | 678 + testbed/nanogui/ext/glfw/examples/gears.c | 357 + testbed/nanogui/ext/glfw/examples/glfw.icns | Bin 0 -> 27988 bytes testbed/nanogui/ext/glfw/examples/glfw.ico | Bin 0 -> 21630 bytes testbed/nanogui/ext/glfw/examples/glfw.rc | 3 + testbed/nanogui/ext/glfw/examples/heightmap.c | 511 + testbed/nanogui/ext/glfw/examples/particles.c | 1068 + testbed/nanogui/ext/glfw/examples/simple.c | 163 + testbed/nanogui/ext/glfw/examples/splitview.c | 545 + testbed/nanogui/ext/glfw/examples/wave.c | 460 + testbed/nanogui/ext/glfw/include/GLFW/glfw3.h | 1969 +- .../ext/glfw/include/GLFW/glfw3native.h | 244 +- testbed/nanogui/ext/glfw/src/CMakeLists.txt | 121 +- testbed/nanogui/ext/glfw/src/cocoa_init.m | 163 +- .../{iokit_joystick.h => cocoa_joystick.h} | 34 +- testbed/nanogui/ext/glfw/src/cocoa_joystick.m | 511 + testbed/nanogui/ext/glfw/src/cocoa_monitor.m | 96 +- testbed/nanogui/ext/glfw/src/cocoa_platform.h | 85 +- .../glfw/src/{mach_time.c => cocoa_time.c} | 27 +- testbed/nanogui/ext/glfw/src/cocoa_window.m | 874 +- testbed/nanogui/ext/glfw/src/context.c | 269 +- testbed/nanogui/ext/glfw/src/egl_context.c | 625 +- testbed/nanogui/ext/glfw/src/egl_context.h | 198 +- .../nanogui/ext/glfw/src/glfw3Config.cmake.in | 16 +- testbed/nanogui/ext/glfw/src/glfw_config.h.in | 36 +- testbed/nanogui/ext/glfw/src/glx_context.c | 519 +- testbed/nanogui/ext/glfw/src/glx_context.h | 193 +- testbed/nanogui/ext/glfw/src/init.c | 39 +- testbed/nanogui/ext/glfw/src/input.c | 329 +- testbed/nanogui/ext/glfw/src/internal.h | 506 +- testbed/nanogui/ext/glfw/src/iokit_joystick.m | 506 - testbed/nanogui/ext/glfw/src/linux_joystick.c | 207 +- testbed/nanogui/ext/glfw/src/linux_joystick.h | 48 +- testbed/nanogui/ext/glfw/src/mir_init.c | 172 +- testbed/nanogui/ext/glfw/src/mir_monitor.c | 56 +- testbed/nanogui/ext/glfw/src/mir_platform.h | 59 +- testbed/nanogui/ext/glfw/src/mir_window.c | 679 +- testbed/nanogui/ext/glfw/src/monitor.c | 85 +- testbed/nanogui/ext/glfw/src/nsgl_context.h | 27 +- testbed/nanogui/ext/glfw/src/nsgl_context.m | 201 +- testbed/nanogui/ext/glfw/src/posix_time.c | 60 +- testbed/nanogui/ext/glfw/src/posix_time.h | 17 +- testbed/nanogui/ext/glfw/src/posix_tls.c | 26 +- testbed/nanogui/ext/glfw/src/posix_tls.h | 16 +- testbed/nanogui/ext/glfw/src/vulkan.c | 287 + testbed/nanogui/ext/glfw/src/wgl_context.c | 624 +- testbed/nanogui/ext/glfw/src/wgl_context.h | 148 +- testbed/nanogui/ext/glfw/src/win32_init.c | 236 +- testbed/nanogui/ext/glfw/src/win32_joystick.c | 763 + .../{winmm_joystick.h => win32_joystick.h} | 47 +- testbed/nanogui/ext/glfw/src/win32_monitor.c | 249 +- testbed/nanogui/ext/glfw/src/win32_platform.h | 213 +- testbed/nanogui/ext/glfw/src/win32_time.c | 50 +- testbed/nanogui/ext/glfw/src/win32_tls.c | 24 +- testbed/nanogui/ext/glfw/src/win32_tls.h | 48 - testbed/nanogui/ext/glfw/src/win32_window.c | 1343 +- testbed/nanogui/ext/glfw/src/window.c | 529 +- testbed/nanogui/ext/glfw/src/winmm_joystick.c | 177 - testbed/nanogui/ext/glfw/src/wl_init.c | 343 +- testbed/nanogui/ext/glfw/src/wl_monitor.c | 33 +- testbed/nanogui/ext/glfw/src/wl_platform.h | 77 +- testbed/nanogui/ext/glfw/src/wl_window.c | 738 +- testbed/nanogui/ext/glfw/src/x11_init.c | 366 +- testbed/nanogui/ext/glfw/src/x11_monitor.c | 69 +- testbed/nanogui/ext/glfw/src/x11_platform.h | 154 +- testbed/nanogui/ext/glfw/src/x11_window.c | 1654 +- testbed/nanogui/ext/glfw/src/xkb_unicode.c | 40 +- testbed/nanogui/ext/glfw/src/xkb_unicode.h | 8 +- testbed/nanogui/ext/glfw/tests/CMakeLists.txt | 78 + testbed/nanogui/ext/glfw/tests/clipboard.c | 157 + testbed/nanogui/ext/glfw/tests/cursor.c | 317 + testbed/nanogui/ext/glfw/tests/empty.c | 131 + testbed/nanogui/ext/glfw/tests/events.c | 620 + testbed/nanogui/ext/glfw/tests/gamma.c | 185 + testbed/nanogui/ext/glfw/tests/glfwinfo.c | 900 + testbed/nanogui/ext/glfw/tests/icon.c | 148 + testbed/nanogui/ext/glfw/tests/iconify.c | 298 + testbed/nanogui/ext/glfw/tests/joysticks.c | 216 + testbed/nanogui/ext/glfw/tests/monitors.c | 243 + testbed/nanogui/ext/glfw/tests/msaa.c | 163 + testbed/nanogui/ext/glfw/tests/reopen.c | 192 + testbed/nanogui/ext/glfw/tests/sharing.c | 186 + testbed/nanogui/ext/glfw/tests/tearing.c | 214 + testbed/nanogui/ext/glfw/tests/threads.c | 143 + testbed/nanogui/ext/glfw/tests/timeout.c | 97 + testbed/nanogui/ext/glfw/tests/title.c | 78 + testbed/nanogui/ext/glfw/tests/vulkan.c | 2245 ++ testbed/nanogui/ext/glfw/tests/windows.c | 166 + testbed/nanogui/ext/nanovg/.gitignore | 28 + testbed/nanogui/ext/nanovg/README.md | 1 + .../ext/nanovg/example/LICENSE_OFL.txt | 92 + .../ext/nanovg/example/NotoEmoji-Regular.ttf | Bin 0 -> 418804 bytes .../ext/nanovg/example/Roboto-Bold.ttf | Bin 0 -> 135820 bytes .../ext/nanovg/example/Roboto-Light.ttf | Bin 0 -> 140276 bytes .../ext/nanovg/example/Roboto-Regular.ttf | Bin 0 -> 145348 bytes testbed/nanogui/ext/nanovg/example/demo.c | 1226 + testbed/nanogui/ext/nanovg/example/demo.h | 26 + testbed/nanogui/ext/nanovg/example/entypo.ttf | Bin 0 -> 35392 bytes .../nanogui/ext/nanovg/example/example_fbo.c | 272 + .../nanogui/ext/nanovg/example/example_gl2.c | 161 + .../nanogui/ext/nanovg/example/example_gl3.c | 197 + .../ext/nanovg/example/example_gles2.c | 154 + .../ext/nanovg/example/example_gles3.c | 154 + testbed/nanogui/ext/nanovg/example/images.txt | 13 + .../ext/nanovg/example/images/image1.jpg | Bin 0 -> 25760 bytes .../ext/nanovg/example/images/image10.jpg | Bin 0 -> 3439 bytes .../ext/nanovg/example/images/image11.jpg | Bin 0 -> 3818 bytes .../ext/nanovg/example/images/image12.jpg | Bin 0 -> 5452 bytes .../ext/nanovg/example/images/image2.jpg | Bin 0 -> 24091 bytes .../ext/nanovg/example/images/image3.jpg | Bin 0 -> 29282 bytes .../ext/nanovg/example/images/image4.jpg | Bin 0 -> 23830 bytes .../ext/nanovg/example/images/image5.jpg | Bin 0 -> 27131 bytes .../ext/nanovg/example/images/image6.jpg | Bin 0 -> 25116 bytes .../ext/nanovg/example/images/image7.jpg | Bin 0 -> 25590 bytes .../ext/nanovg/example/images/image8.jpg | Bin 0 -> 24607 bytes .../ext/nanovg/example/images/image9.jpg | Bin 0 -> 4035 bytes testbed/nanogui/ext/nanovg/example/perf.c | 186 + testbed/nanogui/ext/nanovg/example/perf.h | 46 + .../ext/nanovg/example/screenshot-01.png | Bin 0 -> 989424 bytes .../ext/nanovg/example/screenshot-02.png | Bin 0 -> 229443 bytes .../ext/nanovg/example/stb_image_write.h | 511 + testbed/nanogui/ext/nanovg/src/fontstash.h | 48 +- testbed/nanogui/ext/nanovg/src/nanovg.c | 184 +- testbed/nanogui/ext/nanovg/src/nanovg.h | 77 +- testbed/nanogui/ext/nanovg/src/nanovg_gl.h | 109 +- .../nanogui/ext/nanovg/src/nanovg_gl_utils.h | 12 +- testbed/nanogui/ext/nanovg/src/stb_image.h | 3715 ++- testbed/nanogui/ext/nanovg/src/stb_truetype.h | 5331 +++-- testbed/nanogui/ext/pybind11/.appveyor.yml | 34 + testbed/nanogui/ext/pybind11/.gitignore | 37 + testbed/nanogui/ext/pybind11/.gitmodules | 3 + testbed/nanogui/ext/pybind11/.travis.yml | 142 + testbed/nanogui/ext/pybind11/CMakeLists.txt | 136 + testbed/nanogui/ext/pybind11/CONTRIBUTING.md | 37 + testbed/nanogui/ext/pybind11/LICENSE | 36 + testbed/nanogui/ext/pybind11/MANIFEST.in | 2 + testbed/nanogui/ext/pybind11/README.md | 128 + .../pybind11/docs/_static/theme_overrides.css | 11 + .../pybind11/docs/advanced/cast/chrono.rst | 81 + .../pybind11/docs/advanced/cast/custom.rst | 85 + .../ext/pybind11/docs/advanced/cast/eigen.rst | 50 + .../docs/advanced/cast/functional.rst | 113 + .../ext/pybind11/docs/advanced/cast/index.rst | 41 + .../pybind11/docs/advanced/cast/overview.rst | 146 + .../ext/pybind11/docs/advanced/cast/stl.rst | 154 + .../ext/pybind11/docs/advanced/classes.rst | 643 + .../ext/pybind11/docs/advanced/exceptions.rst | 142 + .../ext/pybind11/docs/advanced/functions.rst | 311 + .../ext/pybind11/docs/advanced/misc.rst | 229 + .../pybind11/docs/advanced/pycpp/index.rst | 13 + .../pybind11/docs/advanced/pycpp/numpy.rst | 302 + .../pybind11/docs/advanced/pycpp/object.rst | 96 + .../docs/advanced/pycpp/utilities.rst | 57 + .../ext/pybind11/docs/advanced/smart_ptrs.rst | 156 + testbed/nanogui/ext/pybind11/docs/basics.rst | 289 + .../nanogui/ext/pybind11/docs/benchmark.py | 90 + .../nanogui/ext/pybind11/docs/benchmark.rst | 99 + .../nanogui/ext/pybind11/docs/changelog.rst | 464 + testbed/nanogui/ext/pybind11/docs/classes.rst | 439 + .../nanogui/ext/pybind11/docs/compiling.rst | 185 + testbed/nanogui/ext/pybind11/docs/conf.py | 308 + testbed/nanogui/ext/pybind11/docs/faq.rst | 253 + testbed/nanogui/ext/pybind11/docs/index.rst | 45 + testbed/nanogui/ext/pybind11/docs/intro.rst | 95 + .../nanogui/ext/pybind11/docs/limitations.rst | 20 + .../ext/pybind11/docs/pybind11-logo.png | Bin 0 -> 58510 bytes .../docs/pybind11_vs_boost_python1.png | Bin 0 -> 44653 bytes .../docs/pybind11_vs_boost_python1.svg | 427 + .../docs/pybind11_vs_boost_python2.png | Bin 0 -> 41121 bytes .../docs/pybind11_vs_boost_python2.svg | 427 + .../nanogui/ext/pybind11/docs/reference.rst | 247 + testbed/nanogui/ext/pybind11/docs/release.rst | 23 + .../ext/pybind11/include/pybind11/attr.h | 386 + .../ext/pybind11/include/pybind11/cast.h | 1473 ++ .../ext/pybind11/include/pybind11/chrono.h | 160 + .../ext/pybind11/include/pybind11/common.h | 617 + .../ext/pybind11/include/pybind11/complex.h | 47 + .../ext/pybind11/include/pybind11/descr.h | 183 + .../ext/pybind11/include/pybind11/eigen.h | 241 + .../ext/pybind11/include/pybind11/eval.h | 112 + .../pybind11/include/pybind11/functional.h | 81 + .../ext/pybind11/include/pybind11/numpy.h | 1171 + .../ext/pybind11/include/pybind11/operators.h | 154 + .../ext/pybind11/include/pybind11/options.h | 65 + .../ext/pybind11/include/pybind11/pybind11.h | 1837 ++ .../ext/pybind11/include/pybind11/pytypes.h | 925 + .../ext/pybind11/include/pybind11/stl.h | 276 + .../ext/pybind11/include/pybind11/stl_bind.h | 541 + .../ext/pybind11/include/pybind11/typeid.h | 53 + .../nanogui/ext/pybind11/pybind11/__init__.py | 11 + .../nanogui/ext/pybind11/pybind11/_version.py | 2 + testbed/nanogui/ext/pybind11/setup.cfg | 10 + testbed/nanogui/ext/pybind11/setup.py | 74 + .../nanogui/ext/pybind11/tests/CMakeLists.txt | 164 + .../nanogui/ext/pybind11/tests/conftest.py | 239 + .../ext/pybind11/tests/constructor_stats.h | 276 + testbed/nanogui/ext/pybind11/tests/object.h | 175 + .../ext/pybind11/tests/pybind11_tests.cpp | 45 + .../ext/pybind11/tests/pybind11_tests.h | 12 + .../tests/test_alias_initialization.cpp | 62 + .../tests/test_alias_initialization.py | 80 + .../ext/pybind11/tests/test_buffers.cpp | 117 + .../ext/pybind11/tests/test_buffers.py | 62 + .../ext/pybind11/tests/test_callbacks.cpp | 149 + .../ext/pybind11/tests/test_callbacks.py | 98 + .../ext/pybind11/tests/test_chrono.cpp | 59 + .../nanogui/ext/pybind11/tests/test_chrono.py | 116 + .../ext/pybind11/tests/test_class_args.cpp | 68 + .../ext/pybind11/tests/test_class_args.py | 8 + .../installed_function/CMakeLists.txt | 12 + .../installed_target/CMakeLists.txt | 18 + .../pybind11/tests/test_cmake_build/main.cpp | 10 + .../subdirectory_function/CMakeLists.txt | 8 + .../subdirectory_target/CMakeLists.txt | 15 + .../pybind11/tests/test_cmake_build/test.py | 5 + .../tests/test_constants_and_functions.cpp | 104 + .../tests/test_constants_and_functions.py | 43 + .../tests/test_copy_move_policies.cpp | 41 + .../pybind11/tests/test_copy_move_policies.py | 15 + .../pybind11/tests/test_docstring_options.cpp | 53 + .../pybind11/tests/test_docstring_options.py | 32 + .../nanogui/ext/pybind11/tests/test_eigen.cpp | 134 + .../nanogui/ext/pybind11/tests/test_eigen.py | 145 + .../nanogui/ext/pybind11/tests/test_enum.cpp | 68 + .../nanogui/ext/pybind11/tests/test_enum.py | 108 + .../nanogui/ext/pybind11/tests/test_eval.cpp | 79 + .../nanogui/ext/pybind11/tests/test_eval.py | 19 + .../ext/pybind11/tests/test_eval_call.py | 4 + .../ext/pybind11/tests/test_exceptions.cpp | 173 + .../ext/pybind11/tests/test_exceptions.py | 74 + .../ext/pybind11/tests/test_inheritance.cpp | 100 + .../ext/pybind11/tests/test_inheritance.py | 55 + .../ext/pybind11/tests/test_issues.cpp | 401 + .../nanogui/ext/pybind11/tests/test_issues.py | 251 + .../ext/pybind11/tests/test_keep_alive.cpp | 40 + .../ext/pybind11/tests/test_keep_alive.py | 97 + .../tests/test_kwargs_and_defaults.cpp | 56 + .../tests/test_kwargs_and_defaults.py | 57 + .../tests/test_methods_and_attributes.cpp | 186 + .../tests/test_methods_and_attributes.py | 205 + .../ext/pybind11/tests/test_modules.cpp | 58 + .../ext/pybind11/tests/test_modules.py | 54 + .../tests/test_multiple_inheritance.cpp | 83 + .../tests/test_multiple_inheritance.py | 62 + .../ext/pybind11/tests/test_numpy_array.cpp | 153 + .../ext/pybind11/tests/test_numpy_array.py | 274 + .../ext/pybind11/tests/test_numpy_dtypes.cpp | 363 + .../ext/pybind11/tests/test_numpy_dtypes.py | 225 + .../pybind11/tests/test_numpy_vectorize.cpp | 41 + .../pybind11/tests/test_numpy_vectorize.py | 76 + .../ext/pybind11/tests/test_opaque_types.cpp | 62 + .../ext/pybind11/tests/test_opaque_types.py | 49 + .../tests/test_operator_overloading.cpp | 76 + .../tests/test_operator_overloading.py | 40 + .../ext/pybind11/tests/test_pickling.cpp | 83 + .../ext/pybind11/tests/test_pickling.py | 35 + .../ext/pybind11/tests/test_python_types.cpp | 429 + .../ext/pybind11/tests/test_python_types.py | 412 + .../tests/test_sequences_and_iterators.cpp | 275 + .../tests/test_sequences_and_iterators.py | 90 + .../ext/pybind11/tests/test_smart_ptr.cpp | 240 + .../ext/pybind11/tests/test_smart_ptr.py | 203 + .../ext/pybind11/tests/test_stl_binders.cpp | 100 + .../ext/pybind11/tests/test_stl_binders.py | 140 + .../pybind11/tests/test_virtual_functions.cpp | 347 + .../pybind11/tests/test_virtual_functions.py | 259 + .../ext/pybind11/tools/FindEigen3.cmake | 81 + .../pybind11/tools/FindPythonLibsNew.cmake | 194 + .../nanogui/ext/pybind11/tools/check-style.sh | 83 + .../ext/pybind11/tools/clang/.gitignore | 4 + .../ext/pybind11/tools/clang/LICENSE.TXT | 63 + .../ext/pybind11/tools/clang/README.md | 2 + .../ext/pybind11/tools/clang/__init__.py | 24 + .../ext/pybind11/tools/clang/cindex.py | 3751 +++ .../ext/pybind11/tools/clang/enumerations.py | 34 + testbed/nanogui/ext/pybind11/tools/libsize.py | 38 + testbed/nanogui/ext/pybind11/tools/mkdoc.py | 309 + .../pybind11/tools/pybind11Config.cmake.in | 92 + .../ext/pybind11/tools/pybind11Tools.cmake | 163 + testbed/nanogui/include/nanogui/button.h | 128 +- testbed/nanogui/include/nanogui/checkbox.h | 99 +- testbed/nanogui/include/nanogui/colorpicker.h | 111 +- testbed/nanogui/include/nanogui/colorwheel.h | 87 +- testbed/nanogui/include/nanogui/combobox.h | 54 +- testbed/nanogui/include/nanogui/common.h | 385 +- testbed/nanogui/include/nanogui/compat.h | 16 +- testbed/nanogui/include/nanogui/entypo.h | 2832 ++- testbed/nanogui/include/nanogui/formhelper.h | 266 +- testbed/nanogui/include/nanogui/glcanvas.h | 93 + testbed/nanogui/include/nanogui/glutil.h | 721 +- testbed/nanogui/include/nanogui/graph.h | 18 +- testbed/nanogui/include/nanogui/imagepanel.h | 18 +- testbed/nanogui/include/nanogui/imageview.h | 167 +- testbed/nanogui/include/nanogui/label.h | 27 +- testbed/nanogui/include/nanogui/layout.h | 287 +- .../nanogui/include/nanogui/messagedialog.h | 11 +- testbed/nanogui/include/nanogui/nanogui.h | 6 +- testbed/nanogui/include/nanogui/object.h | 94 +- testbed/nanogui/include/nanogui/opengl.h | 66 +- testbed/nanogui/include/nanogui/popup.h | 25 +- testbed/nanogui/include/nanogui/popupbutton.h | 31 +- testbed/nanogui/include/nanogui/progressbar.h | 18 +- testbed/nanogui/include/nanogui/python.h | 76 + testbed/nanogui/include/nanogui/screen.h | 93 +- .../nanogui/include/nanogui/serializer/core.h | 50 +- .../include/nanogui/serializer/opengl.h | 7 + .../include/nanogui/serializer/sparse.h | 5 + testbed/nanogui/include/nanogui/slider.h | 26 +- .../nanogui/include/nanogui/stackedwidget.h | 44 + testbed/nanogui/include/nanogui/tabheader.h | 181 + testbed/nanogui/include/nanogui/tabwidget.h | 192 + testbed/nanogui/include/nanogui/textbox.h | 237 +- testbed/nanogui/include/nanogui/theme.h | 165 +- testbed/nanogui/include/nanogui/toolbutton.h | 10 +- .../nanogui/include/nanogui/vscrollpanel.h | 33 +- testbed/nanogui/include/nanogui/widget.h | 116 +- testbed/nanogui/include/nanogui/window.h | 27 +- testbed/nanogui/resources/bin2c.c | 76 - testbed/nanogui/resources/bin2c.cmake | 31 + testbed/nanogui/resources/check-style.sh | 83 + testbed/nanogui/resources/entypo.ttf | Bin 35392 -> 67000 bytes testbed/nanogui/resources/screenshot.png | Bin 0 -> 1155583 bytes testbed/nanogui/resources/screenshot2.png | Bin 0 -> 47727 bytes testbed/nanogui/src/button.cpp | 13 +- testbed/nanogui/src/checkbox.cpp | 16 +- testbed/nanogui/src/colorpicker.cpp | 56 +- testbed/nanogui/src/colorwheel.cpp | 2 +- testbed/nanogui/src/combobox.cpp | 21 +- testbed/nanogui/src/common.cpp | 164 +- testbed/nanogui/src/darwin.mm | 27 +- testbed/nanogui/src/example1.cpp | 369 +- testbed/nanogui/src/example2.cpp | 35 +- testbed/nanogui/src/example3.cpp | 193 + testbed/nanogui/src/example4.cpp | 250 + testbed/nanogui/src/example_icons.cpp | 479 + testbed/nanogui/src/glcanvas.cpp | 92 + testbed/nanogui/src/glutil.cpp | 248 +- testbed/nanogui/src/graph.cpp | 2 +- testbed/nanogui/src/imagepanel.cpp | 4 +- testbed/nanogui/src/imageview.cpp | 466 +- testbed/nanogui/src/label.cpp | 25 +- testbed/nanogui/src/layout.cpp | 60 +- testbed/nanogui/src/messagedialog.cpp | 13 +- testbed/nanogui/src/popup.cpp | 27 +- testbed/nanogui/src/popupbutton.cpp | 40 +- testbed/nanogui/src/progressbar.cpp | 2 +- testbed/nanogui/src/screen.cpp | 266 +- testbed/nanogui/src/serializer.cpp | 4 +- testbed/nanogui/src/slider.cpp | 59 +- testbed/nanogui/src/stackedwidget.cpp | 57 + testbed/nanogui/src/tabheader.cpp | 478 + testbed/nanogui/src/tabwidget.cpp | 201 + testbed/nanogui/src/textbox.cpp | 175 +- testbed/nanogui/src/theme.cpp | 25 +- testbed/nanogui/src/vscrollpanel.cpp | 86 +- testbed/nanogui/src/widget.cpp | 64 +- testbed/nanogui/src/window.cpp | 12 +- testbed/src/Gui.cpp | 11 +- 1917 files changed, 262082 insertions(+), 115576 deletions(-) create mode 100644 testbed/nanogui/CONTRIBUTING.rst create mode 100644 testbed/nanogui/README.rst create mode 100644 testbed/nanogui/ext/coro/LICENSE create mode 100644 testbed/nanogui/ext/coro/README create mode 100644 testbed/nanogui/ext/coro/coro.c create mode 100644 testbed/nanogui/ext/coro/coro.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/Array delete mode 100644 testbed/nanogui/ext/eigen/Eigen/Eigen2Support delete mode 100644 testbed/nanogui/ext/eigen/Eigen/LeastSquares delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Cholesky/CMakeLists.txt rename testbed/nanogui/ext/eigen/Eigen/src/Cholesky/{LLT_MKL.h => LLT_LAPACKE.h} (69%) delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/CholmodSupport/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/ArithmeticSequence.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/AssignEvaluator.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/ConditionEstimator.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/CoreEvaluators.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/CwiseTernaryOp.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/Flagged.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/Functors.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/IndexedView.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/Inverse.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/MathFunctionsImpl.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/Product.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/ProductBase.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/ProductEvaluators.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/Solve.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/SolverBase.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/AVX/Complex.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/AVX/MathFunctions.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/AVX/PacketMath.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/AVX/TypeCasting.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/AVX512/MathFunctions.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/AVX512/PacketMath.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/AltiVec/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/AltiVec/MathFunctions.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/CUDA/Complex.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/CUDA/Half.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/CUDA/MathFunctions.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/CUDA/PacketMath.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/CUDA/PacketMathHalf.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/CUDA/TypeCasting.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/Default/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/NEON/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/NEON/MathFunctions.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/SSE/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/SSE/TypeCasting.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/ZVector/Complex.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/ZVector/MathFunctions.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/arch/ZVector/PacketMath.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/functors/AssignmentFunctors.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/functors/BinaryFunctors.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/functors/NullaryFunctors.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/functors/StlFunctors.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/functors/TernaryFunctors.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/functors/UnaryFunctors.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/products/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/products/CoeffBasedProduct.h rename testbed/nanogui/ext/eigen/Eigen/src/Core/products/{GeneralMatrixMatrixTriangular_MKL.h => GeneralMatrixMatrixTriangular_BLAS.h} (69%) rename testbed/nanogui/ext/eigen/Eigen/src/Core/products/{GeneralMatrixMatrix_MKL.h => GeneralMatrixMatrix_BLAS.h} (76%) rename testbed/nanogui/ext/eigen/Eigen/src/Core/products/{GeneralMatrixVector_MKL.h => GeneralMatrixVector_BLAS.h} (60%) rename testbed/nanogui/ext/eigen/Eigen/src/Core/products/{SelfadjointMatrixMatrix_MKL.h => SelfadjointMatrixMatrix_BLAS.h} (68%) rename testbed/nanogui/ext/eigen/Eigen/src/Core/products/{SelfadjointMatrixVector_MKL.h => SelfadjointMatrixVector_BLAS.h} (72%) rename testbed/nanogui/ext/eigen/Eigen/src/Core/products/{TriangularMatrixMatrix_MKL.h => TriangularMatrixMatrix_BLAS.h} (76%) rename testbed/nanogui/ext/eigen/Eigen/src/Core/products/{TriangularMatrixVector_MKL.h => TriangularMatrixVector_BLAS.h} (74%) rename testbed/nanogui/ext/eigen/Eigen/src/Core/products/{TriangularSolverMatrix_MKL.h => TriangularSolverMatrix_BLAS.h} (75%) delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/util/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/util/IndexedViewHelper.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/util/IntegralConstant.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Core/util/SymbolicIndex.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/Block.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/Cwise.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/CwiseOperators.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/Geometry/AlignedBox.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/Geometry/All.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/Geometry/AngleAxis.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/Geometry/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/Geometry/Hyperplane.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/Geometry/Quaternion.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/Geometry/Rotation2D.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/Geometry/RotationBase.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/Geometry/Scaling.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/Geometry/Transform.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/Geometry/Translation.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/LU.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/Lazy.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/LeastSquares.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/Macros.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/MathFunctions.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/Memory.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/Meta.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/Minor.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/QR.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/SVD.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/TriangularSolver.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigen2Support/VectorBlock.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Eigenvalues/CMakeLists.txt rename testbed/nanogui/ext/eigen/Eigen/src/Eigenvalues/{ComplexSchur_MKL.h => ComplexSchur_LAPACKE.h} (65%) rename testbed/nanogui/ext/eigen/Eigen/src/Eigenvalues/{RealSchur_MKL.h => RealSchur_LAPACKE.h} (64%) rename testbed/nanogui/ext/eigen/Eigen/src/Eigenvalues/{SelfAdjointEigenSolver_MKL.h => SelfAdjointEigenSolver_LAPACKE.h} (62%) delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Geometry/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Geometry/arch/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Householder/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/IterativeLinearSolvers/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/IterativeLinearSolvers/IncompleteCholesky.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/IterativeLinearSolvers/LeastSquareConjugateGradient.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/IterativeLinearSolvers/SolveWithGuess.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/Jacobi/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/LU/CMakeLists.txt rename testbed/nanogui/ext/eigen/Eigen/src/LU/{Inverse.h => InverseImpl.h} (86%) rename testbed/nanogui/ext/eigen/Eigen/src/LU/{PartialPivLU_MKL.h => PartialPivLU_LAPACKE.h} (77%) delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/LU/arch/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/MetisSupport/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/OrderingMethods/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/PaStiXSupport/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/PardisoSupport/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/QR/CMakeLists.txt rename testbed/nanogui/ext/eigen/Eigen/src/QR/{ColPivHouseholderQR_MKL.h => ColPivHouseholderQR_LAPACKE.h} (64%) create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/QR/CompleteOrthogonalDecomposition.h rename testbed/nanogui/ext/eigen/Eigen/src/QR/{HouseholderQR_MKL.h => HouseholderQR_LAPACKE.h} (64%) delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/SPQRSupport/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/SVD/BDCSVD.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/SVD/CMakeLists.txt rename testbed/nanogui/ext/eigen/Eigen/src/SVD/{JacobiSVD_MKL.h => JacobiSVD_LAPACKE.h} (60%) rename testbed/nanogui/ext/eigen/{unsupported => }/Eigen/src/SVD/SVDBase.h (52%) delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/SparseCholesky/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/SparseCore/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/SparseCore/SparseAssign.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/SparseCore/SparseCompressedBase.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/SparseCore/SparseMap.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/SparseCore/SparseRef.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/SparseCore/SparseSolverBase.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/SparseLU/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/SparseQR/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/StlSupport/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/SuperLUSupport/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/UmfPackSupport/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/misc/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/misc/RealSvd2x2.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/misc/Solve.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/misc/SparseSolve.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/misc/lapack.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/misc/lapacke.h create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/misc/lapacke_mangling.h delete mode 100644 testbed/nanogui/ext/eigen/Eigen/src/plugins/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/Eigen/src/plugins/IndexedViewMethods.h create mode 100644 testbed/nanogui/ext/eigen/README.md create mode 100644 testbed/nanogui/ext/eigen/bench/analyze-blocking-sizes.cpp create mode 100644 testbed/nanogui/ext/eigen/bench/benchmark-blocking-sizes.cpp create mode 100644 testbed/nanogui/ext/eigen/bench/btl/cmake/FindBLAZE.cmake delete mode 100644 testbed/nanogui/ext/eigen/bench/btl/cmake/FindGOTO.cmake delete mode 100644 testbed/nanogui/ext/eigen/bench/btl/cmake/FindGOTO2.cmake create mode 100644 testbed/nanogui/ext/eigen/bench/btl/cmake/FindOPENBLAS.cmake create mode 100644 testbed/nanogui/ext/eigen/bench/btl/libs/blaze/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/bench/btl/libs/blaze/blaze_interface.hh create mode 100644 testbed/nanogui/ext/eigen/bench/btl/libs/blaze/main.cpp create mode 100644 testbed/nanogui/ext/eigen/bench/btl/libs/tensors/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/bench/btl/libs/tensors/main_linear.cpp create mode 100644 testbed/nanogui/ext/eigen/bench/btl/libs/tensors/main_matmat.cpp create mode 100644 testbed/nanogui/ext/eigen/bench/btl/libs/tensors/main_vecmat.cpp create mode 100644 testbed/nanogui/ext/eigen/bench/btl/libs/tensors/tensor_interface.hh create mode 100644 testbed/nanogui/ext/eigen/bench/dense_solvers.cpp create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/changesets.txt create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/gemm.cpp create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/gemm_common.h create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/gemm_settings.txt create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/gemm_square_settings.txt create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/gemv.cpp create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/gemv_common.h create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/gemv_settings.txt create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/gemv_square_settings.txt create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/gemvt.cpp create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/lazy_gemm.cpp create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/lazy_gemm_settings.txt create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/llt.cpp create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/make_plot.sh create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/resources/chart_footer.html create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/resources/chart_header.html create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/resources/footer.html create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/resources/header.html create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/resources/s1.js create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/resources/s2.js create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/run.sh create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/runall.sh create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/trmv_lo.cpp create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/trmv_lot.cpp create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/trmv_up.cpp create mode 100644 testbed/nanogui/ext/eigen/bench/perf_monitoring/trmv_upt.cpp create mode 100644 testbed/nanogui/ext/eigen/bench/tensors/README create mode 100644 testbed/nanogui/ext/eigen/bench/tensors/benchmark.h create mode 100644 testbed/nanogui/ext/eigen/bench/tensors/benchmark_main.cc create mode 100644 testbed/nanogui/ext/eigen/bench/tensors/contraction_benchmarks_cpu.cc create mode 100644 testbed/nanogui/ext/eigen/bench/tensors/tensor_benchmarks.h create mode 100644 testbed/nanogui/ext/eigen/bench/tensors/tensor_benchmarks_cpu.cc create mode 100644 testbed/nanogui/ext/eigen/bench/tensors/tensor_benchmarks_fp16_gpu.cu create mode 100644 testbed/nanogui/ext/eigen/bench/tensors/tensor_benchmarks_gpu.cu create mode 100644 testbed/nanogui/ext/eigen/bench/tensors/tensor_benchmarks_sycl.cc delete mode 100644 testbed/nanogui/ext/eigen/blas/chbmv.f delete mode 100644 testbed/nanogui/ext/eigen/blas/chpmv.f delete mode 100644 testbed/nanogui/ext/eigen/blas/ctbmv.f delete mode 100644 testbed/nanogui/ext/eigen/blas/drotm.f delete mode 100644 testbed/nanogui/ext/eigen/blas/drotmg.f delete mode 100644 testbed/nanogui/ext/eigen/blas/dsbmv.f delete mode 100644 testbed/nanogui/ext/eigen/blas/dspmv.f delete mode 100644 testbed/nanogui/ext/eigen/blas/dtbmv.f create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/chbmv.c create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/chpmv.c create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/complexdots.c create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/ctbmv.c create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/d_cnjg.c create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/datatypes.h create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/drotm.c create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/drotmg.c create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/dsbmv.c create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/dspmv.c create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/dtbmv.c create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/lsame.c create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/r_cnjg.c create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/srotm.c create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/srotmg.c create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/ssbmv.c create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/sspmv.c create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/stbmv.c create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/zhbmv.c create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/zhpmv.c create mode 100644 testbed/nanogui/ext/eigen/blas/f2c/ztbmv.c rename testbed/nanogui/ext/eigen/blas/{ => fortran}/complexdots.f (100%) delete mode 100644 testbed/nanogui/ext/eigen/blas/lsame.f delete mode 100644 testbed/nanogui/ext/eigen/blas/srotm.f delete mode 100644 testbed/nanogui/ext/eigen/blas/srotmg.f delete mode 100644 testbed/nanogui/ext/eigen/blas/ssbmv.f delete mode 100644 testbed/nanogui/ext/eigen/blas/sspmv.f delete mode 100644 testbed/nanogui/ext/eigen/blas/stbmv.f delete mode 100644 testbed/nanogui/ext/eigen/blas/zhbmv.f delete mode 100644 testbed/nanogui/ext/eigen/blas/zhpmv.f delete mode 100644 testbed/nanogui/ext/eigen/blas/ztbmv.f create mode 100644 testbed/nanogui/ext/eigen/cmake/Eigen3Config.cmake.in create mode 100644 testbed/nanogui/ext/eigen/cmake/Eigen3ConfigLegacy.cmake.in create mode 100644 testbed/nanogui/ext/eigen/cmake/EigenUninstall.cmake create mode 100644 testbed/nanogui/ext/eigen/cmake/FindComputeCpp.cmake create mode 100644 testbed/nanogui/ext/eigen/cmake/FindXsmm.cmake create mode 100644 testbed/nanogui/ext/eigen/cmake/UseEigen3.cmake create mode 100644 testbed/nanogui/ext/eigen/demos/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/demos/mandelbrot/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/demos/mandelbrot/README create mode 100644 testbed/nanogui/ext/eigen/demos/mandelbrot/mandelbrot.cpp create mode 100644 testbed/nanogui/ext/eigen/demos/mandelbrot/mandelbrot.h create mode 100644 testbed/nanogui/ext/eigen/demos/mix_eigen_and_c/README create mode 100644 testbed/nanogui/ext/eigen/demos/mix_eigen_and_c/binary_library.cpp create mode 100644 testbed/nanogui/ext/eigen/demos/mix_eigen_and_c/binary_library.h create mode 100644 testbed/nanogui/ext/eigen/demos/mix_eigen_and_c/example.c create mode 100644 testbed/nanogui/ext/eigen/demos/opengl/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/demos/opengl/README create mode 100644 testbed/nanogui/ext/eigen/demos/opengl/camera.cpp create mode 100644 testbed/nanogui/ext/eigen/demos/opengl/camera.h create mode 100644 testbed/nanogui/ext/eigen/demos/opengl/gpuhelper.cpp create mode 100644 testbed/nanogui/ext/eigen/demos/opengl/gpuhelper.h create mode 100644 testbed/nanogui/ext/eigen/demos/opengl/icosphere.cpp create mode 100644 testbed/nanogui/ext/eigen/demos/opengl/icosphere.h create mode 100644 testbed/nanogui/ext/eigen/demos/opengl/quaternion_demo.cpp create mode 100644 testbed/nanogui/ext/eigen/demos/opengl/quaternion_demo.h create mode 100644 testbed/nanogui/ext/eigen/demos/opengl/trackball.cpp create mode 100644 testbed/nanogui/ext/eigen/demos/opengl/trackball.h create mode 100644 testbed/nanogui/ext/eigen/doc/A05_PortingFrom2To3.dox create mode 100644 testbed/nanogui/ext/eigen/doc/AsciiQuickReference.txt create mode 100644 testbed/nanogui/ext/eigen/doc/B01_Experimental.dox create mode 100644 testbed/nanogui/ext/eigen/doc/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/doc/ClassHierarchy.dox create mode 100644 testbed/nanogui/ext/eigen/doc/CoeffwiseMathFunctionsTable.dox create mode 100644 testbed/nanogui/ext/eigen/doc/CustomizingEigen_CustomScalar.dox create mode 100644 testbed/nanogui/ext/eigen/doc/CustomizingEigen_InheritingMatrix.dox create mode 100644 testbed/nanogui/ext/eigen/doc/CustomizingEigen_NullaryExpr.dox create mode 100644 testbed/nanogui/ext/eigen/doc/CustomizingEigen_Plugins.dox create mode 100644 testbed/nanogui/ext/eigen/doc/DenseDecompositionBenchmark.dox create mode 100644 testbed/nanogui/ext/eigen/doc/Doxyfile.in create mode 100644 testbed/nanogui/ext/eigen/doc/Eigen_Silly_Professor_64x64.png create mode 100644 testbed/nanogui/ext/eigen/doc/FixedSizeVectorizable.dox create mode 100644 testbed/nanogui/ext/eigen/doc/FunctionsTakingEigenTypes.dox create mode 100644 testbed/nanogui/ext/eigen/doc/HiPerformance.dox create mode 100644 testbed/nanogui/ext/eigen/doc/InplaceDecomposition.dox create mode 100644 testbed/nanogui/ext/eigen/doc/InsideEigenExample.dox create mode 100644 testbed/nanogui/ext/eigen/doc/LeastSquares.dox create mode 100644 testbed/nanogui/ext/eigen/doc/Manual.dox create mode 100644 testbed/nanogui/ext/eigen/doc/MatrixfreeSolverExample.dox create mode 100644 testbed/nanogui/ext/eigen/doc/NewExpressionType.dox create mode 100644 testbed/nanogui/ext/eigen/doc/Overview.dox create mode 100644 testbed/nanogui/ext/eigen/doc/PassingByValue.dox create mode 100644 testbed/nanogui/ext/eigen/doc/Pitfalls.dox create mode 100644 testbed/nanogui/ext/eigen/doc/PreprocessorDirectives.dox create mode 100644 testbed/nanogui/ext/eigen/doc/QuickReference.dox create mode 100644 testbed/nanogui/ext/eigen/doc/QuickStartGuide.dox create mode 100644 testbed/nanogui/ext/eigen/doc/SparseLinearSystems.dox create mode 100644 testbed/nanogui/ext/eigen/doc/SparseQuickReference.dox create mode 100644 testbed/nanogui/ext/eigen/doc/StlContainers.dox create mode 100644 testbed/nanogui/ext/eigen/doc/StorageOrders.dox create mode 100644 testbed/nanogui/ext/eigen/doc/StructHavingEigenMembers.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TemplateKeyword.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TopicAliasing.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TopicAssertions.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TopicCMakeGuide.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TopicEigenExpressionTemplates.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TopicLazyEvaluation.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TopicLinearAlgebraDecompositions.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TopicMultithreading.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TopicResizing.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TopicScalarTypes.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TopicVectorization.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TutorialAdvancedInitialization.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TutorialArrayClass.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TutorialBlockOperations.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TutorialGeometry.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TutorialLinearAlgebra.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TutorialMapClass.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TutorialMatrixArithmetic.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TutorialMatrixClass.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TutorialReductionsVisitorsBroadcasting.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TutorialReshapeSlicing.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TutorialSparse.dox create mode 100644 testbed/nanogui/ext/eigen/doc/TutorialSparse_example_details.dox create mode 100644 testbed/nanogui/ext/eigen/doc/UnalignedArrayAssert.dox create mode 100644 testbed/nanogui/ext/eigen/doc/UsingBlasLapackBackends.dox create mode 100644 testbed/nanogui/ext/eigen/doc/UsingIntelMKL.dox create mode 100644 testbed/nanogui/ext/eigen/doc/UsingNVCC.dox create mode 100644 testbed/nanogui/ext/eigen/doc/WrongStackAlignment.dox create mode 100644 testbed/nanogui/ext/eigen/doc/eigen_navtree_hacks.js create mode 100644 testbed/nanogui/ext/eigen/doc/eigendoxy.css create mode 100644 testbed/nanogui/ext/eigen/doc/eigendoxy_footer.html.in create mode 100644 testbed/nanogui/ext/eigen/doc/eigendoxy_header.html.in create mode 100644 testbed/nanogui/ext/eigen/doc/eigendoxy_layout.xml.in create mode 100644 testbed/nanogui/ext/eigen/doc/eigendoxy_tabs.css create mode 100644 testbed/nanogui/ext/eigen/doc/examples/.krazy create mode 100644 testbed/nanogui/ext/eigen/doc/examples/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/doc/examples/CustomizingEigen_Inheritance.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Cwise_erf.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Cwise_erfc.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Cwise_lgamma.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/DenseBase_middleCols_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/DenseBase_middleRows_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/DenseBase_template_int_middleCols.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/DenseBase_template_int_middleRows.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/QuickStart_example.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/QuickStart_example2_dynamic.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/QuickStart_example2_fixed.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/TemplateKeyword_flexible.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/TemplateKeyword_simple.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/TutorialInplaceLU.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgComputeTwice.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgExComputeSolveError.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgExSolveColPivHouseholderQR.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgExSolveLDLT.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgInverseDeterminant.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgRankRevealing.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgSVDSolve.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgSelfAdjointEigenSolver.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgSetThreshold.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_accessors.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_addition.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_cwise_other.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_interop.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_interop_matrix.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_mult.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_BlockOperations_block_assignment.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_BlockOperations_colrow.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_BlockOperations_corner.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_BlockOperations_print_block.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_BlockOperations_vector.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_PartialLU_solve.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_1nn.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple_rowwise.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_colwise.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_maxnorm.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_bool.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_norm.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_operatornorm.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_rowwise.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_visitors.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_simple_example_dynamic_size.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/Tutorial_simple_example_fixed_size.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/class_Block.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/class_CwiseBinaryOp.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/class_CwiseUnaryOp.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/class_CwiseUnaryOp_ptrfun.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/class_FixedBlock.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/class_FixedVectorBlock.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/class_VectorBlock.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/function_taking_eigenbase.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/function_taking_ref.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.entry create mode 100644 testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.evaluator create mode 100644 testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.expression create mode 100644 testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.main create mode 100644 testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.preamble create mode 100644 testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.traits create mode 100644 testbed/nanogui/ext/eigen/doc/examples/make_circulant2.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/matrixfree_cg.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/nullary_indexing.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/tut_arithmetic_add_sub.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/tut_arithmetic_dot_cross.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/tut_arithmetic_matrix_mul.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/tut_arithmetic_redux_basic.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/tut_arithmetic_scalar_mul_div.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/tut_matrix_coefficient_accessors.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/tut_matrix_resize.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/examples/tut_matrix_resize_fixed_size.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/ftv2node.png create mode 100644 testbed/nanogui/ext/eigen/doc/ftv2pnode.png create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/.krazy create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/AngleAxis_mimic_euler.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/BiCGSTAB_simple.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/BiCGSTAB_step_by_step.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/ColPivHouseholderQR_solve.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/ComplexEigenSolver_compute.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/ComplexEigenSolver_eigenvalues.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/ComplexEigenSolver_eigenvectors.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/ComplexSchur_compute.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/ComplexSchur_matrixT.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/ComplexSchur_matrixU.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_abs.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_abs2.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_acos.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_arg.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_array_power_array.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_asin.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_atan.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_boolean_and.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_boolean_not.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_boolean_or.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_boolean_xor.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_ceil.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_cos.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_cosh.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_cube.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_equal_equal.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_exp.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_floor.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_greater.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_greater_equal.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_inverse.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_isFinite.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_isInf.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_isNaN.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_less.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_less_equal.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_log.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_log10.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_max.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_min.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_minus.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_minus_equal.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_not_equal.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_plus.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_plus_equal.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_pow.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_product.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_quotient.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_round.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_scalar_power_array.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_sign.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_sin.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_sinh.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_slash_equal.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_sqrt.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_square.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_tan.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_tanh.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Cwise_times_equal.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/DenseBase_LinSpaced.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/DenseBase_LinSpacedInt.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/DenseBase_LinSpaced_seq.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/DenseBase_setLinSpaced.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/DirectionWise_hnormalized.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/DirectionWise_replicate.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/DirectionWise_replicate_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/EigenSolver_EigenSolver_MatrixType.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/EigenSolver_compute.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/EigenSolver_eigenvalues.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/EigenSolver_eigenvectors.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/EigenSolver_pseudoEigenvectors.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/FullPivHouseholderQR_solve.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/FullPivLU_image.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/FullPivLU_kernel.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/FullPivLU_solve.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/GeneralizedEigenSolver.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/HessenbergDecomposition_compute.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/HessenbergDecomposition_matrixH.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/HessenbergDecomposition_packedMatrix.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/HouseholderQR_householderQ.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/HouseholderQR_solve.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/HouseholderSequence_HouseholderSequence.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/IOFormat.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/JacobiSVD_basic.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Jacobi_makeGivens.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Jacobi_makeJacobi.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/LLT_example.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/LLT_solve.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/LeastSquaresNormalEquations.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/LeastSquaresQR.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Map_general_stride.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Map_inner_stride.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Map_outer_stride.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Map_placement_new.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Map_simple.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_adjoint.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_all.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_applyOnTheLeft.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_applyOnTheRight.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_array.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_array_const.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_asDiagonal.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_block_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_block_int_int_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_bottomLeftCorner_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_bottomRightCorner_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_bottomRows_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cast.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_col.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_colwise.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_computeInverseAndDetWithCheck.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_computeInverseWithCheck.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseAbs.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseAbs2.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseEqual.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseInverse.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseMax.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseMin.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseNotEqual.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseProduct.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseQuotient.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseSign.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseSqrt.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_diagonal.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_diagonal_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_diagonal_template_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_eigenvalues.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_end_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_eval.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_fixedBlock_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_hnormalized.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_homogeneous.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_identity.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_identity_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_inverse.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isDiagonal.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isIdentity.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isOnes.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isOrthogonal.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isUnitary.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isZero.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_leftCols_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_noalias.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_ones.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_ones_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_ones_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_operatorNorm.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_prod.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_random.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_random_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_random_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_replicate.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_replicate_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_reverse.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_rightCols_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_row.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_rowwise.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_segment_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_select.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_selfadjointView.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_set.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_setIdentity.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_setOnes.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_setRandom.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_setZero.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_start_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_bottomRows.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_end.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_block_int_int_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_bottomLeftCorner.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_bottomLeftCorner_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_bottomRightCorner.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_bottomRightCorner_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_topLeftCorner.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_topLeftCorner_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_topRightCorner.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_topRightCorner_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_leftCols.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_rightCols.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_segment.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_start.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_topRows.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_topLeftCorner_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_topRightCorner_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_topRows_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_transpose.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_triangularView.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_zero.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_zero_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_zero_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Matrix_resize_NoChange_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Matrix_resize_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Matrix_resize_int_NoChange.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Matrix_resize_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Matrix_setConstant_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Matrix_setConstant_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Matrix_setIdentity_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Matrix_setOnes_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Matrix_setOnes_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Matrix_setRandom_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Matrix_setRandom_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Matrix_setZero_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Matrix_setZero_int_int.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/PartialPivLU_solve.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_count.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_maxCoeff.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_minCoeff.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_norm.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_prod.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_squaredNorm.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_sum.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/RealQZ_compute.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/RealSchur_RealSchur_MatrixType.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/RealSchur_compute.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_SelfAdjointEigenSolver.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_SelfAdjointEigenSolver_MatrixType.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_SelfAdjointEigenSolver_MatrixType2.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_compute_MatrixType.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_compute_MatrixType2.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_eigenvalues.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_eigenvectors.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_operatorInverseSqrt.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_operatorSqrt.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointView_eigenvalues.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointView_operatorNorm.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/SparseMatrix_coeffs.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_block.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_block_correct.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_cwise.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_mult1.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_mult2.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_mult3.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_mult4.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_mult5.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/TopicStorageOrders_example.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Triangular_solve.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_Tridiagonalization_MatrixType.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_compute.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_decomposeInPlace.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_diagonal.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_householderCoefficients.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_packedMatrix.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_Block.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_CommaTemporary.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_Join.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_LinSpaced.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_ThreeWays.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_Zero.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_Map_rowmajor.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_Map_using.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_ReshapeMat2Mat.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_ReshapeMat2Vec.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_SlicingCol.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_SlicingVec.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_commainit_01.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_commainit_01b.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_commainit_02.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_matrix_inverse.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_multiple_rhs.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_reuse_decomposition.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_singular.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_triangular.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_triangular_inplace.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/VectorwiseOp_homogeneous.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/Vectorwise_reverse.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/class_FullPivLU.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/compile_snippet.cpp.in create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/tut_arithmetic_redux_minmax.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/tut_arithmetic_transpose_aliasing.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/tut_arithmetic_transpose_conjugate.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/tut_arithmetic_transpose_inplace.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/snippets/tut_matrix_assignment_resizing.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/special_examples/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/doc/special_examples/Tutorial_sparse_example.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/special_examples/Tutorial_sparse_example_details.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/special_examples/random_cpp11.cpp create mode 100644 testbed/nanogui/ext/eigen/doc/tutorial.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/bdcsvd_int.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/colpivqr_int.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/cwiseunaryview_nonconst_ctor_on_const_xpr.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/cwiseunaryview_on_const_type_actually_const.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/eigensolver_cplx.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/eigensolver_int.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/fullpivlu_int.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/fullpivqr_int.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/jacobisvd_int.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/ldlt_int.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/llt_int.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/partialpivlu_int.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/qr_int.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/selfadjointview_nonconst_ctor_on_const_xpr.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/selfadjointview_on_const_type_actually_const.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/sparse_ref_1.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/sparse_ref_2.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/sparse_ref_3.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/sparse_ref_4.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/sparse_ref_5.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/sparse_storage_mismatch.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/swap_1.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/swap_2.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/ternary_1.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/ternary_2.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/triangularview_nonconst_ctor_on_const_xpr.cpp create mode 100644 testbed/nanogui/ext/eigen/failtest/triangularview_on_const_type_actually_const.cpp create mode 100644 testbed/nanogui/ext/eigen/lapack/svd.cpp create mode 100644 testbed/nanogui/ext/eigen/scripts/eigen_monitor_perf.sh create mode 100644 testbed/nanogui/ext/eigen/test/array_of_string.cpp create mode 100644 testbed/nanogui/ext/eigen/test/bdcsvd.cpp create mode 100644 testbed/nanogui/ext/eigen/test/boostmultiprec.cpp create mode 100644 testbed/nanogui/ext/eigen/test/bug1213.cpp create mode 100644 testbed/nanogui/ext/eigen/test/bug1213.h create mode 100644 testbed/nanogui/ext/eigen/test/bug1213_main.cpp create mode 100644 testbed/nanogui/ext/eigen/test/constructor.cpp create mode 100644 testbed/nanogui/ext/eigen/test/ctorleak.cpp create mode 100644 testbed/nanogui/ext/eigen/test/cuda_basic.cu create mode 100644 testbed/nanogui/ext/eigen/test/cuda_common.h delete mode 100644 testbed/nanogui/ext/eigen/test/cwiseop.cpp create mode 100644 testbed/nanogui/ext/eigen/test/dense_storage.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_adjoint.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_alignedbox.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_array.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_basicstuff.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_bug_132.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_cholesky.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_commainitializer.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_cwiseop.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_determinant.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_dynalloc.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_eigensolver.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_first_aligned.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_geometry.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_geometry_with_eigen2_prefix.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_hyperplane.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_inverse.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_linearstructure.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_lu.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_map.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_meta.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_miscmatrices.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_mixingtypes.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_nomalloc.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_packetmath.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_parametrizedline.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_prec_inverse_4x4.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_product_large.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_product_small.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_qr.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_qtvector.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_regression.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_sizeof.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_smallvectors.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_sparse_basic.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_sparse_product.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_sparse_solvers.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_sparse_vector.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_stdvector.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_submatrices.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_sum.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_svd.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_swap.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_triangular.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_unalignedassert.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/eigen2_visitor.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/gsl_helper.h delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/main.h delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/product.h delete mode 100755 testbed/nanogui/ext/eigen/test/eigen2/runtest.sh delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/sparse.h delete mode 100644 testbed/nanogui/ext/eigen/test/eigen2/testsuite.cmake create mode 100644 testbed/nanogui/ext/eigen/test/evaluator_common.h create mode 100644 testbed/nanogui/ext/eigen/test/evaluators.cpp create mode 100644 testbed/nanogui/ext/eigen/test/fastmath.cpp create mode 100644 testbed/nanogui/ext/eigen/test/half_float.cpp create mode 100644 testbed/nanogui/ext/eigen/test/incomplete_cholesky.cpp create mode 100644 testbed/nanogui/ext/eigen/test/indexed_view.cpp create mode 100644 testbed/nanogui/ext/eigen/test/inplace_decomposition.cpp create mode 100644 testbed/nanogui/ext/eigen/test/is_same_dense.cpp create mode 100644 testbed/nanogui/ext/eigen/test/lscg.cpp create mode 100644 testbed/nanogui/ext/eigen/test/mpl2only.cpp create mode 100644 testbed/nanogui/ext/eigen/test/rand.cpp delete mode 100755 testbed/nanogui/ext/eigen/test/runtest.sh create mode 100644 testbed/nanogui/ext/eigen/test/rvalue_types.cpp create mode 100644 testbed/nanogui/ext/eigen/test/sparse_block.cpp create mode 100644 testbed/nanogui/ext/eigen/test/sparse_ref.cpp rename testbed/nanogui/ext/eigen/test/{eigen2/eigen2_newstdvector.cpp => stddeque_overload.cpp} (56%) create mode 100644 testbed/nanogui/ext/eigen/test/stdlist_overload.cpp create mode 100644 testbed/nanogui/ext/eigen/test/svd_common.h create mode 100644 testbed/nanogui/ext/eigen/test/svd_fill.h create mode 100644 testbed/nanogui/ext/eigen/test/symbolic_index.cpp delete mode 100644 testbed/nanogui/ext/eigen/test/testsuite.cmake create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/Tensor create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/TensorSymmetry create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/ThreadPool create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/README.md create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/Tensor.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorArgMax.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorAssign.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBase.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBroadcasting.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorChipping.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConcatenation.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContraction.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionBlocking.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionCuda.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionMapper.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionSycl.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionThreadPool.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConversion.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConvolution.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConvolutionSycl.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorCostModel.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorCustomOp.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDevice.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceCuda.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceDefault.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceSycl.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceThreadPool.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDimensionList.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDimensions.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorEvalTo.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorEvaluator.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorExecutor.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorExpr.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFFT.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFixedSize.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorForcedEval.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorForwardDeclarations.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFunctors.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGenerator.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGlobalFunctions.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIO.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorImagePatch.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIndexList.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorInflation.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorInitializer.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIntDiv.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorLayoutSwap.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMacros.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMap.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMeta.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMorphing.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorPadding.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorPatch.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorRandom.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReduction.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReductionCuda.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReductionSycl.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorRef.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReverse.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorScan.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorShuffling.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorStorage.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorStriding.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorSycl.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorSyclConvertToDeviceExpression.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorSyclExprConstructor.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorSyclExtractAccessor.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorSyclExtractFunctors.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorSyclFunctors.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorSyclLeafCount.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorSyclPlaceHolderExpr.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorSyclRun.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorSyclTuple.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorTraits.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorUInt128.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorVolumePatch.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/TensorSymmetry/DynamicSymmetry.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/TensorSymmetry/StaticSymmetry.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/TensorSymmetry/Symmetry.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/TensorSymmetry/util/TemplateGroupTheory.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/ThreadPool/EventCount.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/ThreadPool/NonBlockingThreadPool.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/ThreadPool/RunQueue.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/ThreadPool/SimpleThreadPool.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/ThreadPool/ThreadCancel.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/ThreadPool/ThreadEnvironment.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/ThreadPool/ThreadLocal.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/ThreadPool/ThreadPoolInterface.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/ThreadPool/ThreadYield.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/util/CXX11Meta.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/util/CXX11Workarounds.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/util/EmulateArray.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/util/EmulateCXX11Meta.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/util/MaxSizeVector.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/EulerAngles delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/SVD create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/SpecialFunctions delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/AutoDiff/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/BVH/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/EulerAngles/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/EulerAngles/EulerAngles.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/EulerAngles/EulerSystem.h delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/FFT/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/IterativeSolvers/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/IterativeSolvers/IncompleteCholesky.h delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/KroneckerProduct/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/LevenbergMarquardt/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/MatrixFunctions/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/MatrixFunctions/MatrixFunctionAtomic.h delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/MoreVectorization/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/NonLinearOptimization/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/NumericalDiff/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/Polynomials/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/SVD/BDCSVD.h delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/SVD/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/SVD/JacobiSVD.h delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/SVD/TODOBdcsvd.txt delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/SVD/doneInBDCSVD.txt delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/Skyline/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/SparseExtra/BlockSparseMatrix.h delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/SparseExtra/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsArrayAPI.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsFunctors.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsHalf.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsImpl.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsPacketMath.h create mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/SpecialFunctions/arch/CUDA/CudaSpecialFunctions.h delete mode 100644 testbed/nanogui/ext/eigen/unsupported/Eigen/src/Splines/CMakeLists.txt create mode 100644 testbed/nanogui/ext/eigen/unsupported/doc/examples/EulerAngles.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/EulerAngles.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/autodiff_scalar.cpp delete mode 100644 testbed/nanogui/ext/eigen/unsupported/test/bdcsvd.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_eventcount.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_meta.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_non_blocking_thread_pool.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_runqueue.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_argmax.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_argmax_cuda.cu create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_assign.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_broadcast_sycl.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_broadcasting.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_builtins_sycl.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_cast_float16_cuda.cu create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_casts.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_chipping.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_chipping_sycl.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_comparisons.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_complex_cuda.cu create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_complex_cwise_ops_cuda.cu create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_concatenation.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_concatenation_sycl.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_const.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_contract_cuda.cu create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_contract_sycl.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_contraction.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_convolution.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_convolution_sycl.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_cuda.cu create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_custom_index.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_custom_op.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_device.cu create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_device_sycl.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_dimension.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_empty.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_expr.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_fft.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_fixed_size.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_forced_eval.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_forced_eval_sycl.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_generator.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_ifft.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_image_patch.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_index_list.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_inflation.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_intdiv.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_io.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_layout_swap.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_lvalue.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_map.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_math.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_mixed_indices.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_morphing.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_morphing_sycl.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_notification.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_of_complex.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_of_const_values.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_of_float16_cuda.cu create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_of_strings.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_padding.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_padding_sycl.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_patch.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_random.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_random_cuda.cu create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_reduction.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_reduction_cuda.cu create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_reduction_sycl.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_ref.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_reverse.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_reverse_sycl.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_roundings.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_scan.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_scan_cuda.cu create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_shuffling.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_shuffling_sycl.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_simple.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_striding.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_striding_sycl.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_sugar.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_sycl.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_symmetry.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_thread_pool.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_uint128.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/cxx11_tensor_volume_patch.cpp delete mode 100644 testbed/nanogui/ext/eigen/unsupported/test/jacobisvd.cpp create mode 100644 testbed/nanogui/ext/eigen/unsupported/test/special_functions.cpp delete mode 100644 testbed/nanogui/ext/eigen/unsupported/test/svd_common.h create mode 100644 testbed/nanogui/ext/glad/include/KHR/khrplatform.h create mode 100644 testbed/nanogui/ext/glad/include/glad/glad.h create mode 100644 testbed/nanogui/ext/glad/src/glad.c delete mode 100644 testbed/nanogui/ext/glew/CMakeLists.txt delete mode 100644 testbed/nanogui/ext/glew/include/GL/glew.h delete mode 100644 testbed/nanogui/ext/glew/include/GL/glxew.h delete mode 100644 testbed/nanogui/ext/glew/include/GL/wglew.h delete mode 100644 testbed/nanogui/ext/glew/src/glew.c create mode 100644 testbed/nanogui/ext/glfw/.appveyor.yml create mode 100644 testbed/nanogui/ext/glfw/.github/CONTRIBUTING.md create mode 100644 testbed/nanogui/ext/glfw/.gitignore create mode 100644 testbed/nanogui/ext/glfw/.travis.yml rename testbed/nanogui/ext/glfw/CMake/{AppleInfo.plist => MacOSXBundleInfo.plist.in} (62%) delete mode 100644 testbed/nanogui/ext/glfw/CMake/modules/FindEGL.cmake delete mode 100644 testbed/nanogui/ext/glfw/CMake/modules/FindGLESv1.cmake delete mode 100644 testbed/nanogui/ext/glfw/CMake/modules/FindGLESv2.cmake create mode 100644 testbed/nanogui/ext/glfw/CMake/modules/FindVulkan.cmake delete mode 100644 testbed/nanogui/ext/glfw/CMake/modules/FindWayland.cmake create mode 100644 testbed/nanogui/ext/glfw/CMake/modules/FindWaylandProtocols.cmake delete mode 100644 testbed/nanogui/ext/glfw/deps/EGL/eglext.h delete mode 100644 testbed/nanogui/ext/glfw/deps/GL/glext.h delete mode 100644 testbed/nanogui/ext/glfw/deps/GL/glxext.h delete mode 100644 testbed/nanogui/ext/glfw/deps/GL/wglext.h create mode 100644 testbed/nanogui/ext/glfw/deps/linmath.h create mode 100644 testbed/nanogui/ext/glfw/deps/mingw/_mingw_dxhelper.h create mode 100644 testbed/nanogui/ext/glfw/deps/mingw/dinput.h create mode 100644 testbed/nanogui/ext/glfw/deps/mingw/xinput.h create mode 100644 testbed/nanogui/ext/glfw/deps/vulkan/vk_platform.h create mode 100644 testbed/nanogui/ext/glfw/deps/vulkan/vulkan.h create mode 100644 testbed/nanogui/ext/glfw/docs/CMakeLists.txt create mode 100644 testbed/nanogui/ext/glfw/docs/Doxyfile.in create mode 100644 testbed/nanogui/ext/glfw/docs/DoxygenLayout.xml create mode 100644 testbed/nanogui/ext/glfw/docs/build.dox create mode 100644 testbed/nanogui/ext/glfw/docs/compat.dox create mode 100644 testbed/nanogui/ext/glfw/docs/compile.dox create mode 100644 testbed/nanogui/ext/glfw/docs/context.dox create mode 100644 testbed/nanogui/ext/glfw/docs/extra.css create mode 100644 testbed/nanogui/ext/glfw/docs/extra.less create mode 100644 testbed/nanogui/ext/glfw/docs/footer.html create mode 100644 testbed/nanogui/ext/glfw/docs/header.html create mode 100644 testbed/nanogui/ext/glfw/docs/input.dox create mode 100644 testbed/nanogui/ext/glfw/docs/internal.dox create mode 100644 testbed/nanogui/ext/glfw/docs/intro.dox create mode 100644 testbed/nanogui/ext/glfw/docs/main.dox create mode 100644 testbed/nanogui/ext/glfw/docs/monitor.dox create mode 100644 testbed/nanogui/ext/glfw/docs/moving.dox create mode 100644 testbed/nanogui/ext/glfw/docs/news.dox create mode 100644 testbed/nanogui/ext/glfw/docs/quick.dox create mode 100644 testbed/nanogui/ext/glfw/docs/spaces.svg create mode 100644 testbed/nanogui/ext/glfw/docs/vulkan.dox create mode 100644 testbed/nanogui/ext/glfw/docs/window.dox create mode 100644 testbed/nanogui/ext/glfw/examples/CMakeLists.txt create mode 100644 testbed/nanogui/ext/glfw/examples/boing.c create mode 100644 testbed/nanogui/ext/glfw/examples/gears.c create mode 100644 testbed/nanogui/ext/glfw/examples/glfw.icns create mode 100644 testbed/nanogui/ext/glfw/examples/glfw.ico create mode 100644 testbed/nanogui/ext/glfw/examples/glfw.rc create mode 100644 testbed/nanogui/ext/glfw/examples/heightmap.c create mode 100644 testbed/nanogui/ext/glfw/examples/particles.c create mode 100644 testbed/nanogui/ext/glfw/examples/simple.c create mode 100644 testbed/nanogui/ext/glfw/examples/splitview.c create mode 100644 testbed/nanogui/ext/glfw/examples/wave.c rename testbed/nanogui/ext/glfw/src/{iokit_joystick.h => cocoa_joystick.h} (68%) create mode 100644 testbed/nanogui/ext/glfw/src/cocoa_joystick.m rename testbed/nanogui/ext/glfw/src/{mach_time.c => cocoa_time.c} (75%) delete mode 100644 testbed/nanogui/ext/glfw/src/iokit_joystick.m create mode 100644 testbed/nanogui/ext/glfw/src/vulkan.c create mode 100644 testbed/nanogui/ext/glfw/src/win32_joystick.c rename testbed/nanogui/ext/glfw/src/{winmm_joystick.h => win32_joystick.h} (52%) delete mode 100644 testbed/nanogui/ext/glfw/src/win32_tls.h delete mode 100644 testbed/nanogui/ext/glfw/src/winmm_joystick.c create mode 100644 testbed/nanogui/ext/glfw/tests/CMakeLists.txt create mode 100644 testbed/nanogui/ext/glfw/tests/clipboard.c create mode 100644 testbed/nanogui/ext/glfw/tests/cursor.c create mode 100644 testbed/nanogui/ext/glfw/tests/empty.c create mode 100644 testbed/nanogui/ext/glfw/tests/events.c create mode 100644 testbed/nanogui/ext/glfw/tests/gamma.c create mode 100644 testbed/nanogui/ext/glfw/tests/glfwinfo.c create mode 100644 testbed/nanogui/ext/glfw/tests/icon.c create mode 100644 testbed/nanogui/ext/glfw/tests/iconify.c create mode 100644 testbed/nanogui/ext/glfw/tests/joysticks.c create mode 100644 testbed/nanogui/ext/glfw/tests/monitors.c create mode 100644 testbed/nanogui/ext/glfw/tests/msaa.c create mode 100644 testbed/nanogui/ext/glfw/tests/reopen.c create mode 100644 testbed/nanogui/ext/glfw/tests/sharing.c create mode 100644 testbed/nanogui/ext/glfw/tests/tearing.c create mode 100644 testbed/nanogui/ext/glfw/tests/threads.c create mode 100644 testbed/nanogui/ext/glfw/tests/timeout.c create mode 100644 testbed/nanogui/ext/glfw/tests/title.c create mode 100644 testbed/nanogui/ext/glfw/tests/vulkan.c create mode 100644 testbed/nanogui/ext/glfw/tests/windows.c create mode 100644 testbed/nanogui/ext/nanovg/.gitignore create mode 100644 testbed/nanogui/ext/nanovg/example/LICENSE_OFL.txt create mode 100644 testbed/nanogui/ext/nanovg/example/NotoEmoji-Regular.ttf create mode 100755 testbed/nanogui/ext/nanovg/example/Roboto-Bold.ttf create mode 100755 testbed/nanogui/ext/nanovg/example/Roboto-Light.ttf create mode 100755 testbed/nanogui/ext/nanovg/example/Roboto-Regular.ttf create mode 100644 testbed/nanogui/ext/nanovg/example/demo.c create mode 100644 testbed/nanogui/ext/nanovg/example/demo.h create mode 100644 testbed/nanogui/ext/nanovg/example/entypo.ttf create mode 100644 testbed/nanogui/ext/nanovg/example/example_fbo.c create mode 100644 testbed/nanogui/ext/nanovg/example/example_gl2.c create mode 100644 testbed/nanogui/ext/nanovg/example/example_gl3.c create mode 100644 testbed/nanogui/ext/nanovg/example/example_gles2.c create mode 100644 testbed/nanogui/ext/nanovg/example/example_gles3.c create mode 100644 testbed/nanogui/ext/nanovg/example/images.txt create mode 100644 testbed/nanogui/ext/nanovg/example/images/image1.jpg create mode 100644 testbed/nanogui/ext/nanovg/example/images/image10.jpg create mode 100644 testbed/nanogui/ext/nanovg/example/images/image11.jpg create mode 100644 testbed/nanogui/ext/nanovg/example/images/image12.jpg create mode 100644 testbed/nanogui/ext/nanovg/example/images/image2.jpg create mode 100644 testbed/nanogui/ext/nanovg/example/images/image3.jpg create mode 100644 testbed/nanogui/ext/nanovg/example/images/image4.jpg create mode 100644 testbed/nanogui/ext/nanovg/example/images/image5.jpg create mode 100644 testbed/nanogui/ext/nanovg/example/images/image6.jpg create mode 100644 testbed/nanogui/ext/nanovg/example/images/image7.jpg create mode 100644 testbed/nanogui/ext/nanovg/example/images/image8.jpg create mode 100644 testbed/nanogui/ext/nanovg/example/images/image9.jpg create mode 100644 testbed/nanogui/ext/nanovg/example/perf.c create mode 100644 testbed/nanogui/ext/nanovg/example/perf.h create mode 100644 testbed/nanogui/ext/nanovg/example/screenshot-01.png create mode 100644 testbed/nanogui/ext/nanovg/example/screenshot-02.png create mode 100644 testbed/nanogui/ext/nanovg/example/stb_image_write.h create mode 100644 testbed/nanogui/ext/pybind11/.appveyor.yml create mode 100644 testbed/nanogui/ext/pybind11/.gitignore create mode 100644 testbed/nanogui/ext/pybind11/.gitmodules create mode 100644 testbed/nanogui/ext/pybind11/.travis.yml create mode 100644 testbed/nanogui/ext/pybind11/CMakeLists.txt create mode 100644 testbed/nanogui/ext/pybind11/CONTRIBUTING.md create mode 100644 testbed/nanogui/ext/pybind11/LICENSE create mode 100644 testbed/nanogui/ext/pybind11/MANIFEST.in create mode 100644 testbed/nanogui/ext/pybind11/README.md create mode 100644 testbed/nanogui/ext/pybind11/docs/_static/theme_overrides.css create mode 100644 testbed/nanogui/ext/pybind11/docs/advanced/cast/chrono.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/advanced/cast/custom.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/advanced/cast/eigen.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/advanced/cast/functional.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/advanced/cast/index.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/advanced/cast/overview.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/advanced/cast/stl.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/advanced/classes.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/advanced/exceptions.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/advanced/functions.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/advanced/misc.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/advanced/pycpp/index.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/advanced/pycpp/numpy.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/advanced/pycpp/object.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/advanced/pycpp/utilities.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/advanced/smart_ptrs.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/basics.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/benchmark.py create mode 100644 testbed/nanogui/ext/pybind11/docs/benchmark.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/changelog.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/classes.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/compiling.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/conf.py create mode 100644 testbed/nanogui/ext/pybind11/docs/faq.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/index.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/intro.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/limitations.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/pybind11-logo.png create mode 100644 testbed/nanogui/ext/pybind11/docs/pybind11_vs_boost_python1.png create mode 100644 testbed/nanogui/ext/pybind11/docs/pybind11_vs_boost_python1.svg create mode 100644 testbed/nanogui/ext/pybind11/docs/pybind11_vs_boost_python2.png create mode 100644 testbed/nanogui/ext/pybind11/docs/pybind11_vs_boost_python2.svg create mode 100644 testbed/nanogui/ext/pybind11/docs/reference.rst create mode 100644 testbed/nanogui/ext/pybind11/docs/release.rst create mode 100644 testbed/nanogui/ext/pybind11/include/pybind11/attr.h create mode 100644 testbed/nanogui/ext/pybind11/include/pybind11/cast.h create mode 100644 testbed/nanogui/ext/pybind11/include/pybind11/chrono.h create mode 100644 testbed/nanogui/ext/pybind11/include/pybind11/common.h create mode 100644 testbed/nanogui/ext/pybind11/include/pybind11/complex.h create mode 100644 testbed/nanogui/ext/pybind11/include/pybind11/descr.h create mode 100644 testbed/nanogui/ext/pybind11/include/pybind11/eigen.h create mode 100644 testbed/nanogui/ext/pybind11/include/pybind11/eval.h create mode 100644 testbed/nanogui/ext/pybind11/include/pybind11/functional.h create mode 100644 testbed/nanogui/ext/pybind11/include/pybind11/numpy.h create mode 100644 testbed/nanogui/ext/pybind11/include/pybind11/operators.h create mode 100644 testbed/nanogui/ext/pybind11/include/pybind11/options.h create mode 100644 testbed/nanogui/ext/pybind11/include/pybind11/pybind11.h create mode 100644 testbed/nanogui/ext/pybind11/include/pybind11/pytypes.h create mode 100644 testbed/nanogui/ext/pybind11/include/pybind11/stl.h create mode 100644 testbed/nanogui/ext/pybind11/include/pybind11/stl_bind.h create mode 100644 testbed/nanogui/ext/pybind11/include/pybind11/typeid.h create mode 100644 testbed/nanogui/ext/pybind11/pybind11/__init__.py create mode 100644 testbed/nanogui/ext/pybind11/pybind11/_version.py create mode 100644 testbed/nanogui/ext/pybind11/setup.cfg create mode 100644 testbed/nanogui/ext/pybind11/setup.py create mode 100644 testbed/nanogui/ext/pybind11/tests/CMakeLists.txt create mode 100644 testbed/nanogui/ext/pybind11/tests/conftest.py create mode 100644 testbed/nanogui/ext/pybind11/tests/constructor_stats.h create mode 100644 testbed/nanogui/ext/pybind11/tests/object.h create mode 100644 testbed/nanogui/ext/pybind11/tests/pybind11_tests.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/pybind11_tests.h create mode 100644 testbed/nanogui/ext/pybind11/tests/test_alias_initialization.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_alias_initialization.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_buffers.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_buffers.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_callbacks.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_callbacks.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_chrono.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_chrono.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_class_args.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_class_args.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_cmake_build/installed_function/CMakeLists.txt create mode 100644 testbed/nanogui/ext/pybind11/tests/test_cmake_build/installed_target/CMakeLists.txt create mode 100644 testbed/nanogui/ext/pybind11/tests/test_cmake_build/main.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_cmake_build/subdirectory_function/CMakeLists.txt create mode 100644 testbed/nanogui/ext/pybind11/tests/test_cmake_build/subdirectory_target/CMakeLists.txt create mode 100644 testbed/nanogui/ext/pybind11/tests/test_cmake_build/test.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_constants_and_functions.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_constants_and_functions.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_copy_move_policies.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_copy_move_policies.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_docstring_options.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_docstring_options.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_eigen.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_eigen.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_enum.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_enum.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_eval.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_eval.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_eval_call.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_exceptions.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_exceptions.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_inheritance.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_inheritance.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_issues.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_issues.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_keep_alive.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_keep_alive.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_kwargs_and_defaults.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_kwargs_and_defaults.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_methods_and_attributes.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_methods_and_attributes.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_modules.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_modules.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_multiple_inheritance.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_multiple_inheritance.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_numpy_array.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_numpy_array.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_numpy_dtypes.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_numpy_dtypes.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_numpy_vectorize.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_numpy_vectorize.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_opaque_types.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_opaque_types.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_operator_overloading.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_operator_overloading.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_pickling.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_pickling.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_python_types.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_python_types.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_sequences_and_iterators.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_sequences_and_iterators.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_smart_ptr.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_smart_ptr.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_stl_binders.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_stl_binders.py create mode 100644 testbed/nanogui/ext/pybind11/tests/test_virtual_functions.cpp create mode 100644 testbed/nanogui/ext/pybind11/tests/test_virtual_functions.py create mode 100644 testbed/nanogui/ext/pybind11/tools/FindEigen3.cmake create mode 100644 testbed/nanogui/ext/pybind11/tools/FindPythonLibsNew.cmake create mode 100755 testbed/nanogui/ext/pybind11/tools/check-style.sh create mode 100644 testbed/nanogui/ext/pybind11/tools/clang/.gitignore create mode 100644 testbed/nanogui/ext/pybind11/tools/clang/LICENSE.TXT create mode 100644 testbed/nanogui/ext/pybind11/tools/clang/README.md create mode 100644 testbed/nanogui/ext/pybind11/tools/clang/__init__.py create mode 100644 testbed/nanogui/ext/pybind11/tools/clang/cindex.py create mode 100644 testbed/nanogui/ext/pybind11/tools/clang/enumerations.py create mode 100644 testbed/nanogui/ext/pybind11/tools/libsize.py create mode 100644 testbed/nanogui/ext/pybind11/tools/mkdoc.py create mode 100644 testbed/nanogui/ext/pybind11/tools/pybind11Config.cmake.in create mode 100644 testbed/nanogui/ext/pybind11/tools/pybind11Tools.cmake create mode 100644 testbed/nanogui/include/nanogui/glcanvas.h create mode 100644 testbed/nanogui/include/nanogui/python.h create mode 100644 testbed/nanogui/include/nanogui/stackedwidget.h create mode 100644 testbed/nanogui/include/nanogui/tabheader.h create mode 100644 testbed/nanogui/include/nanogui/tabwidget.h delete mode 100644 testbed/nanogui/resources/bin2c.c create mode 100644 testbed/nanogui/resources/bin2c.cmake create mode 100755 testbed/nanogui/resources/check-style.sh create mode 100644 testbed/nanogui/resources/screenshot.png create mode 100644 testbed/nanogui/resources/screenshot2.png create mode 100644 testbed/nanogui/src/example3.cpp create mode 100644 testbed/nanogui/src/example4.cpp create mode 100644 testbed/nanogui/src/example_icons.cpp create mode 100644 testbed/nanogui/src/glcanvas.cpp create mode 100644 testbed/nanogui/src/stackedwidget.cpp create mode 100644 testbed/nanogui/src/tabheader.cpp create mode 100644 testbed/nanogui/src/tabwidget.cpp diff --git a/testbed/nanogui/CMakeLists.txt b/testbed/nanogui/CMakeLists.txt index a632e9a8..5447dd1d 100644 --- a/testbed/nanogui/CMakeLists.txt +++ b/testbed/nanogui/CMakeLists.txt @@ -1,29 +1,51 @@ -cmake_minimum_required (VERSION 2.8.3) +cmake_minimum_required (VERSION 2.8.12) + +if (POLICY CMP0048) + # cmake warns if loaded from a min-3.0-required parent dir, so silence the warning: + cmake_policy(SET CMP0048 NEW) +endif() project("NanoGUI") -if(NOT IS_DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}/ext/glfw/src") +if (POLICY CMP0058) + cmake_policy(SET CMP0058 NEW) +endif() + +if (NOT IS_DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}/ext/glfw/src") message(FATAL_ERROR "The NanoGUI dependency repositories (GLFW, etc.) are missing! " "You probably did not clone the project with --recursive. It is possible to recover " "by calling \"git submodule update --init --recursive\"") endif() -option(NANOGUI_BUILD_EXAMPLE "Build NanoGUI example application?" OFF) -option(NANOGUI_BUILD_SHARED "Build NanoGUI as a shared library?" OFF) -option(NANOGUI_BUILD_PYTHON "Build a Python plugin for NanoGUI?" OFF) +if (WIN32) + set(NANOGUI_USE_GLAD_DEFAULT ON) +else() + set(NANOGUI_USE_GLAD_DEFAULT OFF) +endif() + +option(NANOGUI_BUILD_EXAMPLE "Build NanoGUI example application?" ON) +option(NANOGUI_BUILD_SHARED "Build NanoGUI as a shared library?" ON) +option(NANOGUI_BUILD_PYTHON "Build a Python plugin for NanoGUI?" ON) +option(NANOGUI_USE_GLAD "Use Glad OpenGL loader library?" ${NANOGUI_USE_GLAD_DEFAULT}) +option(NANOGUI_INSTALL "Install NanoGUI on `make install`?" ON) + set(NANOGUI_PYTHON_VERSION "" CACHE STRING "Python version to use for compiling the Python plugin") -# Required libraries for linking against nanogui (all targets) +# Required libraries, flags, and include files for compiling and linking against nanogui (all targets) set(NANOGUI_EXTRA_LIBS "") +set(NANOGUI_EXTRA_DEFS "") +set(NANOGUI_EXTRA_INCS "") # Platform-dependent files for libnanogui set(LIBNANOGUI_EXTRA_SOURCE "") +set(LIBNANOGUI_PYTHON_EXTRA_SOURCE "") if(APPLE AND NANOGUI_BUILD_SHARED) set(CMAKE_MACOSX_RPATH ON) endif() include(CheckCXXCompilerFlag) +include(CheckCXXSourceRuns) if(NOT CMAKE_BUILD_TYPE AND NOT CMAKE_CONFIGURATION_TYPES) message(STATUS "Setting build type to 'Release' as none was specified.") @@ -33,11 +55,22 @@ if(NOT CMAKE_BUILD_TYPE AND NOT CMAKE_CONFIGURATION_TYPES) endif() string(TOUPPER "${CMAKE_BUILD_TYPE}" U_CMAKE_BUILD_TYPE) +macro(CHECK_CXX_COMPILER_AND_LINKER_FLAGS _RESULT _CXX_FLAGS _LINKER_FLAGS) + set(CMAKE_REQUIRED_FLAGS ${_CXX_FLAGS}) + set(CMAKE_REQUIRED_LIBRARIES ${_LINKER_FLAGS}) + set(CMAKE_REQUIRED_QUIET TRUE) + check_cxx_source_runs("int main(int argc, char **argv) { return 0; }" ${_RESULT}) + set(CMAKE_REQUIRED_FLAGS "") + set(CMAKE_REQUIRED_LIBRARIES "") +endmacro() + +# Compile GLFW set(GLFW_BUILD_EXAMPLES OFF CACHE BOOL " " FORCE) set(GLFW_BUILD_TESTS OFF CACHE BOOL " " FORCE) set(GLFW_BUILD_DOCS OFF CACHE BOOL " " FORCE) set(GLFW_BUILD_INSTALL OFF CACHE BOOL " " FORCE) set(GLFW_INSTALL OFF CACHE BOOL " " FORCE) +set(GLFW_USE_CHDIR OFF CACHE BOOL " " FORCE) set(BUILD_SHARED_LIBS ${NANOGUI_BUILD_SHARED} CACHE BOOL " " FORCE) if (CMAKE_CXX_COMPILER_ID MATCHES "Clang") @@ -45,17 +78,22 @@ if (CMAKE_CXX_COMPILER_ID MATCHES "Clang") set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wno-deprecated-declarations") endif() -# Compile GLFW add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/ext/glfw" "ext_build/glfw") +# Two targets have now been defined: `glfw_objects`, which will be merged into +# NanoGUI at the end, and `glfw`. The `glfw` target is the library itself +# (e.g., libglfw.so), but can be skipped as we do not need to link against it +# (because we merge `glfw_objects` into NanoGUI). Skipping is required for +# XCode, but preferable for all build systems (reduces build artifacts). +set_target_properties(glfw PROPERTIES EXCLUDE_FROM_ALL 1 EXCLUDE_FROM_DEFAULT_BUILD 1) # Python support: add NANOGUI_PYTHON flag to all targets if (NANOGUI_BUILD_PYTHON) - add_definitions ("-DNANOGUI_PYTHON") + list(APPEND NANOGUI_EXTRA_DEFS -DNANOGUI_PYTHON) endif() -# Shared library mode: add NANOGUI_SHARED flag to all targets +# Shared library mode: add dllimport/dllexport flags to all symbols if (NANOGUI_BUILD_SHARED) - add_definitions ("-DNANOGUI_SHARED") + list(APPEND NANOGUI_EXTRA_DEFS -DNANOGUI_SHARED -DNVG_SHARED -DGLAD_GLAPI_EXPORT) endif() if (MSVC) @@ -69,7 +107,7 @@ if (MSVC) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /arch:SSE2") # Disable Eigen vectorization for Windows 32 bit builds (issues with unaligned access segfaults) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /DEIGEN_DONT_ALIGN") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /DNANOGUI_EIGEN_DONT_ALIGN") endif() endif() @@ -84,7 +122,7 @@ elseif (CMAKE_CXX_COMPILER_ID MATCHES "Clang" OR CMAKE_CXX_COMPILER_ID MATCHES " set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra") endif() -if (CMAKE_CXX_COMPILER_ID MATCHES "Clang" OR CMAKE_CXX_COMPILER_ID MATCHES "GNU") +if (CMAKE_CXX_COMPILER_ID MATCHES "^(GNU|Clang|Intel)$") CHECK_CXX_COMPILER_FLAG("-std=c++14" HAS_CPP14_FLAG) CHECK_CXX_COMPILER_FLAG("-std=c++11" HAS_CPP11_FLAG) @@ -97,11 +135,105 @@ if (CMAKE_CXX_COMPILER_ID MATCHES "Clang" OR CMAKE_CXX_COMPILER_ID MATCHES "GNU" endif() endif() -if(WIN32) - # Build and include GLEW on Windows - list(APPEND LIBNANOGUI_EXTRA_SOURCE "${CMAKE_CURRENT_SOURCE_DIR}/ext/glew/src/glew.c") - set_source_files_properties("${CMAKE_CURRENT_SOURCE_DIR}/ext/glew/src/glew.c" PROPERTIES COMPILE_DEFINITIONS GLEW_BUILD) - include_directories(ext/glew/include) +# Various optimizations for shared library release builds +if (NANOGUI_BUILD_SHARED) + if (U_CMAKE_BUILD_TYPE MATCHES REL AND CMAKE_CXX_COMPILER_ID MATCHES "^(GNU|Clang)$") + # Set the default symbol visibility to hidden + if (NOT CMAKE_CXX_FLAGS MATCHES "-fvisibility") + set(CMAKE_CXX_FLAGS "-fvisibility=hidden ${CMAKE_CXX_FLAGS}") + endif() + + # Enable link time optimization + if (NOT CMAKE_CXX_FLAGS MATCHES "-flto") + if (CMAKE_CXX_COMPILER_ID MATCHES "Clang") + set(LTO_CXX_FLAGS "-flto=thin") + set(LTO_LINKER_FLAGS "-flto=thin") + if (NOT APPLE AND U_CMAKE_BUILD_TYPE MATCHES MINSIZEREL) + # Clang Gold plugin does not support -Os + set(LTO_CXX_FLAGS "${LTO_CXX_FLAGS} -O3") + endif() + else() + set(LTO_CXX_FLAGS "-flto -fno-fat-lto-objects") + set(LTO_LINKER_FLAGS "-flto") + endif() + + CHECK_CXX_COMPILER_AND_LINKER_FLAGS(HAS_LTO ${LTO_CXX_FLAGS} ${LTO_LINKER_FLAGS}) + + if (HAS_LTO) + message(STATUS "NanoGUI: LTO support enabled.") + set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${LTO_LINKER_FLAGS}") + set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} ${LTO_LINKER_FLAGS}") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${LTO_CXX_FLAGS}") + set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${LTO_CXX_FLAGS}") + else() + message(STATUS "NanoGUI: LTO not supported by the compiler.") + endif() + endif() + elseif(MSVC) + set(Configurations RELEASE RELWITHDEBINFO MINSIZEREL) + set(LinkTypes EXE SHARED MODULE STATIC) + foreach(Configuration ${Configurations}) + set("CMAKE_CXX_FLAGS_${Configuration}" "${CMAKE_CXX_FLAGS_${Configuration}} /GL") + foreach(LinkType ${LinkTypes}) + set("CMAKE_${LinkType}_LINKER_FLAGS_${Configuration}" "${CMAKE_${LinkType}_LINKER_FLAGS_${Configuration}} /LTCG") + endforeach() + endforeach() + message(STATUS "NanoGUI: LTO support enabled.") + endif() +endif() + +# Always use libc++ on Clang +if (CMAKE_CXX_COMPILER_ID MATCHES "Clang") + CHECK_CXX_COMPILER_AND_LINKER_FLAGS(HAS_LIBCPP "-stdlib=libc++" "-stdlib=libc++") + if (HAS_LIBCPP) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -stdlib=libc++") + set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -stdlib=libc++") + set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} -stdlib=libc++") + CHECK_CXX_COMPILER_AND_LINKER_FLAGS(HAS_LIBCPPABI "-stdlib=libc++" "-stdlib=libc++ -lc++abi") + if(HAS_LIBCPPABI) + set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -lc++abi") + set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} -lc++abi") + message(STATUS "NanoGUI: using libc++ and libc++abi.") + else() + message(STATUS "NanoGUI: using libc++.") + endif() + else() + message(STATUS "NanoGUI: NOT using libc++.") + endif() +endif() + +if (NANOGUI_USE_GLAD) + # Build and include GLAD on Windows + list(APPEND LIBNANOGUI_EXTRA_SOURCE + "${CMAKE_CURRENT_SOURCE_DIR}/ext/glad/src/glad.c" + "${CMAKE_CURRENT_SOURCE_DIR}/ext/glad/include/glad/glad.h" + "${CMAKE_CURRENT_SOURCE_DIR}/ext/glad/include/KHR/khrplatform.h") + if (MSVC) + set_source_files_properties("${CMAKE_CURRENT_SOURCE_DIR}/ext/glad/src/glad.c" + PROPERTIES COMPILE_FLAGS "/wd4055 ") + endif() + include_directories(ext/glad/include) + list(APPEND NANOGUI_EXTRA_DEFS -DNANOGUI_GLAD) + list(APPEND NANOGUI_EXTRA_INCS "${CMAKE_CURRENT_SOURCE_DIR}/ext/glad/include") +endif() + +list(APPEND NANOGUI_EXTRA_INCS + "${CMAKE_CURRENT_SOURCE_DIR}/ext/glfw/include" + "${CMAKE_CURRENT_SOURCE_DIR}/ext/nanovg/src" +) + +if (NOT NANOGUI_EIGEN_INCLUDE_DIR) + set(NANOGUI_EIGEN_INCLUDE_DIR "${CMAKE_CURRENT_SOURCE_DIR}/ext/eigen") + list(APPEND NANOGUI_EXTRA_INCS "${NANOGUI_EIGEN_INCLUDE_DIR}") +endif() + +if (${CMAKE_SYSTEM_NAME} MATCHES "BSD") + include_directories(/usr/local/include) + link_directories(/usr/local/lib) + if(${CMAKE_SYSTEM_NAME} MATCHES "OpenBSD") + include_directories(/usr/X11R6/include/) + link_directories(/usr/X11R6/lib) + endif() endif() # Required core libraries on various platforms @@ -114,25 +246,40 @@ elseif (APPLE) find_library(iokit_library IOKit) list(APPEND NANOGUI_EXTRA_LIBS ${cocoa_library} ${opengl_library} ${corevideo_library} ${iokit_library}) list(APPEND LIBNANOGUI_EXTRA_SOURCE src/darwin.mm) -elseif(CMAKE_SYSTEM MATCHES "Linux") - list(APPEND NANOGUI_EXTRA_LIBS GL Xxf86vm Xrandr Xinerama Xcursor Xi X11 pthread dl rt) +elseif(CMAKE_SYSTEM MATCHES "Linux" OR CMAKE_SYSTEM_NAME MATCHES "BSD") + list(APPEND NANOGUI_EXTRA_LIBS GL Xxf86vm Xrandr Xinerama Xcursor Xi X11 pthread ) + if (NOT CMAKE_SYSTEM_NAME MATCHES "OpenBSD") + list(APPEND NANOGUI_EXTRA_LIBS rt) + endif() + if(CMAKE_SYSTEM MATCHES "Linux") + list(APPEND NANOGUI_EXTRA_LIBS dl) + endif() endif() -include_directories(ext/eigen ext/glfw/include ext/nanovg/src include ${CMAKE_CURRENT_BINARY_DIR}) +include_directories(${NANOGUI_EIGEN_INCLUDE_DIR} ext/glfw/include ext/nanovg/src include ${CMAKE_CURRENT_BINARY_DIR}) -# Run simple C converter to put font files into the data segment -add_executable(bin2c resources/bin2c.c) -set(bin2c_cmdline nanogui_resources.cpp nanogui_resources.h) + +# Run simple cmake converter to put font files into the data segment + +# Glob up resource files file(GLOB resources "${CMAKE_CURRENT_SOURCE_DIR}/resources/*.ttf") -foreach(file ${resources}) - list(APPEND bin2c_cmdline ${file}) -endforeach() + +# Concatenate resource files into a comma separated string +string (REGEX REPLACE "([^\\]|^);" "\\1," resources_string "${resources}") +string (REGEX REPLACE "[\\](.)" "\\1" resources_string "${resources_string}") + +# Create command line for running bin2c cmake script +set(bin2c_cmdline + -DOUTPUT_C=nanogui_resources.cpp + -DOUTPUT_H=nanogui_resources.h + "-DINPUT_FILES=${resources_string}" + -P "${CMAKE_CURRENT_SOURCE_DIR}/resources/bin2c.cmake") # Run bin2c on resource files add_custom_command( OUTPUT nanogui_resources.cpp nanogui_resources.h - COMMAND bin2c ARGS ${bin2c_cmdline} - DEPENDS bin2c ${resources} + COMMAND ${CMAKE_COMMAND} ARGS ${bin2c_cmdline} + DEPENDS ${resources} COMMENT "Running bin2c" PRE_BUILD VERBATIM) @@ -140,19 +287,31 @@ add_custom_command( include_directories(${CMAKE_CURRENT_BINARY_DIR}) # Set library type -if(NANOGUI_BUILD_SHARED) +if (NANOGUI_BUILD_SHARED) set(NANOGUI_LIBRARY_TYPE "SHARED") else() set(NANOGUI_LIBRARY_TYPE "STATIC") endif() +if (APPLE OR CMAKE_SYSTEM MATCHES "Linux") + # Include coroutine support for running the mainloop in detached mode + add_definitions(-DCORO_SJLJ) + include_directories(ext/coro) + list(APPEND LIBNANOGUI_PYTHON_EXTRA_SOURCE ext/coro/coro.c) +endif() + +if (APPLE) + # Use automatic reference counting for Objective-C portions + add_compile_options(-fobjc-arc) +endif() + +add_definitions(${NANOGUI_EXTRA_DEFS}) + # Compile main NanoGUI library -add_library(nanogui ${NANOGUI_LIBRARY_TYPE} - # Merge GLFW into the NanoGUI library - $ +add_library(nanogui-obj OBJECT # Merge NanoVG into the NanoGUI library ext/nanovg/src/nanovg.c - # Merge GLEW into the NanoGUI library (only if needed) + # Merge GLAD into the NanoGUI library (only if needed) ${LIBNANOGUI_EXTRA_SOURCE} # Fonts etc. nanogui_resources.cpp @@ -179,6 +338,10 @@ add_library(nanogui ${NANOGUI_LIBRARY_TYPE} include/nanogui/colorwheel.h src/colorwheel.cpp include/nanogui/colorpicker.h src/colorpicker.cpp include/nanogui/graph.h src/graph.cpp + include/nanogui/stackedwidget.h src/stackedwidget.cpp + include/nanogui/tabheader.h src/tabheader.cpp + include/nanogui/tabwidget.h src/tabwidget.cpp + include/nanogui/glcanvas.h src/glcanvas.cpp include/nanogui/formhelper.h include/nanogui/toolbutton.h include/nanogui/opengl.h @@ -189,41 +352,64 @@ add_library(nanogui ${NANOGUI_LIBRARY_TYPE} src/serializer.cpp ) +# XCode has a serious bug where the XCode project produces an invalid target +# that will not get linked if it consists only of objects from object libraries, +# it will not generate any products (executables, libraries). The only work +# around is to add a dummy source file to the library definition. This is an +# XCode, not a CMake bug. See: https://itk.org/Bug/view.php?id=14044 +if (CMAKE_GENERATOR STREQUAL Xcode) + set(XCODE_DUMMY ${CMAKE_CURRENT_BINARY_DIR}/xcode_dummy.cpp) + file(WRITE ${XCODE_DUMMY} "") + add_library(nanogui ${NANOGUI_LIBRARY_TYPE} + ${XCODE_DUMMY} + $ + $ + ) +else() + add_library(nanogui ${NANOGUI_LIBRARY_TYPE} + $ + $ + ) +endif() + +if (NANOGUI_BUILD_SHARED) + set_property(TARGET nanogui-obj PROPERTY POSITION_INDEPENDENT_CODE ON) +endif() + # Compile/link flags for NanoGUI -set_property(TARGET nanogui APPEND PROPERTY COMPILE_DEFINITIONS "NANOGUI_BUILD ") +set_property(TARGET nanogui-obj APPEND PROPERTY COMPILE_DEFINITIONS "NANOGUI_BUILD;NVG_BUILD") + +if (NANOGUI_USE_GLAD AND NANOGUI_BUILD_SHARED) + set_property(TARGET nanogui-obj APPEND PROPERTY COMPILE_DEFINITIONS + "GLAD_GLAPI_EXPORT;GLAD_GLAPI_EXPORT_BUILD") +endif() if (NANOGUI_BUILD_SHARED) target_link_libraries(nanogui ${NANOGUI_EXTRA_LIBS}) endif() -if (NOT ${U_CMAKE_BUILD_TYPE} MATCHES DEBUG AND NANOGUI_BUILD_SHARED) - # Link-time code generation (only for shared library) - if (MSVC) - set_property(TARGET nanogui APPEND_STRING PROPERTY LINK_FLAGS "/LTCG ") - set_property(TARGET nanogui APPEND_STRING PROPERTY COMPILE_FLAGS "/GL ") - elseif (CMAKE_CXX_COMPILER_ID MATCHES "Clang" OR CMAKE_CXX_COMPILER_ID MATCHES "GNU") - set_property(TARGET nanogui APPEND_STRING PROPERTY COMPILE_FLAGS "-fvisibility=hidden ") +if (NANOGUI_INSTALL) + install(TARGETS nanogui + LIBRARY DESTINATION lib + ARCHIVE DESTINATION lib) - # Check for Link Time Optimization support - CHECK_CXX_COMPILER_FLAG("-flto" HAS_LTO_FLAG) - if (HAS_LTO_FLAG) - set_property(TARGET nanogui APPEND_STRING PROPERTY COMPILE_FLAGS "-flto ") - endif() - endif() + install(DIRECTORY include/nanogui DESTINATION include + FILES_MATCHING PATTERN "*.h") endif() if (NANOGUI_BUILD_SHARED) # When GLFW is merged into the NanoGUI library, this flag must be specified - set_property(TARGET nanogui APPEND PROPERTY COMPILE_DEFINITIONS "_GLFW_BUILD_DLL ") + set_property(TARGET nanogui-obj APPEND PROPERTY COMPILE_DEFINITIONS "_GLFW_BUILD_DLL;NVG_SHARED") endif() -if (NANOGUI_BUILD_SHARED AND NOT ${U_CMAKE_BUILD_TYPE} MATCHES DEBUG) +if (NANOGUI_BUILD_SHARED AND NOT ${U_CMAKE_BUILD_TYPE} MATCHES DEB) + # Platform-specific strip flags for reducing the library size. if (APPLE) # Strip .dylib library on OSX - add_custom_command(TARGET nanogui POST_BUILD COMMAND strip -u -r ${CMAKE_CURRENT_BINARY_DIR}/libnanogui.dylib) + add_custom_command(TARGET nanogui POST_BUILD COMMAND strip -u -r "$/$") elseif(UNIX) # Strip .so library on Linux - add_custom_command(TARGET nanogui POST_BUILD COMMAND strip ${CMAKE_CURRENT_BINARY_DIR}/libnanogui.so) + add_custom_command(TARGET nanogui POST_BUILD COMMAND strip "$/$") endif() endif() @@ -234,19 +420,18 @@ elseif(MSVC) set_source_files_properties(ext/nanovg/src/nanovg.c PROPERTIES COMPILE_FLAGS "/wd4005 /wd4456 /wd4457") endif() -if (NANOGUI_BUILD_SHARED) - set_source_files_properties(ext/nanovg/src/nanovg.c PROPERTIES COMPILE_DEFINITIONS "NVG_BUILD;NVG_SHARED") -else() - set_source_files_properties(ext/nanovg/src/nanovg.c PROPERTIES COMPILE_DEFINITIONS "NVG_BUILD") -endif() - - # Build example application if desired if(NANOGUI_BUILD_EXAMPLE) - add_executable(example1 src/example1.cpp) - add_executable(example2 src/example2.cpp) - target_link_libraries(example1 nanogui ${NANOGUI_EXTRA_LIBS}) - target_link_libraries(example2 nanogui ${NANOGUI_EXTRA_LIBS}) + add_executable(example1 src/example1.cpp) + add_executable(example2 src/example2.cpp) + add_executable(example3 src/example3.cpp) + add_executable(example4 src/example4.cpp) + add_executable(example_icons src/example_icons.cpp) + target_link_libraries(example1 nanogui ${NANOGUI_EXTRA_LIBS}) + target_link_libraries(example2 nanogui ${NANOGUI_EXTRA_LIBS}) + target_link_libraries(example3 nanogui ${NANOGUI_EXTRA_LIBS}) + target_link_libraries(example4 nanogui ${NANOGUI_EXTRA_LIBS}) + target_link_libraries(example_icons nanogui ${NANOGUI_EXTRA_LIBS}) # Copy icons for example application file(COPY resources/icons DESTINATION ${CMAKE_CURRENT_BINARY_DIR}) @@ -254,88 +439,137 @@ endif() if (NANOGUI_BUILD_PYTHON) # Detect Python - set(Python_ADDITIONAL_VERSIONS 3.4 3.5 3.6 3.7) - find_package(PythonLibs ${NANOGUI_PYTHON_VERSION}) + + # Try to autodetect Python (can be overridden manually if needed) + list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/ext/pybind11/tools") + set(Python_ADDITIONAL_VERSIONS 3.7 3.6 3.5 3.4) + find_package(PythonLibsNew ${NANOGUI_PYTHON_VERSION}) if (NOT PYTHONLIBS_FOUND) # Python not found -- disable the plugin set(NANOGUI_BUILD_PYTHON OFF CACHE BOOL "Build a Python plugin for NanoGUI?" FORCE) + message(WARNING "NanoGUI: not building the Python plugin!") + else() + message(STATUS "NanoGUI: building the Python plugin.") endif() endif() if (NANOGUI_BUILD_PYTHON) # Need PIC code in libnanogui even when compiled as a static library - set_target_properties(nanogui PROPERTIES POSITION_INDEPENDENT_CODE ON) + set_target_properties(nanogui-obj PROPERTIES POSITION_INDEPENDENT_CODE ON) set_target_properties(glfw_objects PROPERTIES POSITION_INDEPENDENT_CODE ON) include_directories("ext/pybind11/include" ${PYTHON_INCLUDE_DIR}) - add_library(nanogui_python SHARED python/python.cpp python/python.h python/py_doc.h) - set_target_properties(nanogui_python PROPERTIES OUTPUT_NAME "nanogui") - target_link_libraries(nanogui_python nanogui ${NANOGUI_EXTRA_LIBS}) + add_library(nanogui-python-obj OBJECT + python/main.cpp + python/constants_glfw.cpp + python/constants_entypo.cpp + python/eigen.cpp + python/widget.cpp + python/layout.cpp + python/basics.cpp + python/button.cpp + python/tabs.cpp + python/textbox.cpp + python/glcanvas.cpp + python/formhelper.cpp + python/misc.cpp + python/glutil.cpp + python/nanovg.cpp + python/python.h python/py_doc.h + ${LIBNANOGUI_PYTHON_EXTRA_SOURCE}) - # Quench GCC-related warnings + add_library(nanogui-python SHARED $) + set_property(TARGET nanogui-python-obj PROPERTY POSITION_INDEPENDENT_CODE ON) + set_target_properties(nanogui-python PROPERTIES OUTPUT_NAME "nanogui") + target_link_libraries(nanogui-python nanogui ${NANOGUI_EXTRA_LIBS}) + + # Quench warnings on GCC if (CMAKE_COMPILER_IS_GNUCC) - set_source_files_properties(python/python.cpp PROPERTIES COMPILE_FLAGS -Wno-unused-variable) + set_property(TARGET nanogui-python-obj APPEND PROPERTY COMPILE_OPTIONS "-Wno-unused-variable") endif() - set_target_properties(nanogui_python PROPERTIES LIBRARY_OUTPUT_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/python) - set_target_properties(nanogui_python PROPERTIES PREFIX "") + set_target_properties(nanogui-python PROPERTIES LIBRARY_OUTPUT_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/python) + # The prefix and extension are provided by FindPythonLibsNew.cmake + set_target_properties(nanogui-python PROPERTIES PREFIX "${PYTHON_MODULE_PREFIX}") + set_target_properties(nanogui-python PROPERTIES SUFFIX "${PYTHON_MODULE_EXTENSION}") if (WIN32) - # .PYD file extension on Windows - set_target_properties(nanogui_python PROPERTIES SUFFIX ".pyd") - # Set output path - set_target_properties(nanogui_python PROPERTIES ARCHIVE_OUTPUT_DIRECTORY_RELEASE "Release/python") - set_target_properties(nanogui_python PROPERTIES ARCHIVE_OUTPUT_DIRECTORY_DEBUG "Debug/python") - set_target_properties(nanogui_python PROPERTIES ARCHIVE_OUTPUT_DIRECTORY_MINSIZEREL "MinSizeRel/python") - set_target_properties(nanogui_python PROPERTIES ARCHIVE_OUTPUT_DIRECTORY_RELWITHDEBINFO "RelWithDebInfo/python") - set_target_properties(nanogui_python PROPERTIES RUNTIME_OUTPUT_DIRECTORY_RELEASE "Release/python") - set_target_properties(nanogui_python PROPERTIES RUNTIME_OUTPUT_DIRECTORY_DEBUG "Debug/python") - set_target_properties(nanogui_python PROPERTIES RUNTIME_OUTPUT_DIRECTORY_MINSIZEREL "MinSizeRel/python") - set_target_properties(nanogui_python PROPERTIES RUNTIME_OUTPUT_DIRECTORY_RELWITHDEBINFO "RelWithDebInfo/python") + set_target_properties(nanogui-python PROPERTIES ARCHIVE_OUTPUT_DIRECTORY_RELEASE "Release/python") + set_target_properties(nanogui-python PROPERTIES ARCHIVE_OUTPUT_DIRECTORY_DEBUG "Debug/python") + set_target_properties(nanogui-python PROPERTIES ARCHIVE_OUTPUT_DIRECTORY_MINSIZEREL "MinSizeRel/python") + set_target_properties(nanogui-python PROPERTIES ARCHIVE_OUTPUT_DIRECTORY_RELWITHDEBINFO "RelWithDebInfo/python") + set_target_properties(nanogui-python PROPERTIES RUNTIME_OUTPUT_DIRECTORY_RELEASE "Release/python") + set_target_properties(nanogui-python PROPERTIES RUNTIME_OUTPUT_DIRECTORY_DEBUG "Debug/python") + set_target_properties(nanogui-python PROPERTIES RUNTIME_OUTPUT_DIRECTORY_MINSIZEREL "MinSizeRel/python") + set_target_properties(nanogui-python PROPERTIES RUNTIME_OUTPUT_DIRECTORY_RELWITHDEBINFO "RelWithDebInfo/python") # Link against the Python shared library - target_link_libraries(nanogui_python ${PYTHON_LIBRARY}) + target_link_libraries(nanogui-python ${PYTHON_LIBRARY}) if (MSVC) - # Optimize size, /bigobj is needed for due to the heavy template metaprogramming in pybind11 - set_target_properties(nanogui_python PROPERTIES COMPILE_FLAGS "/Os /bigobj") + # Optimize for size, /bigobj is needed for due to the heavy template metaprogramming in pybind11 + set_property(TARGET nanogui-python-obj APPEND PROPERTY COMPILE_OPTIONS + "/bigobj" "$<$:/Os>" "$<$:/Os>" + "$<$:/Os>") endif() elseif(UNIX) - # .SO file extension on Linux/Mac OS - set_target_properties(nanogui_python PROPERTIES SUFFIX ".so") - - # Optimize for a small binary size - if (NOT ${U_CMAKE_BUILD_TYPE} MATCHES DEBUG) - set_target_properties(nanogui_python PROPERTIES COMPILE_FLAGS "-Os -fvisibility=hidden ") + # Optimize for size + if (U_CMAKE_BUILD_TYPE MATCHES REL) + set_property(TARGET nanogui-python-obj APPEND PROPERTY COMPILE_OPTIONS "-Os") endif() # Strip unnecessary sections of the binary on Linux/Mac OS if(APPLE) - set_target_properties(nanogui_python PROPERTIES MACOSX_RPATH ".") - set_target_properties(nanogui_python PROPERTIES LINK_FLAGS "-undefined dynamic_lookup ") + set_target_properties(nanogui-python PROPERTIES MACOSX_RPATH ".") + set_target_properties(nanogui-python PROPERTIES LINK_FLAGS "-undefined dynamic_lookup ") - if (NOT ${U_CMAKE_BUILD_TYPE} MATCHES DEBUG) - add_custom_command(TARGET nanogui_python POST_BUILD COMMAND strip -u -r ${CMAKE_CURRENT_BINARY_DIR}/python/nanogui.so) + if (NOT ${U_CMAKE_BUILD_TYPE} MATCHES DEB) + add_custom_command(TARGET nanogui-python POST_BUILD COMMAND strip -u -r $) endif() else() - if (NOT ${U_CMAKE_BUILD_TYPE} MATCHES DEBUG) - add_custom_command(TARGET nanogui_python POST_BUILD COMMAND strip ${CMAKE_CURRENT_BINARY_DIR}/python/nanogui.so) + if (NOT ${U_CMAKE_BUILD_TYPE} MATCHES DEB) + add_custom_command(TARGET nanogui-python POST_BUILD COMMAND strip $) endif() endif() endif() + + if (NANOGUI_INSTALL) + install(TARGETS nanogui-python + LIBRARY DESTINATION lib + ARCHIVE DESTINATION lib) + endif() endif() get_directory_property(NANOGUI_HAS_PARENT PARENT_DIRECTORY) if(NANOGUI_HAS_PARENT) # This project is included from somewhere else. Export NANOGUI_EXTRA_LIBS variable set(NANOGUI_EXTRA_LIBS ${NANOGUI_EXTRA_LIBS} PARENT_SCOPE) + set(NANOGUI_EXTRA_DEFS ${NANOGUI_EXTRA_DEFS} PARENT_SCOPE) + set(NANOGUI_EXTRA_INCS ${NANOGUI_EXTRA_INCS} PARENT_SCOPE) else() # Create documentation for python plugin (optional target for developers) + + string(REPLACE " " ";" MKDOC_CXX_FLAGS_LIST ${CMAKE_CXX_FLAGS}) + get_property(MKDOC_INCLUDE_DIRECTORIES DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} PROPERTY INCLUDE_DIRECTORIES) + get_property(MKDOC_COMPILE_DEFINITIONS DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} PROPERTY COMPILE_DEFINITIONS) + + foreach (value ${MKDOC_INCLUDE_DIRECTORIES}) + list(APPEND MKDOC_CXX_FLAGS_LIST -I${value}) + endforeach() + + # Make sure platform specific code gets kept in py_doc.h (specifically __doc_nanogui_chdir_to_bundle_parent) + list(APPEND MKDOC_COMPILE_DEFINITIONS "DOXYGEN_DOCUMENTATION_BUILD") + foreach (value ${MKDOC_COMPILE_DEFINITIONS}) + list(APPEND MKDOC_CXX_FLAGS_LIST -D${value}) + endforeach() + add_custom_target(mkdoc COMMAND - python3 ${CMAKE_CURRENT_SOURCE_DIR}/ext/pybind11/tools/mkdoc.py - -Iinclude -Iext/nanovg/src - ${CMAKE_CURRENT_SOURCE_DIR}/include/nanogui/*.h > ${CMAKE_CURRENT_SOURCE_DIR}/python/py_doc.h) + python3 ${PROJECT_SOURCE_DIR}/docs/mkdoc_rst.py + ${MKDOC_CXX_FLAGS_LIST} + ${PROJECT_SOURCE_DIR}/include/nanogui/*.h + > ${CMAKE_CURRENT_SOURCE_DIR}/python/py_doc.h) + endif() # vim: set et ts=2 sw=2 ft=cmake nospell: diff --git a/testbed/nanogui/CONTRIBUTING.rst b/testbed/nanogui/CONTRIBUTING.rst new file mode 100644 index 00000000..e660202c --- /dev/null +++ b/testbed/nanogui/CONTRIBUTING.rst @@ -0,0 +1,48 @@ +Contributing +======================================================================================== + +Thank you for your interest in this project! Please refer to the following sections on +how to contribute code and bug reports. + +Reporting bugs +---------------------------------------------------------------------------------------- + +At the moment, this project is run in the spare time of a single person +(`Wenzel Jakob `_) with very limited resources for +issue tracker tickets. Thus, before submitting a question or bug report, please take a +moment of your time and ensure that your issue isn't already discussed in the project +documentation elsewhere on this site. + +Feature requests are generally closed unless they come with a pull request +that implements the desired functionality. + +Assuming that you have identified a previously unknown problem or an important question, +it's essential that you submit a self-contained and minimal piece of code that +reproduces the problem. In other words: no external dependencies, isolate the +function(s) that cause breakage, submit matched and complete C++ or Python snippets +(depending on how you are using NanoGUI) that can be easily compiled and run on my end. + +Pull requests +---------------------------------------------------------------------------------------- +Contributions are submitted, reviewed, and accepted using Github pull requests. Please +refer to `this article `_ for +details and adhere to the following rules to make the process as smooth as possible: + +- Make a new branch for every feature you're working on. +- Make small and clean pull requests that are easy to review but make sure they do add + value by themselves. +- Make sure you have tested any new functionality (e.g. if you made a new Widget). +- This project has a strong focus on providing general solutions using a minimal amount + of code, thus small pull requests are greatly preferred. +- Read the remainder of this document, adhering to the bindings and documentation + requirements. +- If making a purely documentation PR, please prefix the commit with ``[docs]`` + + - E.g. ``[docs] Adding documentation for class X.`` + + +Specific activities for contributions +---------------------------------------------------------------------------------------- + +For a list of specific parts of nanogui which would benefit from outside contributions, +refer to the bottom part of `this page `_. diff --git a/testbed/nanogui/LICENSE.txt b/testbed/nanogui/LICENSE.txt index d134ff5b..6a13fac9 100644 --- a/testbed/nanogui/LICENSE.txt +++ b/testbed/nanogui/LICENSE.txt @@ -1,4 +1,4 @@ -Copyright (c) 2015 Wenzel Jakob , All rights reserved. +Copyright (c) 2017 Wenzel Jakob , All rights reserved. Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: diff --git a/testbed/nanogui/README.rst b/testbed/nanogui/README.rst new file mode 100644 index 00000000..791dd021 --- /dev/null +++ b/testbed/nanogui/README.rst @@ -0,0 +1,217 @@ +NanoGUI +======================================================================================== +|docs| |travis| |appveyor| + +.. |docs| image:: https://readthedocs.org/projects/nanogui/badge/?version=latest + :target: http://nanogui.readthedocs.org/en/latest/?badge=latest + :alt: Docs + +.. |travis| image:: https://travis-ci.org/wjakob/nanogui.svg?branch=master + :target: https://travis-ci.org/wjakob/nanogui + :alt: Travis Build Status + +.. |appveyor| image:: https://ci.appveyor.com/api/projects/status/m8h3uyvdb4ej2i02/branch/master?svg=true + :target: https://ci.appveyor.com/project/wjakob/nanogui/branch/master + :alt: Appveyor Build Status + +.. begin_brief_description + +NanoGUI is a minimalistic cross-platform widget library for OpenGL 3.x or higher. It +supports automatic layout generation, stateful C++11 lambdas callbacks, a variety of +useful widget types and Retina-capable rendering on Apple devices thanks to NanoVG_ by +Mikko Mononen. Python bindings of all functionality are provided using pybind11_. + +.. _NanoVG: https://github.com/memononen/NanoVG +.. _pybind11: https://github.com/wjakob/pybind11 + +.. end_brief_description + +- `Documentation `_ + +.. contents:: Contents + :local: + :backlinks: none + +Example screenshot +---------------------------------------------------------------------------------------- + +.. image:: https://github.com/wjakob/nanogui/raw/master/resources/screenshot.png + :alt: Screenshot of Example 1. + :align: center + +Description +---------------------------------------------------------------------------------------- + +.. begin_long_description + +NanoGUI builds on GLFW_ for cross-platform OpenGL context creation and event handling, +GLAD_ to use OpenGL 3.x or higher Windows, Eigen_ for basic vector types, and NanoVG_ to +draw 2D primitives. + +Note that the dependency library NanoVG already includes some basic example code to draw +good-looking static widgets; what NanoGUI does is to flesh it out into a complete GUI +toolkit with event handling, layout generation, etc. + +NanoGUI currently works on Mac OS X (Clang) Linux (GCC or Clang) and Windows (Visual +Studio ≥ 2015); it requires a recent C++11 capable compiler. All dependencies are +jointly built using a CMake-based build system. + +.. _GLFW: http://www.glfw.org/ +.. _GLAD: https://github.com/Dav1dde/glad +.. _Eigen: http://eigen.tuxfamily.org/index.php?title=Main_Page + +.. end_long_description + +Creating widgets +---------------------------------------------------------------------------------------- + +NanoGUI makes it easy to instantiate widgets, set layout constraints, and +register event callbacks using high-level C++11 code. For instance, the +following two lines from the included example application add a new button to +an existing window `window` and register an event callback. + +.. code-block:: cpp + + Button *b = new Button(window, "Plain button"); + b->setCallback([] { cout << "pushed!" << endl; }); + + +The following lines from the example application create the coupled +slider and text box on the bottom of the second window (see the screenshot). + +.. code-block:: cpp + + /* Create an empty panel with a horizontal layout */ + Widget *panel = new Widget(window); + panel->setLayout(new BoxLayout(BoxLayout::Horizontal, BoxLayout::Middle, 0, 20)); + + /* Add a slider and set defaults */ + Slider *slider = new Slider(panel); + slider->setValue(0.5f); + slider->setFixedWidth(80); + + /* Add a textbox and set defaults */ + TextBox *textBox = new TextBox(panel); + textBox->setFixedSize(Vector2i(60, 25)); + textBox->setValue("50"); + textBox->setUnits("%"); + + /* Propagate slider changes to the text box */ + slider->setCallback([textBox](float value) { + textBox->setValue(std::to_string((int) (value * 100))); + }); + + +The Python version of this same piece of code looks like this: + +.. code-block:: py + + # Create an empty panel with a horizontal layout + panel = Widget(window) + panel.setLayout(BoxLayout(BoxLayout.Horizontal, BoxLayout.Middle, 0, 20)) + + # Add a slider and set defaults + slider = Slider(panel) + slider.setValue(0.5f) + slider.setFixedWidth(80) + + # Add a textbox and set defaults + textBox = TextBox(panel) + textBox.setFixedSize(Vector2i(60, 25)) + textBox.setValue("50") + textBox.setUnits("%") + + # Propagate slider changes to the text box + def cb(value): + textBox.setValue("%i" % int(value * 100)) + slider.setCallback(cb) + +"Simple mode" +---------------------------------------------------------------------------------------- + +Christian Schüller contributed a convenience class that makes it possible to +create AntTweakBar-style variable manipulators using just a few lines of code. +For instance, the source code below was used to create the following example +application. + +.. image:: https://github.com/wjakob/nanogui/raw/master/resources/screenshot2.png + :alt: Screenshot + :align: center + + +.. code-block:: cpp + + /// dvar, bar, strvar, etc. are double/bool/string/.. variables + + FormHelper *gui = new FormHelper(screen); + ref window = gui->addWindow(Eigen::Vector2i(10, 10), "Form helper example"); + gui->addGroup("Basic types"); + gui->addVariable("bool", bvar); + gui->addVariable("string", strvar); + + gui->addGroup("Validating fields"); + gui->addVariable("int", ivar); + gui->addVariable("float", fvar); + gui->addVariable("double", dvar); + + gui->addGroup("Complex types"); + gui->addVariable("Enumeration", enumval, enabled) + ->setItems({"Item 1", "Item 2", "Item 3"}); + gui->addVariable("Color", colval); + + gui->addGroup("Other widgets"); + gui->addButton("A button", [](){ std::cout << "Button pressed." << std::endl; }); + + screen->setVisible(true); + screen->performLayout(); + window->center(); + +Compiling +---------------------------------------------------------------------------------------- + +Clone the repository and all dependencies (with ``git clone --recursive``), +run CMake to generate Makefiles or CMake/Visual Studio project files, and +the rest should just work automatically. + +On Debian/Ubuntu, make sure that you have installed the following packages + +.. code-block:: bash + + $ apt-get install cmake xorg-dev libglu1-mesa-dev + +To also get the Python bindings, you'll need to run + +.. code-block:: bash + + $ apt-get install python-dev + +On RedHat/Fedora, make sure that you have installed the following packages + +.. code-block:: bash + + $ sudo dnf install cmake mesa-libGLU-devel libXi-devel libXcursor-devel libXinerama-devel libXrandr-devel xorg-x11-server-devel + +To also get the Python bindings, you'll need to run + +.. code-block:: bash + + $ sudo dnf install python3-devel + +License +---------------------------------------------------------------------------------------- + +.. begin_license + +NanoGUI is provided under a BSD-style license that can be found in the LICENSE_ +file. By using, distributing, or contributing to this project, you agree to the +terms and conditions of this license. + +.. _LICENSE: https://github.com/wjakob/nanogui/blob/master/LICENSE.txt + +NanoGUI uses Daniel Bruce's `Entypo+ `_ font for the +icons used on various widgets. This work is licensed under a +`CC BY-SA 4.0 `_ license. +Commercial entities using NanoGUI should consult the proper legal counsel for +how to best adhere to the attribution clause of the license. + +.. end_license diff --git a/testbed/nanogui/ext/coro/LICENSE b/testbed/nanogui/ext/coro/LICENSE new file mode 100644 index 00000000..5c9c3bb6 --- /dev/null +++ b/testbed/nanogui/ext/coro/LICENSE @@ -0,0 +1,26 @@ +Copyright (c) 2000-2009 Marc Alexander Lehmann + +Redistribution and use in source and binary forms, with or without modifica- +tion, are permitted provided that the following conditions are met: + + 1. Redistributions of source code must retain the above copyright notice, + this list of conditions and the following disclaimer. + + 2. Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED +WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MER- +CHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO +EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPE- +CIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, +PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; +OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTH- +ERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED +OF THE POSSIBILITY OF SUCH DAMAGE. + +Alternatively, the following files carry an additional notice that +explicitly allows relicensing under the GPLv2: coro.c, coro.h. + diff --git a/testbed/nanogui/ext/coro/README b/testbed/nanogui/ext/coro/README new file mode 100644 index 00000000..28b0a6f5 --- /dev/null +++ b/testbed/nanogui/ext/coro/README @@ -0,0 +1,6 @@ +Configuration, documentation etc. is provided in the coro.h file. Please +note that the file conftest.c in this distribution is under the GPL. It is +not needed for proper operation of this library though, for that, coro.h +and coro.c suffice. + +Marc Lehmann diff --git a/testbed/nanogui/ext/coro/coro.c b/testbed/nanogui/ext/coro/coro.c new file mode 100644 index 00000000..0bd070dd --- /dev/null +++ b/testbed/nanogui/ext/coro/coro.c @@ -0,0 +1,803 @@ +/* + * Copyright (c) 2001-2011 Marc Alexander Lehmann + * + * Redistribution and use in source and binary forms, with or without modifica- + * tion, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MER- + * CHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO + * EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPE- + * CIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, + * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; + * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, + * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTH- + * ERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED + * OF THE POSSIBILITY OF SUCH DAMAGE. + * + * Alternatively, the contents of this file may be used under the terms of + * the GNU General Public License ("GPL") version 2 or any later version, + * in which case the provisions of the GPL are applicable instead of + * the above. If you wish to allow the use of your version of this file + * only under the terms of the GPL and not to allow others to use your + * version of this file under the BSD license, indicate your decision + * by deleting the provisions above and replace them with the notice + * and other provisions required by the GPL. If you do not delete the + * provisions above, a recipient may use your version of this file under + * either the BSD or the GPL. + * + * This library is modelled strictly after Ralf S. Engelschalls article at + * http://www.gnu.org/software/pth/rse-pmt.ps. So most of the credit must + * go to Ralf S. Engelschall . + */ + +#include "coro.h" + +#include +#include + +/*****************************************************************************/ +/* ucontext/setjmp/asm backends */ +/*****************************************************************************/ +#if CORO_UCONTEXT || CORO_SJLJ || CORO_LOSER || CORO_LINUX || CORO_IRIX || CORO_ASM + +# if CORO_UCONTEXT +# include +# endif + +# if !defined(STACK_ADJUST_PTR) +# if __sgi +/* IRIX is decidedly NON-unix */ +# define STACK_ADJUST_PTR(sp,ss) ((char *)(sp) + (ss) - 8) +# define STACK_ADJUST_SIZE(sp,ss) ((ss) - 8) +# elif (__i386__ && CORO_LINUX) || (_M_IX86 && CORO_LOSER) +# define STACK_ADJUST_PTR(sp,ss) ((char *)(sp) + (ss)) +# define STACK_ADJUST_SIZE(sp,ss) (ss) +# elif (__amd64__ && CORO_LINUX) || ((_M_AMD64 || _M_IA64) && CORO_LOSER) +# define STACK_ADJUST_PTR(sp,ss) ((char *)(sp) + (ss) - 8) +# define STACK_ADJUST_SIZE(sp,ss) (ss) +# else +# define STACK_ADJUST_PTR(sp,ss) (sp) +# define STACK_ADJUST_SIZE(sp,ss) (ss) +# endif +# endif + +# include + +# if CORO_SJLJ +# include +# include +# include +# endif + +static coro_func coro_init_func; +static void *coro_init_arg; +static coro_context *new_coro, *create_coro; + +static void +coro_init (void) +{ + volatile coro_func func = coro_init_func; + volatile void *arg = coro_init_arg; + + coro_transfer (new_coro, create_coro); + +#if __GCC_HAVE_DWARF2_CFI_ASM && __amd64 + asm (".cfi_undefined rip"); +#endif + + func ((void *)arg); + + /* the new coro returned. bad. just abort() for now */ + abort (); +} + +# if CORO_SJLJ + +static volatile int trampoline_done; + +/* trampoline signal handler */ +static void +trampoline (int sig) +{ + if (coro_setjmp (new_coro->env)) + coro_init (); /* start it */ + else + trampoline_done = 1; +} + +# endif + +# if CORO_ASM + + #if __arm__ && \ + (defined __ARM_ARCH_7__ || defined __ARM_ARCH_7A__ \ + || defined __ARM_ARCH_7R__ || defined __ARM_ARCH_7M__ \ + || __ARCH_ARCH == 7) + #define CORO_ARM 1 + #endif + + #if _WIN32 || __CYGWIN__ + #define CORO_WIN_TIB 1 + #endif + + asm ( + "\t.text\n" + #if _WIN32 || __CYGWIN__ + "\t.globl _coro_transfer\n" + "_coro_transfer:\n" + #else + "\t.globl coro_transfer\n" + "coro_transfer:\n" + #endif + /* windows, of course, gives a shit on the amd64 ABI and uses different registers */ + /* http://blogs.msdn.com/freik/archive/2005/03/17/398200.aspx */ + #if __amd64 + + #if _WIN32 || __CYGWIN__ + #define NUM_SAVED 29 + "\tsubq $168, %rsp\t" /* one dummy qword to improve alignment */ + "\tmovaps %xmm6, (%rsp)\n" + "\tmovaps %xmm7, 16(%rsp)\n" + "\tmovaps %xmm8, 32(%rsp)\n" + "\tmovaps %xmm9, 48(%rsp)\n" + "\tmovaps %xmm10, 64(%rsp)\n" + "\tmovaps %xmm11, 80(%rsp)\n" + "\tmovaps %xmm12, 96(%rsp)\n" + "\tmovaps %xmm13, 112(%rsp)\n" + "\tmovaps %xmm14, 128(%rsp)\n" + "\tmovaps %xmm15, 144(%rsp)\n" + "\tpushq %rsi\n" + "\tpushq %rdi\n" + "\tpushq %rbp\n" + "\tpushq %rbx\n" + "\tpushq %r12\n" + "\tpushq %r13\n" + "\tpushq %r14\n" + "\tpushq %r15\n" + #if CORO_WIN_TIB + "\tpushq %fs:0x0\n" + "\tpushq %fs:0x8\n" + "\tpushq %fs:0xc\n" + #endif + "\tmovq %rsp, (%rcx)\n" + "\tmovq (%rdx), %rsp\n" + #if CORO_WIN_TIB + "\tpopq %fs:0xc\n" + "\tpopq %fs:0x8\n" + "\tpopq %fs:0x0\n" + #endif + "\tpopq %r15\n" + "\tpopq %r14\n" + "\tpopq %r13\n" + "\tpopq %r12\n" + "\tpopq %rbx\n" + "\tpopq %rbp\n" + "\tpopq %rdi\n" + "\tpopq %rsi\n" + "\tmovaps (%rsp), %xmm6\n" + "\tmovaps 16(%rsp), %xmm7\n" + "\tmovaps 32(%rsp), %xmm8\n" + "\tmovaps 48(%rsp), %xmm9\n" + "\tmovaps 64(%rsp), %xmm10\n" + "\tmovaps 80(%rsp), %xmm11\n" + "\tmovaps 96(%rsp), %xmm12\n" + "\tmovaps 112(%rsp), %xmm13\n" + "\tmovaps 128(%rsp), %xmm14\n" + "\tmovaps 144(%rsp), %xmm15\n" + "\taddq $168, %rsp\n" + #else + #define NUM_SAVED 6 + "\tpushq %rbp\n" + "\tpushq %rbx\n" + "\tpushq %r12\n" + "\tpushq %r13\n" + "\tpushq %r14\n" + "\tpushq %r15\n" + "\tmovq %rsp, (%rdi)\n" + "\tmovq (%rsi), %rsp\n" + "\tpopq %r15\n" + "\tpopq %r14\n" + "\tpopq %r13\n" + "\tpopq %r12\n" + "\tpopq %rbx\n" + "\tpopq %rbp\n" + #endif + "\tpopq %rcx\n" + "\tjmpq *%rcx\n" + + #elif __i386__ + + #define NUM_SAVED 4 + "\tpushl %ebp\n" + "\tpushl %ebx\n" + "\tpushl %esi\n" + "\tpushl %edi\n" + #if CORO_WIN_TIB + #undef NUM_SAVED + #define NUM_SAVED 7 + "\tpushl %fs:0\n" + "\tpushl %fs:4\n" + "\tpushl %fs:8\n" + #endif + "\tmovl %esp, (%eax)\n" + "\tmovl (%edx), %esp\n" + #if CORO_WIN_TIB + "\tpopl %fs:8\n" + "\tpopl %fs:4\n" + "\tpopl %fs:0\n" + #endif + "\tpopl %edi\n" + "\tpopl %esi\n" + "\tpopl %ebx\n" + "\tpopl %ebp\n" + "\tpopl %ecx\n" + "\tjmpl *%ecx\n" + + #elif CORO_ARM /* untested, what about thumb, neon, iwmmxt? */ + + #if __ARM_PCS_VFP + "\tvpush {d8-d15}\n" + #define NUM_SAVED (9 + 8 * 2) + #else + #define NUM_SAVED 9 + #endif + "\tpush {r4-r11,lr}\n" + "\tstr sp, [r0]\n" + "\tldr sp, [r1]\n" + "\tpop {r4-r11,lr}\n" + #if __ARM_PCS_VFP + "\tvpop {d8-d15}\n" + #endif + "\tmov r15, lr\n" + + #elif __mips__ && 0 /* untested, 32 bit only */ + + #define NUM_SAVED (12 + 8 * 2) + /* TODO: n64/o64, lw=>ld */ + + "\t.set nomips16\n" + "\t.frame $sp,112,$31\n" + #if __mips_soft_float + "\taddiu $sp,$sp,-44\n" + #else + "\taddiu $sp,$sp,-112\n" + "\ts.d $f30,88($sp)\n" + "\ts.d $f28,80($sp)\n" + "\ts.d $f26,72($sp)\n" + "\ts.d $f24,64($sp)\n" + "\ts.d $f22,56($sp)\n" + "\ts.d $f20,48($sp)\n" + #endif + "\tsw $28,40($sp)\n" + "\tsw $31,36($sp)\n" + "\tsw $fp,32($sp)\n" + "\tsw $23,28($sp)\n" + "\tsw $22,24($sp)\n" + "\tsw $21,20($sp)\n" + "\tsw $20,16($sp)\n" + "\tsw $19,12($sp)\n" + "\tsw $18,8($sp)\n" + "\tsw $17,4($sp)\n" + "\tsw $16,0($sp)\n" + "\tsw $sp,0($4)\n" + "\tlw $sp,0($5)\n" + #if !__mips_soft_float + "\tl.d $f30,88($sp)\n" + "\tl.d $f28,80($sp)\n" + "\tl.d $f26,72($sp)\n" + "\tl.d $f24,64($sp)\n" + "\tl.d $f22,56($sp)\n" + "\tl.d $f20,48($sp)\n" + #endif + "\tlw $28,40($sp)\n" + "\tlw $31,36($sp)\n" + "\tlw $fp,32($sp)\n" + "\tlw $23,28($sp)\n" + "\tlw $22,24($sp)\n" + "\tlw $21,20($sp)\n" + "\tlw $20,16($sp)\n" + "\tlw $19,12($sp)\n" + "\tlw $18,8($sp)\n" + "\tlw $17,4($sp)\n" + "\tlw $16,0($sp)\n" + "\tj $31\n" + #if __mips_soft_float + "\taddiu $sp,$sp,44\n" + #else + "\taddiu $sp,$sp,112\n" + #endif + + #else + #error unsupported architecture + #endif + ); + +# endif + +void +coro_create (coro_context *ctx, coro_func coro, void *arg, void *sptr, size_t ssize) +{ + coro_context nctx; +# if CORO_SJLJ + stack_t ostk, nstk; + struct sigaction osa, nsa; + sigset_t nsig, osig; +# endif + + if (!coro) + return; + + coro_init_func = coro; + coro_init_arg = arg; + + new_coro = ctx; + create_coro = &nctx; + +# if CORO_SJLJ + /* we use SIGUSR2. first block it, then fiddle with it. */ + + sigemptyset (&nsig); + sigaddset (&nsig, SIGUSR2); + sigprocmask (SIG_BLOCK, &nsig, &osig); + + nsa.sa_handler = trampoline; + sigemptyset (&nsa.sa_mask); + nsa.sa_flags = SA_ONSTACK; + + if (sigaction (SIGUSR2, &nsa, &osa)) + { + perror ("sigaction"); + abort (); + } + + /* set the new stack */ + nstk.ss_sp = STACK_ADJUST_PTR (sptr, ssize); /* yes, some platforms (IRIX) get this wrong. */ + nstk.ss_size = STACK_ADJUST_SIZE (sptr, ssize); + nstk.ss_flags = 0; + + if (sigaltstack (&nstk, &ostk) < 0) + { + perror ("sigaltstack"); + abort (); + } + + trampoline_done = 0; + kill (getpid (), SIGUSR2); + sigfillset (&nsig); sigdelset (&nsig, SIGUSR2); + + while (!trampoline_done) + sigsuspend (&nsig); + + sigaltstack (0, &nstk); + nstk.ss_flags = SS_DISABLE; + if (sigaltstack (&nstk, 0) < 0) + perror ("sigaltstack"); + + sigaltstack (0, &nstk); + if (~nstk.ss_flags & SS_DISABLE) + abort (); + + if (~ostk.ss_flags & SS_DISABLE) + sigaltstack (&ostk, 0); + + sigaction (SIGUSR2, &osa, 0); + sigprocmask (SIG_SETMASK, &osig, 0); + +# elif CORO_LOSER + + coro_setjmp (ctx->env); + #if __CYGWIN__ && __i386__ + ctx->env[8] = (long) coro_init; + ctx->env[7] = (long) ((char *)sptr + ssize) - sizeof (long); + #elif __CYGWIN__ && __x86_64__ + ctx->env[7] = (long) coro_init; + ctx->env[6] = (long) ((char *)sptr + ssize) - sizeof (long); + #elif defined __MINGW32__ + ctx->env[5] = (long) coro_init; + ctx->env[4] = (long) ((char *)sptr + ssize) - sizeof (long); + #elif defined _M_IX86 + ((_JUMP_BUFFER *)&ctx->env)->Eip = (long) coro_init; + ((_JUMP_BUFFER *)&ctx->env)->Esp = (long) STACK_ADJUST_PTR (sptr, ssize) - sizeof (long); + #elif defined _M_AMD64 + ((_JUMP_BUFFER *)&ctx->env)->Rip = (__int64) coro_init; + ((_JUMP_BUFFER *)&ctx->env)->Rsp = (__int64) STACK_ADJUST_PTR (sptr, ssize) - sizeof (__int64); + #elif defined _M_IA64 + ((_JUMP_BUFFER *)&ctx->env)->StIIP = (__int64) coro_init; + ((_JUMP_BUFFER *)&ctx->env)->IntSp = (__int64) STACK_ADJUST_PTR (sptr, ssize) - sizeof (__int64); + #else + #error "microsoft libc or architecture not supported" + #endif + +# elif CORO_LINUX + + coro_setjmp (ctx->env); + #if __GLIBC__ >= 2 && __GLIBC_MINOR__ >= 0 && defined (JB_PC) && defined (JB_SP) + ctx->env[0].__jmpbuf[JB_PC] = (long) coro_init; + ctx->env[0].__jmpbuf[JB_SP] = (long) STACK_ADJUST_PTR (sptr, ssize) - sizeof (long); + #elif __GLIBC__ >= 2 && __GLIBC_MINOR__ >= 0 && defined (__mc68000__) + ctx->env[0].__jmpbuf[0].__aregs[0] = (long int)coro_init; + ctx->env[0].__jmpbuf[0].__sp = (int *) ((char *)sptr + ssize) - sizeof (long); + #elif defined (__GNU_LIBRARY__) && defined (__i386__) + ctx->env[0].__jmpbuf[0].__pc = (char *) coro_init; + ctx->env[0].__jmpbuf[0].__sp = (void *) ((char *)sptr + ssize) - sizeof (long); + #elif defined (__GNU_LIBRARY__) && defined (__x86_64__) + ctx->env[0].__jmpbuf[JB_PC] = (long) coro_init; + ctx->env[0].__jmpbuf[0].__sp = (void *) ((char *)sptr + ssize) - sizeof (long); + #else + #error "linux libc or architecture not supported" + #endif + +# elif CORO_IRIX + + coro_setjmp (ctx->env, 0); + ctx->env[JB_PC] = (__uint64_t)coro_init; + ctx->env[JB_SP] = (__uint64_t)STACK_ADJUST_PTR (sptr, ssize) - sizeof (long); + +# elif CORO_ASM + + #if __i386__ || __x86_64__ + ctx->sp = (void **)(ssize + (char *)sptr); + *--ctx->sp = (void *)abort; /* needed for alignment only */ + *--ctx->sp = (void *)coro_init; + #if CORO_WIN_TIB + *--ctx->sp = 0; /* ExceptionList */ + *--ctx->sp = (char *)sptr + ssize; /* StackBase */ + *--ctx->sp = sptr; /* StackLimit */ + #endif + #elif CORO_ARM + /* return address stored in lr register, don't push anything */ + #else + #error unsupported architecture + #endif + + ctx->sp -= NUM_SAVED; + memset (ctx->sp, 0, sizeof (*ctx->sp) * NUM_SAVED); + + #if __i386__ || __x86_64__ + /* done already */ + #elif CORO_ARM + ctx->sp[0] = coro; /* r4 */ + ctx->sp[1] = arg; /* r5 */ + ctx->sp[8] = (char *)coro_init; /* lr */ + #else + #error unsupported architecture + #endif + +# elif CORO_UCONTEXT + + getcontext (&(ctx->uc)); + + ctx->uc.uc_link = 0; + ctx->uc.uc_stack.ss_sp = sptr; + ctx->uc.uc_stack.ss_size = (size_t)ssize; + ctx->uc.uc_stack.ss_flags = 0; + + makecontext (&(ctx->uc), (void (*)())coro_init, 0); + +# endif + + coro_transfer (create_coro, new_coro); +} + +/*****************************************************************************/ +/* pthread backend */ +/*****************************************************************************/ +#elif CORO_PTHREAD + +/* this mutex will be locked by the running coroutine */ +pthread_mutex_t coro_mutex = PTHREAD_MUTEX_INITIALIZER; + +struct coro_init_args +{ + coro_func func; + void *arg; + coro_context *self, *main; +}; + +static pthread_t null_tid; + +/* I'd so love to cast pthread_mutex_unlock to void (*)(void *)... */ +static void +mutex_unlock_wrapper (void *arg) +{ + pthread_mutex_unlock ((pthread_mutex_t *)arg); +} + +static void * +coro_init (void *args_) +{ + struct coro_init_args *args = (struct coro_init_args *)args_; + coro_func func = args->func; + void *arg = args->arg; + + pthread_mutex_lock (&coro_mutex); + + /* we try to be good citizens and use deferred cancellation and cleanup handlers */ + pthread_cleanup_push (mutex_unlock_wrapper, &coro_mutex); + coro_transfer (args->self, args->main); + func (arg); + pthread_cleanup_pop (1); + + return 0; +} + +void +coro_transfer (coro_context *prev, coro_context *next) +{ + pthread_cond_signal (&next->cv); + pthread_cond_wait (&prev->cv, &coro_mutex); +#if __FreeBSD__ /* freebsd is of course broken and needs manual testcancel calls... yay... */ + pthread_testcancel (); +#endif +} + +void +coro_create (coro_context *ctx, coro_func coro, void *arg, void *sptr, size_t ssize) +{ + static coro_context nctx; + static int once; + + if (!once) + { + once = 1; + + pthread_mutex_lock (&coro_mutex); + pthread_cond_init (&nctx.cv, 0); + null_tid = pthread_self (); + } + + pthread_cond_init (&ctx->cv, 0); + + if (coro) + { + pthread_attr_t attr; + struct coro_init_args args; + + args.func = coro; + args.arg = arg; + args.self = ctx; + args.main = &nctx; + + pthread_attr_init (&attr); +#if __UCLIBC__ + /* exists, but is borked */ + /*pthread_attr_setstacksize (&attr, (size_t)ssize);*/ +#elif __CYGWIN__ + /* POSIX, not here */ + pthread_attr_setstacksize (&attr, (size_t)ssize); +#else + pthread_attr_setstack (&attr, sptr, (size_t)ssize); +#endif + pthread_attr_setscope (&attr, PTHREAD_SCOPE_PROCESS); + pthread_create (&ctx->id, &attr, coro_init, &args); + + coro_transfer (args.main, args.self); + } + else + ctx->id = null_tid; +} + +void +coro_destroy (coro_context *ctx) +{ + if (!pthread_equal (ctx->id, null_tid)) + { + pthread_cancel (ctx->id); + pthread_mutex_unlock (&coro_mutex); + pthread_join (ctx->id, 0); + pthread_mutex_lock (&coro_mutex); + } + + pthread_cond_destroy (&ctx->cv); +} + +/*****************************************************************************/ +/* fiber backend */ +/*****************************************************************************/ +#elif CORO_FIBER + +#define WIN32_LEAN_AND_MEAN +#if _WIN32_WINNT < 0x0400 + #undef _WIN32_WINNT + #define _WIN32_WINNT 0x0400 +#endif +#include + +VOID CALLBACK +coro_init (PVOID arg) +{ + coro_context *ctx = (coro_context *)arg; + + ctx->coro (ctx->arg); +} + +void +coro_transfer (coro_context *prev, coro_context *next) +{ + if (!prev->fiber) + { + prev->fiber = GetCurrentFiber (); + + if (prev->fiber == 0 || prev->fiber == (void *)0x1e00) + prev->fiber = ConvertThreadToFiber (0); + } + + SwitchToFiber (next->fiber); +} + +void +coro_create (coro_context *ctx, coro_func coro, void *arg, void *sptr, size_t ssize) +{ + ctx->fiber = 0; + ctx->coro = coro; + ctx->arg = arg; + + if (!coro) + return; + + ctx->fiber = CreateFiber (ssize, coro_init, ctx); +} + +void +coro_destroy (coro_context *ctx) +{ + DeleteFiber (ctx->fiber); +} + +#else + #error unsupported backend +#endif + +/*****************************************************************************/ +/* stack management */ +/*****************************************************************************/ +#if CORO_STACKALLOC + +#include + +#ifndef _WIN32 +# include +#endif + +#if CORO_USE_VALGRIND +# include +#endif + +#if _POSIX_MAPPED_FILES +# include +# define CORO_MMAP 1 +# ifndef MAP_ANONYMOUS +# ifdef MAP_ANON +# define MAP_ANONYMOUS MAP_ANON +# else +# undef CORO_MMAP +# endif +# endif +# include +#else +# undef CORO_MMAP +#endif + +#if _POSIX_MEMORY_PROTECTION +# ifndef CORO_GUARDPAGES +# define CORO_GUARDPAGES 4 +# endif +#else +# undef CORO_GUARDPAGES +#endif + +#if !CORO_MMAP +# undef CORO_GUARDPAGES +#endif + +#if !__i386__ && !__x86_64__ && !__powerpc__ && !__arm__ && !__aarch64__ && !__m68k__ && !__alpha__ && !__mips__ && !__sparc64__ +# undef CORO_GUARDPAGES +#endif + +#ifndef CORO_GUARDPAGES +# define CORO_GUARDPAGES 0 +#endif + +#if !PAGESIZE + #if !CORO_MMAP + #define PAGESIZE 4096 + #else + static size_t + coro_pagesize (void) + { + static size_t pagesize; + + if (!pagesize) + pagesize = sysconf (_SC_PAGESIZE); + + return pagesize; + } + + #define PAGESIZE coro_pagesize () + #endif +#endif + +int +coro_stack_alloc (struct coro_stack *stack, unsigned int size) +{ + if (!size) + size = 256 * 1024; + + stack->sptr = 0; + stack->ssze = ((size_t)size * sizeof (void *) + PAGESIZE - 1) / PAGESIZE * PAGESIZE; + +#if CORO_FIBER + + stack->sptr = (void *)stack; + return 1; + +#else + + size_t ssze = stack->ssze + CORO_GUARDPAGES * PAGESIZE; + void *base; + + #if CORO_MMAP + /* mmap supposedly does allocate-on-write for us */ + base = mmap (0, ssze, PROT_READ | PROT_WRITE | PROT_EXEC, MAP_PRIVATE | MAP_ANONYMOUS, -1, 0); + + if (base == (void *)-1) + { + /* some systems don't let us have executable heap */ + /* we assume they won't need executable stack in that case */ + base = mmap (0, ssze, PROT_READ | PROT_WRITE, MAP_PRIVATE | MAP_ANONYMOUS, -1, 0); + + if (base == (void *)-1) + return 0; + } + + #if CORO_GUARDPAGES + mprotect (base, CORO_GUARDPAGES * PAGESIZE, PROT_NONE); + #endif + + base = (void*)((char *)base + CORO_GUARDPAGES * PAGESIZE); + #else + base = malloc (ssze); + if (!base) + return 0; + #endif + + #if CORO_USE_VALGRIND + stack->valgrind_id = VALGRIND_STACK_REGISTER ((char *)base, ((char *)base) + ssze - CORO_GUARDPAGES * PAGESIZE); + #endif + + stack->sptr = base; + return 1; + +#endif +} + +void +coro_stack_free (struct coro_stack *stack) +{ +#if CORO_FIBER + /* nop */ +#else + #if CORO_USE_VALGRIND + VALGRIND_STACK_DEREGISTER (stack->valgrind_id); + #endif + + #if CORO_MMAP + if (stack->sptr) + munmap ((void*)((char *)stack->sptr - CORO_GUARDPAGES * PAGESIZE), + stack->ssze + CORO_GUARDPAGES * PAGESIZE); + #else + free (stack->sptr); + #endif +#endif +} + +#endif + diff --git a/testbed/nanogui/ext/coro/coro.h b/testbed/nanogui/ext/coro/coro.h new file mode 100644 index 00000000..8df287e0 --- /dev/null +++ b/testbed/nanogui/ext/coro/coro.h @@ -0,0 +1,425 @@ +/* + * Copyright (c) 2001-2012,2015 Marc Alexander Lehmann + * + * Redistribution and use in source and binary forms, with or without modifica- + * tion, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MER- + * CHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO + * EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPE- + * CIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, + * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; + * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, + * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTH- + * ERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED + * OF THE POSSIBILITY OF SUCH DAMAGE. + * + * Alternatively, the contents of this file may be used under the terms of + * the GNU General Public License ("GPL") version 2 or any later version, + * in which case the provisions of the GPL are applicable instead of + * the above. If you wish to allow the use of your version of this file + * only under the terms of the GPL and not to allow others to use your + * version of this file under the BSD license, indicate your decision + * by deleting the provisions above and replace them with the notice + * and other provisions required by the GPL. If you do not delete the + * provisions above, a recipient may use your version of this file under + * either the BSD or the GPL. + * + * This library is modelled strictly after Ralf S. Engelschalls article at + * http://www.gnu.org/software/pth/rse-pmt.ps. So most of the credit must + * go to Ralf S. Engelschall . + * + * This coroutine library is very much stripped down. You should either + * build your own process abstraction using it or - better - just use GNU + * Portable Threads, http://www.gnu.org/software/pth/. + * + */ + +/* + * 2006-10-26 Include stddef.h on OS X to work around one of its bugs. + * Reported by Michael_G_Schwern. + * 2006-11-26 Use _setjmp instead of setjmp on GNU/Linux. + * 2007-04-27 Set unwind frame info if gcc 3+ and ELF is detected. + * Use _setjmp instead of setjmp on _XOPEN_SOURCE >= 600. + * 2007-05-02 Add assembly versions for x86 and amd64 (to avoid reliance + * on SIGUSR2 and sigaltstack in Crossfire). + * 2008-01-21 Disable CFI usage on anything but GNU/Linux. + * 2008-03-02 Switched to 2-clause BSD license with GPL exception. + * 2008-04-04 New (but highly unrecommended) pthreads backend. + * 2008-04-24 Reinstate CORO_LOSER (had wrong stack adjustments). + * 2008-10-30 Support assembly method on x86 with and without frame pointer. + * 2008-11-03 Use a global asm statement for CORO_ASM, idea by pippijn. + * 2008-11-05 Hopefully fix misaligned stacks with CORO_ASM/SETJMP. + * 2008-11-07 rbp wasn't saved in CORO_ASM on x86_64. + * introduce coro_destroy, which is a nop except for pthreads. + * speed up CORO_PTHREAD. Do no longer leak threads either. + * coro_create now allows one to create source coro_contexts. + * do not rely on makecontext passing a void * correctly. + * try harder to get _setjmp/_longjmp. + * major code cleanup/restructuring. + * 2008-11-10 the .cfi hacks are no longer needed. + * 2008-11-16 work around a freebsd pthread bug. + * 2008-11-19 define coro_*jmp symbols for easier porting. + * 2009-06-23 tentative win32-backend support for mingw32 (Yasuhiro Matsumoto). + * 2010-12-03 tentative support for uclibc (which lacks all sorts of things). + * 2011-05-30 set initial callee-saved-registers to zero with CORO_ASM. + * use .cfi_undefined rip on linux-amd64 for better backtraces. + * 2011-06-08 maybe properly implement weird windows amd64 calling conventions. + * 2011-07-03 rely on __GCC_HAVE_DWARF2_CFI_ASM for cfi detection. + * 2011-08-08 cygwin trashes stacks, use pthreads with double stack on cygwin. + * 2012-12-04 reduce misprediction penalty for x86/amd64 assembly switcher. + * 2012-12-05 experimental fiber backend (allocates stack twice). + * 2012-12-07 API version 3 - add coro_stack_alloc/coro_stack_free. + * 2012-12-21 valgrind stack registering was broken. + * 2015-12-05 experimental asm be for arm7, based on a patch by Nick Zavaritsky. + * use __name__ for predefined symbols, as in libecb. + * enable guard pages on arm, aarch64 and mips. + */ + +#ifndef CORO_H +#define CORO_H + +#if __cplusplus +extern "C" { +#endif + +/* + * This library consists of only three files + * coro.h, coro.c and LICENSE (and optionally README) + * + * It implements what is known as coroutines, in a hopefully + * portable way. + * + * All compiletime symbols must be defined both when including coro.h + * (using libcoro) as well as when compiling coro.c (the implementation). + * + * You can manually specify which flavour you want. If you don't define + * any of these, libcoro tries to choose a safe and fast default: + * + * -DCORO_UCONTEXT + * + * This flavour uses SUSv2's get/set/swap/makecontext functions that + * unfortunately only some unices support, and is quite slow. + * + * -DCORO_SJLJ + * + * This flavour uses SUSv2's setjmp/longjmp and sigaltstack functions to + * do it's job. Coroutine creation is much slower than UCONTEXT, but + * context switching is a bit cheaper. It should work on almost all unices. + * + * -DCORO_LINUX + * + * CORO_SJLJ variant. + * Old GNU/Linux systems (<= glibc-2.1) only work with this implementation + * (it is very fast and therefore recommended over other methods, but + * doesn't work with anything newer). + * + * -DCORO_LOSER + * + * CORO_SJLJ variant. + * Microsoft's highly proprietary platform doesn't support sigaltstack, and + * this selects a suitable workaround for this platform. It might not work + * with your compiler though - it has only been tested with MSVC 6. + * + * -DCORO_FIBER + * + * Slower, but probably more portable variant for the Microsoft operating + * system, using fibers. Ignores the passed stack and allocates it internally. + * Also, due to bugs in cygwin, this does not work with cygwin. + * + * -DCORO_IRIX + * + * CORO_SJLJ variant. + * For SGI's version of Microsoft's NT ;) + * + * -DCORO_ASM + * + * Hand coded assembly, known to work only on a few architectures/ABI: + * GCC + arm7/x86/IA32/amd64/x86_64 + GNU/Linux and a few BSDs. Fastest + * choice, if it works. + * + * -DCORO_PTHREAD + * + * Use the pthread API. You have to provide and -lpthread. + * This is likely the slowest backend, and it also does not support fork(), + * so avoid it at all costs. + * + * If you define neither of these symbols, coro.h will try to autodetect + * the best/safest model. To help with the autodetection, you should check + * (e.g. using autoconf) and define the following symbols: HAVE_UCONTEXT_H + * / HAVE_SETJMP_H / HAVE_SIGALTSTACK. + */ + +/* + * Changes when the API changes incompatibly. + * This is ONLY the API version - there is no ABI compatibility between releases. + * + * Changes in API version 2: + * replaced bogus -DCORO_LOOSE with grammatically more correct -DCORO_LOSER + * Changes in API version 3: + * introduced stack management (CORO_STACKALLOC) + */ +#define CORO_VERSION 3 + +#include + +/* + * This is the type for the initialization function of a new coroutine. + */ +typedef void (*coro_func)(void *); + +/* + * A coroutine state is saved in the following structure. Treat it as an + * opaque type. errno and sigmask might be saved, but don't rely on it, + * implement your own switching primitive if you need that. + */ +typedef struct coro_context coro_context; + +/* + * This function creates a new coroutine. Apart from a pointer to an + * uninitialised coro_context, it expects a pointer to the entry function + * and the single pointer value that is given to it as argument. + * + * Allocating/deallocating the stack is your own responsibility. + * + * As a special case, if coro, arg, sptr and ssze are all zero, + * then an "empty" coro_context will be created that is suitable + * as an initial source for coro_transfer. + * + * This function is not reentrant, but putting a mutex around it + * will work. + */ +void coro_create (coro_context *ctx, /* an uninitialised coro_context */ + coro_func coro, /* the coroutine code to be executed */ + void *arg, /* a single pointer passed to the coro */ + void *sptr, /* start of stack area */ + size_t ssze); /* size of stack area in bytes */ + +/* + * The following prototype defines the coroutine switching function. It is + * sometimes implemented as a macro, so watch out. + * + * This function is thread-safe and reentrant. + */ +#if 0 +void coro_transfer (coro_context *prev, coro_context *next); +#endif + +/* + * The following prototype defines the coroutine destroy function. It + * is sometimes implemented as a macro, so watch out. It also serves no + * purpose unless you want to use the CORO_PTHREAD backend, where it is + * used to clean up the thread. You are responsible for freeing the stack + * and the context itself. + * + * This function is thread-safe and reentrant. + */ +#if 0 +void coro_destroy (coro_context *ctx); +#endif + +/*****************************************************************************/ +/* optional stack management */ +/*****************************************************************************/ +/* + * You can disable all of the stack management functions by + * defining CORO_STACKALLOC to 0. Otherwise, they are enabled by default. + * + * If stack management is enabled, you can influence the implementation via these + * symbols: + * + * -DCORO_USE_VALGRIND + * + * If defined, then libcoro will include valgrind/valgrind.h and register + * and unregister stacks with valgrind. + * + * -DCORO_GUARDPAGES=n + * + * libcoro will try to use the specified number of guard pages to protect against + * stack overflow. If n is 0, then the feature will be disabled. If it isn't + * defined, then libcoro will choose a suitable default. If guardpages are not + * supported on the platform, then the feature will be silently disabled. + */ +#ifndef CORO_STACKALLOC +# define CORO_STACKALLOC 1 +#endif + +#if CORO_STACKALLOC + +/* + * The only allowed operations on these struct members is to read the + * "sptr" and "ssze" members to pass it to coro_create, to read the "sptr" + * member to see if it is false, in which case the stack isn't allocated, + * and to set the "sptr" member to 0, to indicate to coro_stack_free to + * not actually do anything. + */ + +struct coro_stack +{ + void *sptr; + size_t ssze; +#if CORO_USE_VALGRIND + int valgrind_id; +#endif +}; + +/* + * Try to allocate a stack of at least the given size and return true if + * successful, or false otherwise. + * + * The size is *NOT* specified in bytes, but in units of sizeof (void *), + * i.e. the stack is typically 4(8) times larger on 32 bit(64 bit) platforms + * then the size passed in. + * + * If size is 0, then a "suitable" stack size is chosen (usually 1-2MB). + */ +int coro_stack_alloc (struct coro_stack *stack, unsigned int size); + +/* + * Free the stack allocated by coro_stack_alloc again. It is safe to + * call this function on the coro_stack structure even if coro_stack_alloc + * failed. + */ +void coro_stack_free (struct coro_stack *stack); + +#endif + +/* + * That was it. No other user-serviceable parts below here. + */ + +/*****************************************************************************/ + +#if !defined CORO_LOSER && !defined CORO_UCONTEXT \ + && !defined CORO_SJLJ && !defined CORO_LINUX \ + && !defined CORO_IRIX && !defined CORO_ASM \ + && !defined CORO_PTHREAD && !defined CORO_FIBER +# if defined WINDOWS && (defined __i386__ || (__x86_64__ || defined _M_IX86 || defined _M_AMD64)) +# define CORO_ASM 1 +# elif defined WINDOWS || defined _WIN32 +# define CORO_LOSER 1 /* you don't win with windoze */ +# elif __linux && (__i386__ || (__x86_64__ && !__ILP32__) || (__arm__ && __ARCH_ARCH == 7)) +# define CORO_ASM 1 +# elif defined HAVE_UCONTEXT_H +# define CORO_UCONTEXT 1 +# elif defined HAVE_SETJMP_H && defined HAVE_SIGALTSTACK +# define CORO_SJLJ 1 +# else +error unknown or unsupported architecture +# endif +#endif + +/*****************************************************************************/ + +#if CORO_UCONTEXT + +# include + +struct coro_context +{ + ucontext_t uc; +}; + +# define coro_transfer(p,n) swapcontext (&((p)->uc), &((n)->uc)) +# define coro_destroy(ctx) (void *)(ctx) + +#elif CORO_SJLJ || CORO_LOSER || CORO_LINUX || CORO_IRIX + +# if defined(CORO_LINUX) && !defined(_GNU_SOURCE) +# define _GNU_SOURCE /* for glibc */ +# endif + +# if !CORO_LOSER +# include +# endif + +/* solaris is hopelessly borked, it expands _XOPEN_UNIX to nothing */ +# if __sun +# undef _XOPEN_UNIX +# define _XOPEN_UNIX 1 +# endif + +# include + +# if _XOPEN_UNIX > 0 || defined (_setjmp) +# define coro_jmp_buf jmp_buf +# define coro_setjmp(env) _setjmp (env) +# define coro_longjmp(env) _longjmp ((env), 1) +# elif CORO_LOSER +# define coro_jmp_buf jmp_buf +# define coro_setjmp(env) setjmp (env) +# define coro_longjmp(env) longjmp ((env), 1) +# else +# define coro_jmp_buf sigjmp_buf +# define coro_setjmp(env) sigsetjmp (env, 0) +# define coro_longjmp(env) siglongjmp ((env), 1) +# endif + +struct coro_context +{ + coro_jmp_buf env; +}; + +# define coro_transfer(p,n) do { if (!coro_setjmp ((p)->env)) coro_longjmp ((n)->env); } while (0) +# define coro_destroy(ctx) (void *)(ctx) + +#elif CORO_ASM + +struct coro_context +{ + void **sp; /* must be at offset 0 */ +}; + +#if __i386__ || __x86_64__ +void __attribute__ ((__noinline__, __regparm__(2))) +#else +void __attribute__ ((__noinline__)) +#endif +coro_transfer (coro_context *prev, coro_context *next); + +# define coro_destroy(ctx) (void *)(ctx) + +#elif CORO_PTHREAD + +# include + +extern pthread_mutex_t coro_mutex; + +struct coro_context +{ + pthread_cond_t cv; + pthread_t id; +}; + +void coro_transfer (coro_context *prev, coro_context *next); +void coro_destroy (coro_context *ctx); + +#elif CORO_FIBER + +struct coro_context +{ + void *fiber; + /* only used for initialisation */ + coro_func coro; + void *arg; +}; + +void coro_transfer (coro_context *prev, coro_context *next); +void coro_destroy (coro_context *ctx); + +#endif + +#if __cplusplus +} +#endif + +#endif + diff --git a/testbed/nanogui/ext/eigen/CMakeLists.txt b/testbed/nanogui/ext/eigen/CMakeLists.txt index 76a11b9d..fe4227cb 100644 --- a/testbed/nanogui/ext/eigen/CMakeLists.txt +++ b/testbed/nanogui/ext/eigen/CMakeLists.txt @@ -1,6 +1,6 @@ -project(Eigen) +project(Eigen3) -cmake_minimum_required(VERSION 2.8.2) +cmake_minimum_required(VERSION 2.8.5) # guard against in-source builds @@ -8,6 +8,11 @@ if(${CMAKE_SOURCE_DIR} STREQUAL ${CMAKE_BINARY_DIR}) message(FATAL_ERROR "In-source builds not allowed. Please make a new directory (called a build directory) and run CMake from there. You may need to remove CMakeCache.txt. ") endif() +# Alias Eigen_*_DIR to Eigen3_*_DIR: + +set(Eigen_SOURCE_DIR ${Eigen3_SOURCE_DIR}) +set(Eigen_BINARY_DIR ${Eigen3_BINARY_DIR}) + # guard against bad build-type strings if (NOT CMAKE_BUILD_TYPE) @@ -23,7 +28,7 @@ endif() ############################################################################# -# retrieve version infomation # +# retrieve version information # ############################################################################# # automatically parse the version number @@ -55,6 +60,7 @@ endif(EIGEN_HG_CHANGESET) include(CheckCXXCompilerFlag) +include(GNUInstallDirs) set(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake) @@ -92,9 +98,11 @@ else() endif() option(EIGEN_BUILD_BTL "Build benchmark suite" OFF) -if(NOT WIN32) + +# Disable pkgconfig only for native Windows builds +if(NOT WIN32 OR NOT CMAKE_HOST_SYSTEM_NAME MATCHES Windows) option(EIGEN_BUILD_PKGCONFIG "Build pkg-config .pc file for Eigen" ON) -endif(NOT WIN32) +endif() set(CMAKE_INCLUDE_CURRENT_DIR ON) @@ -108,7 +116,8 @@ endif() set(EIGEN_TEST_MAX_SIZE "320" CACHE STRING "Maximal matrix/vector size, default is 320") macro(ei_add_cxx_compiler_flag FLAG) - string(REGEX REPLACE "-" "" SFLAG ${FLAG}) + string(REGEX REPLACE "-" "" SFLAG1 ${FLAG}) + string(REGEX REPLACE "\\+" "p" SFLAG ${SFLAG1}) check_cxx_compiler_flag(${FLAG} COMPILER_SUPPORT_${SFLAG}) if(COMPILER_SUPPORT_${SFLAG}) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${FLAG}") @@ -117,18 +126,13 @@ endmacro(ei_add_cxx_compiler_flag) if(NOT MSVC) # We assume that other compilers are partly compatible with GNUCC - - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fexceptions") - set(CMAKE_CXX_FLAGS_DEBUG "-g3") - set(CMAKE_CXX_FLAGS_RELEASE "-g0 -O2") - - # clang outputs some warnings for unknwon flags that are not caught by check_cxx_compiler_flag + + # clang outputs some warnings for unknown flags that are not caught by check_cxx_compiler_flag # adding -Werror turns such warnings into errors check_cxx_compiler_flag("-Werror" COMPILER_SUPPORT_WERROR) if(COMPILER_SUPPORT_WERROR) set(CMAKE_REQUIRED_FLAGS "-Werror") endif() - ei_add_cxx_compiler_flag("-pedantic") ei_add_cxx_compiler_flag("-Wall") ei_add_cxx_compiler_flag("-Wextra") @@ -142,6 +146,18 @@ if(NOT MSVC) ei_add_cxx_compiler_flag("-Wpointer-arith") ei_add_cxx_compiler_flag("-Wwrite-strings") ei_add_cxx_compiler_flag("-Wformat-security") + ei_add_cxx_compiler_flag("-Wshorten-64-to-32") + ei_add_cxx_compiler_flag("-Wlogical-op") + ei_add_cxx_compiler_flag("-Wenum-conversion") + ei_add_cxx_compiler_flag("-Wc++11-extensions") + ei_add_cxx_compiler_flag("-Wdouble-promotion") +# ei_add_cxx_compiler_flag("-Wconversion") + + # -Wshadow is insanely too strict with gcc, hopefully it will become usable with gcc 6 + # if(NOT CMAKE_COMPILER_IS_GNUCXX OR (CMAKE_CXX_COMPILER_VERSION VERSION_GREATER "5.0.0")) + if(NOT CMAKE_COMPILER_IS_GNUCXX) + ei_add_cxx_compiler_flag("-Wshadow") + endif() ei_add_cxx_compiler_flag("-Wno-psabi") ei_add_cxx_compiler_flag("-Wno-variadic-macros") @@ -151,7 +167,8 @@ if(NOT MSVC) ei_add_cxx_compiler_flag("-fno-common") ei_add_cxx_compiler_flag("-fstrict-aliasing") ei_add_cxx_compiler_flag("-wd981") # disable ICC's "operands are evaluated in unspecified order" remark - ei_add_cxx_compiler_flag("-wd2304") # disbale ICC's "warning #2304: non-explicit constructor with single argument may cause implicit type conversion" produced by -Wnon-virtual-dtor + ei_add_cxx_compiler_flag("-wd2304") # disable ICC's "warning #2304: non-explicit constructor with single argument may cause implicit type conversion" produced by -Wnon-virtual-dtor + # The -ansi flag must be added last, otherwise it is also used as a linker flag by check_cxx_compiler_flag making it fails # Moreover we should not set both -strict-ansi and -ansi @@ -163,6 +180,11 @@ if(NOT MSVC) else() ei_add_cxx_compiler_flag("-ansi") endif() + + if(ANDROID_NDK) + ei_add_cxx_compiler_flag("-pie") + ei_add_cxx_compiler_flag("-fPIE") + endif() set(CMAKE_REQUIRED_FLAGS "") @@ -196,18 +218,65 @@ if(NOT MSVC) message(STATUS "Enabling SSE4.2 in tests/examples") endif() + option(EIGEN_TEST_AVX "Enable/Disable AVX in tests/examples" OFF) + if(EIGEN_TEST_AVX) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mavx") + message(STATUS "Enabling AVX in tests/examples") + endif() + + option(EIGEN_TEST_FMA "Enable/Disable FMA in tests/examples" OFF) + if(EIGEN_TEST_FMA AND NOT EIGEN_TEST_NEON) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mfma") + message(STATUS "Enabling FMA in tests/examples") + endif() + + option(EIGEN_TEST_AVX512 "Enable/Disable AVX512 in tests/examples" OFF) + if(EIGEN_TEST_AVX512) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mavx512f -fabi-version=6 -DEIGEN_ENABLE_AVX512") + message(STATUS "Enabling AVX512 in tests/examples") + endif() + + option(EIGEN_TEST_F16C "Enable/Disable F16C in tests/examples" OFF) + if(EIGEN_TEST_F16C) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mf16c") + message(STATUS "Enabling F16C in tests/examples") + endif() + option(EIGEN_TEST_ALTIVEC "Enable/Disable AltiVec in tests/examples" OFF) if(EIGEN_TEST_ALTIVEC) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -maltivec -mabi=altivec") message(STATUS "Enabling AltiVec in tests/examples") endif() + option(EIGEN_TEST_VSX "Enable/Disable VSX in tests/examples" OFF) + if(EIGEN_TEST_VSX) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -m64 -mvsx") + message(STATUS "Enabling VSX in tests/examples") + endif() + option(EIGEN_TEST_NEON "Enable/Disable Neon in tests/examples" OFF) if(EIGEN_TEST_NEON) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mfpu=neon -mcpu=cortex-a8") + if(EIGEN_TEST_FMA) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mfpu=neon-vfpv4") + else() + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mfpu=neon") + endif() + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mfloat-abi=hard") message(STATUS "Enabling NEON in tests/examples") endif() + option(EIGEN_TEST_NEON64 "Enable/Disable Neon in tests/examples" OFF) + if(EIGEN_TEST_NEON64) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") + message(STATUS "Enabling NEON in tests/examples") + endif() + + option(EIGEN_TEST_ZVECTOR "Enable/Disable S390X(zEC13) ZVECTOR in tests/examples" OFF) + if(EIGEN_TEST_ZVECTOR) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -march=z13 -mzvector") + message(STATUS "Enabling S390X(zEC13) ZVECTOR in tests/examples") + endif() + check_cxx_compiler_flag("-fopenmp" COMPILER_SUPPORT_OPENMP) if(COMPILER_SUPPORT_OPENMP) option(EIGEN_TEST_OPENMP "Enable/Disable OpenMP in tests/examples" OFF) @@ -284,28 +353,41 @@ if(EIGEN_TEST_NO_EXPLICIT_ALIGNMENT) message(STATUS "Disabling alignment in tests/examples") endif() -option(EIGEN_TEST_C++0x "Enables all C++0x features." OFF) +option(EIGEN_TEST_NO_EXCEPTIONS "Disables C++ exceptions" OFF) +if(EIGEN_TEST_NO_EXCEPTIONS) + ei_add_cxx_compiler_flag("-fno-exceptions") + message(STATUS "Disabling exceptions in tests/examples") +endif() + +option(EIGEN_TEST_CXX11 "Enable testing with C++11 and C++11 features (e.g. Tensor module)." OFF) + +set(EIGEN_CUDA_COMPUTE_ARCH 30 CACHE STRING "The CUDA compute architecture level to target when compiling CUDA code") include_directories(${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_BINARY_DIR}) -# the user modifiable install path for header files -set(EIGEN_INCLUDE_INSTALL_DIR ${EIGEN_INCLUDE_INSTALL_DIR} CACHE PATH "The directory where we install the header files (optional)") - -# set the internal install path for header files which depends on wether the user modifiable -# EIGEN_INCLUDE_INSTALL_DIR has been set by the user or not. +# Backward compatibility support for EIGEN_INCLUDE_INSTALL_DIR if(EIGEN_INCLUDE_INSTALL_DIR) - set(INCLUDE_INSTALL_DIR - ${EIGEN_INCLUDE_INSTALL_DIR} - CACHE INTERNAL - "The directory where we install the header files (internal)" - ) + message(WARNING "EIGEN_INCLUDE_INSTALL_DIR is deprecated. Use INCLUDE_INSTALL_DIR instead.") +endif() + +if(EIGEN_INCLUDE_INSTALL_DIR AND NOT INCLUDE_INSTALL_DIR) + set(INCLUDE_INSTALL_DIR ${EIGEN_INCLUDE_INSTALL_DIR} + CACHE PATH "The directory relative to CMAKE_PREFIX_PATH where Eigen header files are installed") else() set(INCLUDE_INSTALL_DIR - "${CMAKE_INSTALL_PREFIX}/include/eigen3" - CACHE INTERNAL - "The directory where we install the header files (internal)" - ) + "${CMAKE_INSTALL_INCLUDEDIR}/eigen3" + CACHE PATH "The directory relative to CMAKE_PREFIX_PATH where Eigen header files are installed" + ) endif() +set(CMAKEPACKAGE_INSTALL_DIR + "${CMAKE_INSTALL_DATADIR}/eigen3/cmake" + CACHE PATH "The directory relative to CMAKE_PREFIX_PATH where Eigen3Config.cmake is installed" + ) +set(PKGCONFIG_INSTALL_DIR + "${CMAKE_INSTALL_DATADIR}/pkgconfig" + CACHE PATH "The directory relative to CMAKE_PREFIX_PATH where eigen3.pc is installed" + ) + # similar to set_target_properties but append the property instead of overwriting it macro(ei_add_target_property target prop value) @@ -324,38 +406,25 @@ install(FILES ) if(EIGEN_BUILD_PKGCONFIG) - SET(path_separator ":") - STRING(REPLACE ${path_separator} ";" pkg_config_libdir_search "$ENV{PKG_CONFIG_LIBDIR}") - message(STATUS "searching for 'pkgconfig' directory in PKG_CONFIG_LIBDIR ( $ENV{PKG_CONFIG_LIBDIR} ), ${CMAKE_INSTALL_PREFIX}/share, and ${CMAKE_INSTALL_PREFIX}/lib") - FIND_PATH(pkg_config_libdir pkgconfig ${pkg_config_libdir_search} ${CMAKE_INSTALL_PREFIX}/share ${CMAKE_INSTALL_PREFIX}/lib ${pkg_config_libdir_search}) - if(pkg_config_libdir) - SET(pkg_config_install_dir ${pkg_config_libdir}) - message(STATUS "found ${pkg_config_libdir}/pkgconfig" ) - else(pkg_config_libdir) - SET(pkg_config_install_dir ${CMAKE_INSTALL_PREFIX}/share) - message(STATUS "pkgconfig not found; installing in ${pkg_config_install_dir}" ) - endif(pkg_config_libdir) - - configure_file(eigen3.pc.in eigen3.pc) + configure_file(eigen3.pc.in eigen3.pc @ONLY) install(FILES ${CMAKE_CURRENT_BINARY_DIR}/eigen3.pc - DESTINATION ${pkg_config_install_dir}/pkgconfig + DESTINATION ${PKGCONFIG_INSTALL_DIR} ) -endif(EIGEN_BUILD_PKGCONFIG) +endif() add_subdirectory(Eigen) add_subdirectory(doc EXCLUDE_FROM_ALL) -include(EigenConfigureTesting) +option(BUILD_TESTING "Enable creation of Eigen tests." ON) +if(BUILD_TESTING) + include(EigenConfigureTesting) -# fixme, not sure this line is still needed: -enable_testing() # must be called from the root CMakeLists, see man page - - -if(EIGEN_LEAVE_TEST_IN_ALL_TARGET) - add_subdirectory(test) # can't do EXCLUDE_FROM_ALL here, breaks CTest -else() - add_subdirectory(test EXCLUDE_FROM_ALL) + if(EIGEN_LEAVE_TEST_IN_ALL_TARGET) + add_subdirectory(test) # can't do EXCLUDE_FROM_ALL here, breaks CTest + else() + add_subdirectory(test EXCLUDE_FROM_ALL) + endif() endif() if(EIGEN_LEAVE_TEST_IN_ALL_TARGET) @@ -366,6 +435,13 @@ else() add_subdirectory(lapack EXCLUDE_FROM_ALL) endif() +# add SYCL +option(EIGEN_TEST_SYCL "Add Sycl support." OFF) +if(EIGEN_TEST_SYCL) + set (CMAKE_MODULE_PATH "${CMAKE_ROOT}/Modules" "cmake/Modules/" "${CMAKE_MODULE_PATH}") + include(FindComputeCpp) +endif() + add_subdirectory(unsupported) add_subdirectory(demos EXCLUDE_FROM_ALL) @@ -384,7 +460,9 @@ endif(NOT WIN32) configure_file(scripts/cdashtesting.cmake.in cdashtesting.cmake @ONLY) -ei_testing_print_summary() +if(BUILD_TESTING) + ei_testing_print_summary() +endif() message(STATUS "") message(STATUS "Configured Eigen ${EIGEN_VERSION_NUMBER}") @@ -401,16 +479,20 @@ if(cmake_generator_tolower MATCHES "makefile") message(STATUS "--------------+--------------------------------------------------------------") message(STATUS "Command | Description") message(STATUS "--------------+--------------------------------------------------------------") - message(STATUS "make install | Install to ${CMAKE_INSTALL_PREFIX}. To change that:") - message(STATUS " | cmake . -DCMAKE_INSTALL_PREFIX=yourpath") - message(STATUS " | Eigen headers will then be installed to:") - message(STATUS " | ${INCLUDE_INSTALL_DIR}") - message(STATUS " | To install Eigen headers to a separate location, do:") - message(STATUS " | cmake . -DEIGEN_INCLUDE_INSTALL_DIR=yourpath") + message(STATUS "make install | Install Eigen. Headers will be installed to:") + message(STATUS " | /") + message(STATUS " | Using the following values:") + message(STATUS " | CMAKE_INSTALL_PREFIX: ${CMAKE_INSTALL_PREFIX}") + message(STATUS " | INCLUDE_INSTALL_DIR: ${INCLUDE_INSTALL_DIR}") + message(STATUS " | Change the install location of Eigen headers using:") + message(STATUS " | cmake . -DCMAKE_INSTALL_PREFIX=yourprefix") + message(STATUS " | Or:") + message(STATUS " | cmake . -DINCLUDE_INSTALL_DIR=yourdir") message(STATUS "make doc | Generate the API documentation, requires Doxygen & LaTeX") message(STATUS "make check | Build and run the unit-tests. Read this page:") message(STATUS " | http://eigen.tuxfamily.org/index.php?title=Tests") message(STATUS "make blas | Build BLAS library (not the same thing as Eigen)") + message(STATUS "make uninstall| Removes files installed by make install") message(STATUS "--------------+--------------------------------------------------------------") else() message(STATUS "To build/run the unit tests, read this page:") @@ -418,3 +500,98 @@ else() endif() message(STATUS "") + + +set ( EIGEN_VERSION_STRING ${EIGEN_VERSION_NUMBER} ) +set ( EIGEN_VERSION_MAJOR ${EIGEN_WORLD_VERSION} ) +set ( EIGEN_VERSION_MINOR ${EIGEN_MAJOR_VERSION} ) +set ( EIGEN_VERSION_PATCH ${EIGEN_MINOR_VERSION} ) +set ( EIGEN_DEFINITIONS "") +set ( EIGEN_INCLUDE_DIR "${CMAKE_INSTALL_PREFIX}/${INCLUDE_INSTALL_DIR}" ) +set ( EIGEN_ROOT_DIR ${CMAKE_INSTALL_PREFIX} ) + +# Interface libraries require at least CMake 3.0 +if (NOT CMAKE_VERSION VERSION_LESS 3.0) + include (CMakePackageConfigHelpers) + + # Imported target support + add_library (eigen INTERFACE) + + target_compile_definitions (eigen INTERFACE ${EIGEN_DEFINITIONS}) + target_include_directories (eigen INTERFACE + $ + $ + ) + + # Export as title case Eigen + set_target_properties (eigen PROPERTIES EXPORT_NAME Eigen) + + install (TARGETS eigen EXPORT Eigen3Targets) + + configure_package_config_file ( + ${CMAKE_CURRENT_SOURCE_DIR}/cmake/Eigen3Config.cmake.in + ${CMAKE_CURRENT_BINARY_DIR}/Eigen3Config.cmake + PATH_VARS EIGEN_INCLUDE_DIR EIGEN_ROOT_DIR + INSTALL_DESTINATION ${CMAKEPACKAGE_INSTALL_DIR} + NO_CHECK_REQUIRED_COMPONENTS_MACRO # Eigen does not provide components + ) + # Remove CMAKE_SIZEOF_VOID_P from Eigen3ConfigVersion.cmake since Eigen does + # not depend on architecture specific settings or libraries. More + # specifically, an Eigen3Config.cmake generated from a 64 bit target can be + # used for 32 bit targets as well (and vice versa). + set (_Eigen3_CMAKE_SIZEOF_VOID_P ${CMAKE_SIZEOF_VOID_P}) + unset (CMAKE_SIZEOF_VOID_P) + write_basic_package_version_file (Eigen3ConfigVersion.cmake + VERSION ${EIGEN_VERSION_NUMBER} + COMPATIBILITY SameMajorVersion) + set (CMAKE_SIZEOF_VOID_P ${_Eigen3_CMAKE_SIZEOF_VOID_P}) + + # The Eigen target will be located in the Eigen3 namespace. Other CMake + # targets can refer to it using Eigen3::Eigen. + export (TARGETS eigen NAMESPACE Eigen3:: FILE Eigen3Targets.cmake) + # Export Eigen3 package to CMake registry such that it can be easily found by + # CMake even if it has not been installed to a standard directory. + export (PACKAGE Eigen3) + + install (EXPORT Eigen3Targets NAMESPACE Eigen3:: DESTINATION ${CMAKEPACKAGE_INSTALL_DIR}) + +else (NOT CMAKE_VERSION VERSION_LESS 3.0) + # Fallback to legacy Eigen3Config.cmake without the imported target + + # If CMakePackageConfigHelpers module is available (CMake >= 2.8.8) + # create a relocatable Config file, otherwise leave the hardcoded paths + include(CMakePackageConfigHelpers OPTIONAL RESULT_VARIABLE CPCH_PATH) + + if(CPCH_PATH) + configure_package_config_file ( + ${CMAKE_CURRENT_SOURCE_DIR}/cmake/Eigen3ConfigLegacy.cmake.in + ${CMAKE_CURRENT_BINARY_DIR}/Eigen3Config.cmake + PATH_VARS EIGEN_INCLUDE_DIR EIGEN_ROOT_DIR + INSTALL_DESTINATION ${CMAKEPACKAGE_INSTALL_DIR} + NO_CHECK_REQUIRED_COMPONENTS_MACRO # Eigen does not provide components + ) + else() + # The PACKAGE_* variables are defined by the configure_package_config_file + # but without it we define them manually to the hardcoded paths + set(PACKAGE_INIT "") + set(PACKAGE_EIGEN_INCLUDE_DIR ${EIGEN_INCLUDE_DIR}) + set(PACKAGE_EIGEN_ROOT_DIR ${EIGEN_ROOT_DIR}) + configure_file ( ${CMAKE_CURRENT_SOURCE_DIR}/cmake/Eigen3ConfigLegacy.cmake.in + ${CMAKE_CURRENT_BINARY_DIR}/Eigen3Config.cmake + @ONLY ESCAPE_QUOTES ) + endif() + + write_basic_package_version_file( Eigen3ConfigVersion.cmake + VERSION ${EIGEN_VERSION_NUMBER} + COMPATIBILITY SameMajorVersion ) + +endif (NOT CMAKE_VERSION VERSION_LESS 3.0) + +install ( FILES ${CMAKE_CURRENT_SOURCE_DIR}/cmake/UseEigen3.cmake + ${CMAKE_CURRENT_BINARY_DIR}/Eigen3Config.cmake + ${CMAKE_CURRENT_BINARY_DIR}/Eigen3ConfigVersion.cmake + DESTINATION ${CMAKEPACKAGE_INSTALL_DIR} ) + +# Add uninstall target +add_custom_target ( uninstall + COMMAND ${CMAKE_COMMAND} -P ${CMAKE_CURRENT_SOURCE_DIR}/cmake/EigenUninstall.cmake) diff --git a/testbed/nanogui/ext/eigen/COPYING.MINPACK b/testbed/nanogui/ext/eigen/COPYING.MINPACK index ae7984da..11d8a9a6 100644 --- a/testbed/nanogui/ext/eigen/COPYING.MINPACK +++ b/testbed/nanogui/ext/eigen/COPYING.MINPACK @@ -1,52 +1,52 @@ -Minpack Copyright Notice (1999) University of Chicago. All rights reserved - -Redistribution and use in source and binary forms, with or -without modification, are permitted provided that the -following conditions are met: - -1. Redistributions of source code must retain the above -copyright notice, this list of conditions and the following -disclaimer. - -2. Redistributions in binary form must reproduce the above -copyright notice, this list of conditions and the following -disclaimer in the documentation and/or other materials -provided with the distribution. - -3. The end-user documentation included with the -redistribution, if any, must include the following -acknowledgment: - - "This product includes software developed by the - University of Chicago, as Operator of Argonne National - Laboratory. - -Alternately, this acknowledgment may appear in the software -itself, if and wherever such third-party acknowledgments -normally appear. - -4. WARRANTY DISCLAIMER. THE SOFTWARE IS SUPPLIED "AS IS" -WITHOUT WARRANTY OF ANY KIND. THE COPYRIGHT HOLDER, THE -UNITED STATES, THE UNITED STATES DEPARTMENT OF ENERGY, AND -THEIR EMPLOYEES: (1) DISCLAIM ANY WARRANTIES, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO ANY IMPLIED WARRANTIES -OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, TITLE -OR NON-INFRINGEMENT, (2) DO NOT ASSUME ANY LEGAL LIABILITY -OR RESPONSIBILITY FOR THE ACCURACY, COMPLETENESS, OR -USEFULNESS OF THE SOFTWARE, (3) DO NOT REPRESENT THAT USE OF -THE SOFTWARE WOULD NOT INFRINGE PRIVATELY OWNED RIGHTS, (4) -DO NOT WARRANT THAT THE SOFTWARE WILL FUNCTION -UNINTERRUPTED, THAT IT IS ERROR-FREE OR THAT ANY ERRORS WILL -BE CORRECTED. - -5. LIMITATION OF LIABILITY. IN NO EVENT WILL THE COPYRIGHT -HOLDER, THE UNITED STATES, THE UNITED STATES DEPARTMENT OF -ENERGY, OR THEIR EMPLOYEES: BE LIABLE FOR ANY INDIRECT, -INCIDENTAL, CONSEQUENTIAL, SPECIAL OR PUNITIVE DAMAGES OF -ANY KIND OR NATURE, INCLUDING BUT NOT LIMITED TO LOSS OF -PROFITS OR LOSS OF DATA, FOR ANY REASON WHATSOEVER, WHETHER -SUCH LIABILITY IS ASSERTED ON THE BASIS OF CONTRACT, TORT -(INCLUDING NEGLIGENCE OR STRICT LIABILITY), OR OTHERWISE, -EVEN IF ANY OF SAID PARTIES HAS BEEN WARNED OF THE -POSSIBILITY OF SUCH LOSS OR DAMAGES. - +Minpack Copyright Notice (1999) University of Chicago. All rights reserved + +Redistribution and use in source and binary forms, with or +without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above +copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above +copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials +provided with the distribution. + +3. The end-user documentation included with the +redistribution, if any, must include the following +acknowledgment: + + "This product includes software developed by the + University of Chicago, as Operator of Argonne National + Laboratory. + +Alternately, this acknowledgment may appear in the software +itself, if and wherever such third-party acknowledgments +normally appear. + +4. WARRANTY DISCLAIMER. THE SOFTWARE IS SUPPLIED "AS IS" +WITHOUT WARRANTY OF ANY KIND. THE COPYRIGHT HOLDER, THE +UNITED STATES, THE UNITED STATES DEPARTMENT OF ENERGY, AND +THEIR EMPLOYEES: (1) DISCLAIM ANY WARRANTIES, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO ANY IMPLIED WARRANTIES +OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, TITLE +OR NON-INFRINGEMENT, (2) DO NOT ASSUME ANY LEGAL LIABILITY +OR RESPONSIBILITY FOR THE ACCURACY, COMPLETENESS, OR +USEFULNESS OF THE SOFTWARE, (3) DO NOT REPRESENT THAT USE OF +THE SOFTWARE WOULD NOT INFRINGE PRIVATELY OWNED RIGHTS, (4) +DO NOT WARRANT THAT THE SOFTWARE WILL FUNCTION +UNINTERRUPTED, THAT IT IS ERROR-FREE OR THAT ANY ERRORS WILL +BE CORRECTED. + +5. LIMITATION OF LIABILITY. IN NO EVENT WILL THE COPYRIGHT +HOLDER, THE UNITED STATES, THE UNITED STATES DEPARTMENT OF +ENERGY, OR THEIR EMPLOYEES: BE LIABLE FOR ANY INDIRECT, +INCIDENTAL, CONSEQUENTIAL, SPECIAL OR PUNITIVE DAMAGES OF +ANY KIND OR NATURE, INCLUDING BUT NOT LIMITED TO LOSS OF +PROFITS OR LOSS OF DATA, FOR ANY REASON WHATSOEVER, WHETHER +SUCH LIABILITY IS ASSERTED ON THE BASIS OF CONTRACT, TORT +(INCLUDING NEGLIGENCE OR STRICT LIABILITY), OR OTHERWISE, +EVEN IF ANY OF SAID PARTIES HAS BEEN WARNED OF THE +POSSIBILITY OF SUCH LOSS OR DAMAGES. + diff --git a/testbed/nanogui/ext/eigen/CTestConfig.cmake b/testbed/nanogui/ext/eigen/CTestConfig.cmake index 0557c491..4c002782 100644 --- a/testbed/nanogui/ext/eigen/CTestConfig.cmake +++ b/testbed/nanogui/ext/eigen/CTestConfig.cmake @@ -4,10 +4,14 @@ ## # The following are required to uses Dart and the Cdash dashboard ## ENABLE_TESTING() ## INCLUDE(CTest) -set(CTEST_PROJECT_NAME "Eigen3.2") +set(CTEST_PROJECT_NAME "Eigen") set(CTEST_NIGHTLY_START_TIME "00:00:00 UTC") set(CTEST_DROP_METHOD "http") set(CTEST_DROP_SITE "manao.inria.fr") -set(CTEST_DROP_LOCATION "/CDash/submit.php?project=Eigen3.2") +set(CTEST_DROP_LOCATION "/CDash/submit.php?project=Eigen") set(CTEST_DROP_SITE_CDASH TRUE) +set(CTEST_PROJECT_SUBPROJECTS +Official +Unsupported +) diff --git a/testbed/nanogui/ext/eigen/Eigen/Array b/testbed/nanogui/ext/eigen/Eigen/Array deleted file mode 100644 index 3d004fb6..00000000 --- a/testbed/nanogui/ext/eigen/Eigen/Array +++ /dev/null @@ -1,11 +0,0 @@ -#ifndef EIGEN_ARRAY_MODULE_H -#define EIGEN_ARRAY_MODULE_H - -// include Core first to handle Eigen2 support macros -#include "Core" - -#ifndef EIGEN2_SUPPORT - #error The Eigen/Array header does no longer exist in Eigen3. All that functionality has moved to Eigen/Core. -#endif - -#endif // EIGEN_ARRAY_MODULE_H diff --git a/testbed/nanogui/ext/eigen/Eigen/CMakeLists.txt b/testbed/nanogui/ext/eigen/Eigen/CMakeLists.txt index a92dd6f6..9eb502b7 100644 --- a/testbed/nanogui/ext/eigen/Eigen/CMakeLists.txt +++ b/testbed/nanogui/ext/eigen/Eigen/CMakeLists.txt @@ -16,4 +16,4 @@ install(FILES DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen COMPONENT Devel ) -add_subdirectory(src) +install(DIRECTORY src DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen COMPONENT Devel FILES_MATCHING PATTERN "*.h") diff --git a/testbed/nanogui/ext/eigen/Eigen/Cholesky b/testbed/nanogui/ext/eigen/Eigen/Cholesky index f727f5d8..369d1f5e 100644 --- a/testbed/nanogui/ext/eigen/Eigen/Cholesky +++ b/testbed/nanogui/ext/eigen/Eigen/Cholesky @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_CHOLESKY_MODULE_H #define EIGEN_CHOLESKY_MODULE_H @@ -10,20 +17,22 @@ * * * This module provides two variants of the Cholesky decomposition for selfadjoint (hermitian) matrices. - * Those decompositions are accessible via the following MatrixBase methods: - * - MatrixBase::llt(), + * Those decompositions are also accessible via the following methods: + * - MatrixBase::llt() * - MatrixBase::ldlt() + * - SelfAdjointView::llt() + * - SelfAdjointView::ldlt() * * \code * #include * \endcode */ -#include "src/misc/Solve.h" #include "src/Cholesky/LLT.h" #include "src/Cholesky/LDLT.h" #ifdef EIGEN_USE_LAPACKE -#include "src/Cholesky/LLT_MKL.h" +#include "src/misc/lapacke.h" +#include "src/Cholesky/LLT_LAPACKE.h" #endif #include "src/Core/util/ReenableStupidWarnings.h" diff --git a/testbed/nanogui/ext/eigen/Eigen/CholmodSupport b/testbed/nanogui/ext/eigen/Eigen/CholmodSupport index 745b884e..bed8924d 100644 --- a/testbed/nanogui/ext/eigen/Eigen/CholmodSupport +++ b/testbed/nanogui/ext/eigen/Eigen/CholmodSupport @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_CHOLMODSUPPORT_MODULE_H #define EIGEN_CHOLMODSUPPORT_MODULE_H @@ -12,7 +19,7 @@ extern "C" { /** \ingroup Support_modules * \defgroup CholmodSupport_Module CholmodSupport module * - * This module provides an interface to the Cholmod library which is part of the suitesparse package. + * This module provides an interface to the Cholmod library which is part of the suitesparse package. * It provides the two following main factorization classes: * - class CholmodSupernodalLLT: a supernodal LLT Cholesky factorization. * - class CholmodDecomposiiton: a general L(D)LT Cholesky factorization with automatic or explicit runtime selection of the underlying factorization method (supernodal or simplicial). @@ -33,12 +40,8 @@ extern "C" { * */ -#include "src/misc/Solve.h" -#include "src/misc/SparseSolve.h" - #include "src/CholmodSupport/CholmodSupport.h" - #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_CHOLMODSUPPORT_MODULE_H diff --git a/testbed/nanogui/ext/eigen/Eigen/Core b/testbed/nanogui/ext/eigen/Eigen/Core index c87f99df..d1883561 100644 --- a/testbed/nanogui/ext/eigen/Eigen/Core +++ b/testbed/nanogui/ext/eigen/Eigen/Core @@ -14,6 +14,56 @@ // first thing Eigen does: stop the compiler from committing suicide #include "src/Core/util/DisableStupidWarnings.h" +// Handle NVCC/CUDA/SYCL +#if defined(__CUDACC__) || defined(__SYCL_DEVICE_ONLY__) + // Do not try asserts on CUDA and SYCL! + #ifndef EIGEN_NO_DEBUG + #define EIGEN_NO_DEBUG + #endif + + #ifdef EIGEN_INTERNAL_DEBUGGING + #undef EIGEN_INTERNAL_DEBUGGING + #endif + + #ifdef EIGEN_EXCEPTIONS + #undef EIGEN_EXCEPTIONS + #endif + + // All functions callable from CUDA code must be qualified with __device__ + #ifdef __CUDACC__ + // Do not try to vectorize on CUDA and SYCL! + #ifndef EIGEN_DONT_VECTORIZE + #define EIGEN_DONT_VECTORIZE + #endif + + #define EIGEN_DEVICE_FUNC __host__ __device__ + // We need math_functions.hpp to ensure that that EIGEN_USING_STD_MATH macro + // works properly on the device side + #include + #else + #define EIGEN_DEVICE_FUNC + #endif +#else + #define EIGEN_DEVICE_FUNC +#endif + +// When compiling CUDA device code with NVCC, pull in math functions from the +// global namespace. In host mode, and when device doee with clang, use the +// std versions. +#if defined(__CUDA_ARCH__) && defined(__NVCC__) + #define EIGEN_USING_STD_MATH(FUNC) using ::FUNC; +#else + #define EIGEN_USING_STD_MATH(FUNC) using std::FUNC; +#endif + +#if (defined(_CPPUNWIND) || defined(__EXCEPTIONS)) && !defined(__CUDA_ARCH__) && !defined(EIGEN_EXCEPTIONS) && !defined(EIGEN_USE_SYCL) + #define EIGEN_EXCEPTIONS +#endif + +#ifdef EIGEN_EXCEPTIONS + #include +#endif + // then include this file where all our macros are defined. It's really important to do it first because // it's where we do all the alignment settings (platform detection and honoring the user's will if he // defined e.g. EIGEN_DONT_ALIGN) so it needs to be done before we do anything with vectorization. @@ -21,7 +71,7 @@ // Disable the ipa-cp-clone optimization flag with MinGW 6.x or newer (enabled by default with -O3) // See http://eigen.tuxfamily.org/bz/show_bug.cgi?id=556 for details. -#if defined(__MINGW32__) && EIGEN_GNUC_AT_LEAST(4,6) +#if EIGEN_COMP_MINGW && EIGEN_GNUC_AT_LEAST(4,6) #pragma GCC optimize ("-fno-ipa-cp-clone") #endif @@ -31,26 +81,26 @@ // and inclusion of their respective header files #include "src/Core/util/MKL_support.h" -// if alignment is disabled, then disable vectorization. Note: EIGEN_ALIGN is the proper check, it takes into -// account both the user's will (EIGEN_DONT_ALIGN) and our own platform checks -#if !EIGEN_ALIGN +// if alignment is disabled, then disable vectorization. Note: EIGEN_MAX_ALIGN_BYTES is the proper check, it takes into +// account both the user's will (EIGEN_MAX_ALIGN_BYTES,EIGEN_DONT_ALIGN) and our own platform checks +#if EIGEN_MAX_ALIGN_BYTES==0 #ifndef EIGEN_DONT_VECTORIZE #define EIGEN_DONT_VECTORIZE #endif #endif -#ifdef _MSC_VER +#if EIGEN_COMP_MSVC #include // for _aligned_malloc -- need it regardless of whether vectorization is enabled - #if (_MSC_VER >= 1500) // 2008 or later + #if (EIGEN_COMP_MSVC >= 1500) // 2008 or later // Remember that usage of defined() in a #define is undefined by the standard. // a user reported that in 64-bit mode, MSVC doesn't care to define _M_IX86_FP. - #if (defined(_M_IX86_FP) && (_M_IX86_FP >= 2)) || defined(_M_X64) + #if (defined(_M_IX86_FP) && (_M_IX86_FP >= 2)) || EIGEN_ARCH_x86_64 #define EIGEN_SSE2_ON_MSVC_2008_OR_LATER #endif #endif #else // Remember that usage of defined() in a #define is undefined by the standard - #if (defined __SSE2__) && ( (!defined __GNUC__) || (defined __INTEL_COMPILER) || EIGEN_GNUC_AT_LEAST(4,2) ) + #if (defined __SSE2__) && ( (!EIGEN_COMP_GNUC) || EIGEN_COMP_ICC || EIGEN_GNUC_AT_LEAST(4,2) ) #define EIGEN_SSE2_ON_NON_MSVC_BUT_NOT_OLD_GCC #endif #endif @@ -82,6 +132,37 @@ #ifdef __SSE4_2__ #define EIGEN_VECTORIZE_SSE4_2 #endif + #ifdef __AVX__ + #define EIGEN_VECTORIZE_AVX + #define EIGEN_VECTORIZE_SSE3 + #define EIGEN_VECTORIZE_SSSE3 + #define EIGEN_VECTORIZE_SSE4_1 + #define EIGEN_VECTORIZE_SSE4_2 + #endif + #ifdef __AVX2__ + #define EIGEN_VECTORIZE_AVX2 + #define EIGEN_VECTORIZE_AVX + #define EIGEN_VECTORIZE_SSE3 + #define EIGEN_VECTORIZE_SSSE3 + #define EIGEN_VECTORIZE_SSE4_1 + #define EIGEN_VECTORIZE_SSE4_2 + #endif + #ifdef __FMA__ + #define EIGEN_VECTORIZE_FMA + #endif + #if defined(__AVX512F__) + #define EIGEN_VECTORIZE_AVX512 + #define EIGEN_VECTORIZE_AVX2 + #define EIGEN_VECTORIZE_AVX + #define EIGEN_VECTORIZE_FMA + #define EIGEN_VECTORIZE_SSE3 + #define EIGEN_VECTORIZE_SSSE3 + #define EIGEN_VECTORIZE_SSE4_1 + #define EIGEN_VECTORIZE_SSE4_2 + #ifdef __AVX512DQ__ + #define EIGEN_VECTORIZE_AVX512DQ + #endif + #endif // include files @@ -95,9 +176,10 @@ extern "C" { // In theory we should only include immintrin.h and not the other *mmintrin.h header files directly. // Doing so triggers some issues with ICC. However old gcc versions seems to not have this file, thus: - #if defined(__INTEL_COMPILER) && __INTEL_COMPILER >= 1110 + #if EIGEN_COMP_ICC >= 1110 #include #else + #include #include #include #ifdef EIGEN_VECTORIZE_SSE3 @@ -112,8 +194,20 @@ #ifdef EIGEN_VECTORIZE_SSE4_2 #include #endif + #if defined(EIGEN_VECTORIZE_AVX) || defined(EIGEN_VECTORIZE_AVX512) + #include + #endif #endif } // end extern "C" + #elif defined __VSX__ + #define EIGEN_VECTORIZE + #define EIGEN_VECTORIZE_VSX + #include + // We need to #undef all these ugly tokens defined in + // => use __vector instead of vector + #undef bool + #undef vector + #undef pixel #elif defined __ALTIVEC__ #define EIGEN_VECTORIZE #define EIGEN_VECTORIZE_ALTIVEC @@ -123,13 +217,35 @@ #undef bool #undef vector #undef pixel - #elif defined __ARM_NEON__ + #elif (defined __ARM_NEON) || (defined __ARM_NEON__) #define EIGEN_VECTORIZE #define EIGEN_VECTORIZE_NEON #include + #elif (defined __s390x__ && defined __VEC__) + #define EIGEN_VECTORIZE + #define EIGEN_VECTORIZE_ZVECTOR + #include #endif #endif +#if defined(__F16C__) && !defined(EIGEN_COMP_CLANG) + // We can use the optimized fp16 to float and float to fp16 conversion routines + #define EIGEN_HAS_FP16_C +#endif + +#if defined __CUDACC__ + #define EIGEN_VECTORIZE_CUDA + #include + #if defined __CUDACC_VER__ && __CUDACC_VER__ >= 70500 + #define EIGEN_HAS_CUDA_FP16 + #endif +#endif + +#if defined EIGEN_HAS_CUDA_FP16 + #include + #include +#endif + #if (defined _OPENMP) && (!defined EIGEN_DONT_PARALLELIZE) #define EIGEN_HAS_OPENMP #endif @@ -139,7 +255,7 @@ #endif // MSVC for windows mobile does not have the errno.h file -#if !(defined(_MSC_VER) && defined(_WIN32_WCE)) && !defined(__ARMCC_VERSION) +#if !(EIGEN_COMP_MSVC && EIGEN_OS_WINCE) && !EIGEN_COMP_ARM #define EIGEN_HAS_ERRNO #endif @@ -159,29 +275,39 @@ // for min/max: #include +// for std::is_nothrow_move_assignable +#ifdef EIGEN_INCLUDE_TYPE_TRAITS +#include +#endif + // for outputting debug info #ifdef EIGEN_DEBUG_ASSIGN #include #endif // required for __cpuid, needs to be included after cmath -#if defined(_MSC_VER) && (defined(_M_IX86)||defined(_M_X64)) && (!defined(_WIN32_WCE)) +#if EIGEN_COMP_MSVC && EIGEN_ARCH_i386_OR_x86_64 && !EIGEN_OS_WINCE #include #endif -#if defined(_CPPUNWIND) || defined(__EXCEPTIONS) - #define EIGEN_EXCEPTIONS -#endif - -#ifdef EIGEN_EXCEPTIONS - #include +#if defined(__SYCL_DEVICE_ONLY__) + #undef min + #undef max + #undef isnan + #undef isinf + #undef isfinite + #include #endif /** \brief Namespace containing all symbols from the %Eigen library. */ namespace Eigen { inline static const char *SimdInstructionSetsInUse(void) { -#if defined(EIGEN_VECTORIZE_SSE4_2) +#if defined(EIGEN_VECTORIZE_AVX512) + return "AVX512, FMA, AVX2, AVX, SSE, SSE2, SSE3, SSSE3, SSE4.1, SSE4.2"; +#elif defined(EIGEN_VECTORIZE_AVX) + return "AVX SSE, SSE2, SSE3, SSSE3, SSE4.1, SSE4.2"; +#elif defined(EIGEN_VECTORIZE_SSE4_2) return "SSE, SSE2, SSE3, SSSE3, SSE4.1, SSE4.2"; #elif defined(EIGEN_VECTORIZE_SSE4_1) return "SSE, SSE2, SSE3, SSSE3, SSE4.1"; @@ -193,8 +319,12 @@ inline static const char *SimdInstructionSetsInUse(void) { return "SSE, SSE2"; #elif defined(EIGEN_VECTORIZE_ALTIVEC) return "AltiVec"; +#elif defined(EIGEN_VECTORIZE_VSX) + return "VSX"; #elif defined(EIGEN_VECTORIZE_NEON) return "ARM NEON"; +#elif defined(EIGEN_VECTORIZE_ZVECTOR) + return "S390X ZVECTOR"; #else return "None"; #endif @@ -202,42 +332,21 @@ inline static const char *SimdInstructionSetsInUse(void) { } // end namespace Eigen -#define STAGE10_FULL_EIGEN2_API 10 -#define STAGE20_RESOLVE_API_CONFLICTS 20 -#define STAGE30_FULL_EIGEN3_API 30 -#define STAGE40_FULL_EIGEN3_STRICTNESS 40 -#define STAGE99_NO_EIGEN2_SUPPORT 99 - -#if defined EIGEN2_SUPPORT_STAGE40_FULL_EIGEN3_STRICTNESS - #define EIGEN2_SUPPORT - #define EIGEN2_SUPPORT_STAGE STAGE40_FULL_EIGEN3_STRICTNESS -#elif defined EIGEN2_SUPPORT_STAGE30_FULL_EIGEN3_API - #define EIGEN2_SUPPORT - #define EIGEN2_SUPPORT_STAGE STAGE30_FULL_EIGEN3_API -#elif defined EIGEN2_SUPPORT_STAGE20_RESOLVE_API_CONFLICTS - #define EIGEN2_SUPPORT - #define EIGEN2_SUPPORT_STAGE STAGE20_RESOLVE_API_CONFLICTS -#elif defined EIGEN2_SUPPORT_STAGE10_FULL_EIGEN2_API - #define EIGEN2_SUPPORT - #define EIGEN2_SUPPORT_STAGE STAGE10_FULL_EIGEN2_API -#elif defined EIGEN2_SUPPORT - // default to stage 3, that's what it's always meant - #define EIGEN2_SUPPORT_STAGE30_FULL_EIGEN3_API - #define EIGEN2_SUPPORT_STAGE STAGE30_FULL_EIGEN3_API -#else - #define EIGEN2_SUPPORT_STAGE STAGE99_NO_EIGEN2_SUPPORT +#if defined EIGEN2_SUPPORT_STAGE40_FULL_EIGEN3_STRICTNESS || defined EIGEN2_SUPPORT_STAGE30_FULL_EIGEN3_API || defined EIGEN2_SUPPORT_STAGE20_RESOLVE_API_CONFLICTS || defined EIGEN2_SUPPORT_STAGE10_FULL_EIGEN2_API || defined EIGEN2_SUPPORT +// This will generate an error message: +#error Eigen2-support is only available up to version 3.2. Please go to "http://eigen.tuxfamily.org/index.php?title=Eigen2" for further information #endif -#ifdef EIGEN2_SUPPORT -#undef minor -#endif +namespace Eigen { // we use size_t frequently and we'll never remember to prepend it with std:: everytime just to // ensure QNX/QCC support using std::size_t; -// gcc 4.6.0 wants std:: for ptrdiff_t +// gcc 4.6.0 wants std:: for ptrdiff_t using std::ptrdiff_t; +} + /** \defgroup Core_Module Core module * This is the main module of Eigen providing dense matrix and vector support * (both fixed and dynamic size) with all the features corresponding to a BLAS library @@ -249,50 +358,108 @@ using std::ptrdiff_t; */ #include "src/Core/util/Constants.h" -#include "src/Core/util/ForwardDeclarations.h" #include "src/Core/util/Meta.h" +#include "src/Core/util/ForwardDeclarations.h" #include "src/Core/util/StaticAssert.h" #include "src/Core/util/XprHelper.h" #include "src/Core/util/Memory.h" +#include "src/Core/util/IntegralConstant.h" +#include "src/Core/util/SymbolicIndex.h" + #include "src/Core/NumTraits.h" #include "src/Core/MathFunctions.h" #include "src/Core/GenericPacketMath.h" +#include "src/Core/MathFunctionsImpl.h" -#if defined EIGEN_VECTORIZE_SSE +#if defined EIGEN_VECTORIZE_AVX512 + #include "src/Core/arch/SSE/PacketMath.h" + #include "src/Core/arch/AVX/PacketMath.h" + #include "src/Core/arch/AVX512/PacketMath.h" + #include "src/Core/arch/SSE/MathFunctions.h" + #include "src/Core/arch/AVX/MathFunctions.h" + #include "src/Core/arch/AVX512/MathFunctions.h" +#elif defined EIGEN_VECTORIZE_AVX + // Use AVX for floats and doubles, SSE for integers + #include "src/Core/arch/SSE/PacketMath.h" + #include "src/Core/arch/SSE/Complex.h" + #include "src/Core/arch/SSE/MathFunctions.h" + #include "src/Core/arch/AVX/PacketMath.h" + #include "src/Core/arch/AVX/MathFunctions.h" + #include "src/Core/arch/AVX/Complex.h" + #include "src/Core/arch/AVX/TypeCasting.h" +#elif defined EIGEN_VECTORIZE_SSE #include "src/Core/arch/SSE/PacketMath.h" #include "src/Core/arch/SSE/MathFunctions.h" #include "src/Core/arch/SSE/Complex.h" -#elif defined EIGEN_VECTORIZE_ALTIVEC + #include "src/Core/arch/SSE/TypeCasting.h" +#elif defined(EIGEN_VECTORIZE_ALTIVEC) || defined(EIGEN_VECTORIZE_VSX) #include "src/Core/arch/AltiVec/PacketMath.h" + #include "src/Core/arch/AltiVec/MathFunctions.h" #include "src/Core/arch/AltiVec/Complex.h" #elif defined EIGEN_VECTORIZE_NEON #include "src/Core/arch/NEON/PacketMath.h" + #include "src/Core/arch/NEON/MathFunctions.h" #include "src/Core/arch/NEON/Complex.h" +#elif defined EIGEN_VECTORIZE_ZVECTOR + #include "src/Core/arch/ZVector/PacketMath.h" + #include "src/Core/arch/ZVector/MathFunctions.h" + #include "src/Core/arch/ZVector/Complex.h" +#endif + +// Half float support +#include "src/Core/arch/CUDA/Half.h" +#include "src/Core/arch/CUDA/PacketMathHalf.h" +#include "src/Core/arch/CUDA/TypeCasting.h" + +#if defined EIGEN_VECTORIZE_CUDA + #include "src/Core/arch/CUDA/PacketMath.h" + #include "src/Core/arch/CUDA/MathFunctions.h" #endif #include "src/Core/arch/Default/Settings.h" -#include "src/Core/Functors.h" +#include "src/Core/functors/TernaryFunctors.h" +#include "src/Core/functors/BinaryFunctors.h" +#include "src/Core/functors/UnaryFunctors.h" +#include "src/Core/functors/NullaryFunctors.h" +#include "src/Core/functors/StlFunctors.h" +#include "src/Core/functors/AssignmentFunctors.h" + +// Specialized functors to enable the processing of complex numbers +// on CUDA devices +#include "src/Core/arch/CUDA/Complex.h" + +#include "src/Core/util/IndexedViewHelper.h" +#include "src/Core/ArithmeticSequence.h" +#include "src/Core/IO.h" #include "src/Core/DenseCoeffsBase.h" #include "src/Core/DenseBase.h" #include "src/Core/MatrixBase.h" #include "src/Core/EigenBase.h" +#include "src/Core/Product.h" +#include "src/Core/CoreEvaluators.h" +#include "src/Core/AssignEvaluator.h" + #ifndef EIGEN_PARSED_BY_DOXYGEN // work around Doxygen bug triggered by Assign.h r814874 // at least confirmed with Doxygen 1.5.5 and 1.5.6 #include "src/Core/Assign.h" #endif +#include "src/Core/ArrayBase.h" #include "src/Core/util/BlasUtil.h" #include "src/Core/DenseStorage.h" #include "src/Core/NestByValue.h" -#include "src/Core/ForceAlignedAccess.h" + +// #include "src/Core/ForceAlignedAccess.h" + #include "src/Core/ReturnByValue.h" #include "src/Core/NoAlias.h" #include "src/Core/PlainObjectBase.h" #include "src/Core/Matrix.h" #include "src/Core/Array.h" +#include "src/Core/CwiseTernaryOp.h" #include "src/Core/CwiseBinaryOp.h" #include "src/Core/CwiseUnaryOp.h" #include "src/Core/CwiseNullaryOp.h" @@ -300,32 +467,33 @@ using std::ptrdiff_t; #include "src/Core/SelfCwiseBinaryOp.h" #include "src/Core/Dot.h" #include "src/Core/StableNorm.h" -#include "src/Core/MapBase.h" #include "src/Core/Stride.h" +#include "src/Core/MapBase.h" #include "src/Core/Map.h" +#include "src/Core/Ref.h" #include "src/Core/Block.h" #include "src/Core/VectorBlock.h" -#include "src/Core/Ref.h" +#include "src/Core/IndexedView.h" #include "src/Core/Transpose.h" #include "src/Core/DiagonalMatrix.h" #include "src/Core/Diagonal.h" #include "src/Core/DiagonalProduct.h" -#include "src/Core/PermutationMatrix.h" -#include "src/Core/Transpositions.h" #include "src/Core/Redux.h" #include "src/Core/Visitor.h" #include "src/Core/Fuzzy.h" -#include "src/Core/IO.h" #include "src/Core/Swap.h" #include "src/Core/CommaInitializer.h" -#include "src/Core/Flagged.h" -#include "src/Core/ProductBase.h" #include "src/Core/GeneralProduct.h" +#include "src/Core/Solve.h" +#include "src/Core/Inverse.h" +#include "src/Core/SolverBase.h" +#include "src/Core/PermutationMatrix.h" +#include "src/Core/Transpositions.h" #include "src/Core/TriangularMatrix.h" #include "src/Core/SelfAdjointView.h" #include "src/Core/products/GeneralBlockPanelKernel.h" #include "src/Core/products/Parallelizer.h" -#include "src/Core/products/CoeffBasedProduct.h" +#include "src/Core/ProductEvaluators.h" #include "src/Core/products/GeneralMatrixVector.h" #include "src/Core/products/GeneralMatrixMatrix.h" #include "src/Core/SolveTriangular.h" @@ -340,6 +508,7 @@ using std::ptrdiff_t; #include "src/Core/products/TriangularSolverVector.h" #include "src/Core/BandMatrix.h" #include "src/Core/CoreIterators.h" +#include "src/Core/ConditionEstimator.h" #include "src/Core/BooleanRedux.h" #include "src/Core/Select.h" @@ -347,18 +516,17 @@ using std::ptrdiff_t; #include "src/Core/Random.h" #include "src/Core/Replicate.h" #include "src/Core/Reverse.h" -#include "src/Core/ArrayBase.h" #include "src/Core/ArrayWrapper.h" #ifdef EIGEN_USE_BLAS -#include "src/Core/products/GeneralMatrixMatrix_MKL.h" -#include "src/Core/products/GeneralMatrixVector_MKL.h" -#include "src/Core/products/GeneralMatrixMatrixTriangular_MKL.h" -#include "src/Core/products/SelfadjointMatrixMatrix_MKL.h" -#include "src/Core/products/SelfadjointMatrixVector_MKL.h" -#include "src/Core/products/TriangularMatrixMatrix_MKL.h" -#include "src/Core/products/TriangularMatrixVector_MKL.h" -#include "src/Core/products/TriangularSolverMatrix_MKL.h" +#include "src/Core/products/GeneralMatrixMatrix_BLAS.h" +#include "src/Core/products/GeneralMatrixVector_BLAS.h" +#include "src/Core/products/GeneralMatrixMatrixTriangular_BLAS.h" +#include "src/Core/products/SelfadjointMatrixMatrix_BLAS.h" +#include "src/Core/products/SelfadjointMatrixVector_BLAS.h" +#include "src/Core/products/TriangularMatrixMatrix_BLAS.h" +#include "src/Core/products/TriangularMatrixVector_BLAS.h" +#include "src/Core/products/TriangularSolverMatrix_BLAS.h" #endif // EIGEN_USE_BLAS #ifdef EIGEN_USE_MKL_VML @@ -369,8 +537,4 @@ using std::ptrdiff_t; #include "src/Core/util/ReenableStupidWarnings.h" -#ifdef EIGEN2_SUPPORT -#include "Eigen2Support" -#endif - #endif // EIGEN_CORE_H diff --git a/testbed/nanogui/ext/eigen/Eigen/Eigen b/testbed/nanogui/ext/eigen/Eigen/Eigen index 19b40ea4..654c8dc6 100644 --- a/testbed/nanogui/ext/eigen/Eigen/Eigen +++ b/testbed/nanogui/ext/eigen/Eigen/Eigen @@ -1,2 +1,2 @@ #include "Dense" -//#include "Sparse" +#include "Sparse" diff --git a/testbed/nanogui/ext/eigen/Eigen/Eigen2Support b/testbed/nanogui/ext/eigen/Eigen/Eigen2Support deleted file mode 100644 index 6aa009d2..00000000 --- a/testbed/nanogui/ext/eigen/Eigen/Eigen2Support +++ /dev/null @@ -1,95 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2009 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#ifndef EIGEN2SUPPORT_H -#define EIGEN2SUPPORT_H - -#if (!defined(EIGEN2_SUPPORT)) || (!defined(EIGEN_CORE_H)) -#error Eigen2 support must be enabled by defining EIGEN2_SUPPORT before including any Eigen header -#endif - -#ifndef EIGEN_NO_EIGEN2_DEPRECATED_WARNING - -#if defined(__GNUC__) || defined(__INTEL_COMPILER) || defined(__clang__) -#warning "Eigen2 support is deprecated in Eigen 3.2.x and it will be removed in Eigen 3.3. (Define EIGEN_NO_EIGEN2_DEPRECATED_WARNING to disable this warning)" -#else -#pragma message ("Eigen2 support is deprecated in Eigen 3.2.x and it will be removed in Eigen 3.3. (Define EIGEN_NO_EIGEN2_DEPRECATED_WARNING to disable this warning)") -#endif - -#endif // EIGEN_NO_EIGEN2_DEPRECATED_WARNING - -#include "src/Core/util/DisableStupidWarnings.h" - -/** \ingroup Support_modules - * \defgroup Eigen2Support_Module Eigen2 support module - * - * \warning Eigen2 support is deprecated in Eigen 3.2.x and it will be removed in Eigen 3.3. - * - * This module provides a couple of deprecated functions improving the compatibility with Eigen2. - * - * To use it, define EIGEN2_SUPPORT before including any Eigen header - * \code - * #define EIGEN2_SUPPORT - * \endcode - * - */ - -#include "src/Eigen2Support/Macros.h" -#include "src/Eigen2Support/Memory.h" -#include "src/Eigen2Support/Meta.h" -#include "src/Eigen2Support/Lazy.h" -#include "src/Eigen2Support/Cwise.h" -#include "src/Eigen2Support/CwiseOperators.h" -#include "src/Eigen2Support/TriangularSolver.h" -#include "src/Eigen2Support/Block.h" -#include "src/Eigen2Support/VectorBlock.h" -#include "src/Eigen2Support/Minor.h" -#include "src/Eigen2Support/MathFunctions.h" - - -#include "src/Core/util/ReenableStupidWarnings.h" - -// Eigen2 used to include iostream -#include - -#define EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, SizeSuffix) \ -using Eigen::Matrix##SizeSuffix##TypeSuffix; \ -using Eigen::Vector##SizeSuffix##TypeSuffix; \ -using Eigen::RowVector##SizeSuffix##TypeSuffix; - -#define EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(TypeSuffix) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, 2) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, 3) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, 4) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, X) \ - -#define EIGEN_USING_MATRIX_TYPEDEFS \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(i) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(f) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(d) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(cf) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(cd) - -#define USING_PART_OF_NAMESPACE_EIGEN \ -EIGEN_USING_MATRIX_TYPEDEFS \ -using Eigen::Matrix; \ -using Eigen::MatrixBase; \ -using Eigen::ei_random; \ -using Eigen::ei_real; \ -using Eigen::ei_imag; \ -using Eigen::ei_conj; \ -using Eigen::ei_abs; \ -using Eigen::ei_abs2; \ -using Eigen::ei_sqrt; \ -using Eigen::ei_exp; \ -using Eigen::ei_log; \ -using Eigen::ei_sin; \ -using Eigen::ei_cos; - -#endif // EIGEN2SUPPORT_H diff --git a/testbed/nanogui/ext/eigen/Eigen/Eigenvalues b/testbed/nanogui/ext/eigen/Eigen/Eigenvalues index 53c5a73a..009e529e 100644 --- a/testbed/nanogui/ext/eigen/Eigen/Eigenvalues +++ b/testbed/nanogui/ext/eigen/Eigen/Eigenvalues @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_EIGENVALUES_MODULE_H #define EIGEN_EIGENVALUES_MODULE_H @@ -25,6 +32,7 @@ * \endcode */ +#include "src/misc/RealSvd2x2.h" #include "src/Eigenvalues/Tridiagonalization.h" #include "src/Eigenvalues/RealSchur.h" #include "src/Eigenvalues/EigenSolver.h" @@ -37,9 +45,10 @@ #include "src/Eigenvalues/GeneralizedEigenSolver.h" #include "src/Eigenvalues/MatrixBaseEigenvalues.h" #ifdef EIGEN_USE_LAPACKE -#include "src/Eigenvalues/RealSchur_MKL.h" -#include "src/Eigenvalues/ComplexSchur_MKL.h" -#include "src/Eigenvalues/SelfAdjointEigenSolver_MKL.h" +#include "src/misc/lapacke.h" +#include "src/Eigenvalues/RealSchur_LAPACKE.h" +#include "src/Eigenvalues/ComplexSchur_LAPACKE.h" +#include "src/Eigenvalues/SelfAdjointEigenSolver_LAPACKE.h" #endif #include "src/Core/util/ReenableStupidWarnings.h" diff --git a/testbed/nanogui/ext/eigen/Eigen/Geometry b/testbed/nanogui/ext/eigen/Eigen/Geometry index efd9d450..131a4edf 100644 --- a/testbed/nanogui/ext/eigen/Eigen/Geometry +++ b/testbed/nanogui/ext/eigen/Eigen/Geometry @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_GEOMETRY_MODULE_H #define EIGEN_GEOMETRY_MODULE_H @@ -9,21 +16,17 @@ #include "LU" #include -#ifndef M_PI -#define M_PI 3.14159265358979323846 -#endif - /** \defgroup Geometry_Module Geometry module - * - * * * This module provides support for: * - fixed-size homogeneous transformations * - translation, scaling, 2D and 3D rotations - * - quaternions - * - \ref MatrixBase::cross() "cross product" - * - \ref MatrixBase::unitOrthogonal() "orthognal vector generation" - * - some linear components: parametrized-lines and hyperplanes + * - \link Quaternion quaternions \endlink + * - cross products (\ref MatrixBase::cross, \ref MatrixBase::cross3) + * - orthognal vector generation (\ref MatrixBase::unitOrthogonal) + * - some linear components: \link ParametrizedLine parametrized-lines \endlink and \link Hyperplane hyperplanes \endlink + * - \link AlignedBox axis aligned bounding boxes \endlink + * - \link umeyama least-square transformation fitting \endlink * * \code * #include @@ -33,31 +36,26 @@ #include "src/Geometry/OrthoMethods.h" #include "src/Geometry/EulerAngles.h" -#if EIGEN2_SUPPORT_STAGE > STAGE20_RESOLVE_API_CONFLICTS - #include "src/Geometry/Homogeneous.h" - #include "src/Geometry/RotationBase.h" - #include "src/Geometry/Rotation2D.h" - #include "src/Geometry/Quaternion.h" - #include "src/Geometry/AngleAxis.h" - #include "src/Geometry/Transform.h" - #include "src/Geometry/Translation.h" - #include "src/Geometry/Scaling.h" - #include "src/Geometry/Hyperplane.h" - #include "src/Geometry/ParametrizedLine.h" - #include "src/Geometry/AlignedBox.h" - #include "src/Geometry/Umeyama.h" +#include "src/Geometry/Homogeneous.h" +#include "src/Geometry/RotationBase.h" +#include "src/Geometry/Rotation2D.h" +#include "src/Geometry/Quaternion.h" +#include "src/Geometry/AngleAxis.h" +#include "src/Geometry/Transform.h" +#include "src/Geometry/Translation.h" +#include "src/Geometry/Scaling.h" +#include "src/Geometry/Hyperplane.h" +#include "src/Geometry/ParametrizedLine.h" +#include "src/Geometry/AlignedBox.h" +#include "src/Geometry/Umeyama.h" - #if defined EIGEN_VECTORIZE_SSE - #include "src/Geometry/arch/Geometry_SSE.h" - #endif -#endif - -#ifdef EIGEN2_SUPPORT -#include "src/Eigen2Support/Geometry/All.h" +// Use the SSE optimized version whenever possible. At the moment the +// SSE version doesn't compile when AVX is enabled +#if defined EIGEN_VECTORIZE_SSE && !defined EIGEN_VECTORIZE_AVX +#include "src/Geometry/arch/Geometry_SSE.h" #endif #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_GEOMETRY_MODULE_H /* vim: set filetype=cpp et sw=2 ts=2 ai: */ - diff --git a/testbed/nanogui/ext/eigen/Eigen/Householder b/testbed/nanogui/ext/eigen/Eigen/Householder index 6e348db5..89cd81b1 100644 --- a/testbed/nanogui/ext/eigen/Eigen/Householder +++ b/testbed/nanogui/ext/eigen/Eigen/Householder @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_HOUSEHOLDER_MODULE_H #define EIGEN_HOUSEHOLDER_MODULE_H diff --git a/testbed/nanogui/ext/eigen/Eigen/IterativeLinearSolvers b/testbed/nanogui/ext/eigen/Eigen/IterativeLinearSolvers index 0f4159dc..957d5750 100644 --- a/testbed/nanogui/ext/eigen/Eigen/IterativeLinearSolvers +++ b/testbed/nanogui/ext/eigen/Eigen/IterativeLinearSolvers @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_ITERATIVELINEARSOLVERS_MODULE_H #define EIGEN_ITERATIVELINEARSOLVERS_MODULE_H @@ -12,28 +19,29 @@ * This module currently provides iterative methods to solve problems of the form \c A \c x = \c b, where \c A is a squared matrix, usually very large and sparse. * Those solvers are accessible via the following classes: * - ConjugateGradient for selfadjoint (hermitian) matrices, + * - LeastSquaresConjugateGradient for rectangular least-square problems, * - BiCGSTAB for general square matrices. * * These iterative solvers are associated with some preconditioners: * - IdentityPreconditioner - not really useful - * - DiagonalPreconditioner - also called JAcobi preconditioner, work very well on diagonal dominant matrices. - * - IncompleteILUT - incomplete LU factorization with dual thresholding + * - DiagonalPreconditioner - also called Jacobi preconditioner, work very well on diagonal dominant matrices. + * - IncompleteLUT - incomplete LU factorization with dual thresholding * * Such problems can also be solved using the direct sparse decomposition modules: SparseCholesky, CholmodSupport, UmfPackSupport, SuperLUSupport. * - * \code - * #include - * \endcode + \code + #include + \endcode */ -#include "src/misc/Solve.h" -#include "src/misc/SparseSolve.h" - +#include "src/IterativeLinearSolvers/SolveWithGuess.h" #include "src/IterativeLinearSolvers/IterativeSolverBase.h" #include "src/IterativeLinearSolvers/BasicPreconditioners.h" #include "src/IterativeLinearSolvers/ConjugateGradient.h" +#include "src/IterativeLinearSolvers/LeastSquareConjugateGradient.h" #include "src/IterativeLinearSolvers/BiCGSTAB.h" #include "src/IterativeLinearSolvers/IncompleteLUT.h" +#include "src/IterativeLinearSolvers/IncompleteCholesky.h" #include "src/Core/util/ReenableStupidWarnings.h" diff --git a/testbed/nanogui/ext/eigen/Eigen/Jacobi b/testbed/nanogui/ext/eigen/Eigen/Jacobi index ba8a4dc3..17c1d785 100644 --- a/testbed/nanogui/ext/eigen/Eigen/Jacobi +++ b/testbed/nanogui/ext/eigen/Eigen/Jacobi @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_JACOBI_MODULE_H #define EIGEN_JACOBI_MODULE_H diff --git a/testbed/nanogui/ext/eigen/Eigen/LU b/testbed/nanogui/ext/eigen/Eigen/LU index db579550..6f6c5562 100644 --- a/testbed/nanogui/ext/eigen/Eigen/LU +++ b/testbed/nanogui/ext/eigen/Eigen/LU @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_LU_MODULE_H #define EIGEN_LU_MODULE_H @@ -16,25 +23,23 @@ * \endcode */ -#include "src/misc/Solve.h" #include "src/misc/Kernel.h" #include "src/misc/Image.h" #include "src/LU/FullPivLU.h" #include "src/LU/PartialPivLU.h" #ifdef EIGEN_USE_LAPACKE -#include "src/LU/PartialPivLU_MKL.h" +#include "src/misc/lapacke.h" +#include "src/LU/PartialPivLU_LAPACKE.h" #endif #include "src/LU/Determinant.h" -#include "src/LU/Inverse.h" +#include "src/LU/InverseImpl.h" -#if defined EIGEN_VECTORIZE_SSE +// Use the SSE optimized version whenever possible. At the moment the +// SSE version doesn't compile when AVX is enabled +#if defined EIGEN_VECTORIZE_SSE && !defined EIGEN_VECTORIZE_AVX #include "src/LU/arch/Inverse_SSE.h" #endif -#ifdef EIGEN2_SUPPORT - #include "src/Eigen2Support/LU.h" -#endif - #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_LU_MODULE_H diff --git a/testbed/nanogui/ext/eigen/Eigen/LeastSquares b/testbed/nanogui/ext/eigen/Eigen/LeastSquares deleted file mode 100644 index 35137c25..00000000 --- a/testbed/nanogui/ext/eigen/Eigen/LeastSquares +++ /dev/null @@ -1,32 +0,0 @@ -#ifndef EIGEN_REGRESSION_MODULE_H -#define EIGEN_REGRESSION_MODULE_H - -#ifndef EIGEN2_SUPPORT -#error LeastSquares is only available in Eigen2 support mode (define EIGEN2_SUPPORT) -#endif - -// exclude from normal eigen3-only documentation -#ifdef EIGEN2_SUPPORT - -#include "Core" - -#include "src/Core/util/DisableStupidWarnings.h" - -#include "Eigenvalues" -#include "Geometry" - -/** \defgroup LeastSquares_Module LeastSquares module - * This module provides linear regression and related features. - * - * \code - * #include - * \endcode - */ - -#include "src/Eigen2Support/LeastSquares.h" - -#include "src/Core/util/ReenableStupidWarnings.h" - -#endif // EIGEN2_SUPPORT - -#endif // EIGEN_REGRESSION_MODULE_H diff --git a/testbed/nanogui/ext/eigen/Eigen/MetisSupport b/testbed/nanogui/ext/eigen/Eigen/MetisSupport index 6a113f7a..85c41bf3 100644 --- a/testbed/nanogui/ext/eigen/Eigen/MetisSupport +++ b/testbed/nanogui/ext/eigen/Eigen/MetisSupport @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_METISSUPPORT_MODULE_H #define EIGEN_METISSUPPORT_MODULE_H diff --git a/testbed/nanogui/ext/eigen/Eigen/OrderingMethods b/testbed/nanogui/ext/eigen/Eigen/OrderingMethods index 7c0f1fff..d8ea3619 100644 --- a/testbed/nanogui/ext/eigen/Eigen/OrderingMethods +++ b/testbed/nanogui/ext/eigen/Eigen/OrderingMethods @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_ORDERINGMETHODS_MODULE_H #define EIGEN_ORDERINGMETHODS_MODULE_H diff --git a/testbed/nanogui/ext/eigen/Eigen/PaStiXSupport b/testbed/nanogui/ext/eigen/Eigen/PaStiXSupport index 7c616ee5..de3a63b4 100644 --- a/testbed/nanogui/ext/eigen/Eigen/PaStiXSupport +++ b/testbed/nanogui/ext/eigen/Eigen/PaStiXSupport @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_PASTIXSUPPORT_MODULE_H #define EIGEN_PASTIXSUPPORT_MODULE_H @@ -5,7 +12,6 @@ #include "src/Core/util/DisableStupidWarnings.h" -#include extern "C" { #include #include @@ -35,12 +41,8 @@ extern "C" { * */ -#include "src/misc/Solve.h" -#include "src/misc/SparseSolve.h" - #include "src/PaStiXSupport/PaStiXSupport.h" - #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_PASTIXSUPPORT_MODULE_H diff --git a/testbed/nanogui/ext/eigen/Eigen/PardisoSupport b/testbed/nanogui/ext/eigen/Eigen/PardisoSupport index 99330ce7..340edf51 100644 --- a/testbed/nanogui/ext/eigen/Eigen/PardisoSupport +++ b/testbed/nanogui/ext/eigen/Eigen/PardisoSupport @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_PARDISOSUPPORT_MODULE_H #define EIGEN_PARDISOSUPPORT_MODULE_H @@ -7,8 +14,6 @@ #include -#include - /** \ingroup Support_modules * \defgroup PardisoSupport_Module PardisoSupport module * diff --git a/testbed/nanogui/ext/eigen/Eigen/QR b/testbed/nanogui/ext/eigen/Eigen/QR index ac5b0269..80838e3b 100644 --- a/testbed/nanogui/ext/eigen/Eigen/QR +++ b/testbed/nanogui/ext/eigen/Eigen/QR @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_QR_MODULE_H #define EIGEN_QR_MODULE_H @@ -15,31 +22,26 @@ * * This module provides various QR decompositions * This module also provides some MatrixBase methods, including: - * - MatrixBase::qr(), + * - MatrixBase::householderQr() + * - MatrixBase::colPivHouseholderQr() + * - MatrixBase::fullPivHouseholderQr() * * \code * #include * \endcode */ -#include "src/misc/Solve.h" #include "src/QR/HouseholderQR.h" #include "src/QR/FullPivHouseholderQR.h" #include "src/QR/ColPivHouseholderQR.h" +#include "src/QR/CompleteOrthogonalDecomposition.h" #ifdef EIGEN_USE_LAPACKE -#include "src/QR/HouseholderQR_MKL.h" -#include "src/QR/ColPivHouseholderQR_MKL.h" -#endif - -#ifdef EIGEN2_SUPPORT -#include "src/Eigen2Support/QR.h" +#include "src/misc/lapacke.h" +#include "src/QR/HouseholderQR_LAPACKE.h" +#include "src/QR/ColPivHouseholderQR_LAPACKE.h" #endif #include "src/Core/util/ReenableStupidWarnings.h" -#ifdef EIGEN2_SUPPORT -#include "Eigenvalues" -#endif - #endif // EIGEN_QR_MODULE_H /* vim: set filetype=cpp et sw=2 ts=2 ai: */ diff --git a/testbed/nanogui/ext/eigen/Eigen/QtAlignedMalloc b/testbed/nanogui/ext/eigen/Eigen/QtAlignedMalloc index 46f7d83b..c6571f12 100644 --- a/testbed/nanogui/ext/eigen/Eigen/QtAlignedMalloc +++ b/testbed/nanogui/ext/eigen/Eigen/QtAlignedMalloc @@ -1,3 +1,9 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. #ifndef EIGEN_QTMALLOC_MODULE_H #define EIGEN_QTMALLOC_MODULE_H @@ -8,7 +14,7 @@ #include "src/Core/util/DisableStupidWarnings.h" -void *qMalloc(size_t size) +void *qMalloc(std::size_t size) { return Eigen::internal::aligned_malloc(size); } @@ -18,7 +24,7 @@ void qFree(void *ptr) Eigen::internal::aligned_free(ptr); } -void *qRealloc(void *ptr, size_t size) +void *qRealloc(void *ptr, std::size_t size) { void* newPtr = Eigen::internal::aligned_malloc(size); memcpy(newPtr, ptr, size); diff --git a/testbed/nanogui/ext/eigen/Eigen/SPQRSupport b/testbed/nanogui/ext/eigen/Eigen/SPQRSupport index 77016442..f70390c1 100644 --- a/testbed/nanogui/ext/eigen/Eigen/SPQRSupport +++ b/testbed/nanogui/ext/eigen/Eigen/SPQRSupport @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_SPQRSUPPORT_MODULE_H #define EIGEN_SPQRSUPPORT_MODULE_H @@ -10,7 +17,7 @@ /** \ingroup Support_modules * \defgroup SPQRSupport_Module SuiteSparseQR module * - * This module provides an interface to the SPQR library, which is part of the suitesparse package. + * This module provides an interface to the SPQR library, which is part of the suitesparse package. * * \code * #include @@ -21,8 +28,6 @@ * */ -#include "src/misc/Solve.h" -#include "src/misc/SparseSolve.h" #include "src/CholmodSupport/CholmodSupport.h" #include "src/SPQRSupport/SuiteSparseQRSupport.h" diff --git a/testbed/nanogui/ext/eigen/Eigen/SVD b/testbed/nanogui/ext/eigen/Eigen/SVD index fd310017..86143c23 100644 --- a/testbed/nanogui/ext/eigen/Eigen/SVD +++ b/testbed/nanogui/ext/eigen/Eigen/SVD @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_SVD_MODULE_H #define EIGEN_SVD_MODULE_H @@ -12,23 +19,26 @@ * * * This module provides SVD decomposition for matrices (both real and complex). - * This decomposition is accessible via the following MatrixBase method: + * Two decomposition algorithms are provided: + * - JacobiSVD implementing two-sided Jacobi iterations is numerically very accurate, fast for small matrices, but very slow for larger ones. + * - BDCSVD implementing a recursive divide & conquer strategy on top of an upper-bidiagonalization which remains fast for large problems. + * These decompositions are accessible via the respective classes and following MatrixBase methods: * - MatrixBase::jacobiSvd() + * - MatrixBase::bdcSvd() * * \code * #include * \endcode */ -#include "src/misc/Solve.h" -#include "src/SVD/JacobiSVD.h" -#if defined(EIGEN_USE_LAPACKE) && !defined(EIGEN_USE_LAPACKE_STRICT) -#include "src/SVD/JacobiSVD_MKL.h" -#endif +#include "src/misc/RealSvd2x2.h" #include "src/SVD/UpperBidiagonalization.h" - -#ifdef EIGEN2_SUPPORT -#include "src/Eigen2Support/SVD.h" +#include "src/SVD/SVDBase.h" +#include "src/SVD/JacobiSVD.h" +#include "src/SVD/BDCSVD.h" +#if defined(EIGEN_USE_LAPACKE) && !defined(EIGEN_USE_LAPACKE_STRICT) +#include "src/misc/lapacke.h" +#include "src/SVD/JacobiSVD_LAPACKE.h" #endif #include "src/Core/util/ReenableStupidWarnings.h" diff --git a/testbed/nanogui/ext/eigen/Eigen/Sparse b/testbed/nanogui/ext/eigen/Eigen/Sparse index 7cc9c091..136e681a 100644 --- a/testbed/nanogui/ext/eigen/Eigen/Sparse +++ b/testbed/nanogui/ext/eigen/Eigen/Sparse @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_SPARSE_MODULE_H #define EIGEN_SPARSE_MODULE_H @@ -11,14 +18,16 @@ * - \ref SparseQR_Module * - \ref IterativeLinearSolvers_Module * - * \code - * #include - * \endcode + \code + #include + \endcode */ #include "SparseCore" #include "OrderingMethods" +#ifndef EIGEN_MPL2_ONLY #include "SparseCholesky" +#endif #include "SparseLU" #include "SparseQR" #include "IterativeLinearSolvers" diff --git a/testbed/nanogui/ext/eigen/Eigen/SparseCholesky b/testbed/nanogui/ext/eigen/Eigen/SparseCholesky index 9f5056aa..b6a320c4 100644 --- a/testbed/nanogui/ext/eigen/Eigen/SparseCholesky +++ b/testbed/nanogui/ext/eigen/Eigen/SparseCholesky @@ -34,8 +34,6 @@ #error The SparseCholesky module has nothing to offer in MPL2 only mode #endif -#include "src/misc/Solve.h" -#include "src/misc/SparseSolve.h" #include "src/SparseCholesky/SimplicialCholesky.h" #ifndef EIGEN_MPL2_ONLY diff --git a/testbed/nanogui/ext/eigen/Eigen/SparseCore b/testbed/nanogui/ext/eigen/Eigen/SparseCore index 9b5be5e1..76966c4c 100644 --- a/testbed/nanogui/ext/eigen/Eigen/SparseCore +++ b/testbed/nanogui/ext/eigen/Eigen/SparseCore @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_SPARSECORE_MODULE_H #define EIGEN_SPARSECORE_MODULE_H @@ -14,7 +21,7 @@ /** * \defgroup SparseCore_Module SparseCore module * - * This module provides a sparse matrix representation, and basic associatd matrix manipulations + * This module provides a sparse matrix representation, and basic associated matrix manipulations * and operations. * * See the \ref TutorialSparse "Sparse tutorial" @@ -26,37 +33,35 @@ * This module depends on: Core. */ -namespace Eigen { - -/** The type used to identify a general sparse storage. */ -struct Sparse {}; - -} - #include "src/SparseCore/SparseUtil.h" #include "src/SparseCore/SparseMatrixBase.h" +#include "src/SparseCore/SparseAssign.h" #include "src/SparseCore/CompressedStorage.h" #include "src/SparseCore/AmbiVector.h" +#include "src/SparseCore/SparseCompressedBase.h" #include "src/SparseCore/SparseMatrix.h" +#include "src/SparseCore/SparseMap.h" #include "src/SparseCore/MappedSparseMatrix.h" #include "src/SparseCore/SparseVector.h" -#include "src/SparseCore/SparseBlock.h" -#include "src/SparseCore/SparseTranspose.h" +#include "src/SparseCore/SparseRef.h" #include "src/SparseCore/SparseCwiseUnaryOp.h" #include "src/SparseCore/SparseCwiseBinaryOp.h" +#include "src/SparseCore/SparseTranspose.h" +#include "src/SparseCore/SparseBlock.h" #include "src/SparseCore/SparseDot.h" -#include "src/SparseCore/SparsePermutation.h" #include "src/SparseCore/SparseRedux.h" -#include "src/SparseCore/SparseFuzzy.h" +#include "src/SparseCore/SparseView.h" +#include "src/SparseCore/SparseDiagonalProduct.h" #include "src/SparseCore/ConservativeSparseSparseProduct.h" #include "src/SparseCore/SparseSparseProductWithPruning.h" #include "src/SparseCore/SparseProduct.h" #include "src/SparseCore/SparseDenseProduct.h" -#include "src/SparseCore/SparseDiagonalProduct.h" -#include "src/SparseCore/SparseTriangularView.h" #include "src/SparseCore/SparseSelfAdjointView.h" +#include "src/SparseCore/SparseTriangularView.h" #include "src/SparseCore/TriangularSolver.h" -#include "src/SparseCore/SparseView.h" +#include "src/SparseCore/SparsePermutation.h" +#include "src/SparseCore/SparseFuzzy.h" +#include "src/SparseCore/SparseSolverBase.h" #include "src/Core/util/ReenableStupidWarnings.h" diff --git a/testbed/nanogui/ext/eigen/Eigen/SparseLU b/testbed/nanogui/ext/eigen/Eigen/SparseLU index 8527a49b..38b38b53 100644 --- a/testbed/nanogui/ext/eigen/Eigen/SparseLU +++ b/testbed/nanogui/ext/eigen/Eigen/SparseLU @@ -20,9 +20,6 @@ * Please, see the documentation of the SparseLU class for more details. */ -#include "src/misc/Solve.h" -#include "src/misc/SparseSolve.h" - // Ordering interface #include "OrderingMethods" diff --git a/testbed/nanogui/ext/eigen/Eigen/SparseQR b/testbed/nanogui/ext/eigen/Eigen/SparseQR index 4ee42065..a6f3b7f7 100644 --- a/testbed/nanogui/ext/eigen/Eigen/SparseQR +++ b/testbed/nanogui/ext/eigen/Eigen/SparseQR @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_SPARSEQR_MODULE_H #define EIGEN_SPARSEQR_MODULE_H @@ -21,9 +28,6 @@ * */ -#include "src/misc/Solve.h" -#include "src/misc/SparseSolve.h" - #include "OrderingMethods" #include "src/SparseCore/SparseColEtree.h" #include "src/SparseQR/SparseQR.h" diff --git a/testbed/nanogui/ext/eigen/Eigen/StdDeque b/testbed/nanogui/ext/eigen/Eigen/StdDeque index f2723477..bc68397b 100644 --- a/testbed/nanogui/ext/eigen/Eigen/StdDeque +++ b/testbed/nanogui/ext/eigen/Eigen/StdDeque @@ -14,7 +14,7 @@ #include "Core" #include -#if (defined(_MSC_VER) && defined(_WIN64)) /* MSVC auto aligns in 64 bit builds */ +#if EIGEN_COMP_MSVC && EIGEN_OS_WIN64 && (EIGEN_MAX_STATIC_ALIGN_BYTES<=16) /* MSVC auto aligns up to 16 bytes in 64 bit builds */ #define EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(...) diff --git a/testbed/nanogui/ext/eigen/Eigen/StdList b/testbed/nanogui/ext/eigen/Eigen/StdList index 225c1e18..4c6262c0 100644 --- a/testbed/nanogui/ext/eigen/Eigen/StdList +++ b/testbed/nanogui/ext/eigen/Eigen/StdList @@ -13,7 +13,7 @@ #include "Core" #include -#if (defined(_MSC_VER) && defined(_WIN64)) /* MSVC auto aligns in 64 bit builds */ +#if EIGEN_COMP_MSVC && EIGEN_OS_WIN64 && (EIGEN_MAX_STATIC_ALIGN_BYTES<=16) /* MSVC auto aligns up to 16 bytes in 64 bit builds */ #define EIGEN_DEFINE_STL_LIST_SPECIALIZATION(...) diff --git a/testbed/nanogui/ext/eigen/Eigen/StdVector b/testbed/nanogui/ext/eigen/Eigen/StdVector index 6b22627f..0c4697ad 100644 --- a/testbed/nanogui/ext/eigen/Eigen/StdVector +++ b/testbed/nanogui/ext/eigen/Eigen/StdVector @@ -14,7 +14,7 @@ #include "Core" #include -#if (defined(_MSC_VER) && defined(_WIN64)) /* MSVC auto aligns in 64 bit builds */ +#if EIGEN_COMP_MSVC && EIGEN_OS_WIN64 && (EIGEN_MAX_STATIC_ALIGN_BYTES<=16) /* MSVC auto aligns up to 16 bytes in 64 bit builds */ #define EIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(...) diff --git a/testbed/nanogui/ext/eigen/Eigen/SuperLUSupport b/testbed/nanogui/ext/eigen/Eigen/SuperLUSupport index 575e14fb..59312a82 100644 --- a/testbed/nanogui/ext/eigen/Eigen/SuperLUSupport +++ b/testbed/nanogui/ext/eigen/Eigen/SuperLUSupport @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_SUPERLUSUPPORT_MODULE_H #define EIGEN_SUPERLUSUPPORT_MODULE_H @@ -36,6 +43,8 @@ namespace Eigen { struct SluMatrix; } * - class SuperLU: a supernodal sequential LU factorization. * - class SuperILU: a supernodal sequential incomplete LU factorization (to be used as a preconditioner for iterative methods). * + * \warning This wrapper requires at least versions 4.0 of SuperLU. The 3.x versions are not supported. + * * \warning When including this module, you have to use SUPERLU_EMPTY instead of EMPTY which is no longer defined because it is too polluting. * * \code @@ -48,12 +57,8 @@ namespace Eigen { struct SluMatrix; } * */ -#include "src/misc/Solve.h" -#include "src/misc/SparseSolve.h" - #include "src/SuperLUSupport/SuperLUSupport.h" - #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_SUPERLUSUPPORT_MODULE_H diff --git a/testbed/nanogui/ext/eigen/Eigen/UmfPackSupport b/testbed/nanogui/ext/eigen/Eigen/UmfPackSupport index 984f64a8..00eec808 100644 --- a/testbed/nanogui/ext/eigen/Eigen/UmfPackSupport +++ b/testbed/nanogui/ext/eigen/Eigen/UmfPackSupport @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_UMFPACKSUPPORT_MODULE_H #define EIGEN_UMFPACKSUPPORT_MODULE_H @@ -12,7 +19,7 @@ extern "C" { /** \ingroup Support_modules * \defgroup UmfPackSupport_Module UmfPackSupport module * - * This module provides an interface to the UmfPack library which is part of the suitesparse package. + * This module provides an interface to the UmfPack library which is part of the suitesparse package. * It provides the following factorization class: * - class UmfPackLU: a multifrontal sequential LU factorization. * @@ -26,9 +33,6 @@ extern "C" { * */ -#include "src/misc/Solve.h" -#include "src/misc/SparseSolve.h" - #include "src/UmfPackSupport/UmfPackSupport.h" #include "src/Core/util/ReenableStupidWarnings.h" diff --git a/testbed/nanogui/ext/eigen/Eigen/src/CMakeLists.txt b/testbed/nanogui/ext/eigen/Eigen/src/CMakeLists.txt deleted file mode 100644 index c326f374..00000000 --- a/testbed/nanogui/ext/eigen/Eigen/src/CMakeLists.txt +++ /dev/null @@ -1,7 +0,0 @@ -file(GLOB Eigen_src_subdirectories "*") -escape_string_as_regex(ESCAPED_CMAKE_CURRENT_SOURCE_DIR "${CMAKE_CURRENT_SOURCE_DIR}") -foreach(f ${Eigen_src_subdirectories}) - if(NOT f MATCHES "\\.txt" AND NOT f MATCHES "${ESCAPED_CMAKE_CURRENT_SOURCE_DIR}/[.].+" ) - add_subdirectory(${f}) - endif() -endforeach() diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Cholesky/CMakeLists.txt b/testbed/nanogui/ext/eigen/Eigen/src/Cholesky/CMakeLists.txt deleted file mode 100644 index d01488b4..00000000 --- a/testbed/nanogui/ext/eigen/Eigen/src/Cholesky/CMakeLists.txt +++ /dev/null @@ -1,6 +0,0 @@ -FILE(GLOB Eigen_Cholesky_SRCS "*.h") - -INSTALL(FILES - ${Eigen_Cholesky_SRCS} - DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen/src/Cholesky COMPONENT Devel - ) diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Cholesky/LDLT.h b/testbed/nanogui/ext/eigen/Eigen/src/Cholesky/LDLT.h index 02ab9388..9b4fdb41 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Cholesky/LDLT.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Cholesky/LDLT.h @@ -13,7 +13,7 @@ #ifndef EIGEN_LDLT_H #define EIGEN_LDLT_H -namespace Eigen { +namespace Eigen { namespace internal { template struct LDLT_Traits; @@ -28,8 +28,8 @@ namespace internal { * * \brief Robust Cholesky decomposition of a matrix with pivoting * - * \param MatrixType the type of the matrix of which to compute the LDL^T Cholesky decomposition - * \param UpLo the triangular part that will be used for the decompositon: Lower (default) or Upper. + * \tparam _MatrixType the type of the matrix of which to compute the LDL^T Cholesky decomposition + * \tparam _UpLo the triangular part that will be used for the decompositon: Lower (default) or Upper. * The other triangular part won't be read. * * Perform a robust Cholesky decomposition of a positive semidefinite or negative semidefinite @@ -43,7 +43,9 @@ namespace internal { * Remember that Cholesky decompositions are not rank-revealing. Also, do not use a Cholesky * decomposition to determine whether a system of equations has a solution. * - * \sa MatrixBase::ldlt(), class LLT + * This class supports the \link InplaceDecomposition inplace decomposition \endlink mechanism. + * + * \sa MatrixBase::ldlt(), SelfAdjointView::ldlt(), class LLT */ template class LDLT { @@ -52,15 +54,15 @@ template class LDLT enum { RowsAtCompileTime = MatrixType::RowsAtCompileTime, ColsAtCompileTime = MatrixType::ColsAtCompileTime, - Options = MatrixType::Options & ~RowMajorBit, // these are the options for the TmpMatrixType, we need a ColMajor matrix here! MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime, MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime, UpLo = _UpLo }; typedef typename MatrixType::Scalar Scalar; typedef typename NumTraits::Real RealScalar; - typedef typename MatrixType::Index Index; - typedef Matrix TmpMatrixType; + typedef Eigen::Index Index; ///< \deprecated since Eigen 3.3 + typedef typename MatrixType::StorageIndex StorageIndex; + typedef Matrix TmpMatrixType; typedef Transpositions TranspositionType; typedef PermutationMatrix PermutationType; @@ -72,11 +74,11 @@ template class LDLT * The default constructor is useful in cases in which the user intends to * perform decompositions via LDLT::compute(const MatrixType&). */ - LDLT() - : m_matrix(), - m_transpositions(), + LDLT() + : m_matrix(), + m_transpositions(), m_sign(internal::ZeroSign), - m_isInitialized(false) + m_isInitialized(false) {} /** \brief Default Constructor with memory preallocation @@ -85,7 +87,7 @@ template class LDLT * according to the specified problem \a size. * \sa LDLT() */ - LDLT(Index size) + explicit LDLT(Index size) : m_matrix(size, size), m_transpositions(size), m_temporary(size), @@ -96,16 +98,35 @@ template class LDLT /** \brief Constructor with decomposition * * This calculates the decomposition for the input \a matrix. + * * \sa LDLT(Index size) */ - LDLT(const MatrixType& matrix) + template + explicit LDLT(const EigenBase& matrix) : m_matrix(matrix.rows(), matrix.cols()), m_transpositions(matrix.rows()), m_temporary(matrix.rows()), m_sign(internal::ZeroSign), m_isInitialized(false) { - compute(matrix); + compute(matrix.derived()); + } + + /** \brief Constructs a LDLT factorization from a given matrix + * + * This overloaded constructor is provided for \link InplaceDecomposition inplace decomposition \endlink when \c MatrixType is a Eigen::Ref. + * + * \sa LDLT(const EigenBase&) + */ + template + explicit LDLT(EigenBase& matrix) + : m_matrix(matrix.derived()), + m_transpositions(matrix.rows()), + m_temporary(matrix.rows()), + m_sign(internal::ZeroSign), + m_isInitialized(false) + { + compute(matrix.derived()); } /** Clear any existing decomposition @@ -151,13 +172,6 @@ template class LDLT eigen_assert(m_isInitialized && "LDLT is not initialized."); return m_sign == internal::PositiveSemiDef || m_sign == internal::ZeroSign; } - - #ifdef EIGEN2_SUPPORT - inline bool isPositiveDefinite() const - { - return isPositive(); - } - #endif /** \returns true if the matrix is negative (semidefinite) */ inline bool isNegative(void) const @@ -173,37 +187,38 @@ template class LDLT * \note_about_checking_solutions * * More precisely, this method solves \f$ A x = b \f$ using the decomposition \f$ A = P^T L D L^* P \f$ - * by solving the systems \f$ P^T y_1 = b \f$, \f$ L y_2 = y_1 \f$, \f$ D y_3 = y_2 \f$, + * by solving the systems \f$ P^T y_1 = b \f$, \f$ L y_2 = y_1 \f$, \f$ D y_3 = y_2 \f$, * \f$ L^* y_4 = y_3 \f$ and \f$ P x = y_4 \f$ in succession. If the matrix \f$ A \f$ is singular, then * \f$ D \f$ will also be singular (all the other matrices are invertible). In that case, the * least-square solution of \f$ D y_3 = y_2 \f$ is computed. This does not mean that this function * computes the least-square solution of \f$ A x = b \f$ is \f$ A \f$ is singular. * - * \sa MatrixBase::ldlt() + * \sa MatrixBase::ldlt(), SelfAdjointView::ldlt() */ template - inline const internal::solve_retval + inline const Solve solve(const MatrixBase& b) const { eigen_assert(m_isInitialized && "LDLT is not initialized."); eigen_assert(m_matrix.rows()==b.rows() && "LDLT::solve(): invalid number of rows of the right hand side matrix b"); - return internal::solve_retval(*this, b.derived()); + return Solve(*this, b.derived()); } - #ifdef EIGEN2_SUPPORT - template - bool solve(const MatrixBase& b, ResultType *result) const - { - *result = this->solve(b); - return true; - } - #endif - template bool solveInPlace(MatrixBase &bAndX) const; - LDLT& compute(const MatrixType& matrix); + template + LDLT& compute(const EigenBase& matrix); + + /** \returns an estimate of the reciprocal condition number of the matrix of + * which \c *this is the LDLT decomposition. + */ + RealScalar rcond() const + { + eigen_assert(m_isInitialized && "LDLT is not initialized."); + return internal::rcond_estimate_helper(m_l1_norm, *this); + } template LDLT& rankUpdate(const MatrixBase& w, const RealScalar& alpha=1); @@ -220,6 +235,13 @@ template class LDLT MatrixType reconstructedMatrix() const; + /** \returns the adjoint of \c *this, that is, a const reference to the decomposition itself as the underlying matrix is self-adjoint. + * + * This method is provided for compatibility with other matrix decompositions, thus enabling generic code such as: + * \code x = decomposition.adjoint().solve(b) \endcode + */ + const LDLT& adjoint() const { return *this; }; + inline Index rows() const { return m_matrix.rows(); } inline Index cols() const { return m_matrix.cols(); } @@ -231,11 +253,21 @@ template class LDLT ComputationInfo info() const { eigen_assert(m_isInitialized && "LDLT is not initialized."); - return Success; + return m_info; } + #ifndef EIGEN_PARSED_BY_DOXYGEN + template + void _solve_impl(const RhsType &rhs, DstType &dst) const; + #endif + protected: + static void check_template_parameters() + { + EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar); + } + /** \internal * Used to compute and store the Cholesky decomposition A = L D L^* = U^* D U. * The strict upper part is used during the decomposition, the strict lower @@ -243,10 +275,12 @@ template class LDLT * is not stored), and the diagonal entries correspond to D. */ MatrixType m_matrix; + RealScalar m_l1_norm; TranspositionType m_transpositions; TmpMatrixType m_temporary; internal::SignMatrix m_sign; bool m_isInitialized; + ComputationInfo m_info; }; namespace internal { @@ -261,15 +295,17 @@ template<> struct ldlt_inplace using std::abs; typedef typename MatrixType::Scalar Scalar; typedef typename MatrixType::RealScalar RealScalar; - typedef typename MatrixType::Index Index; + typedef typename TranspositionType::StorageIndex IndexType; eigen_assert(mat.rows()==mat.cols()); const Index size = mat.rows(); + bool found_zero_pivot = false; + bool ret = true; if (size <= 1) { transpositions.setIdentity(); - if (numext::real(mat.coeff(0,0)) > 0) sign = PositiveSemiDef; - else if (numext::real(mat.coeff(0,0)) < 0) sign = NegativeSemiDef; + if (numext::real(mat.coeff(0,0)) > static_cast(0) ) sign = PositiveSemiDef; + else if (numext::real(mat.coeff(0,0)) < static_cast(0)) sign = NegativeSemiDef; else sign = ZeroSign; return true; } @@ -281,7 +317,7 @@ template<> struct ldlt_inplace mat.diagonal().tail(size-k).cwiseAbs().maxCoeff(&index_of_biggest_in_corner); index_of_biggest_in_corner += k; - transpositions.coeffRef(k) = index_of_biggest_in_corner; + transpositions.coeffRef(k) = IndexType(index_of_biggest_in_corner); if(k != index_of_biggest_in_corner) { // apply the transposition while taking care to consider only @@ -290,7 +326,7 @@ template<> struct ldlt_inplace mat.row(k).head(k).swap(mat.row(index_of_biggest_in_corner).head(k)); mat.col(k).tail(s).swap(mat.col(index_of_biggest_in_corner).tail(s)); std::swap(mat.coeffRef(k,k),mat.coeffRef(index_of_biggest_in_corner,index_of_biggest_in_corner)); - for(int i=k+1;i struct ldlt_inplace if(rs>0) A21.noalias() -= A20 * temp.head(k); } - + // In some previous versions of Eigen (e.g., 3.2.1), the scaling was omitted if the pivot - // was smaller than the cutoff value. However, soince LDLT is not rank-revealing - // we should only make sure we do not introduce INF or NaN values. - // LAPACK also uses 0 as the cutoff value. + // was smaller than the cutoff value. However, since LDLT is not rank-revealing + // we should only make sure that we do not introduce INF or NaN values. + // Remark that LAPACK also uses 0 as the cutoff value. RealScalar realAkk = numext::real(mat.coeffRef(k,k)); - if((rs>0) && (abs(realAkk) > RealScalar(0))) + bool pivot_is_valid = (abs(realAkk) > RealScalar(0)); + + if(k==0 && !pivot_is_valid) + { + // The entire diagonal is zero, there is nothing more to do + // except filling the transpositions, and checking whether the matrix is zero. + sign = ZeroSign; + for(Index j = 0; j0) && pivot_is_valid) A21 /= realAkk; + if(found_zero_pivot && pivot_is_valid) ret = false; // factorization failed + else if(!pivot_is_valid) found_zero_pivot = true; + if (sign == PositiveSemiDef) { - if (realAkk < 0) sign = Indefinite; + if (realAkk < static_cast(0)) sign = Indefinite; } else if (sign == NegativeSemiDef) { - if (realAkk > 0) sign = Indefinite; + if (realAkk > static_cast(0)) sign = Indefinite; } else if (sign == ZeroSign) { - if (realAkk > 0) sign = PositiveSemiDef; - else if (realAkk < 0) sign = NegativeSemiDef; + if (realAkk > static_cast(0)) sign = PositiveSemiDef; + else if (realAkk < static_cast(0)) sign = NegativeSemiDef; } } - return true; + return ret; } // Reference for the algorithm: Davis and Hager, "Multiple Rank @@ -351,7 +405,6 @@ template<> struct ldlt_inplace using numext::isfinite; typedef typename MatrixType::Scalar Scalar; typedef typename MatrixType::RealScalar RealScalar; - typedef typename MatrixType::Index Index; const Index size = mat.rows(); eigen_assert(mat.cols() == size && w.size()==size); @@ -415,16 +468,16 @@ template struct LDLT_Traits { typedef const TriangularView MatrixL; typedef const TriangularView MatrixU; - static inline MatrixL getL(const MatrixType& m) { return m; } - static inline MatrixU getU(const MatrixType& m) { return m.adjoint(); } + static inline MatrixL getL(const MatrixType& m) { return MatrixL(m); } + static inline MatrixU getU(const MatrixType& m) { return MatrixU(m.adjoint()); } }; template struct LDLT_Traits { typedef const TriangularView MatrixL; typedef const TriangularView MatrixU; - static inline MatrixL getL(const MatrixType& m) { return m.adjoint(); } - static inline MatrixU getU(const MatrixType& m) { return m; } + static inline MatrixL getL(const MatrixType& m) { return MatrixL(m.adjoint()); } + static inline MatrixU getU(const MatrixType& m) { return MatrixU(m); } }; } // end namespace internal @@ -432,19 +485,35 @@ template struct LDLT_Traits /** Compute / recompute the LDLT decomposition A = L D L^* = U^* D U of \a matrix */ template -LDLT& LDLT::compute(const MatrixType& a) +template +LDLT& LDLT::compute(const EigenBase& a) { + check_template_parameters(); + eigen_assert(a.rows()==a.cols()); const Index size = a.rows(); - m_matrix = a; + m_matrix = a.derived(); + + // Compute matrix L1 norm = max abs column sum. + m_l1_norm = RealScalar(0); + // TODO move this code to SelfAdjointView + for (Index col = 0; col < size; ++col) { + RealScalar abs_col_sum; + if (_UpLo == Lower) + abs_col_sum = m_matrix.col(col).tail(size - col).template lpNorm<1>() + m_matrix.row(col).head(col).template lpNorm<1>(); + else + abs_col_sum = m_matrix.col(col).head(col).template lpNorm<1>() + m_matrix.row(col).tail(size - col).template lpNorm<1>(); + if (abs_col_sum > m_l1_norm) + m_l1_norm = abs_col_sum; + } m_transpositions.resize(size); m_isInitialized = false; m_temporary.resize(size); m_sign = internal::ZeroSign; - internal::ldlt_inplace::unblocked(m_matrix, m_transpositions, m_temporary, m_sign); + m_info = internal::ldlt_inplace::unblocked(m_matrix, m_transpositions, m_temporary, m_sign) ? Success : NumericalIssue; m_isInitialized = true; return *this; @@ -457,20 +526,21 @@ LDLT& LDLT::compute(const MatrixType& a) */ template template -LDLT& LDLT::rankUpdate(const MatrixBase& w, const typename NumTraits::Real& sigma) +LDLT& LDLT::rankUpdate(const MatrixBase& w, const typename LDLT::RealScalar& sigma) { + typedef typename TranspositionType::StorageIndex IndexType; const Index size = w.rows(); if (m_isInitialized) { eigen_assert(m_matrix.rows()==size); } else - { + { m_matrix.resize(size,size); m_matrix.setZero(); m_transpositions.resize(size); for (Index i = 0; i < size; i++) - m_transpositions.coeffRef(i) = i; + m_transpositions.coeffRef(i) = IndexType(i); m_temporary.resize(size); m_sign = sigma>=0 ? internal::PositiveSemiDef : internal::NegativeSemiDef; m_isInitialized = true; @@ -481,53 +551,45 @@ LDLT& LDLT::rankUpdate(const MatrixBase -struct solve_retval, Rhs> - : solve_retval_base, Rhs> +#ifndef EIGEN_PARSED_BY_DOXYGEN +template +template +void LDLT<_MatrixType,_UpLo>::_solve_impl(const RhsType &rhs, DstType &dst) const { - typedef LDLT<_MatrixType,_UpLo> LDLTType; - EIGEN_MAKE_SOLVE_HELPERS(LDLTType,Rhs) + eigen_assert(rhs.rows() == rows()); + // dst = P b + dst = m_transpositions * rhs; - template void evalTo(Dest& dst) const + // dst = L^-1 (P b) + matrixL().solveInPlace(dst); + + // dst = D^-1 (L^-1 P b) + // more precisely, use pseudo-inverse of D (see bug 241) + using std::abs; + const typename Diagonal::RealReturnType vecD(vectorD()); + // In some previous versions, tolerance was set to the max of 1/highest and the maximal diagonal entry * epsilon + // as motivated by LAPACK's xGELSS: + // RealScalar tolerance = numext::maxi(vecD.array().abs().maxCoeff() * NumTraits::epsilon(),RealScalar(1) / NumTraits::highest()); + // However, LDLT is not rank revealing, and so adjusting the tolerance wrt to the highest + // diagonal element is not well justified and leads to numerical issues in some cases. + // Moreover, Lapack's xSYTRS routines use 0 for the tolerance. + RealScalar tolerance = RealScalar(1) / NumTraits::highest(); + + for (Index i = 0; i < vecD.size(); ++i) { - eigen_assert(rhs().rows() == dec().matrixLDLT().rows()); - // dst = P b - dst = dec().transpositionsP() * rhs(); - - // dst = L^-1 (P b) - dec().matrixL().solveInPlace(dst); - - // dst = D^-1 (L^-1 P b) - // more precisely, use pseudo-inverse of D (see bug 241) - using std::abs; - using std::max; - typedef typename LDLTType::MatrixType MatrixType; - typedef typename LDLTType::RealScalar RealScalar; - const typename Diagonal::RealReturnType vectorD(dec().vectorD()); - // In some previous versions, tolerance was set to the max of 1/highest and the maximal diagonal entry * epsilon - // as motivated by LAPACK's xGELSS: - // RealScalar tolerance = (max)(vectorD.array().abs().maxCoeff() *NumTraits::epsilon(),RealScalar(1) / NumTraits::highest()); - // However, LDLT is not rank revealing, and so adjusting the tolerance wrt to the highest - // diagonal element is not well justified and to numerical issues in some cases. - // Moreover, Lapack's xSYTRS routines use 0 for the tolerance. - RealScalar tolerance = RealScalar(1) / NumTraits::highest(); - - for (Index i = 0; i < vectorD.size(); ++i) { - if(abs(vectorD(i)) > tolerance) - dst.row(i) /= vectorD(i); - else - dst.row(i).setZero(); - } - - // dst = L^-T (D^-1 L^-1 P b) - dec().matrixU().solveInPlace(dst); - - // dst = P^-1 (L^-T D^-1 L^-1 P b) = A^-1 b - dst = dec().transpositionsP().transpose() * dst; + if(abs(vecD(i)) > tolerance) + dst.row(i) /= vecD(i); + else + dst.row(i).setZero(); } -}; + + // dst = L^-T (D^-1 L^-1 P b) + matrixU().solveInPlace(dst); + + // dst = P^-1 (L^-T D^-1 L^-1 P b) = A^-1 b + dst = m_transpositions.transpose() * dst; } +#endif /** \internal use x = ldlt_object.solve(x); * @@ -581,6 +643,7 @@ MatrixType LDLT::reconstructedMatrix() const /** \cholesky_module * \returns the Cholesky decomposition with full pivoting without square root of \c *this + * \sa MatrixBase::ldlt() */ template inline const LDLT::PlainObject, UpLo> @@ -591,6 +654,7 @@ SelfAdjointView::ldlt() const /** \cholesky_module * \returns the Cholesky decomposition with full pivoting without square root of \c *this + * \sa SelfAdjointView::ldlt() */ template inline const LDLT::PlainObject> diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Cholesky/LLT.h b/testbed/nanogui/ext/eigen/Eigen/src/Cholesky/LLT.h index 2e6189f7..e6c02d80 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Cholesky/LLT.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Cholesky/LLT.h @@ -10,7 +10,7 @@ #ifndef EIGEN_LLT_H #define EIGEN_LLT_H -namespace Eigen { +namespace Eigen { namespace internal{ template struct LLT_Traits; @@ -22,8 +22,8 @@ template struct LLT_Traits; * * \brief Standard Cholesky decomposition (LL^T) of a matrix and associated features * - * \param MatrixType the type of the matrix of which we are computing the LL^T Cholesky decomposition - * \param UpLo the triangular part that will be used for the decompositon: Lower (default) or Upper. + * \tparam _MatrixType the type of the matrix of which we are computing the LL^T Cholesky decomposition + * \tparam _UpLo the triangular part that will be used for the decompositon: Lower (default) or Upper. * The other triangular part won't be read. * * This class performs a LL^T Cholesky decomposition of a symmetric, positive definite @@ -40,8 +40,10 @@ template struct LLT_Traits; * * Example: \include LLT_example.cpp * Output: \verbinclude LLT_example.out - * - * \sa MatrixBase::llt(), class LDLT + * + * This class supports the \link InplaceDecomposition inplace decomposition \endlink mechanism. + * + * \sa MatrixBase::llt(), SelfAdjointView::llt(), class LDLT */ /* HEY THIS DOX IS DISABLED BECAUSE THERE's A BUG EITHER HERE OR IN LDLT ABOUT THAT (OR BOTH) * Note that during the decomposition, only the upper triangular part of A is considered. Therefore, @@ -54,12 +56,12 @@ template class LLT enum { RowsAtCompileTime = MatrixType::RowsAtCompileTime, ColsAtCompileTime = MatrixType::ColsAtCompileTime, - Options = MatrixType::Options, MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime }; typedef typename MatrixType::Scalar Scalar; typedef typename NumTraits::Real RealScalar; - typedef typename MatrixType::Index Index; + typedef Eigen::Index Index; ///< \deprecated since Eigen 3.3 + typedef typename MatrixType::StorageIndex StorageIndex; enum { PacketSize = internal::packet_traits::size, @@ -83,14 +85,30 @@ template class LLT * according to the specified problem \a size. * \sa LLT() */ - LLT(Index size) : m_matrix(size, size), + explicit LLT(Index size) : m_matrix(size, size), m_isInitialized(false) {} - LLT(const MatrixType& matrix) + template + explicit LLT(const EigenBase& matrix) : m_matrix(matrix.rows(), matrix.cols()), m_isInitialized(false) { - compute(matrix); + compute(matrix.derived()); + } + + /** \brief Constructs a LDLT factorization from a given matrix + * + * This overloaded constructor is provided for \link InplaceDecomposition inplace decomposition \endlink when + * \c MatrixType is a Eigen::Ref. + * + * \sa LLT(const EigenBase&) + */ + template + explicit LLT(EigenBase& matrix) + : m_matrix(matrix.derived()), + m_isInitialized(false) + { + compute(matrix.derived()); } /** \returns a view of the upper triangular matrix U */ @@ -115,33 +133,33 @@ template class LLT * Example: \include LLT_solve.cpp * Output: \verbinclude LLT_solve.out * - * \sa solveInPlace(), MatrixBase::llt() + * \sa solveInPlace(), MatrixBase::llt(), SelfAdjointView::llt() */ template - inline const internal::solve_retval + inline const Solve solve(const MatrixBase& b) const { eigen_assert(m_isInitialized && "LLT is not initialized."); eigen_assert(m_matrix.rows()==b.rows() && "LLT::solve(): invalid number of rows of the right hand side matrix b"); - return internal::solve_retval(*this, b.derived()); + return Solve(*this, b.derived()); } - #ifdef EIGEN2_SUPPORT - template - bool solve(const MatrixBase& b, ResultType *result) const - { - *result = this->solve(b); - return true; - } - - bool isPositiveDefinite() const { return true; } - #endif - template void solveInPlace(MatrixBase &bAndX) const; - LLT& compute(const MatrixType& matrix); + template + LLT& compute(const EigenBase& matrix); + + /** \returns an estimate of the reciprocal condition number of the matrix of + * which \c *this is the Cholesky decomposition. + */ + RealScalar rcond() const + { + eigen_assert(m_isInitialized && "LLT is not initialized."); + eigen_assert(m_info == Success && "LLT failed because matrix appears to be negative"); + return internal::rcond_estimate_helper(m_l1_norm, *this); + } /** \returns the LLT decomposition matrix * @@ -167,18 +185,37 @@ template class LLT return m_info; } + /** \returns the adjoint of \c *this, that is, a const reference to the decomposition itself as the underlying matrix is self-adjoint. + * + * This method is provided for compatibility with other matrix decompositions, thus enabling generic code such as: + * \code x = decomposition.adjoint().solve(b) \endcode + */ + const LLT& adjoint() const { return *this; }; + inline Index rows() const { return m_matrix.rows(); } inline Index cols() const { return m_matrix.cols(); } template LLT rankUpdate(const VectorType& vec, const RealScalar& sigma = 1); + #ifndef EIGEN_PARSED_BY_DOXYGEN + template + void _solve_impl(const RhsType &rhs, DstType &dst) const; + #endif + protected: + + static void check_template_parameters() + { + EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar); + } + /** \internal * Used to compute and store L * The strict upper part is not used and even not initialized. */ MatrixType m_matrix; + RealScalar m_l1_norm; bool m_isInitialized; ComputationInfo m_info; }; @@ -188,12 +225,11 @@ namespace internal { template struct llt_inplace; template -static typename MatrixType::Index llt_rank_update_lower(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma) +static Index llt_rank_update_lower(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma) { using std::sqrt; typedef typename MatrixType::Scalar Scalar; typedef typename MatrixType::RealScalar RealScalar; - typedef typename MatrixType::Index Index; typedef typename MatrixType::ColXpr ColXpr; typedef typename internal::remove_all::type ColXprCleaned; typedef typename ColXprCleaned::SegmentReturnType ColXprSegment; @@ -262,11 +298,10 @@ template struct llt_inplace { typedef typename NumTraits::Real RealScalar; template - static typename MatrixType::Index unblocked(MatrixType& mat) + static Index unblocked(MatrixType& mat) { using std::sqrt; - typedef typename MatrixType::Index Index; - + eigen_assert(mat.rows()==mat.cols()); const Index size = mat.rows(); for(Index k = 0; k < size; ++k) @@ -283,15 +318,14 @@ template struct llt_inplace return k; mat.coeffRef(k,k) = x = sqrt(x); if (k>0 && rs>0) A21.noalias() -= A20 * A10.adjoint(); - if (rs>0) A21 *= RealScalar(1)/x; + if (rs>0) A21 /= x; } return -1; } template - static typename MatrixType::Index blocked(MatrixType& m) + static Index blocked(MatrixType& m) { - typedef typename MatrixType::Index Index; eigen_assert(m.rows()==m.cols()); Index size = m.rows(); if(size<32) @@ -316,36 +350,36 @@ template struct llt_inplace Index ret; if((ret=unblocked(A11))>=0) return k+ret; if(rs>0) A11.adjoint().template triangularView().template solveInPlace(A21); - if(rs>0) A22.template selfadjointView().rankUpdate(A21,-1); // bottleneck + if(rs>0) A22.template selfadjointView().rankUpdate(A21,typename NumTraits::Literal(-1)); // bottleneck } return -1; } template - static typename MatrixType::Index rankUpdate(MatrixType& mat, const VectorType& vec, const RealScalar& sigma) + static Index rankUpdate(MatrixType& mat, const VectorType& vec, const RealScalar& sigma) { return Eigen::internal::llt_rank_update_lower(mat, vec, sigma); } }; - + template struct llt_inplace { typedef typename NumTraits::Real RealScalar; template - static EIGEN_STRONG_INLINE typename MatrixType::Index unblocked(MatrixType& mat) + static EIGEN_STRONG_INLINE Index unblocked(MatrixType& mat) { Transpose matt(mat); return llt_inplace::unblocked(matt); } template - static EIGEN_STRONG_INLINE typename MatrixType::Index blocked(MatrixType& mat) + static EIGEN_STRONG_INLINE Index blocked(MatrixType& mat) { Transpose matt(mat); return llt_inplace::blocked(matt); } template - static typename MatrixType::Index rankUpdate(MatrixType& mat, const VectorType& vec, const RealScalar& sigma) + static Index rankUpdate(MatrixType& mat, const VectorType& vec, const RealScalar& sigma) { Transpose matt(mat); return llt_inplace::rankUpdate(matt, vec.conjugate(), sigma); @@ -356,8 +390,8 @@ template struct LLT_Traits { typedef const TriangularView MatrixL; typedef const TriangularView MatrixU; - static inline MatrixL getL(const MatrixType& m) { return m; } - static inline MatrixU getU(const MatrixType& m) { return m.adjoint(); } + static inline MatrixL getL(const MatrixType& m) { return MatrixL(m); } + static inline MatrixU getU(const MatrixType& m) { return MatrixU(m.adjoint()); } static bool inplace_decomposition(MatrixType& m) { return llt_inplace::blocked(m)==-1; } }; @@ -366,8 +400,8 @@ template struct LLT_Traits { typedef const TriangularView MatrixL; typedef const TriangularView MatrixU; - static inline MatrixL getL(const MatrixType& m) { return m.adjoint(); } - static inline MatrixU getU(const MatrixType& m) { return m; } + static inline MatrixL getL(const MatrixType& m) { return MatrixL(m.adjoint()); } + static inline MatrixU getU(const MatrixType& m) { return MatrixU(m); } static bool inplace_decomposition(MatrixType& m) { return llt_inplace::blocked(m)==-1; } }; @@ -382,12 +416,28 @@ template struct LLT_Traits * Output: \verbinclude TutorialLinAlgComputeTwice.out */ template -LLT& LLT::compute(const MatrixType& a) +template +LLT& LLT::compute(const EigenBase& a) { + check_template_parameters(); + eigen_assert(a.rows()==a.cols()); const Index size = a.rows(); m_matrix.resize(size, size); - m_matrix = a; + m_matrix = a.derived(); + + // Compute matrix L1 norm = max abs column sum. + m_l1_norm = RealScalar(0); + // TODO move this code to SelfAdjointView + for (Index col = 0; col < size; ++col) { + RealScalar abs_col_sum; + if (_UpLo == Lower) + abs_col_sum = m_matrix.col(col).tail(size - col).template lpNorm<1>() + m_matrix.row(col).head(col).template lpNorm<1>(); + else + abs_col_sum = m_matrix.col(col).head(col).template lpNorm<1>() + m_matrix.row(col).tail(size - col).template lpNorm<1>(); + if (abs_col_sum > m_l1_norm) + m_l1_norm = abs_col_sum; + } m_isInitialized = true; bool ok = Traits::inplace_decomposition(m_matrix); @@ -415,33 +465,24 @@ LLT<_MatrixType,_UpLo> LLT<_MatrixType,_UpLo>::rankUpdate(const VectorType& v, c return *this; } - -namespace internal { -template -struct solve_retval, Rhs> - : solve_retval_base, Rhs> -{ - typedef LLT<_MatrixType,UpLo> LLTType; - EIGEN_MAKE_SOLVE_HELPERS(LLTType,Rhs) - template void evalTo(Dest& dst) const - { - dst = rhs(); - dec().solveInPlace(dst); - } -}; +#ifndef EIGEN_PARSED_BY_DOXYGEN +template +template +void LLT<_MatrixType,_UpLo>::_solve_impl(const RhsType &rhs, DstType &dst) const +{ + dst = rhs; + solveInPlace(dst); } +#endif /** \internal use x = llt_object.solve(x); - * + * * This is the \em in-place version of solve(). * * \param bAndX represents both the right-hand side matrix b and result x. * - * \returns true always! If you need to check for existence of solutions, use another decomposition like LU, QR, or SVD. - * - * This version avoids a copy when the right hand side matrix b is not - * needed anymore. + * This version avoids a copy when the right hand side matrix b is not needed anymore. * * \sa LLT::solve(), MatrixBase::llt() */ @@ -467,6 +508,7 @@ MatrixType LLT::reconstructedMatrix() const /** \cholesky_module * \returns the LLT decomposition of \c *this + * \sa SelfAdjointView::llt() */ template inline const LLT::PlainObject> @@ -477,6 +519,7 @@ MatrixBase::llt() const /** \cholesky_module * \returns the LLT decomposition of \c *this + * \sa SelfAdjointView::llt() */ template inline const LLT::PlainObject, UpLo> diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Cholesky/LLT_MKL.h b/testbed/nanogui/ext/eigen/Eigen/src/Cholesky/LLT_LAPACKE.h similarity index 69% rename from testbed/nanogui/ext/eigen/Eigen/src/Cholesky/LLT_MKL.h rename to testbed/nanogui/ext/eigen/Eigen/src/Cholesky/LLT_LAPACKE.h index 64daa445..bc6489e6 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Cholesky/LLT_MKL.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Cholesky/LLT_LAPACKE.h @@ -25,78 +25,75 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ******************************************************************************** - * Content : Eigen bindings to Intel(R) MKL + * Content : Eigen bindings to LAPACKe * LLt decomposition based on LAPACKE_?potrf function. ******************************************************************************** */ -#ifndef EIGEN_LLT_MKL_H -#define EIGEN_LLT_MKL_H - -#include "Eigen/src/Core/util/MKL_support.h" -#include +#ifndef EIGEN_LLT_LAPACKE_H +#define EIGEN_LLT_LAPACKE_H namespace Eigen { namespace internal { -template struct mkl_llt; +template struct lapacke_llt; -#define EIGEN_MKL_LLT(EIGTYPE, MKLTYPE, MKLPREFIX) \ -template<> struct mkl_llt \ +#define EIGEN_LAPACKE_LLT(EIGTYPE, BLASTYPE, LAPACKE_PREFIX) \ +template<> struct lapacke_llt \ { \ template \ - static inline typename MatrixType::Index potrf(MatrixType& m, char uplo) \ + static inline Index potrf(MatrixType& m, char uplo) \ { \ lapack_int matrix_order; \ lapack_int size, lda, info, StorageOrder; \ EIGTYPE* a; \ eigen_assert(m.rows()==m.cols()); \ /* Set up parameters for ?potrf */ \ - size = m.rows(); \ + size = convert_index(m.rows()); \ StorageOrder = MatrixType::Flags&RowMajorBit?RowMajor:ColMajor; \ matrix_order = StorageOrder==RowMajor ? LAPACK_ROW_MAJOR : LAPACK_COL_MAJOR; \ a = &(m.coeffRef(0,0)); \ - lda = m.outerStride(); \ + lda = convert_index(m.outerStride()); \ \ - info = LAPACKE_##MKLPREFIX##potrf( matrix_order, uplo, size, (MKLTYPE*)a, lda ); \ - info = (info==0) ? Success : NumericalIssue; \ + info = LAPACKE_##LAPACKE_PREFIX##potrf( matrix_order, uplo, size, (BLASTYPE*)a, lda ); \ + info = (info==0) ? -1 : info>0 ? info-1 : size; \ return info; \ } \ }; \ template<> struct llt_inplace \ { \ template \ - static typename MatrixType::Index blocked(MatrixType& m) \ + static Index blocked(MatrixType& m) \ { \ - return mkl_llt::potrf(m, 'L'); \ + return lapacke_llt::potrf(m, 'L'); \ } \ template \ - static typename MatrixType::Index rankUpdate(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma) \ + static Index rankUpdate(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma) \ { return Eigen::internal::llt_rank_update_lower(mat, vec, sigma); } \ }; \ template<> struct llt_inplace \ { \ template \ - static typename MatrixType::Index blocked(MatrixType& m) \ + static Index blocked(MatrixType& m) \ { \ - return mkl_llt::potrf(m, 'U'); \ + return lapacke_llt::potrf(m, 'U'); \ } \ template \ - static typename MatrixType::Index rankUpdate(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma) \ + static Index rankUpdate(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma) \ { \ Transpose matt(mat); \ return llt_inplace::rankUpdate(matt, vec.conjugate(), sigma); \ } \ }; -EIGEN_MKL_LLT(double, double, d) -EIGEN_MKL_LLT(float, float, s) -EIGEN_MKL_LLT(dcomplex, MKL_Complex16, z) -EIGEN_MKL_LLT(scomplex, MKL_Complex8, c) +EIGEN_LAPACKE_LLT(double, double, d) +EIGEN_LAPACKE_LLT(float, float, s) +EIGEN_LAPACKE_LLT(dcomplex, lapack_complex_double, z) +EIGEN_LAPACKE_LLT(scomplex, lapack_complex_float, c) } // end namespace internal } // end namespace Eigen -#endif // EIGEN_LLT_MKL_H +#endif // EIGEN_LLT_LAPACKE_H diff --git a/testbed/nanogui/ext/eigen/Eigen/src/CholmodSupport/CMakeLists.txt b/testbed/nanogui/ext/eigen/Eigen/src/CholmodSupport/CMakeLists.txt deleted file mode 100644 index 814dfa61..00000000 --- a/testbed/nanogui/ext/eigen/Eigen/src/CholmodSupport/CMakeLists.txt +++ /dev/null @@ -1,6 +0,0 @@ -FILE(GLOB Eigen_CholmodSupport_SRCS "*.h") - -INSTALL(FILES - ${Eigen_CholmodSupport_SRCS} - DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen/src/CholmodSupport COMPONENT Devel - ) diff --git a/testbed/nanogui/ext/eigen/Eigen/src/CholmodSupport/CholmodSupport.h b/testbed/nanogui/ext/eigen/Eigen/src/CholmodSupport/CholmodSupport.h index c449960d..61faf43b 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/CholmodSupport/CholmodSupport.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/CholmodSupport/CholmodSupport.h @@ -14,46 +14,52 @@ namespace Eigen { namespace internal { -template -void cholmod_configure_matrix(CholmodType& mat) -{ - if (internal::is_same::value) - { - mat.xtype = CHOLMOD_REAL; - mat.dtype = CHOLMOD_SINGLE; - } - else if (internal::is_same::value) - { +template struct cholmod_configure_matrix; + +template<> struct cholmod_configure_matrix { + template + static void run(CholmodType& mat) { mat.xtype = CHOLMOD_REAL; mat.dtype = CHOLMOD_DOUBLE; } - else if (internal::is_same >::value) - { - mat.xtype = CHOLMOD_COMPLEX; - mat.dtype = CHOLMOD_SINGLE; - } - else if (internal::is_same >::value) - { +}; + +template<> struct cholmod_configure_matrix > { + template + static void run(CholmodType& mat) { mat.xtype = CHOLMOD_COMPLEX; mat.dtype = CHOLMOD_DOUBLE; } - else - { - eigen_assert(false && "Scalar type not supported by CHOLMOD"); - } -} +}; + +// Other scalar types are not yet supported by Cholmod +// template<> struct cholmod_configure_matrix { +// template +// static void run(CholmodType& mat) { +// mat.xtype = CHOLMOD_REAL; +// mat.dtype = CHOLMOD_SINGLE; +// } +// }; +// +// template<> struct cholmod_configure_matrix > { +// template +// static void run(CholmodType& mat) { +// mat.xtype = CHOLMOD_COMPLEX; +// mat.dtype = CHOLMOD_SINGLE; +// } +// }; } // namespace internal /** Wraps the Eigen sparse matrix \a mat into a Cholmod sparse matrix object. * Note that the data are shared. */ -template -cholmod_sparse viewAsCholmod(SparseMatrix<_Scalar,_Options,_Index>& mat) +template +cholmod_sparse viewAsCholmod(Ref > mat) { cholmod_sparse res; res.nzmax = mat.nonZeros(); - res.nrow = mat.rows();; + res.nrow = mat.rows(); res.ncol = mat.cols(); res.p = mat.outerIndexPtr(); res.i = mat.innerIndexPtr(); @@ -74,11 +80,11 @@ cholmod_sparse viewAsCholmod(SparseMatrix<_Scalar,_Options,_Index>& mat) res.dtype = 0; res.stype = -1; - if (internal::is_same<_Index,int>::value) + if (internal::is_same<_StorageIndex,int>::value) { res.itype = CHOLMOD_INT; } - else if (internal::is_same<_Index,UF_long>::value) + else if (internal::is_same<_StorageIndex,long>::value) { res.itype = CHOLMOD_LONG; } @@ -88,7 +94,7 @@ cholmod_sparse viewAsCholmod(SparseMatrix<_Scalar,_Options,_Index>& mat) } // setup res.xtype - internal::cholmod_configure_matrix<_Scalar>(res); + internal::cholmod_configure_matrix<_Scalar>::run(res); res.stype = 0; @@ -98,19 +104,29 @@ cholmod_sparse viewAsCholmod(SparseMatrix<_Scalar,_Options,_Index>& mat) template const cholmod_sparse viewAsCholmod(const SparseMatrix<_Scalar,_Options,_Index>& mat) { - cholmod_sparse res = viewAsCholmod(mat.const_cast_derived()); + cholmod_sparse res = viewAsCholmod(Ref >(mat.const_cast_derived())); + return res; +} + +template +const cholmod_sparse viewAsCholmod(const SparseVector<_Scalar,_Options,_Index>& mat) +{ + cholmod_sparse res = viewAsCholmod(Ref >(mat.const_cast_derived())); return res; } /** Returns a view of the Eigen sparse matrix \a mat as Cholmod sparse matrix. * The data are not copied but shared. */ template -cholmod_sparse viewAsCholmod(const SparseSelfAdjointView, UpLo>& mat) +cholmod_sparse viewAsCholmod(const SparseSelfAdjointView, UpLo>& mat) { - cholmod_sparse res = viewAsCholmod(mat.matrix().const_cast_derived()); + cholmod_sparse res = viewAsCholmod(Ref >(mat.matrix().const_cast_derived())); if(UpLo==Upper) res.stype = 1; if(UpLo==Lower) res.stype = -1; + // swap stype for rowmajor matrices (only works for real matrices) + EIGEN_STATIC_ASSERT((_Options & RowMajorBit) == 0 || NumTraits<_Scalar>::IsComplex == 0, THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES); + if(_Options & RowMajorBit) res.stype *=-1; return res; } @@ -131,21 +147,59 @@ cholmod_dense viewAsCholmod(MatrixBase& mat) res.x = (void*)(mat.derived().data()); res.z = 0; - internal::cholmod_configure_matrix(res); + internal::cholmod_configure_matrix::run(res); return res; } /** Returns a view of the Cholmod sparse matrix \a cm as an Eigen sparse matrix. * The data are not copied but shared. */ -template -MappedSparseMatrix viewAsEigen(cholmod_sparse& cm) +template +MappedSparseMatrix viewAsEigen(cholmod_sparse& cm) { - return MappedSparseMatrix - (cm.nrow, cm.ncol, static_cast(cm.p)[cm.ncol], - static_cast(cm.p), static_cast(cm.i),static_cast(cm.x) ); + return MappedSparseMatrix + (cm.nrow, cm.ncol, static_cast(cm.p)[cm.ncol], + static_cast(cm.p), static_cast(cm.i),static_cast(cm.x) ); } +namespace internal { + +// template specializations for int and long that call the correct cholmod method + +#define EIGEN_CHOLMOD_SPECIALIZE0(ret, name) \ + template ret cm_ ## name (cholmod_common &Common) { return cholmod_ ## name (&Common); } \ + template<> ret cm_ ## name (cholmod_common &Common) { return cholmod_l_ ## name (&Common); } + +#define EIGEN_CHOLMOD_SPECIALIZE1(ret, name, t1, a1) \ + template ret cm_ ## name (t1& a1, cholmod_common &Common) { return cholmod_ ## name (&a1, &Common); } \ + template<> ret cm_ ## name (t1& a1, cholmod_common &Common) { return cholmod_l_ ## name (&a1, &Common); } + +EIGEN_CHOLMOD_SPECIALIZE0(int, start) +EIGEN_CHOLMOD_SPECIALIZE0(int, finish) + +EIGEN_CHOLMOD_SPECIALIZE1(int, free_factor, cholmod_factor*, L) +EIGEN_CHOLMOD_SPECIALIZE1(int, free_dense, cholmod_dense*, X) +EIGEN_CHOLMOD_SPECIALIZE1(int, free_sparse, cholmod_sparse*, A) + +EIGEN_CHOLMOD_SPECIALIZE1(cholmod_factor*, analyze, cholmod_sparse, A) + +template cholmod_dense* cm_solve (int sys, cholmod_factor& L, cholmod_dense& B, cholmod_common &Common) { return cholmod_solve (sys, &L, &B, &Common); } +template<> cholmod_dense* cm_solve (int sys, cholmod_factor& L, cholmod_dense& B, cholmod_common &Common) { return cholmod_l_solve (sys, &L, &B, &Common); } + +template cholmod_sparse* cm_spsolve (int sys, cholmod_factor& L, cholmod_sparse& B, cholmod_common &Common) { return cholmod_spsolve (sys, &L, &B, &Common); } +template<> cholmod_sparse* cm_spsolve (int sys, cholmod_factor& L, cholmod_sparse& B, cholmod_common &Common) { return cholmod_l_spsolve (sys, &L, &B, &Common); } + +template +int cm_factorize_p (cholmod_sparse* A, double beta[2], _StorageIndex* fset, std::size_t fsize, cholmod_factor* L, cholmod_common &Common) { return cholmod_factorize_p (A, beta, fset, fsize, L, &Common); } +template<> +int cm_factorize_p (cholmod_sparse* A, double beta[2], long* fset, std::size_t fsize, cholmod_factor* L, cholmod_common &Common) { return cholmod_l_factorize_p (A, beta, fset, fsize, L, &Common); } + +#undef EIGEN_CHOLMOD_SPECIALIZE0 +#undef EIGEN_CHOLMOD_SPECIALIZE1 + +} // namespace internal + + enum CholmodMode { CholmodAuto, CholmodSimplicialLLt, CholmodSupernodalLLt, CholmodLDLt }; @@ -157,49 +211,56 @@ enum CholmodMode { * \sa class CholmodSupernodalLLT, class CholmodSimplicialLDLT, class CholmodSimplicialLLT */ template -class CholmodBase : internal::noncopyable +class CholmodBase : public SparseSolverBase { + protected: + typedef SparseSolverBase Base; + using Base::derived; + using Base::m_isInitialized; public: typedef _MatrixType MatrixType; enum { UpLo = _UpLo }; typedef typename MatrixType::Scalar Scalar; typedef typename MatrixType::RealScalar RealScalar; typedef MatrixType CholMatrixType; - typedef typename MatrixType::Index Index; + typedef typename MatrixType::StorageIndex StorageIndex; + enum { + ColsAtCompileTime = MatrixType::ColsAtCompileTime, + MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime + }; public: CholmodBase() - : m_cholmodFactor(0), m_info(Success), m_isInitialized(false) + : m_cholmodFactor(0), m_info(Success), m_factorizationIsOk(false), m_analysisIsOk(false) { - m_shiftOffset[0] = m_shiftOffset[1] = RealScalar(0.0); - cholmod_start(&m_cholmod); + EIGEN_STATIC_ASSERT((internal::is_same::value), CHOLMOD_SUPPORTS_DOUBLE_PRECISION_ONLY); + m_shiftOffset[0] = m_shiftOffset[1] = 0.0; + internal::cm_start(m_cholmod); } - CholmodBase(const MatrixType& matrix) - : m_cholmodFactor(0), m_info(Success), m_isInitialized(false) + explicit CholmodBase(const MatrixType& matrix) + : m_cholmodFactor(0), m_info(Success), m_factorizationIsOk(false), m_analysisIsOk(false) { - m_shiftOffset[0] = m_shiftOffset[1] = RealScalar(0.0); - cholmod_start(&m_cholmod); + EIGEN_STATIC_ASSERT((internal::is_same::value), CHOLMOD_SUPPORTS_DOUBLE_PRECISION_ONLY); + m_shiftOffset[0] = m_shiftOffset[1] = 0.0; + internal::cm_start(m_cholmod); compute(matrix); } ~CholmodBase() { if(m_cholmodFactor) - cholmod_free_factor(&m_cholmodFactor, &m_cholmod); - cholmod_finish(&m_cholmod); + internal::cm_free_factor(m_cholmodFactor, m_cholmod); + internal::cm_finish(m_cholmod); } - inline Index cols() const { return m_cholmodFactor->n; } - inline Index rows() const { return m_cholmodFactor->n; } - - Derived& derived() { return *static_cast(this); } - const Derived& derived() const { return *static_cast(this); } + inline StorageIndex cols() const { return internal::convert_index(m_cholmodFactor->n); } + inline StorageIndex rows() const { return internal::convert_index(m_cholmodFactor->n); } /** \brief Reports whether previous computation was successful. * - * \returns \c Success if computation was succesful, + * \returns \c Success if computation was successful, * \c NumericalIssue if the matrix.appears to be negative. */ ComputationInfo info() const @@ -216,34 +277,6 @@ class CholmodBase : internal::noncopyable return derived(); } - /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. - * - * \sa compute() - */ - template - inline const internal::solve_retval - solve(const MatrixBase& b) const - { - eigen_assert(m_isInitialized && "LLT is not initialized."); - eigen_assert(rows()==b.rows() - && "CholmodDecomposition::solve(): invalid number of rows of the right hand side matrix b"); - return internal::solve_retval(*this, b.derived()); - } - - /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. - * - * \sa compute() - */ - template - inline const internal::sparse_solve_retval - solve(const SparseMatrixBase& b) const - { - eigen_assert(m_isInitialized && "LLT is not initialized."); - eigen_assert(rows()==b.rows() - && "CholmodDecomposition::solve(): invalid number of rows of the right hand side matrix b"); - return internal::sparse_solve_retval(*this, b.derived()); - } - /** Performs a symbolic decomposition on the sparsity pattern of \a matrix. * * This function is particularly useful when solving for several problems having the same structure. @@ -254,11 +287,11 @@ class CholmodBase : internal::noncopyable { if(m_cholmodFactor) { - cholmod_free_factor(&m_cholmodFactor, &m_cholmod); + internal::cm_free_factor(m_cholmodFactor, m_cholmod); m_cholmodFactor = 0; } cholmod_sparse A = viewAsCholmod(matrix.template selfadjointView()); - m_cholmodFactor = cholmod_analyze(&A, &m_cholmod); + m_cholmodFactor = internal::cm_analyze(A, m_cholmod); this->m_isInitialized = true; this->m_info = Success; @@ -276,8 +309,8 @@ class CholmodBase : internal::noncopyable { eigen_assert(m_analysisIsOk && "You must first call analyzePattern()"); cholmod_sparse A = viewAsCholmod(matrix.template selfadjointView()); - cholmod_factorize_p(&A, m_shiftOffset, 0, 0, m_cholmodFactor, &m_cholmod); - + internal::cm_factorize_p(&A, m_shiftOffset, 0, 0, m_cholmodFactor, m_cholmod); + // If the factorization failed, minor is the column at which it did. On success minor == n. this->m_info = (m_cholmodFactor->minor == m_cholmodFactor->n ? Success : NumericalIssue); m_factorizationIsOk = true; @@ -290,29 +323,32 @@ class CholmodBase : internal::noncopyable #ifndef EIGEN_PARSED_BY_DOXYGEN /** \internal */ template - void _solve(const MatrixBase &b, MatrixBase &dest) const + void _solve_impl(const MatrixBase &b, MatrixBase &dest) const { eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()"); const Index size = m_cholmodFactor->n; EIGEN_UNUSED_VARIABLE(size); eigen_assert(size==b.rows()); + + // Cholmod needs column-major storage without inner-stride, which corresponds to the default behavior of Ref. + Ref > b_ref(b.derived()); - // note: cd stands for Cholmod Dense - Rhs& b_ref(b.const_cast_derived()); cholmod_dense b_cd = viewAsCholmod(b_ref); - cholmod_dense* x_cd = cholmod_solve(CHOLMOD_A, m_cholmodFactor, &b_cd, &m_cholmod); + cholmod_dense* x_cd = internal::cm_solve(CHOLMOD_A, *m_cholmodFactor, b_cd, m_cholmod); if(!x_cd) { this->m_info = NumericalIssue; + return; } // TODO optimize this copy by swapping when possible (be careful with alignment, etc.) + // NOTE Actually, the copy can be avoided by calling cholmod_solve2 instead of cholmod_solve dest = Matrix::Map(reinterpret_cast(x_cd->x),b.rows(),b.cols()); - cholmod_free_dense(&x_cd, &m_cholmod); + internal::cm_free_dense(x_cd, m_cholmod); } /** \internal */ - template - void _solve(const SparseMatrix &b, SparseMatrix &dest) const + template + void _solve_impl(const SparseMatrixBase &b, SparseMatrixBase &dest) const { eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()"); const Index size = m_cholmodFactor->n; @@ -320,15 +356,18 @@ class CholmodBase : internal::noncopyable eigen_assert(size==b.rows()); // note: cs stands for Cholmod Sparse - cholmod_sparse b_cs = viewAsCholmod(b); - cholmod_sparse* x_cs = cholmod_spsolve(CHOLMOD_A, m_cholmodFactor, &b_cs, &m_cholmod); + Ref > b_ref(b.const_cast_derived()); + cholmod_sparse b_cs = viewAsCholmod(b_ref); + cholmod_sparse* x_cs = internal::cm_spsolve(CHOLMOD_A, *m_cholmodFactor, b_cs, m_cholmod); if(!x_cs) { this->m_info = NumericalIssue; + return; } // TODO optimize this copy by swapping when possible (be careful with alignment, etc.) - dest = viewAsEigen(*x_cs); - cholmod_free_sparse(&x_cs, &m_cholmod); + // NOTE cholmod_spsolve in fact just calls the dense solver for blocks of 4 columns at a time (similar to Eigen's sparse solver) + dest.derived() = viewAsEigen(*x_cs); + internal::cm_free_sparse(x_cs, m_cholmod); } #endif // EIGEN_PARSED_BY_DOXYGEN @@ -344,10 +383,61 @@ class CholmodBase : internal::noncopyable */ Derived& setShift(const RealScalar& offset) { - m_shiftOffset[0] = offset; + m_shiftOffset[0] = double(offset); return derived(); } + /** \returns the determinant of the underlying matrix from the current factorization */ + Scalar determinant() const + { + using std::exp; + return exp(logDeterminant()); + } + + /** \returns the log determinant of the underlying matrix from the current factorization */ + Scalar logDeterminant() const + { + using std::log; + using numext::real; + eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()"); + + RealScalar logDet = 0; + Scalar *x = static_cast(m_cholmodFactor->x); + if (m_cholmodFactor->is_super) + { + // Supernodal factorization stored as a packed list of dense column-major blocs, + // as described by the following structure: + + // super[k] == index of the first column of the j-th super node + StorageIndex *super = static_cast(m_cholmodFactor->super); + // pi[k] == offset to the description of row indices + StorageIndex *pi = static_cast(m_cholmodFactor->pi); + // px[k] == offset to the respective dense block + StorageIndex *px = static_cast(m_cholmodFactor->px); + + Index nb_super_nodes = m_cholmodFactor->nsuper; + for (Index k=0; k < nb_super_nodes; ++k) + { + StorageIndex ncols = super[k + 1] - super[k]; + StorageIndex nrows = pi[k + 1] - pi[k]; + + Map, 0, InnerStride<> > sk(x + px[k], ncols, InnerStride<>(nrows+1)); + logDet += sk.real().log().sum(); + } + } + else + { + // Simplicial factorization stored as standard CSC matrix. + StorageIndex *p = static_cast(m_cholmodFactor->p); + Index size = m_cholmodFactor->n; + for (Index k=0; kis_ll) + logDet *= 2.0; + return logDet; + }; + template void dumpMemory(Stream& /*s*/) {} @@ -355,9 +445,8 @@ class CholmodBase : internal::noncopyable protected: mutable cholmod_common m_cholmod; cholmod_factor* m_cholmodFactor; - RealScalar m_shiftOffset[2]; + double m_shiftOffset[2]; mutable ComputationInfo m_info; - bool m_isInitialized; int m_factorizationIsOk; int m_analysisIsOk; }; @@ -376,9 +465,13 @@ class CholmodBase : internal::noncopyable * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower * or Upper. Default is Lower. * + * \implsparsesolverconcept + * * This class supports all kind of SparseMatrix<>: row or column major; upper, lower, or both; compressed or non compressed. * - * \sa \ref TutorialSparseDirectSolvers, class CholmodSupernodalLLT, class SimplicialLLT + * \warning Only double precision real and complex scalar types are supported by Cholmod. + * + * \sa \ref TutorialSparseSolverConcept, class CholmodSupernodalLLT, class SimplicialLLT */ template class CholmodSimplicialLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimplicialLLT<_MatrixType, _UpLo> > @@ -395,7 +488,7 @@ class CholmodSimplicialLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimpl CholmodSimplicialLLT(const MatrixType& matrix) : Base() { init(); - compute(matrix); + this->compute(matrix); } ~CholmodSimplicialLLT() {} @@ -423,9 +516,13 @@ class CholmodSimplicialLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimpl * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower * or Upper. Default is Lower. * + * \implsparsesolverconcept + * * This class supports all kind of SparseMatrix<>: row or column major; upper, lower, or both; compressed or non compressed. * - * \sa \ref TutorialSparseDirectSolvers, class CholmodSupernodalLLT, class SimplicialLDLT + * \warning Only double precision real and complex scalar types are supported by Cholmod. + * + * \sa \ref TutorialSparseSolverConcept, class CholmodSupernodalLLT, class SimplicialLDLT */ template class CholmodSimplicialLDLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimplicialLDLT<_MatrixType, _UpLo> > @@ -442,7 +539,7 @@ class CholmodSimplicialLDLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimp CholmodSimplicialLDLT(const MatrixType& matrix) : Base() { init(); - compute(matrix); + this->compute(matrix); } ~CholmodSimplicialLDLT() {} @@ -468,9 +565,13 @@ class CholmodSimplicialLDLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimp * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower * or Upper. Default is Lower. * + * \implsparsesolverconcept + * * This class supports all kind of SparseMatrix<>: row or column major; upper, lower, or both; compressed or non compressed. * - * \sa \ref TutorialSparseDirectSolvers + * \warning Only double precision real and complex scalar types are supported by Cholmod. + * + * \sa \ref TutorialSparseSolverConcept */ template class CholmodSupernodalLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSupernodalLLT<_MatrixType, _UpLo> > @@ -487,7 +588,7 @@ class CholmodSupernodalLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSuper CholmodSupernodalLLT(const MatrixType& matrix) : Base() { init(); - compute(matrix); + this->compute(matrix); } ~CholmodSupernodalLLT() {} @@ -515,9 +616,13 @@ class CholmodSupernodalLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSuper * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower * or Upper. Default is Lower. * + * \implsparsesolverconcept + * * This class supports all kind of SparseMatrix<>: row or column major; upper, lower, or both; compressed or non compressed. * - * \sa \ref TutorialSparseDirectSolvers + * \warning Only double precision real and complex scalar types are supported by Cholmod. + * + * \sa \ref TutorialSparseSolverConcept */ template class CholmodDecomposition : public CholmodBase<_MatrixType, _UpLo, CholmodDecomposition<_MatrixType, _UpLo> > @@ -534,7 +639,7 @@ class CholmodDecomposition : public CholmodBase<_MatrixType, _UpLo, CholmodDecom CholmodDecomposition(const MatrixType& matrix) : Base() { init(); - compute(matrix); + this->compute(matrix); } ~CholmodDecomposition() {} @@ -572,36 +677,6 @@ class CholmodDecomposition : public CholmodBase<_MatrixType, _UpLo, CholmodDecom } }; -namespace internal { - -template -struct solve_retval, Rhs> - : solve_retval_base, Rhs> -{ - typedef CholmodBase<_MatrixType,_UpLo,Derived> Dec; - EIGEN_MAKE_SOLVE_HELPERS(Dec,Rhs) - - template void evalTo(Dest& dst) const - { - dec()._solve(rhs(),dst); - } -}; - -template -struct sparse_solve_retval, Rhs> - : sparse_solve_retval_base, Rhs> -{ - typedef CholmodBase<_MatrixType,_UpLo,Derived> Dec; - EIGEN_MAKE_SPARSE_SOLVE_HELPERS(Dec,Rhs) - - template void evalTo(Dest& dst) const - { - dec()._solve(rhs(),dst); - } -}; - -} // end namespace internal - } // end namespace Eigen #endif // EIGEN_CHOLMODSUPPORT_H diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/ArithmeticSequence.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/ArithmeticSequence.h new file mode 100644 index 00000000..ada1571f --- /dev/null +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/ArithmeticSequence.h @@ -0,0 +1,350 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2017 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_ARITHMETIC_SEQUENCE_H +#define EIGEN_ARITHMETIC_SEQUENCE_H + +namespace Eigen { + +namespace internal { + +#if (!EIGEN_HAS_CXX11) || !((!EIGEN_COMP_GNUC) || EIGEN_COMP_GNUC>=48) +template struct aseq_negate {}; + +template<> struct aseq_negate { + typedef Index type; +}; + +template struct aseq_negate > { + typedef FixedInt<-N> type; +}; + +// Compilation error in the following case: +template<> struct aseq_negate > {}; + +template::value, + bool SizeIsSymbolic =Symbolic::is_symbolic::value> +struct aseq_reverse_first_type { + typedef Index type; +}; + +template +struct aseq_reverse_first_type { + typedef Symbolic::AddExpr > >, + Symbolic::ValueExpr > + > type; +}; + +template +struct aseq_reverse_first_type_aux { + typedef Index type; +}; + +template +struct aseq_reverse_first_type_aux::type> { + typedef FixedInt<(SizeType::value-1)*IncrType::value> type; +}; + +template +struct aseq_reverse_first_type { + typedef typename aseq_reverse_first_type_aux::type Aux; + typedef Symbolic::AddExpr > type; +}; + +template +struct aseq_reverse_first_type { + typedef Symbolic::AddExpr > >, + Symbolic::ValueExpr >, + Symbolic::ValueExpr<> > type; +}; +#endif + +// Helper to cleanup the type of the increment: +template struct cleanup_seq_incr { + typedef typename cleanup_index_type::type type; +}; + +} + +//-------------------------------------------------------------------------------- +// seq(first,last,incr) and seqN(first,size,incr) +//-------------------------------------------------------------------------------- + +template > +class ArithmeticSequence; + +template +ArithmeticSequence::type, + typename internal::cleanup_index_type::type, + typename internal::cleanup_seq_incr::type > +seqN(FirstType first, SizeType size, IncrType incr); + +/** \class ArithmeticSequence + * \ingroup Core_Module + * + * This class represents an arithmetic progression \f$ a_0, a_1, a_2, ..., a_{n-1}\f$ defined by + * its \em first value \f$ a_0 \f$, its \em size (aka length) \em n, and the \em increment (aka stride) + * that is equal to \f$ a_{i+1}-a_{i}\f$ for any \em i. + * + * It is internally used as the return type of the Eigen::seq and Eigen::seqN functions, and as the input arguments + * of DenseBase::operator()(const RowIndices&, const ColIndices&), and most of the time this is the + * only way it is used. + * + * \tparam FirstType type of the first element, usually an Index, + * but internally it can be a symbolic expression + * \tparam SizeType type representing the size of the sequence, usually an Index + * or a compile time integral constant. Internally, it can also be a symbolic expression + * \tparam IncrType type of the increment, can be a runtime Index, or a compile time integral constant (default is compile-time 1) + * + * \sa Eigen::seq, Eigen::seqN, DenseBase::operator()(const RowIndices&, const ColIndices&), class IndexedView + */ +template +class ArithmeticSequence +{ +public: + ArithmeticSequence(FirstType first, SizeType size) : m_first(first), m_size(size) {} + ArithmeticSequence(FirstType first, SizeType size, IncrType incr) : m_first(first), m_size(size), m_incr(incr) {} + + enum { + SizeAtCompileTime = internal::get_fixed_value::value, + IncrAtCompileTime = internal::get_fixed_value::value + }; + + /** \returns the size, i.e., number of elements, of the sequence */ + Index size() const { return m_size; } + + /** \returns the first element \f$ a_0 \f$ in the sequence */ + Index first() const { return m_first; } + + /** \returns the value \f$ a_i \f$ at index \a i in the sequence. */ + Index operator[](Index i) const { return m_first + i * m_incr; } + + const FirstType& firstObject() const { return m_first; } + const SizeType& sizeObject() const { return m_size; } + const IncrType& incrObject() const { return m_incr; } + +protected: + FirstType m_first; + SizeType m_size; + IncrType m_incr; + +public: + +#if EIGEN_HAS_CXX11 && ((!EIGEN_COMP_GNUC) || EIGEN_COMP_GNUC>=48) + auto reverse() const -> decltype(Eigen::seqN(m_first+(m_size+fix<-1>())*m_incr,m_size,-m_incr)) { + return seqN(m_first+(m_size+fix<-1>())*m_incr,m_size,-m_incr); + } +#else +protected: + typedef typename internal::aseq_negate::type ReverseIncrType; + typedef typename internal::aseq_reverse_first_type::type ReverseFirstType; +public: + ArithmeticSequence + reverse() const { + return seqN(m_first+(m_size+fix<-1>())*m_incr,m_size,-m_incr); + } +#endif +}; + +/** \returns an ArithmeticSequence starting at \a first, of length \a size, and increment \a incr + * + * \sa seqN(FirstType,SizeType), seq(FirstType,LastType,IncrType) */ +template +ArithmeticSequence::type,typename internal::cleanup_index_type::type,typename internal::cleanup_seq_incr::type > +seqN(FirstType first, SizeType size, IncrType incr) { + return ArithmeticSequence::type,typename internal::cleanup_index_type::type,typename internal::cleanup_seq_incr::type>(first,size,incr); +} + +/** \returns an ArithmeticSequence starting at \a first, of length \a size, and unit increment + * + * \sa seqN(FirstType,SizeType,IncrType), seq(FirstType,LastType) */ +template +ArithmeticSequence::type,typename internal::cleanup_index_type::type > +seqN(FirstType first, SizeType size) { + return ArithmeticSequence::type,typename internal::cleanup_index_type::type>(first,size); +} + +#ifdef EIGEN_PARSED_BY_DOXYGEN + +/** \returns an ArithmeticSequence starting at \a f, up (or down) to \a l, and with positive (or negative) increment \a incr + * + * It is essentially an alias to: + * \code + * seqN(f, (l-f+incr)/incr, incr); + * \endcode + * + * \sa seqN(FirstType,SizeType,IncrType), seq(FirstType,LastType) + */ +template +auto seq(FirstType f, LastType l, IncrType incr); + +/** \returns an ArithmeticSequence starting at \a f, up (or down) to \a l, and unit increment + * + * It is essentially an alias to: + * \code + * seqN(f,l-f+1); + * \endcode + * + * \sa seqN(FirstType,SizeType), seq(FirstType,LastType,IncrType) + */ +template +auto seq(FirstType f, LastType l); + +#else // EIGEN_PARSED_BY_DOXYGEN + +#if EIGEN_HAS_CXX11 +template +auto seq(FirstType f, LastType l) -> decltype(seqN(typename internal::cleanup_index_type::type(f), + ( typename internal::cleanup_index_type::type(l) + - typename internal::cleanup_index_type::type(f)+fix<1>()))) +{ + return seqN(typename internal::cleanup_index_type::type(f), + (typename internal::cleanup_index_type::type(l) + -typename internal::cleanup_index_type::type(f)+fix<1>())); +} + +template +auto seq(FirstType f, LastType l, IncrType incr) + -> decltype(seqN(typename internal::cleanup_index_type::type(f), + ( typename internal::cleanup_index_type::type(l) + - typename internal::cleanup_index_type::type(f)+typename internal::cleanup_seq_incr::type(incr) + ) / typename internal::cleanup_seq_incr::type(incr), + typename internal::cleanup_seq_incr::type(incr))) +{ + typedef typename internal::cleanup_seq_incr::type CleanedIncrType; + return seqN(typename internal::cleanup_index_type::type(f), + ( typename internal::cleanup_index_type::type(l) + -typename internal::cleanup_index_type::type(f)+CleanedIncrType(incr)) / CleanedIncrType(incr), + CleanedIncrType(incr)); +} +#else + +template +typename internal::enable_if::value || Symbolic::is_symbolic::value), + ArithmeticSequence::type,Index> >::type +seq(FirstType f, LastType l) +{ + return seqN(typename internal::cleanup_index_type::type(f), + Index((typename internal::cleanup_index_type::type(l)-typename internal::cleanup_index_type::type(f)+fix<1>()))); +} + +template +typename internal::enable_if::value, + ArithmeticSequence,Symbolic::ValueExpr<> >, + Symbolic::ValueExpr > > > >::type +seq(const Symbolic::BaseExpr &f, LastType l) +{ + return seqN(f.derived(),(typename internal::cleanup_index_type::type(l)-f.derived()+fix<1>())); +} + +template +typename internal::enable_if::value, + ArithmeticSequence::type, + Symbolic::AddExpr >, + Symbolic::ValueExpr > > > >::type +seq(FirstType f, const Symbolic::BaseExpr &l) +{ + return seqN(typename internal::cleanup_index_type::type(f),(l.derived()-typename internal::cleanup_index_type::type(f)+fix<1>())); +} + +template +ArithmeticSequence >,Symbolic::ValueExpr > > > +seq(const Symbolic::BaseExpr &f, const Symbolic::BaseExpr &l) +{ + return seqN(f.derived(),(l.derived()-f.derived()+fix<1>())); +} + + +template +typename internal::enable_if::value || Symbolic::is_symbolic::value), + ArithmeticSequence::type,Index,typename internal::cleanup_seq_incr::type> >::type +seq(FirstType f, LastType l, IncrType incr) +{ + typedef typename internal::cleanup_seq_incr::type CleanedIncrType; + return seqN(typename internal::cleanup_index_type::type(f), + Index((typename internal::cleanup_index_type::type(l)-typename internal::cleanup_index_type::type(f)+CleanedIncrType(incr))/CleanedIncrType(incr)), incr); +} + +template +typename internal::enable_if::value, + ArithmeticSequence, + Symbolic::ValueExpr<> >, + Symbolic::ValueExpr::type> >, + Symbolic::ValueExpr::type> >, + typename internal::cleanup_seq_incr::type> >::type +seq(const Symbolic::BaseExpr &f, LastType l, IncrType incr) +{ + typedef typename internal::cleanup_seq_incr::type CleanedIncrType; + return seqN(f.derived(),(typename internal::cleanup_index_type::type(l)-f.derived()+CleanedIncrType(incr))/CleanedIncrType(incr), incr); +} + +template +typename internal::enable_if::value, + ArithmeticSequence::type, + Symbolic::QuotientExpr >, + Symbolic::ValueExpr::type> >, + Symbolic::ValueExpr::type> >, + typename internal::cleanup_seq_incr::type> >::type +seq(FirstType f, const Symbolic::BaseExpr &l, IncrType incr) +{ + typedef typename internal::cleanup_seq_incr::type CleanedIncrType; + return seqN(typename internal::cleanup_index_type::type(f), + (l.derived()-typename internal::cleanup_index_type::type(f)+CleanedIncrType(incr))/CleanedIncrType(incr), incr); +} + +template +ArithmeticSequence >, + Symbolic::ValueExpr::type> >, + Symbolic::ValueExpr::type> >, + typename internal::cleanup_seq_incr::type> +seq(const Symbolic::BaseExpr &f, const Symbolic::BaseExpr &l, IncrType incr) +{ + typedef typename internal::cleanup_seq_incr::type CleanedIncrType; + return seqN(f.derived(),(l.derived()-f.derived()+CleanedIncrType(incr))/CleanedIncrType(incr), incr); +} +#endif + +#endif // EIGEN_PARSED_BY_DOXYGEN + +namespace internal { + +// Convert a symbolic span into a usable one (i.e., remove last/end "keywords") +template +struct make_size_type { + typedef typename internal::conditional::value, Index, T>::type type; +}; + +template +struct IndexedViewCompatibleType, XprSize> { + typedef ArithmeticSequence::type,IncrType> type; +}; + +template +ArithmeticSequence::type,IncrType> +makeIndexedViewCompatible(const ArithmeticSequence& ids, Index size,SpecializedType) { + return ArithmeticSequence::type,IncrType>( + eval_expr_given_size(ids.firstObject(),size),eval_expr_given_size(ids.sizeObject(),size),ids.incrObject()); +} + +template +struct get_compile_time_incr > { + enum { value = get_fixed_value::value }; +}; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_ARITHMETIC_SEQUENCE_H diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/Array.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/Array.h index 0ab03eff..0d34269f 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/Array.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/Array.h @@ -12,7 +12,16 @@ namespace Eigen { -/** \class Array +namespace internal { +template +struct traits > : traits > +{ + typedef ArrayXpr XprKind; + typedef ArrayBase > XprBase; +}; +} + +/** \class Array * \ingroup Core_Module * * \brief General-purpose arrays with easy API for coefficient-wise operations @@ -24,20 +33,14 @@ namespace Eigen { * API for the %Matrix class provides easy access to linear-algebra * operations. * - * This class can be extended with the help of the plugin mechanism described on the page - * \ref TopicCustomizingEigen by defining the preprocessor symbol \c EIGEN_ARRAY_PLUGIN. + * See documentation of class Matrix for detailed information on the template parameters + * storage layout. * - * \sa \ref TutorialArrayClass, \ref TopicClassHierarchy + * This class can be extended with the help of the plugin mechanism described on the page + * \ref TopicCustomizing_Plugins by defining the preprocessor symbol \c EIGEN_ARRAY_PLUGIN. + * + * \sa \blank \ref TutorialArrayClass, \ref TopicClassHierarchy */ -namespace internal { -template -struct traits > : traits > -{ - typedef ArrayXpr XprKind; - typedef ArrayBase > XprBase; -}; -} - template class Array : public PlainObjectBase > @@ -69,11 +72,27 @@ class Array * the usage of 'using'. This should be done only for operator=. */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Array& operator=(const EigenBase &other) { return Base::operator=(other); } + /** Set all the entries to \a value. + * \sa DenseBase::setConstant(), DenseBase::fill() + */ + /* This overload is needed because the usage of + * using Base::operator=; + * fails on MSVC. Since the code below is working with GCC and MSVC, we skipped + * the usage of 'using'. This should be done only for operator=. + */ + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Array& operator=(const Scalar &value) + { + Base::setConstant(value); + return *this; + } + /** Copies the value of the expression \a other into \c *this with automatic resizing. * * *this might be resized to match the dimensions of \a other. If *this was a null matrix (not already initialized), @@ -84,7 +103,8 @@ class Array * remain row-vectors and vectors remain vectors. */ template - EIGEN_STRONG_INLINE Array& operator=(const ArrayBase& other) + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Array& operator=(const DenseBase& other) { return Base::_set(other); } @@ -92,11 +112,12 @@ class Array /** This is a special case of the templated operator=. Its purpose is to * prevent a default operator= from hiding the templated operator=. */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Array& operator=(const Array& other) { return Base::_set(other); } - + /** Default constructor. * * For fixed-size matrices, does nothing. @@ -107,6 +128,7 @@ class Array * * \sa resize(Index,Index) */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Array() : Base() { Base::_check_template_params(); @@ -116,6 +138,7 @@ class Array #ifndef EIGEN_PARSED_BY_DOXYGEN // FIXME is it still needed ?? /** \internal */ + EIGEN_DEVICE_FUNC Array(internal::constructor_without_unaligned_array_assert) : Base(internal::constructor_without_unaligned_array_assert()) { @@ -124,41 +147,64 @@ class Array } #endif - /** Constructs a vector or row-vector with given dimension. \only_for_vectors - * - * Note that this is only useful for dynamic-size vectors. For fixed-size vectors, - * it is redundant to pass the dimension here, so it makes more sense to use the default - * constructor Matrix() instead. - */ - EIGEN_STRONG_INLINE explicit Array(Index dim) - : Base(dim, RowsAtCompileTime == 1 ? 1 : dim, ColsAtCompileTime == 1 ? 1 : dim) +#if EIGEN_HAS_RVALUE_REFERENCES + EIGEN_DEVICE_FUNC + Array(Array&& other) EIGEN_NOEXCEPT_IF(std::is_nothrow_move_constructible::value) + : Base(std::move(other)) { Base::_check_template_params(); - EIGEN_STATIC_ASSERT_VECTOR_ONLY(Array) - eigen_assert(dim >= 0); - eigen_assert(SizeAtCompileTime == Dynamic || SizeAtCompileTime == dim); - EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED + if (RowsAtCompileTime!=Dynamic && ColsAtCompileTime!=Dynamic) + Base::_set_noalias(other); } + EIGEN_DEVICE_FUNC + Array& operator=(Array&& other) EIGEN_NOEXCEPT_IF(std::is_nothrow_move_assignable::value) + { + other.swap(*this); + return *this; + } +#endif #ifndef EIGEN_PARSED_BY_DOXYGEN + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE explicit Array(const T& x) + { + Base::_check_template_params(); + Base::template _init1(x); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Array(const T0& val0, const T1& val1) { Base::_check_template_params(); this->template _init2(val0, val1); } #else - /** constructs an uninitialized matrix with \a rows rows and \a cols columns. + /** \brief Constructs a fixed-sized array initialized with coefficients starting at \a data */ + EIGEN_DEVICE_FUNC explicit Array(const Scalar *data); + /** Constructs a vector or row-vector with given dimension. \only_for_vectors * - * This is useful for dynamic-size matrices. For fixed-size matrices, + * Note that this is only useful for dynamic-size vectors. For fixed-size vectors, + * it is redundant to pass the dimension here, so it makes more sense to use the default + * constructor Array() instead. + */ + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE explicit Array(Index dim); + /** constructs an initialized 1x1 Array with the given coefficient */ + Array(const Scalar& value); + /** constructs an uninitialized array with \a rows rows and \a cols columns. + * + * This is useful for dynamic-size arrays. For fixed-size arrays, * it is redundant to pass these parameters, so one should use the default constructor - * Matrix() instead. */ + * Array() instead. */ Array(Index rows, Index cols); /** constructs an initialized 2D vector with given coefficients */ Array(const Scalar& val0, const Scalar& val1); #endif /** constructs an initialized 3D vector with given coefficients */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Array(const Scalar& val0, const Scalar& val1, const Scalar& val2) { Base::_check_template_params(); @@ -168,6 +214,7 @@ class Array m_storage.data()[2] = val2; } /** constructs an initialized 4D vector with given coefficients */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Array(const Scalar& val0, const Scalar& val1, const Scalar& val2, const Scalar& val3) { Base::_check_template_params(); @@ -178,51 +225,21 @@ class Array m_storage.data()[3] = val3; } - explicit Array(const Scalar *data); - - /** Constructor copying the value of the expression \a other */ - template - EIGEN_STRONG_INLINE Array(const ArrayBase& other) - : Base(other.rows() * other.cols(), other.rows(), other.cols()) - { - Base::_check_template_params(); - Base::_set_noalias(other); - } /** Copy constructor */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Array(const Array& other) - : Base(other.rows() * other.cols(), other.rows(), other.cols()) - { - Base::_check_template_params(); - Base::_set_noalias(other); - } - /** Copy constructor with in-place evaluation */ - template - EIGEN_STRONG_INLINE Array(const ReturnByValue& other) - { - Base::_check_template_params(); - Base::resize(other.rows(), other.cols()); - other.evalTo(*this); - } + : Base(other) + { } /** \sa MatrixBase::operator=(const EigenBase&) */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Array(const EigenBase &other) - : Base(other.derived().rows() * other.derived().cols(), other.derived().rows(), other.derived().cols()) - { - Base::_check_template_params(); - Base::_resize_to_match(other); - *this = other; - } + : Base(other.derived()) + { } - /** Override MatrixBase::swap() since for dynamic-sized matrices of same type it is enough to swap the - * data pointers. - */ - template - void swap(ArrayBase const & other) - { this->_swap(other.derived()); } - - inline Index innerStride() const { return 1; } - inline Index outerStride() const { return this->innerSize(); } + EIGEN_DEVICE_FUNC inline Index innerStride() const { return 1; } + EIGEN_DEVICE_FUNC inline Index outerStride() const { return this->innerSize(); } #ifdef EIGEN_ARRAY_PLUGIN #include EIGEN_ARRAY_PLUGIN diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/ArrayBase.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/ArrayBase.h index 38852600..9da960f0 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/ArrayBase.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/ArrayBase.h @@ -32,7 +32,7 @@ template class MatrixWrapper; * \tparam Derived is the derived type, e.g., an array or an expression type. * * This class can be extended with the help of the plugin mechanism described on the page - * \ref TopicCustomizingEigen by defining the preprocessor symbol \c EIGEN_ARRAYBASE_PLUGIN. + * \ref TopicCustomizing_Plugins by defining the preprocessor symbol \c EIGEN_ARRAYBASE_PLUGIN. * * \sa class MatrixBase, \ref TopicClassHierarchy */ @@ -46,11 +46,7 @@ template class ArrayBase typedef ArrayBase Eigen_BaseClassForSpecializationOfGlobalMathFuncImpl; - using internal::special_scalar_op_base::Scalar, - typename NumTraits::Scalar>::Real>::operator*; - typedef typename internal::traits::StorageKind StorageKind; - typedef typename internal::traits::Index Index; typedef typename internal::traits::Scalar Scalar; typedef typename internal::packet_traits::type PacketScalar; typedef typename NumTraits::Real RealScalar; @@ -64,8 +60,7 @@ template class ArrayBase using Base::MaxSizeAtCompileTime; using Base::IsVectorAtCompileTime; using Base::Flags; - using Base::CoeffReadCost; - + using Base::derived; using Base::const_cast_derived; using Base::rows; @@ -74,6 +69,7 @@ template class ArrayBase using Base::coeff; using Base::coeffRef; using Base::lazyAssign; + using Base::operator-; using Base::operator=; using Base::operator+=; using Base::operator-=; @@ -85,26 +81,14 @@ template class ArrayBase #endif // not EIGEN_PARSED_BY_DOXYGEN #ifndef EIGEN_PARSED_BY_DOXYGEN - /** \internal the plain matrix type corresponding to this expression. Note that is not necessarily - * exactly the return type of eval(): in the case of plain matrices, the return type of eval() is a const - * reference to a matrix, not a matrix! It is however guaranteed that the return type of eval() is either - * PlainObject or const PlainObject&. - */ - typedef Array::Scalar, - internal::traits::RowsAtCompileTime, - internal::traits::ColsAtCompileTime, - AutoAlign | (internal::traits::Flags&RowMajorBit ? RowMajor : ColMajor), - internal::traits::MaxRowsAtCompileTime, - internal::traits::MaxColsAtCompileTime - > PlainObject; - + typedef typename Base::PlainObject PlainObject; /** \internal Represents a matrix with all coefficients equal to one another*/ - typedef CwiseNullaryOp,Derived> ConstantReturnType; + typedef CwiseNullaryOp,PlainObject> ConstantReturnType; #endif // not EIGEN_PARSED_BY_DOXYGEN #define EIGEN_CURRENT_STORAGE_BASE_CLASS Eigen::ArrayBase -# include "../plugins/CommonCwiseUnaryOps.h" +#define EIGEN_DOC_UNARY_ADDONS(X,Y) # include "../plugins/MatrixCwiseUnaryOps.h" # include "../plugins/ArrayCwiseUnaryOps.h" # include "../plugins/CommonCwiseBinaryOps.h" @@ -114,44 +98,62 @@ template class ArrayBase # include EIGEN_ARRAYBASE_PLUGIN # endif #undef EIGEN_CURRENT_STORAGE_BASE_CLASS +#undef EIGEN_DOC_UNARY_ADDONS /** Special case of the template operator=, in order to prevent the compiler * from generating a default operator= (issue hit with g++ 4.1) */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const ArrayBase& other) { - return internal::assign_selector::run(derived(), other.derived()); + internal::call_assignment(derived(), other.derived()); + return derived(); } + + /** Set all the entries to \a value. + * \sa DenseBase::setConstant(), DenseBase::fill() */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Derived& operator=(const Scalar &value) + { Base::setConstant(value); return derived(); } - Derived& operator+=(const Scalar& scalar) - { return *this = derived() + scalar; } - Derived& operator-=(const Scalar& scalar) - { return *this = derived() - scalar; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Derived& operator+=(const Scalar& scalar); + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Derived& operator-=(const Scalar& scalar); template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator+=(const ArrayBase& other); template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator-=(const ArrayBase& other); template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator*=(const ArrayBase& other); template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator/=(const ArrayBase& other); public: + EIGEN_DEVICE_FUNC ArrayBase& array() { return *this; } + EIGEN_DEVICE_FUNC const ArrayBase& array() const { return *this; } /** \returns an \link Eigen::MatrixBase Matrix \endlink expression of this array * \sa MatrixBase::array() */ - MatrixWrapper matrix() { return derived(); } - const MatrixWrapper matrix() const { return derived(); } + EIGEN_DEVICE_FUNC + MatrixWrapper matrix() { return MatrixWrapper(derived()); } + EIGEN_DEVICE_FUNC + const MatrixWrapper matrix() const { return MatrixWrapper(derived()); } // template // inline void evalTo(Dest& dst) const { dst = matrix(); } protected: + EIGEN_DEVICE_FUNC ArrayBase() : Base() {} private: @@ -173,11 +175,10 @@ template class ArrayBase */ template template -EIGEN_STRONG_INLINE Derived & +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived & ArrayBase::operator-=(const ArrayBase &other) { - SelfCwiseBinaryOp, Derived, OtherDerived> tmp(derived()); - tmp = other.derived(); + call_assignment(derived(), other.derived(), internal::sub_assign_op()); return derived(); } @@ -187,11 +188,10 @@ ArrayBase::operator-=(const ArrayBase &other) */ template template -EIGEN_STRONG_INLINE Derived & +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived & ArrayBase::operator+=(const ArrayBase& other) { - SelfCwiseBinaryOp, Derived, OtherDerived> tmp(derived()); - tmp = other.derived(); + call_assignment(derived(), other.derived(), internal::add_assign_op()); return derived(); } @@ -201,11 +201,10 @@ ArrayBase::operator+=(const ArrayBase& other) */ template template -EIGEN_STRONG_INLINE Derived & +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived & ArrayBase::operator*=(const ArrayBase& other) { - SelfCwiseBinaryOp, Derived, OtherDerived> tmp(derived()); - tmp = other.derived(); + call_assignment(derived(), other.derived(), internal::mul_assign_op()); return derived(); } @@ -215,11 +214,10 @@ ArrayBase::operator*=(const ArrayBase& other) */ template template -EIGEN_STRONG_INLINE Derived & +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived & ArrayBase::operator/=(const ArrayBase& other) { - SelfCwiseBinaryOp, Derived, OtherDerived> tmp(derived()); - tmp = other.derived(); + call_assignment(derived(), other.derived(), internal::div_assign_op()); return derived(); } diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/ArrayWrapper.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/ArrayWrapper.h index b4641e2a..a04521a1 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/ArrayWrapper.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/ArrayWrapper.h @@ -44,6 +44,7 @@ class ArrayWrapper : public ArrayBase > typedef ArrayBase Base; EIGEN_DENSE_PUBLIC_INTERFACE(ArrayWrapper) EIGEN_INHERIT_ASSIGNMENT_OPERATORS(ArrayWrapper) + typedef typename internal::remove_all::type NestedExpression; typedef typename internal::conditional< internal::is_lvalue::value, @@ -51,76 +52,45 @@ class ArrayWrapper : public ArrayBase > const Scalar >::type ScalarWithConstIfNotLvalue; - typedef typename internal::nested::type NestedExpressionType; + typedef typename internal::ref_selector::non_const_type NestedExpressionType; - inline ArrayWrapper(ExpressionType& matrix) : m_expression(matrix) {} + using Base::coeffRef; + EIGEN_DEVICE_FUNC + explicit EIGEN_STRONG_INLINE ArrayWrapper(ExpressionType& matrix) : m_expression(matrix) {} + + EIGEN_DEVICE_FUNC inline Index rows() const { return m_expression.rows(); } + EIGEN_DEVICE_FUNC inline Index cols() const { return m_expression.cols(); } + EIGEN_DEVICE_FUNC inline Index outerStride() const { return m_expression.outerStride(); } + EIGEN_DEVICE_FUNC inline Index innerStride() const { return m_expression.innerStride(); } - inline ScalarWithConstIfNotLvalue* data() { return m_expression.const_cast_derived().data(); } + EIGEN_DEVICE_FUNC + inline ScalarWithConstIfNotLvalue* data() { return m_expression.data(); } + EIGEN_DEVICE_FUNC inline const Scalar* data() const { return m_expression.data(); } - inline CoeffReturnType coeff(Index rowId, Index colId) const - { - return m_expression.coeff(rowId, colId); - } - - inline Scalar& coeffRef(Index rowId, Index colId) - { - return m_expression.const_cast_derived().coeffRef(rowId, colId); - } - + EIGEN_DEVICE_FUNC inline const Scalar& coeffRef(Index rowId, Index colId) const { - return m_expression.const_cast_derived().coeffRef(rowId, colId); - } - - inline CoeffReturnType coeff(Index index) const - { - return m_expression.coeff(index); - } - - inline Scalar& coeffRef(Index index) - { - return m_expression.const_cast_derived().coeffRef(index); + return m_expression.coeffRef(rowId, colId); } + EIGEN_DEVICE_FUNC inline const Scalar& coeffRef(Index index) const { - return m_expression.const_cast_derived().coeffRef(index); - } - - template - inline const PacketScalar packet(Index rowId, Index colId) const - { - return m_expression.template packet(rowId, colId); - } - - template - inline void writePacket(Index rowId, Index colId, const PacketScalar& val) - { - m_expression.const_cast_derived().template writePacket(rowId, colId, val); - } - - template - inline const PacketScalar packet(Index index) const - { - return m_expression.template packet(index); - } - - template - inline void writePacket(Index index, const PacketScalar& val) - { - m_expression.const_cast_derived().template writePacket(index, val); + return m_expression.coeffRef(index); } template + EIGEN_DEVICE_FUNC inline void evalTo(Dest& dst) const { dst = m_expression; } const typename internal::remove_all::type& + EIGEN_DEVICE_FUNC nestedExpression() const { return m_expression; @@ -128,10 +98,12 @@ class ArrayWrapper : public ArrayBase > /** Forwards the resizing request to the nested expression * \sa DenseBase::resize(Index) */ - void resize(Index newSize) { m_expression.const_cast_derived().resize(newSize); } + EIGEN_DEVICE_FUNC + void resize(Index newSize) { m_expression.resize(newSize); } /** Forwards the resizing request to the nested expression * \sa DenseBase::resize(Index,Index)*/ - void resize(Index nbRows, Index nbCols) { m_expression.const_cast_derived().resize(nbRows,nbCols); } + EIGEN_DEVICE_FUNC + void resize(Index rows, Index cols) { m_expression.resize(rows,cols); } protected: NestedExpressionType m_expression; @@ -169,6 +141,7 @@ class MatrixWrapper : public MatrixBase > typedef MatrixBase > Base; EIGEN_DENSE_PUBLIC_INTERFACE(MatrixWrapper) EIGEN_INHERIT_ASSIGNMENT_OPERATORS(MatrixWrapper) + typedef typename internal::remove_all::type NestedExpression; typedef typename internal::conditional< internal::is_lvalue::value, @@ -176,72 +149,40 @@ class MatrixWrapper : public MatrixBase > const Scalar >::type ScalarWithConstIfNotLvalue; - typedef typename internal::nested::type NestedExpressionType; + typedef typename internal::ref_selector::non_const_type NestedExpressionType; - inline MatrixWrapper(ExpressionType& a_matrix) : m_expression(a_matrix) {} + using Base::coeffRef; + EIGEN_DEVICE_FUNC + explicit inline MatrixWrapper(ExpressionType& matrix) : m_expression(matrix) {} + + EIGEN_DEVICE_FUNC inline Index rows() const { return m_expression.rows(); } + EIGEN_DEVICE_FUNC inline Index cols() const { return m_expression.cols(); } + EIGEN_DEVICE_FUNC inline Index outerStride() const { return m_expression.outerStride(); } + EIGEN_DEVICE_FUNC inline Index innerStride() const { return m_expression.innerStride(); } - inline ScalarWithConstIfNotLvalue* data() { return m_expression.const_cast_derived().data(); } + EIGEN_DEVICE_FUNC + inline ScalarWithConstIfNotLvalue* data() { return m_expression.data(); } + EIGEN_DEVICE_FUNC inline const Scalar* data() const { return m_expression.data(); } - inline CoeffReturnType coeff(Index rowId, Index colId) const - { - return m_expression.coeff(rowId, colId); - } - - inline Scalar& coeffRef(Index rowId, Index colId) - { - return m_expression.const_cast_derived().coeffRef(rowId, colId); - } - + EIGEN_DEVICE_FUNC inline const Scalar& coeffRef(Index rowId, Index colId) const { return m_expression.derived().coeffRef(rowId, colId); } - inline CoeffReturnType coeff(Index index) const - { - return m_expression.coeff(index); - } - - inline Scalar& coeffRef(Index index) - { - return m_expression.const_cast_derived().coeffRef(index); - } - + EIGEN_DEVICE_FUNC inline const Scalar& coeffRef(Index index) const { - return m_expression.const_cast_derived().coeffRef(index); - } - - template - inline const PacketScalar packet(Index rowId, Index colId) const - { - return m_expression.template packet(rowId, colId); - } - - template - inline void writePacket(Index rowId, Index colId, const PacketScalar& val) - { - m_expression.const_cast_derived().template writePacket(rowId, colId, val); - } - - template - inline const PacketScalar packet(Index index) const - { - return m_expression.template packet(index); - } - - template - inline void writePacket(Index index, const PacketScalar& val) - { - m_expression.const_cast_derived().template writePacket(index, val); + return m_expression.coeffRef(index); } + EIGEN_DEVICE_FUNC const typename internal::remove_all::type& nestedExpression() const { @@ -250,10 +191,12 @@ class MatrixWrapper : public MatrixBase > /** Forwards the resizing request to the nested expression * \sa DenseBase::resize(Index) */ - void resize(Index newSize) { m_expression.const_cast_derived().resize(newSize); } + EIGEN_DEVICE_FUNC + void resize(Index newSize) { m_expression.resize(newSize); } /** Forwards the resizing request to the nested expression * \sa DenseBase::resize(Index,Index)*/ - void resize(Index nbRows, Index nbCols) { m_expression.const_cast_derived().resize(nbRows,nbCols); } + EIGEN_DEVICE_FUNC + void resize(Index rows, Index cols) { m_expression.resize(rows,cols); } protected: NestedExpressionType m_expression; diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/Assign.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/Assign.h index 1dccc2f4..655412ef 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/Assign.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/Assign.h @@ -14,474 +14,9 @@ namespace Eigen { -namespace internal { - -/*************************************************************************** -* Part 1 : the logic deciding a strategy for traversal and unrolling * -***************************************************************************/ - -template -struct assign_traits -{ -public: - enum { - DstIsAligned = Derived::Flags & AlignedBit, - DstHasDirectAccess = Derived::Flags & DirectAccessBit, - SrcIsAligned = OtherDerived::Flags & AlignedBit, - JointAlignment = bool(DstIsAligned) && bool(SrcIsAligned) ? Aligned : Unaligned - }; - -private: - enum { - InnerSize = int(Derived::IsVectorAtCompileTime) ? int(Derived::SizeAtCompileTime) - : int(Derived::Flags)&RowMajorBit ? int(Derived::ColsAtCompileTime) - : int(Derived::RowsAtCompileTime), - InnerMaxSize = int(Derived::IsVectorAtCompileTime) ? int(Derived::MaxSizeAtCompileTime) - : int(Derived::Flags)&RowMajorBit ? int(Derived::MaxColsAtCompileTime) - : int(Derived::MaxRowsAtCompileTime), - MaxSizeAtCompileTime = Derived::SizeAtCompileTime, - PacketSize = packet_traits::size - }; - - enum { - StorageOrdersAgree = (int(Derived::IsRowMajor) == int(OtherDerived::IsRowMajor)), - MightVectorize = StorageOrdersAgree - && (int(Derived::Flags) & int(OtherDerived::Flags) & ActualPacketAccessBit), - MayInnerVectorize = MightVectorize && int(InnerSize)!=Dynamic && int(InnerSize)%int(PacketSize)==0 - && int(DstIsAligned) && int(SrcIsAligned), - MayLinearize = StorageOrdersAgree && (int(Derived::Flags) & int(OtherDerived::Flags) & LinearAccessBit), - MayLinearVectorize = MightVectorize && MayLinearize && DstHasDirectAccess - && (DstIsAligned || MaxSizeAtCompileTime == Dynamic), - /* If the destination isn't aligned, we have to do runtime checks and we don't unroll, - so it's only good for large enough sizes. */ - MaySliceVectorize = MightVectorize && DstHasDirectAccess - && (int(InnerMaxSize)==Dynamic || int(InnerMaxSize)>=3*PacketSize) - /* slice vectorization can be slow, so we only want it if the slices are big, which is - indicated by InnerMaxSize rather than InnerSize, think of the case of a dynamic block - in a fixed-size matrix */ - }; - -public: - enum { - Traversal = int(MayInnerVectorize) ? int(InnerVectorizedTraversal) - : int(MayLinearVectorize) ? int(LinearVectorizedTraversal) - : int(MaySliceVectorize) ? int(SliceVectorizedTraversal) - : int(MayLinearize) ? int(LinearTraversal) - : int(DefaultTraversal), - Vectorized = int(Traversal) == InnerVectorizedTraversal - || int(Traversal) == LinearVectorizedTraversal - || int(Traversal) == SliceVectorizedTraversal - }; - -private: - enum { - UnrollingLimit = EIGEN_UNROLLING_LIMIT * (Vectorized ? int(PacketSize) : 1), - MayUnrollCompletely = int(Derived::SizeAtCompileTime) != Dynamic - && int(OtherDerived::CoeffReadCost) != Dynamic - && int(Derived::SizeAtCompileTime) * int(OtherDerived::CoeffReadCost) <= int(UnrollingLimit), - MayUnrollInner = int(InnerSize) != Dynamic - && int(OtherDerived::CoeffReadCost) != Dynamic - && int(InnerSize) * int(OtherDerived::CoeffReadCost) <= int(UnrollingLimit) - }; - -public: - enum { - Unrolling = (int(Traversal) == int(InnerVectorizedTraversal) || int(Traversal) == int(DefaultTraversal)) - ? ( - int(MayUnrollCompletely) ? int(CompleteUnrolling) - : int(MayUnrollInner) ? int(InnerUnrolling) - : int(NoUnrolling) - ) - : int(Traversal) == int(LinearVectorizedTraversal) - ? ( bool(MayUnrollCompletely) && bool(DstIsAligned) ? int(CompleteUnrolling) : int(NoUnrolling) ) - : int(Traversal) == int(LinearTraversal) - ? ( bool(MayUnrollCompletely) ? int(CompleteUnrolling) : int(NoUnrolling) ) - : int(NoUnrolling) - }; - -#ifdef EIGEN_DEBUG_ASSIGN - static void debug() - { - EIGEN_DEBUG_VAR(DstIsAligned) - EIGEN_DEBUG_VAR(SrcIsAligned) - EIGEN_DEBUG_VAR(JointAlignment) - EIGEN_DEBUG_VAR(InnerSize) - EIGEN_DEBUG_VAR(InnerMaxSize) - EIGEN_DEBUG_VAR(PacketSize) - EIGEN_DEBUG_VAR(StorageOrdersAgree) - EIGEN_DEBUG_VAR(MightVectorize) - EIGEN_DEBUG_VAR(MayLinearize) - EIGEN_DEBUG_VAR(MayInnerVectorize) - EIGEN_DEBUG_VAR(MayLinearVectorize) - EIGEN_DEBUG_VAR(MaySliceVectorize) - EIGEN_DEBUG_VAR(Traversal) - EIGEN_DEBUG_VAR(UnrollingLimit) - EIGEN_DEBUG_VAR(MayUnrollCompletely) - EIGEN_DEBUG_VAR(MayUnrollInner) - EIGEN_DEBUG_VAR(Unrolling) - } -#endif -}; - -/*************************************************************************** -* Part 2 : meta-unrollers -***************************************************************************/ - -/************************ -*** Default traversal *** -************************/ - -template -struct assign_DefaultTraversal_CompleteUnrolling -{ - enum { - outer = Index / Derived1::InnerSizeAtCompileTime, - inner = Index % Derived1::InnerSizeAtCompileTime - }; - - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) - { - dst.copyCoeffByOuterInner(outer, inner, src); - assign_DefaultTraversal_CompleteUnrolling::run(dst, src); - } -}; - -template -struct assign_DefaultTraversal_CompleteUnrolling -{ - static EIGEN_STRONG_INLINE void run(Derived1 &, const Derived2 &) {} -}; - -template -struct assign_DefaultTraversal_InnerUnrolling -{ - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src, typename Derived1::Index outer) - { - dst.copyCoeffByOuterInner(outer, Index, src); - assign_DefaultTraversal_InnerUnrolling::run(dst, src, outer); - } -}; - -template -struct assign_DefaultTraversal_InnerUnrolling -{ - static EIGEN_STRONG_INLINE void run(Derived1 &, const Derived2 &, typename Derived1::Index) {} -}; - -/*********************** -*** Linear traversal *** -***********************/ - -template -struct assign_LinearTraversal_CompleteUnrolling -{ - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) - { - dst.copyCoeff(Index, src); - assign_LinearTraversal_CompleteUnrolling::run(dst, src); - } -}; - -template -struct assign_LinearTraversal_CompleteUnrolling -{ - static EIGEN_STRONG_INLINE void run(Derived1 &, const Derived2 &) {} -}; - -/************************** -*** Inner vectorization *** -**************************/ - -template -struct assign_innervec_CompleteUnrolling -{ - enum { - outer = Index / Derived1::InnerSizeAtCompileTime, - inner = Index % Derived1::InnerSizeAtCompileTime, - JointAlignment = assign_traits::JointAlignment - }; - - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) - { - dst.template copyPacketByOuterInner(outer, inner, src); - assign_innervec_CompleteUnrolling::size, Stop>::run(dst, src); - } -}; - -template -struct assign_innervec_CompleteUnrolling -{ - static EIGEN_STRONG_INLINE void run(Derived1 &, const Derived2 &) {} -}; - -template -struct assign_innervec_InnerUnrolling -{ - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src, typename Derived1::Index outer) - { - dst.template copyPacketByOuterInner(outer, Index, src); - assign_innervec_InnerUnrolling::size, Stop>::run(dst, src, outer); - } -}; - -template -struct assign_innervec_InnerUnrolling -{ - static EIGEN_STRONG_INLINE void run(Derived1 &, const Derived2 &, typename Derived1::Index) {} -}; - -/*************************************************************************** -* Part 3 : implementation of all cases -***************************************************************************/ - -template::Traversal, - int Unrolling = assign_traits::Unrolling, - int Version = Specialized> -struct assign_impl; - -/************************ -*** Default traversal *** -************************/ - -template -struct assign_impl -{ - static inline void run(Derived1 &, const Derived2 &) { } -}; - -template -struct assign_impl -{ - typedef typename Derived1::Index Index; - static inline void run(Derived1 &dst, const Derived2 &src) - { - const Index innerSize = dst.innerSize(); - const Index outerSize = dst.outerSize(); - for(Index outer = 0; outer < outerSize; ++outer) - for(Index inner = 0; inner < innerSize; ++inner) - dst.copyCoeffByOuterInner(outer, inner, src); - } -}; - -template -struct assign_impl -{ - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) - { - assign_DefaultTraversal_CompleteUnrolling - ::run(dst, src); - } -}; - -template -struct assign_impl -{ - typedef typename Derived1::Index Index; - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) - { - const Index outerSize = dst.outerSize(); - for(Index outer = 0; outer < outerSize; ++outer) - assign_DefaultTraversal_InnerUnrolling - ::run(dst, src, outer); - } -}; - -/*********************** -*** Linear traversal *** -***********************/ - -template -struct assign_impl -{ - typedef typename Derived1::Index Index; - static inline void run(Derived1 &dst, const Derived2 &src) - { - const Index size = dst.size(); - for(Index i = 0; i < size; ++i) - dst.copyCoeff(i, src); - } -}; - -template -struct assign_impl -{ - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) - { - assign_LinearTraversal_CompleteUnrolling - ::run(dst, src); - } -}; - -/************************** -*** Inner vectorization *** -**************************/ - -template -struct assign_impl -{ - typedef typename Derived1::Index Index; - static inline void run(Derived1 &dst, const Derived2 &src) - { - const Index innerSize = dst.innerSize(); - const Index outerSize = dst.outerSize(); - const Index packetSize = packet_traits::size; - for(Index outer = 0; outer < outerSize; ++outer) - for(Index inner = 0; inner < innerSize; inner+=packetSize) - dst.template copyPacketByOuterInner(outer, inner, src); - } -}; - -template -struct assign_impl -{ - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) - { - assign_innervec_CompleteUnrolling - ::run(dst, src); - } -}; - -template -struct assign_impl -{ - typedef typename Derived1::Index Index; - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) - { - const Index outerSize = dst.outerSize(); - for(Index outer = 0; outer < outerSize; ++outer) - assign_innervec_InnerUnrolling - ::run(dst, src, outer); - } -}; - -/*************************** -*** Linear vectorization *** -***************************/ - -template -struct unaligned_assign_impl -{ - template - static EIGEN_STRONG_INLINE void run(const Derived&, OtherDerived&, typename Derived::Index, typename Derived::Index) {} -}; - -template <> -struct unaligned_assign_impl -{ - // MSVC must not inline this functions. If it does, it fails to optimize the - // packet access path. -#ifdef _MSC_VER - template - static EIGEN_DONT_INLINE void run(const Derived& src, OtherDerived& dst, typename Derived::Index start, typename Derived::Index end) -#else - template - static EIGEN_STRONG_INLINE void run(const Derived& src, OtherDerived& dst, typename Derived::Index start, typename Derived::Index end) -#endif - { - for (typename Derived::Index index = start; index < end; ++index) - dst.copyCoeff(index, src); - } -}; - -template -struct assign_impl -{ - typedef typename Derived1::Index Index; - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) - { - const Index size = dst.size(); - typedef packet_traits PacketTraits; - enum { - packetSize = PacketTraits::size, - dstAlignment = PacketTraits::AlignedOnScalar ? Aligned : int(assign_traits::DstIsAligned) , - srcAlignment = assign_traits::JointAlignment - }; - const Index alignedStart = assign_traits::DstIsAligned ? 0 - : internal::first_aligned(&dst.coeffRef(0), size); - const Index alignedEnd = alignedStart + ((size-alignedStart)/packetSize)*packetSize; - - unaligned_assign_impl::DstIsAligned!=0>::run(src,dst,0,alignedStart); - - for(Index index = alignedStart; index < alignedEnd; index += packetSize) - { - dst.template copyPacket(index, src); - } - - unaligned_assign_impl<>::run(src,dst,alignedEnd,size); - } -}; - -template -struct assign_impl -{ - typedef typename Derived1::Index Index; - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) - { - enum { size = Derived1::SizeAtCompileTime, - packetSize = packet_traits::size, - alignedSize = (size/packetSize)*packetSize }; - - assign_innervec_CompleteUnrolling::run(dst, src); - assign_DefaultTraversal_CompleteUnrolling::run(dst, src); - } -}; - -/************************** -*** Slice vectorization *** -***************************/ - -template -struct assign_impl -{ - typedef typename Derived1::Index Index; - static inline void run(Derived1 &dst, const Derived2 &src) - { - typedef packet_traits PacketTraits; - enum { - packetSize = PacketTraits::size, - alignable = PacketTraits::AlignedOnScalar, - dstAlignment = alignable ? Aligned : int(assign_traits::DstIsAligned) , - srcAlignment = assign_traits::JointAlignment - }; - const Index packetAlignedMask = packetSize - 1; - const Index innerSize = dst.innerSize(); - const Index outerSize = dst.outerSize(); - const Index alignedStep = alignable ? (packetSize - dst.outerStride() % packetSize) & packetAlignedMask : 0; - Index alignedStart = ((!alignable) || assign_traits::DstIsAligned) ? 0 - : internal::first_aligned(&dst.coeffRef(0,0), innerSize); - - for(Index outer = 0; outer < outerSize; ++outer) - { - const Index alignedEnd = alignedStart + ((innerSize-alignedStart) & ~packetAlignedMask); - // do the non-vectorizable part of the assignment - for(Index inner = 0; inner(outer, inner, src); - - // do the non-vectorizable part of the assignment - for(Index inner = alignedEnd; inner((alignedStart+alignedStep)%packetSize, innerSize); - } - } -}; - -} // end namespace internal - -/*************************************************************************** -* Part 4 : implementation of DenseBase methods -***************************************************************************/ - template template -EIGEN_STRONG_INLINE Derived& DenseBase +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& DenseBase ::lazyAssign(const DenseBase& other) { enum{ @@ -492,90 +27,62 @@ EIGEN_STRONG_INLINE Derived& DenseBase EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Derived,OtherDerived) EIGEN_STATIC_ASSERT(SameType,YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) -#ifdef EIGEN_DEBUG_ASSIGN - internal::assign_traits::debug(); -#endif eigen_assert(rows() == other.rows() && cols() == other.cols()); - internal::assign_impl::Traversal) - : int(InvalidTraversal)>::run(derived(),other.derived()); -#ifndef EIGEN_NO_DEBUG - checkTransposeAliasing(other.derived()); -#endif + internal::call_assignment_no_alias(derived(),other.derived()); + return derived(); } -namespace internal { - -template::Flags) & EvalBeforeAssigningBit) != 0, - bool NeedToTranspose = ((int(Derived::RowsAtCompileTime) == 1 && int(OtherDerived::ColsAtCompileTime) == 1) - | // FIXME | instead of || to please GCC 4.4.0 stupid warning "suggest parentheses around &&". - // revert to || as soon as not needed anymore. - (int(Derived::ColsAtCompileTime) == 1 && int(OtherDerived::RowsAtCompileTime) == 1)) - && int(Derived::SizeAtCompileTime) != 1> -struct assign_selector; - -template -struct assign_selector { - static EIGEN_STRONG_INLINE Derived& run(Derived& dst, const OtherDerived& other) { return dst.lazyAssign(other.derived()); } - template - static EIGEN_STRONG_INLINE Derived& evalTo(ActualDerived& dst, const ActualOtherDerived& other) { other.evalTo(dst); return dst; } -}; -template -struct assign_selector { - static EIGEN_STRONG_INLINE Derived& run(Derived& dst, const OtherDerived& other) { return dst.lazyAssign(other.eval()); } -}; -template -struct assign_selector { - static EIGEN_STRONG_INLINE Derived& run(Derived& dst, const OtherDerived& other) { return dst.lazyAssign(other.transpose()); } - template - static EIGEN_STRONG_INLINE Derived& evalTo(ActualDerived& dst, const ActualOtherDerived& other) { Transpose dstTrans(dst); other.evalTo(dstTrans); return dst; } -}; -template -struct assign_selector { - static EIGEN_STRONG_INLINE Derived& run(Derived& dst, const OtherDerived& other) { return dst.lazyAssign(other.transpose().eval()); } -}; - -} // end namespace internal - template template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& DenseBase::operator=(const DenseBase& other) { - return internal::assign_selector::run(derived(), other.derived()); + internal::call_assignment(derived(), other.derived()); + return derived(); } template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& DenseBase::operator=(const DenseBase& other) { - return internal::assign_selector::run(derived(), other.derived()); + internal::call_assignment(derived(), other.derived()); + return derived(); } template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& MatrixBase::operator=(const MatrixBase& other) { - return internal::assign_selector::run(derived(), other.derived()); + internal::call_assignment(derived(), other.derived()); + return derived(); } template template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& MatrixBase::operator=(const DenseBase& other) { - return internal::assign_selector::run(derived(), other.derived()); + internal::call_assignment(derived(), other.derived()); + return derived(); } template template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& MatrixBase::operator=(const EigenBase& other) { - return internal::assign_selector::evalTo(derived(), other.derived()); + internal::call_assignment(derived(), other.derived()); + return derived(); } template template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& MatrixBase::operator=(const ReturnByValue& other) { - return internal::assign_selector::evalTo(derived(), other.derived()); + other.derived().evalTo(derived()); + return derived(); } } // end namespace Eigen diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/AssignEvaluator.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/AssignEvaluator.h new file mode 100644 index 00000000..b0ec7b7c --- /dev/null +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/AssignEvaluator.h @@ -0,0 +1,935 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Benoit Jacob +// Copyright (C) 2011-2014 Gael Guennebaud +// Copyright (C) 2011-2012 Jitse Niesen +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_ASSIGN_EVALUATOR_H +#define EIGEN_ASSIGN_EVALUATOR_H + +namespace Eigen { + +// This implementation is based on Assign.h + +namespace internal { + +/*************************************************************************** +* Part 1 : the logic deciding a strategy for traversal and unrolling * +***************************************************************************/ + +// copy_using_evaluator_traits is based on assign_traits + +template +struct copy_using_evaluator_traits +{ + typedef typename DstEvaluator::XprType Dst; + typedef typename Dst::Scalar DstScalar; + + enum { + DstFlags = DstEvaluator::Flags, + SrcFlags = SrcEvaluator::Flags + }; + +public: + enum { + DstAlignment = DstEvaluator::Alignment, + SrcAlignment = SrcEvaluator::Alignment, + DstHasDirectAccess = DstFlags & DirectAccessBit, + JointAlignment = EIGEN_PLAIN_ENUM_MIN(DstAlignment,SrcAlignment) + }; + +private: + enum { + InnerSize = int(Dst::IsVectorAtCompileTime) ? int(Dst::SizeAtCompileTime) + : int(DstFlags)&RowMajorBit ? int(Dst::ColsAtCompileTime) + : int(Dst::RowsAtCompileTime), + InnerMaxSize = int(Dst::IsVectorAtCompileTime) ? int(Dst::MaxSizeAtCompileTime) + : int(DstFlags)&RowMajorBit ? int(Dst::MaxColsAtCompileTime) + : int(Dst::MaxRowsAtCompileTime), + OuterStride = int(outer_stride_at_compile_time::ret), + MaxSizeAtCompileTime = Dst::SizeAtCompileTime + }; + + // TODO distinguish between linear traversal and inner-traversals + typedef typename find_best_packet::type LinearPacketType; + typedef typename find_best_packet::type InnerPacketType; + + enum { + LinearPacketSize = unpacket_traits::size, + InnerPacketSize = unpacket_traits::size + }; + +public: + enum { + LinearRequiredAlignment = unpacket_traits::alignment, + InnerRequiredAlignment = unpacket_traits::alignment + }; + +private: + enum { + DstIsRowMajor = DstFlags&RowMajorBit, + SrcIsRowMajor = SrcFlags&RowMajorBit, + StorageOrdersAgree = (int(DstIsRowMajor) == int(SrcIsRowMajor)), + MightVectorize = bool(StorageOrdersAgree) + && (int(DstFlags) & int(SrcFlags) & ActualPacketAccessBit) + && bool(functor_traits::PacketAccess), + MayInnerVectorize = MightVectorize + && int(InnerSize)!=Dynamic && int(InnerSize)%int(InnerPacketSize)==0 + && int(OuterStride)!=Dynamic && int(OuterStride)%int(InnerPacketSize)==0 + && (EIGEN_UNALIGNED_VECTORIZE || int(JointAlignment)>=int(InnerRequiredAlignment)), + MayLinearize = bool(StorageOrdersAgree) && (int(DstFlags) & int(SrcFlags) & LinearAccessBit), + MayLinearVectorize = bool(MightVectorize) && MayLinearize && DstHasDirectAccess + && (EIGEN_UNALIGNED_VECTORIZE || (int(DstAlignment)>=int(LinearRequiredAlignment)) || MaxSizeAtCompileTime == Dynamic), + /* If the destination isn't aligned, we have to do runtime checks and we don't unroll, + so it's only good for large enough sizes. */ + MaySliceVectorize = bool(MightVectorize) && bool(DstHasDirectAccess) + && (int(InnerMaxSize)==Dynamic || int(InnerMaxSize)>=(EIGEN_UNALIGNED_VECTORIZE?InnerPacketSize:(3*InnerPacketSize))) + /* slice vectorization can be slow, so we only want it if the slices are big, which is + indicated by InnerMaxSize rather than InnerSize, think of the case of a dynamic block + in a fixed-size matrix + However, with EIGEN_UNALIGNED_VECTORIZE and unrolling, slice vectorization is still worth it */ + }; + +public: + enum { + Traversal = int(MayLinearVectorize) && (LinearPacketSize>InnerPacketSize) ? int(LinearVectorizedTraversal) + : int(MayInnerVectorize) ? int(InnerVectorizedTraversal) + : int(MayLinearVectorize) ? int(LinearVectorizedTraversal) + : int(MaySliceVectorize) ? int(SliceVectorizedTraversal) + : int(MayLinearize) ? int(LinearTraversal) + : int(DefaultTraversal), + Vectorized = int(Traversal) == InnerVectorizedTraversal + || int(Traversal) == LinearVectorizedTraversal + || int(Traversal) == SliceVectorizedTraversal + }; + + typedef typename conditional::type PacketType; + +private: + enum { + ActualPacketSize = int(Traversal)==LinearVectorizedTraversal ? LinearPacketSize + : Vectorized ? InnerPacketSize + : 1, + UnrollingLimit = EIGEN_UNROLLING_LIMIT * ActualPacketSize, + MayUnrollCompletely = int(Dst::SizeAtCompileTime) != Dynamic + && int(Dst::SizeAtCompileTime) * (int(DstEvaluator::CoeffReadCost)+int(SrcEvaluator::CoeffReadCost)) <= int(UnrollingLimit), + MayUnrollInner = int(InnerSize) != Dynamic + && int(InnerSize) * (int(DstEvaluator::CoeffReadCost)+int(SrcEvaluator::CoeffReadCost)) <= int(UnrollingLimit) + }; + +public: + enum { + Unrolling = (int(Traversal) == int(InnerVectorizedTraversal) || int(Traversal) == int(DefaultTraversal)) + ? ( + int(MayUnrollCompletely) ? int(CompleteUnrolling) + : int(MayUnrollInner) ? int(InnerUnrolling) + : int(NoUnrolling) + ) + : int(Traversal) == int(LinearVectorizedTraversal) + ? ( bool(MayUnrollCompletely) && ( EIGEN_UNALIGNED_VECTORIZE || (int(DstAlignment)>=int(LinearRequiredAlignment))) + ? int(CompleteUnrolling) + : int(NoUnrolling) ) + : int(Traversal) == int(LinearTraversal) + ? ( bool(MayUnrollCompletely) ? int(CompleteUnrolling) + : int(NoUnrolling) ) +#if EIGEN_UNALIGNED_VECTORIZE + : int(Traversal) == int(SliceVectorizedTraversal) + ? ( bool(MayUnrollInner) ? int(InnerUnrolling) + : int(NoUnrolling) ) +#endif + : int(NoUnrolling) + }; + +#ifdef EIGEN_DEBUG_ASSIGN + static void debug() + { + std::cerr << "DstXpr: " << typeid(typename DstEvaluator::XprType).name() << std::endl; + std::cerr << "SrcXpr: " << typeid(typename SrcEvaluator::XprType).name() << std::endl; + std::cerr.setf(std::ios::hex, std::ios::basefield); + std::cerr << "DstFlags" << " = " << DstFlags << " (" << demangle_flags(DstFlags) << " )" << std::endl; + std::cerr << "SrcFlags" << " = " << SrcFlags << " (" << demangle_flags(SrcFlags) << " )" << std::endl; + std::cerr.unsetf(std::ios::hex); + EIGEN_DEBUG_VAR(DstAlignment) + EIGEN_DEBUG_VAR(SrcAlignment) + EIGEN_DEBUG_VAR(LinearRequiredAlignment) + EIGEN_DEBUG_VAR(InnerRequiredAlignment) + EIGEN_DEBUG_VAR(JointAlignment) + EIGEN_DEBUG_VAR(InnerSize) + EIGEN_DEBUG_VAR(InnerMaxSize) + EIGEN_DEBUG_VAR(LinearPacketSize) + EIGEN_DEBUG_VAR(InnerPacketSize) + EIGEN_DEBUG_VAR(ActualPacketSize) + EIGEN_DEBUG_VAR(StorageOrdersAgree) + EIGEN_DEBUG_VAR(MightVectorize) + EIGEN_DEBUG_VAR(MayLinearize) + EIGEN_DEBUG_VAR(MayInnerVectorize) + EIGEN_DEBUG_VAR(MayLinearVectorize) + EIGEN_DEBUG_VAR(MaySliceVectorize) + std::cerr << "Traversal" << " = " << Traversal << " (" << demangle_traversal(Traversal) << ")" << std::endl; + EIGEN_DEBUG_VAR(SrcEvaluator::CoeffReadCost) + EIGEN_DEBUG_VAR(UnrollingLimit) + EIGEN_DEBUG_VAR(MayUnrollCompletely) + EIGEN_DEBUG_VAR(MayUnrollInner) + std::cerr << "Unrolling" << " = " << Unrolling << " (" << demangle_unrolling(Unrolling) << ")" << std::endl; + std::cerr << std::endl; + } +#endif +}; + +/*************************************************************************** +* Part 2 : meta-unrollers +***************************************************************************/ + +/************************ +*** Default traversal *** +************************/ + +template +struct copy_using_evaluator_DefaultTraversal_CompleteUnrolling +{ + // FIXME: this is not very clean, perhaps this information should be provided by the kernel? + typedef typename Kernel::DstEvaluatorType DstEvaluatorType; + typedef typename DstEvaluatorType::XprType DstXprType; + + enum { + outer = Index / DstXprType::InnerSizeAtCompileTime, + inner = Index % DstXprType::InnerSizeAtCompileTime + }; + + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + kernel.assignCoeffByOuterInner(outer, inner); + copy_using_evaluator_DefaultTraversal_CompleteUnrolling::run(kernel); + } +}; + +template +struct copy_using_evaluator_DefaultTraversal_CompleteUnrolling +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel&) { } +}; + +template +struct copy_using_evaluator_DefaultTraversal_InnerUnrolling +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel, Index outer) + { + kernel.assignCoeffByOuterInner(outer, Index_); + copy_using_evaluator_DefaultTraversal_InnerUnrolling::run(kernel, outer); + } +}; + +template +struct copy_using_evaluator_DefaultTraversal_InnerUnrolling +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel&, Index) { } +}; + +/*********************** +*** Linear traversal *** +***********************/ + +template +struct copy_using_evaluator_LinearTraversal_CompleteUnrolling +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel& kernel) + { + kernel.assignCoeff(Index); + copy_using_evaluator_LinearTraversal_CompleteUnrolling::run(kernel); + } +}; + +template +struct copy_using_evaluator_LinearTraversal_CompleteUnrolling +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel&) { } +}; + +/************************** +*** Inner vectorization *** +**************************/ + +template +struct copy_using_evaluator_innervec_CompleteUnrolling +{ + // FIXME: this is not very clean, perhaps this information should be provided by the kernel? + typedef typename Kernel::DstEvaluatorType DstEvaluatorType; + typedef typename DstEvaluatorType::XprType DstXprType; + typedef typename Kernel::PacketType PacketType; + + enum { + outer = Index / DstXprType::InnerSizeAtCompileTime, + inner = Index % DstXprType::InnerSizeAtCompileTime, + SrcAlignment = Kernel::AssignmentTraits::SrcAlignment, + DstAlignment = Kernel::AssignmentTraits::DstAlignment + }; + + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + kernel.template assignPacketByOuterInner(outer, inner); + enum { NextIndex = Index + unpacket_traits::size }; + copy_using_evaluator_innervec_CompleteUnrolling::run(kernel); + } +}; + +template +struct copy_using_evaluator_innervec_CompleteUnrolling +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel&) { } +}; + +template +struct copy_using_evaluator_innervec_InnerUnrolling +{ + typedef typename Kernel::PacketType PacketType; + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel, Index outer) + { + kernel.template assignPacketByOuterInner(outer, Index_); + enum { NextIndex = Index_ + unpacket_traits::size }; + copy_using_evaluator_innervec_InnerUnrolling::run(kernel, outer); + } +}; + +template +struct copy_using_evaluator_innervec_InnerUnrolling +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &, Index) { } +}; + +/*************************************************************************** +* Part 3 : implementation of all cases +***************************************************************************/ + +// dense_assignment_loop is based on assign_impl + +template +struct dense_assignment_loop; + +/************************ +*** Default traversal *** +************************/ + +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static void EIGEN_STRONG_INLINE run(Kernel &kernel) + { + for(Index outer = 0; outer < kernel.outerSize(); ++outer) { + for(Index inner = 0; inner < kernel.innerSize(); ++inner) { + kernel.assignCoeffByOuterInner(outer, inner); + } + } + } +}; + +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + typedef typename Kernel::DstEvaluatorType::XprType DstXprType; + copy_using_evaluator_DefaultTraversal_CompleteUnrolling::run(kernel); + } +}; + +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + typedef typename Kernel::DstEvaluatorType::XprType DstXprType; + + const Index outerSize = kernel.outerSize(); + for(Index outer = 0; outer < outerSize; ++outer) + copy_using_evaluator_DefaultTraversal_InnerUnrolling::run(kernel, outer); + } +}; + +/*************************** +*** Linear vectorization *** +***************************/ + + +// The goal of unaligned_dense_assignment_loop is simply to factorize the handling +// of the non vectorizable beginning and ending parts + +template +struct unaligned_dense_assignment_loop +{ + // if IsAligned = true, then do nothing + template + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel&, Index, Index) {} +}; + +template <> +struct unaligned_dense_assignment_loop +{ + // MSVC must not inline this functions. If it does, it fails to optimize the + // packet access path. + // FIXME check which version exhibits this issue +#if EIGEN_COMP_MSVC + template + static EIGEN_DONT_INLINE void run(Kernel &kernel, + Index start, + Index end) +#else + template + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel, + Index start, + Index end) +#endif + { + for (Index index = start; index < end; ++index) + kernel.assignCoeff(index); + } +}; + +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + const Index size = kernel.size(); + typedef typename Kernel::Scalar Scalar; + typedef typename Kernel::PacketType PacketType; + enum { + requestedAlignment = Kernel::AssignmentTraits::LinearRequiredAlignment, + packetSize = unpacket_traits::size, + dstIsAligned = int(Kernel::AssignmentTraits::DstAlignment)>=int(requestedAlignment), + dstAlignment = packet_traits::AlignedOnScalar ? int(requestedAlignment) + : int(Kernel::AssignmentTraits::DstAlignment), + srcAlignment = Kernel::AssignmentTraits::JointAlignment + }; + const Index alignedStart = dstIsAligned ? 0 : internal::first_aligned(kernel.dstDataPtr(), size); + const Index alignedEnd = alignedStart + ((size-alignedStart)/packetSize)*packetSize; + + unaligned_dense_assignment_loop::run(kernel, 0, alignedStart); + + for(Index index = alignedStart; index < alignedEnd; index += packetSize) + kernel.template assignPacket(index); + + unaligned_dense_assignment_loop<>::run(kernel, alignedEnd, size); + } +}; + +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + typedef typename Kernel::DstEvaluatorType::XprType DstXprType; + typedef typename Kernel::PacketType PacketType; + + enum { size = DstXprType::SizeAtCompileTime, + packetSize =unpacket_traits::size, + alignedSize = (size/packetSize)*packetSize }; + + copy_using_evaluator_innervec_CompleteUnrolling::run(kernel); + copy_using_evaluator_DefaultTraversal_CompleteUnrolling::run(kernel); + } +}; + +/************************** +*** Inner vectorization *** +**************************/ + +template +struct dense_assignment_loop +{ + typedef typename Kernel::PacketType PacketType; + enum { + SrcAlignment = Kernel::AssignmentTraits::SrcAlignment, + DstAlignment = Kernel::AssignmentTraits::DstAlignment + }; + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + const Index innerSize = kernel.innerSize(); + const Index outerSize = kernel.outerSize(); + const Index packetSize = unpacket_traits::size; + for(Index outer = 0; outer < outerSize; ++outer) + for(Index inner = 0; inner < innerSize; inner+=packetSize) + kernel.template assignPacketByOuterInner(outer, inner); + } +}; + +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + typedef typename Kernel::DstEvaluatorType::XprType DstXprType; + copy_using_evaluator_innervec_CompleteUnrolling::run(kernel); + } +}; + +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + typedef typename Kernel::DstEvaluatorType::XprType DstXprType; + typedef typename Kernel::AssignmentTraits Traits; + const Index outerSize = kernel.outerSize(); + for(Index outer = 0; outer < outerSize; ++outer) + copy_using_evaluator_innervec_InnerUnrolling::run(kernel, outer); + } +}; + +/*********************** +*** Linear traversal *** +***********************/ + +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + const Index size = kernel.size(); + for(Index i = 0; i < size; ++i) + kernel.assignCoeff(i); + } +}; + +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + typedef typename Kernel::DstEvaluatorType::XprType DstXprType; + copy_using_evaluator_LinearTraversal_CompleteUnrolling::run(kernel); + } +}; + +/************************** +*** Slice vectorization *** +***************************/ + +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + typedef typename Kernel::Scalar Scalar; + typedef typename Kernel::PacketType PacketType; + enum { + packetSize = unpacket_traits::size, + requestedAlignment = int(Kernel::AssignmentTraits::InnerRequiredAlignment), + alignable = packet_traits::AlignedOnScalar || int(Kernel::AssignmentTraits::DstAlignment)>=sizeof(Scalar), + dstIsAligned = int(Kernel::AssignmentTraits::DstAlignment)>=int(requestedAlignment), + dstAlignment = alignable ? int(requestedAlignment) + : int(Kernel::AssignmentTraits::DstAlignment) + }; + const Scalar *dst_ptr = kernel.dstDataPtr(); + if((!bool(dstIsAligned)) && (UIntPtr(dst_ptr) % sizeof(Scalar))>0) + { + // the pointer is not aligend-on scalar, so alignment is not possible + return dense_assignment_loop::run(kernel); + } + const Index packetAlignedMask = packetSize - 1; + const Index innerSize = kernel.innerSize(); + const Index outerSize = kernel.outerSize(); + const Index alignedStep = alignable ? (packetSize - kernel.outerStride() % packetSize) & packetAlignedMask : 0; + Index alignedStart = ((!alignable) || bool(dstIsAligned)) ? 0 : internal::first_aligned(dst_ptr, innerSize); + + for(Index outer = 0; outer < outerSize; ++outer) + { + const Index alignedEnd = alignedStart + ((innerSize-alignedStart) & ~packetAlignedMask); + // do the non-vectorizable part of the assignment + for(Index inner = 0; inner(outer, inner); + + // do the non-vectorizable part of the assignment + for(Index inner = alignedEnd; inner +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + typedef typename Kernel::DstEvaluatorType::XprType DstXprType; + typedef typename Kernel::PacketType PacketType; + + enum { size = DstXprType::InnerSizeAtCompileTime, + packetSize =unpacket_traits::size, + vectorizableSize = (size/packetSize)*packetSize }; + + for(Index outer = 0; outer < kernel.outerSize(); ++outer) + { + copy_using_evaluator_innervec_InnerUnrolling::run(kernel, outer); + copy_using_evaluator_DefaultTraversal_InnerUnrolling::run(kernel, outer); + } + } +}; +#endif + + +/*************************************************************************** +* Part 4 : Generic dense assignment kernel +***************************************************************************/ + +// This class generalize the assignment of a coefficient (or packet) from one dense evaluator +// to another dense writable evaluator. +// It is parametrized by the two evaluators, and the actual assignment functor. +// This abstraction level permits to keep the evaluation loops as simple and as generic as possible. +// One can customize the assignment using this generic dense_assignment_kernel with different +// functors, or by completely overloading it, by-passing a functor. +template +class generic_dense_assignment_kernel +{ +protected: + typedef typename DstEvaluatorTypeT::XprType DstXprType; + typedef typename SrcEvaluatorTypeT::XprType SrcXprType; +public: + + typedef DstEvaluatorTypeT DstEvaluatorType; + typedef SrcEvaluatorTypeT SrcEvaluatorType; + typedef typename DstEvaluatorType::Scalar Scalar; + typedef copy_using_evaluator_traits AssignmentTraits; + typedef typename AssignmentTraits::PacketType PacketType; + + + EIGEN_DEVICE_FUNC generic_dense_assignment_kernel(DstEvaluatorType &dst, const SrcEvaluatorType &src, const Functor &func, DstXprType& dstExpr) + : m_dst(dst), m_src(src), m_functor(func), m_dstExpr(dstExpr) + { + #ifdef EIGEN_DEBUG_ASSIGN + AssignmentTraits::debug(); + #endif + } + + EIGEN_DEVICE_FUNC Index size() const { return m_dstExpr.size(); } + EIGEN_DEVICE_FUNC Index innerSize() const { return m_dstExpr.innerSize(); } + EIGEN_DEVICE_FUNC Index outerSize() const { return m_dstExpr.outerSize(); } + EIGEN_DEVICE_FUNC Index rows() const { return m_dstExpr.rows(); } + EIGEN_DEVICE_FUNC Index cols() const { return m_dstExpr.cols(); } + EIGEN_DEVICE_FUNC Index outerStride() const { return m_dstExpr.outerStride(); } + + EIGEN_DEVICE_FUNC DstEvaluatorType& dstEvaluator() { return m_dst; } + EIGEN_DEVICE_FUNC const SrcEvaluatorType& srcEvaluator() const { return m_src; } + + /// Assign src(row,col) to dst(row,col) through the assignment functor. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void assignCoeff(Index row, Index col) + { + m_functor.assignCoeff(m_dst.coeffRef(row,col), m_src.coeff(row,col)); + } + + /// \sa assignCoeff(Index,Index) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void assignCoeff(Index index) + { + m_functor.assignCoeff(m_dst.coeffRef(index), m_src.coeff(index)); + } + + /// \sa assignCoeff(Index,Index) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void assignCoeffByOuterInner(Index outer, Index inner) + { + Index row = rowIndexByOuterInner(outer, inner); + Index col = colIndexByOuterInner(outer, inner); + assignCoeff(row, col); + } + + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void assignPacket(Index row, Index col) + { + m_functor.template assignPacket(&m_dst.coeffRef(row,col), m_src.template packet(row,col)); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void assignPacket(Index index) + { + m_functor.template assignPacket(&m_dst.coeffRef(index), m_src.template packet(index)); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void assignPacketByOuterInner(Index outer, Index inner) + { + Index row = rowIndexByOuterInner(outer, inner); + Index col = colIndexByOuterInner(outer, inner); + assignPacket(row, col); + } + + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Index rowIndexByOuterInner(Index outer, Index inner) + { + typedef typename DstEvaluatorType::ExpressionTraits Traits; + return int(Traits::RowsAtCompileTime) == 1 ? 0 + : int(Traits::ColsAtCompileTime) == 1 ? inner + : int(DstEvaluatorType::Flags)&RowMajorBit ? outer + : inner; + } + + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Index colIndexByOuterInner(Index outer, Index inner) + { + typedef typename DstEvaluatorType::ExpressionTraits Traits; + return int(Traits::ColsAtCompileTime) == 1 ? 0 + : int(Traits::RowsAtCompileTime) == 1 ? inner + : int(DstEvaluatorType::Flags)&RowMajorBit ? inner + : outer; + } + + EIGEN_DEVICE_FUNC const Scalar* dstDataPtr() const + { + return m_dstExpr.data(); + } + +protected: + DstEvaluatorType& m_dst; + const SrcEvaluatorType& m_src; + const Functor &m_functor; + // TODO find a way to avoid the needs of the original expression + DstXprType& m_dstExpr; +}; + +/*************************************************************************** +* Part 5 : Entry point for dense rectangular assignment +***************************************************************************/ + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void resize_if_allowed(DstXprType &dst, const SrcXprType& src, const Functor &/*func*/) +{ + EIGEN_ONLY_USED_FOR_DEBUG(dst); + EIGEN_ONLY_USED_FOR_DEBUG(src); + eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); +} + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void resize_if_allowed(DstXprType &dst, const SrcXprType& src, const internal::assign_op &/*func*/) +{ + Index dstRows = src.rows(); + Index dstCols = src.cols(); + if(((dst.rows()!=dstRows) || (dst.cols()!=dstCols))) + dst.resize(dstRows, dstCols); + eigen_assert(dst.rows() == dstRows && dst.cols() == dstCols); +} + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void call_dense_assignment_loop(DstXprType& dst, const SrcXprType& src, const Functor &func) +{ + typedef evaluator DstEvaluatorType; + typedef evaluator SrcEvaluatorType; + + SrcEvaluatorType srcEvaluator(src); + + // NOTE To properly handle A = (A*A.transpose())/s with A rectangular, + // we need to resize the destination after the source evaluator has been created. + resize_if_allowed(dst, src, func); + + DstEvaluatorType dstEvaluator(dst); + + typedef generic_dense_assignment_kernel Kernel; + Kernel kernel(dstEvaluator, srcEvaluator, func, dst.const_cast_derived()); + + dense_assignment_loop::run(kernel); +} + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void call_dense_assignment_loop(DstXprType& dst, const SrcXprType& src) +{ + call_dense_assignment_loop(dst, src, internal::assign_op()); +} + +/*************************************************************************** +* Part 6 : Generic assignment +***************************************************************************/ + +// Based on the respective shapes of the destination and source, +// the class AssignmentKind determine the kind of assignment mechanism. +// AssignmentKind must define a Kind typedef. +template struct AssignmentKind; + +// Assignement kind defined in this file: +struct Dense2Dense {}; +struct EigenBase2EigenBase {}; + +template struct AssignmentKind { typedef EigenBase2EigenBase Kind; }; +template<> struct AssignmentKind { typedef Dense2Dense Kind; }; + +// This is the main assignment class +template< typename DstXprType, typename SrcXprType, typename Functor, + typename Kind = typename AssignmentKind< typename evaluator_traits::Shape , typename evaluator_traits::Shape >::Kind, + typename EnableIf = void> +struct Assignment; + + +// The only purpose of this call_assignment() function is to deal with noalias() / "assume-aliasing" and automatic transposition. +// Indeed, I (Gael) think that this concept of "assume-aliasing" was a mistake, and it makes thing quite complicated. +// So this intermediate function removes everything related to "assume-aliasing" such that Assignment +// does not has to bother about these annoying details. + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void call_assignment(Dst& dst, const Src& src) +{ + call_assignment(dst, src, internal::assign_op()); +} +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void call_assignment(const Dst& dst, const Src& src) +{ + call_assignment(dst, src, internal::assign_op()); +} + +// Deal with "assume-aliasing" +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void call_assignment(Dst& dst, const Src& src, const Func& func, typename enable_if< evaluator_assume_aliasing::value, void*>::type = 0) +{ + typename plain_matrix_type::type tmp(src); + call_assignment_no_alias(dst, tmp, func); +} + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void call_assignment(Dst& dst, const Src& src, const Func& func, typename enable_if::value, void*>::type = 0) +{ + call_assignment_no_alias(dst, src, func); +} + +// by-pass "assume-aliasing" +// When there is no aliasing, we require that 'dst' has been properly resized +template class StorageBase, typename Src, typename Func> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void call_assignment(NoAlias& dst, const Src& src, const Func& func) +{ + call_assignment_no_alias(dst.expression(), src, func); +} + + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void call_assignment_no_alias(Dst& dst, const Src& src, const Func& func) +{ + enum { + NeedToTranspose = ( (int(Dst::RowsAtCompileTime) == 1 && int(Src::ColsAtCompileTime) == 1) + || (int(Dst::ColsAtCompileTime) == 1 && int(Src::RowsAtCompileTime) == 1) + ) && int(Dst::SizeAtCompileTime) != 1 + }; + + typedef typename internal::conditional, Dst>::type ActualDstTypeCleaned; + typedef typename internal::conditional, Dst&>::type ActualDstType; + ActualDstType actualDst(dst); + + // TODO check whether this is the right place to perform these checks: + EIGEN_STATIC_ASSERT_LVALUE(Dst) + EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(ActualDstTypeCleaned,Src) + EIGEN_CHECK_BINARY_COMPATIBILIY(Func,typename ActualDstTypeCleaned::Scalar,typename Src::Scalar); + + Assignment::run(actualDst, src, func); +} +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void call_assignment_no_alias(Dst& dst, const Src& src) +{ + call_assignment_no_alias(dst, src, internal::assign_op()); +} + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void call_assignment_no_alias_no_transpose(Dst& dst, const Src& src, const Func& func) +{ + // TODO check whether this is the right place to perform these checks: + EIGEN_STATIC_ASSERT_LVALUE(Dst) + EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Dst,Src) + EIGEN_CHECK_BINARY_COMPATIBILIY(Func,typename Dst::Scalar,typename Src::Scalar); + + Assignment::run(dst, src, func); +} +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void call_assignment_no_alias_no_transpose(Dst& dst, const Src& src) +{ + call_assignment_no_alias_no_transpose(dst, src, internal::assign_op()); +} + +// forward declaration +template void check_for_aliasing(const Dst &dst, const Src &src); + +// Generic Dense to Dense assignment +// Note that the last template argument "Weak" is needed to make it possible to perform +// both partial specialization+SFINAE without ambiguous specialization +template< typename DstXprType, typename SrcXprType, typename Functor, typename Weak> +struct Assignment +{ + EIGEN_DEVICE_FUNC + static EIGEN_STRONG_INLINE void run(DstXprType &dst, const SrcXprType &src, const Functor &func) + { +#ifndef EIGEN_NO_DEBUG + internal::check_for_aliasing(dst, src); +#endif + + call_dense_assignment_loop(dst, src, func); + } +}; + +// Generic assignment through evalTo. +// TODO: not sure we have to keep that one, but it helps porting current code to new evaluator mechanism. +// Note that the last template argument "Weak" is needed to make it possible to perform +// both partial specialization+SFINAE without ambiguous specialization +template< typename DstXprType, typename SrcXprType, typename Functor, typename Weak> +struct Assignment +{ + EIGEN_DEVICE_FUNC + static EIGEN_STRONG_INLINE void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op &/*func*/) + { + Index dstRows = src.rows(); + Index dstCols = src.cols(); + if((dst.rows()!=dstRows) || (dst.cols()!=dstCols)) + dst.resize(dstRows, dstCols); + + eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); + src.evalTo(dst); + } + + // NOTE The following two functions are templated to avoid their instanciation if not needed + // This is needed because some expressions supports evalTo only and/or have 'void' as scalar type. + template + EIGEN_DEVICE_FUNC + static EIGEN_STRONG_INLINE void run(DstXprType &dst, const SrcXprType &src, const internal::add_assign_op &/*func*/) + { + Index dstRows = src.rows(); + Index dstCols = src.cols(); + if((dst.rows()!=dstRows) || (dst.cols()!=dstCols)) + dst.resize(dstRows, dstCols); + + eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); + src.addTo(dst); + } + + template + EIGEN_DEVICE_FUNC + static EIGEN_STRONG_INLINE void run(DstXprType &dst, const SrcXprType &src, const internal::sub_assign_op &/*func*/) + { + Index dstRows = src.rows(); + Index dstCols = src.cols(); + if((dst.rows()!=dstRows) || (dst.cols()!=dstCols)) + dst.resize(dstRows, dstCols); + + eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); + src.subTo(dst); + } +}; + +} // namespace internal + +} // end namespace Eigen + +#endif // EIGEN_ASSIGN_EVALUATOR_H diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/Assign_MKL.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/Assign_MKL.h index 7772951b..6c2ab926 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/Assign_MKL.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/Assign_MKL.h @@ -1,6 +1,7 @@ /* Copyright (c) 2011, Intel Corporation. All rights reserved. - + Copyright (C) 2015 Gael Guennebaud + Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: @@ -37,17 +38,13 @@ namespace Eigen { namespace internal { -template struct vml_call -{ enum { IsSupported = 0 }; }; - -template +template class vml_assign_traits { private: enum { DstHasDirectAccess = Dst::Flags & DirectAccessBit, SrcHasDirectAccess = Src::Flags & DirectAccessBit, - StorageOrdersAgree = (int(Dst::IsRowMajor) == int(Src::IsRowMajor)), InnerSize = int(Dst::IsVectorAtCompileTime) ? int(Dst::SizeAtCompileTime) : int(Dst::Flags)&RowMajorBit ? int(Dst::ColsAtCompileTime) @@ -57,165 +54,120 @@ class vml_assign_traits : int(Dst::MaxRowsAtCompileTime), MaxSizeAtCompileTime = Dst::SizeAtCompileTime, - MightEnableVml = vml_call::IsSupported && StorageOrdersAgree && DstHasDirectAccess && SrcHasDirectAccess - && Src::InnerStrideAtCompileTime==1 && Dst::InnerStrideAtCompileTime==1, + MightEnableVml = StorageOrdersAgree && DstHasDirectAccess && SrcHasDirectAccess && Src::InnerStrideAtCompileTime==1 && Dst::InnerStrideAtCompileTime==1, MightLinearize = MightEnableVml && (int(Dst::Flags) & int(Src::Flags) & LinearAccessBit), VmlSize = MightLinearize ? MaxSizeAtCompileTime : InnerMaxSize, - LargeEnough = VmlSize==Dynamic || VmlSize>=EIGEN_MKL_VML_THRESHOLD, - MayEnableVml = MightEnableVml && LargeEnough, - MayLinearize = MayEnableVml && MightLinearize + LargeEnough = VmlSize==Dynamic || VmlSize>=EIGEN_MKL_VML_THRESHOLD }; public: enum { - Traversal = MayLinearize ? LinearVectorizedTraversal - : MayEnableVml ? InnerVectorizedTraversal - : DefaultTraversal + EnableVml = MightEnableVml && LargeEnough, + Traversal = MightLinearize ? LinearTraversal : DefaultTraversal }; }; -template::Traversal > -struct vml_assign_impl - : assign_impl,Traversal,Unrolling,BuiltIn> -{ -}; - -template -struct vml_assign_impl -{ - typedef typename Derived1::Scalar Scalar; - typedef typename Derived1::Index Index; - static inline void run(Derived1& dst, const CwiseUnaryOp& src) - { - // in case we want to (or have to) skip VML at runtime we can call: - // assign_impl,Traversal,Unrolling,BuiltIn>::run(dst,src); - const Index innerSize = dst.innerSize(); - const Index outerSize = dst.outerSize(); - for(Index outer = 0; outer < outerSize; ++outer) { - const Scalar *src_ptr = src.IsRowMajor ? &(src.nestedExpression().coeffRef(outer,0)) : - &(src.nestedExpression().coeffRef(0, outer)); - Scalar *dst_ptr = dst.IsRowMajor ? &(dst.coeffRef(outer,0)) : &(dst.coeffRef(0, outer)); - vml_call::run(src.functor(), innerSize, src_ptr, dst_ptr ); - } - } -}; - -template -struct vml_assign_impl -{ - static inline void run(Derived1& dst, const CwiseUnaryOp& src) - { - // in case we want to (or have to) skip VML at runtime we can call: - // assign_impl,Traversal,Unrolling,BuiltIn>::run(dst,src); - vml_call::run(src.functor(), dst.size(), src.nestedExpression().data(), dst.data() ); - } -}; - -// Macroses - -#define EIGEN_MKL_VML_SPECIALIZE_ASSIGN(TRAVERSAL,UNROLLING) \ - template \ - struct assign_impl, TRAVERSAL, UNROLLING, Specialized> { \ - static inline void run(Derived1 &dst, const Eigen::CwiseUnaryOp &src) { \ - vml_assign_impl::run(dst, src); \ - } \ - }; - -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(DefaultTraversal,NoUnrolling) -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(DefaultTraversal,CompleteUnrolling) -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(DefaultTraversal,InnerUnrolling) -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(LinearTraversal,NoUnrolling) -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(LinearTraversal,CompleteUnrolling) -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(InnerVectorizedTraversal,NoUnrolling) -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(InnerVectorizedTraversal,CompleteUnrolling) -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(InnerVectorizedTraversal,InnerUnrolling) -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(LinearVectorizedTraversal,CompleteUnrolling) -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(LinearVectorizedTraversal,NoUnrolling) -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(SliceVectorizedTraversal,NoUnrolling) - - +#define EIGEN_PP_EXPAND(ARG) ARG #if !defined (EIGEN_FAST_MATH) || (EIGEN_FAST_MATH != 1) -#define EIGEN_MKL_VML_MODE VML_HA +#define EIGEN_VMLMODE_EXPAND_LA , VML_HA #else -#define EIGEN_MKL_VML_MODE VML_LA +#define EIGEN_VMLMODE_EXPAND_LA , VML_LA #endif -#define EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, VMLOP, EIGENTYPE, VMLTYPE) \ - template<> struct vml_call< scalar_##EIGENOP##_op > { \ - enum { IsSupported = 1 }; \ - static inline void run( const scalar_##EIGENOP##_op& /*func*/, \ - int size, const EIGENTYPE* src, EIGENTYPE* dst) { \ - VMLOP(size, (const VMLTYPE*)src, (VMLTYPE*)dst); \ - } \ +#define EIGEN_VMLMODE_EXPAND__ + +#define EIGEN_VMLMODE_PREFIX_LA vm +#define EIGEN_VMLMODE_PREFIX__ v +#define EIGEN_VMLMODE_PREFIX(VMLMODE) EIGEN_CAT(EIGEN_VMLMODE_PREFIX_,VMLMODE) + +#define EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, VMLOP, EIGENTYPE, VMLTYPE, VMLMODE) \ + template< typename DstXprType, typename SrcXprNested> \ + struct Assignment, SrcXprNested>, assign_op, \ + Dense2Dense, typename enable_if::EnableVml>::type> { \ + typedef CwiseUnaryOp, SrcXprNested> SrcXprType; \ + static void run(DstXprType &dst, const SrcXprType &src, const assign_op &/*func*/) { \ + eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); \ + if(vml_assign_traits::Traversal==LinearTraversal) { \ + VMLOP(dst.size(), (const VMLTYPE*)src.nestedExpression().data(), \ + (VMLTYPE*)dst.data() EIGEN_PP_EXPAND(EIGEN_VMLMODE_EXPAND_##VMLMODE) ); \ + } else { \ + const Index outerSize = dst.outerSize(); \ + for(Index outer = 0; outer < outerSize; ++outer) { \ + const EIGENTYPE *src_ptr = src.IsRowMajor ? &(src.nestedExpression().coeffRef(outer,0)) : \ + &(src.nestedExpression().coeffRef(0, outer)); \ + EIGENTYPE *dst_ptr = dst.IsRowMajor ? &(dst.coeffRef(outer,0)) : &(dst.coeffRef(0, outer)); \ + VMLOP( dst.innerSize(), (const VMLTYPE*)src_ptr, \ + (VMLTYPE*)dst_ptr EIGEN_PP_EXPAND(EIGEN_VMLMODE_EXPAND_##VMLMODE)); \ + } \ + } \ + } \ + }; \ + + +#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(EIGENOP, VMLOP, VMLMODE) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, EIGEN_CAT(EIGEN_VMLMODE_PREFIX(VMLMODE),s##VMLOP), float, float, VMLMODE) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, EIGEN_CAT(EIGEN_VMLMODE_PREFIX(VMLMODE),d##VMLOP), double, double, VMLMODE) + +#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS_CPLX(EIGENOP, VMLOP, VMLMODE) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, EIGEN_CAT(EIGEN_VMLMODE_PREFIX(VMLMODE),c##VMLOP), scomplex, MKL_Complex8, VMLMODE) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, EIGEN_CAT(EIGEN_VMLMODE_PREFIX(VMLMODE),z##VMLOP), dcomplex, MKL_Complex16, VMLMODE) + +#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS(EIGENOP, VMLOP, VMLMODE) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(EIGENOP, VMLOP, VMLMODE) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALLS_CPLX(EIGENOP, VMLOP, VMLMODE) + + +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(sin, Sin, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(asin, Asin, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(sinh, Sinh, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(cos, Cos, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(acos, Acos, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(cosh, Cosh, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(tan, Tan, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(atan, Atan, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(tanh, Tanh, LA) +// EIGEN_MKL_VML_DECLARE_UNARY_CALLS(abs, Abs, _) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(exp, Exp, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(log, Ln, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(log10, Log10, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(sqrt, Sqrt, _) + +EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(square, Sqr, _) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS_CPLX(arg, Arg, _) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(round, Round, _) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(floor, Floor, _) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(ceil, Ceil, _) + +#define EIGEN_MKL_VML_DECLARE_POW_CALL(EIGENOP, VMLOP, EIGENTYPE, VMLTYPE, VMLMODE) \ + template< typename DstXprType, typename SrcXprNested, typename Plain> \ + struct Assignment, SrcXprNested, \ + const CwiseNullaryOp,Plain> >, assign_op, \ + Dense2Dense, typename enable_if::EnableVml>::type> { \ + typedef CwiseBinaryOp, SrcXprNested, \ + const CwiseNullaryOp,Plain> > SrcXprType; \ + static void run(DstXprType &dst, const SrcXprType &src, const assign_op &/*func*/) { \ + eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); \ + VMLTYPE exponent = reinterpret_cast(src.rhs().functor().m_other); \ + if(vml_assign_traits::Traversal==LinearTraversal) \ + { \ + VMLOP( dst.size(), (const VMLTYPE*)src.lhs().data(), exponent, \ + (VMLTYPE*)dst.data() EIGEN_PP_EXPAND(EIGEN_VMLMODE_EXPAND_##VMLMODE) ); \ + } else { \ + const Index outerSize = dst.outerSize(); \ + for(Index outer = 0; outer < outerSize; ++outer) { \ + const EIGENTYPE *src_ptr = src.IsRowMajor ? &(src.lhs().coeffRef(outer,0)) : \ + &(src.lhs().coeffRef(0, outer)); \ + EIGENTYPE *dst_ptr = dst.IsRowMajor ? &(dst.coeffRef(outer,0)) : &(dst.coeffRef(0, outer)); \ + VMLOP( dst.innerSize(), (const VMLTYPE*)src_ptr, exponent, \ + (VMLTYPE*)dst_ptr EIGEN_PP_EXPAND(EIGEN_VMLMODE_EXPAND_##VMLMODE)); \ + } \ + } \ + } \ }; - -#define EIGEN_MKL_VML_DECLARE_UNARY_CALL_LA(EIGENOP, VMLOP, EIGENTYPE, VMLTYPE) \ - template<> struct vml_call< scalar_##EIGENOP##_op > { \ - enum { IsSupported = 1 }; \ - static inline void run( const scalar_##EIGENOP##_op& /*func*/, \ - int size, const EIGENTYPE* src, EIGENTYPE* dst) { \ - MKL_INT64 vmlMode = EIGEN_MKL_VML_MODE; \ - VMLOP(size, (const VMLTYPE*)src, (VMLTYPE*)dst, vmlMode); \ - } \ - }; - -#define EIGEN_MKL_VML_DECLARE_POW_CALL(EIGENOP, VMLOP, EIGENTYPE, VMLTYPE) \ - template<> struct vml_call< scalar_##EIGENOP##_op > { \ - enum { IsSupported = 1 }; \ - static inline void run( const scalar_##EIGENOP##_op& func, \ - int size, const EIGENTYPE* src, EIGENTYPE* dst) { \ - EIGENTYPE exponent = func.m_exponent; \ - MKL_INT64 vmlMode = EIGEN_MKL_VML_MODE; \ - VMLOP(&size, (const VMLTYPE*)src, (const VMLTYPE*)&exponent, \ - (VMLTYPE*)dst, &vmlMode); \ - } \ - }; - -#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(EIGENOP, VMLOP) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, vs##VMLOP, float, float) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, vd##VMLOP, double, double) - -#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS_COMPLEX(EIGENOP, VMLOP) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, vc##VMLOP, scomplex, MKL_Complex8) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, vz##VMLOP, dcomplex, MKL_Complex16) - -#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS(EIGENOP, VMLOP) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(EIGENOP, VMLOP) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALLS_COMPLEX(EIGENOP, VMLOP) - - -#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL_LA(EIGENOP, VMLOP) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALL_LA(EIGENOP, vms##VMLOP, float, float) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALL_LA(EIGENOP, vmd##VMLOP, double, double) - -#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS_COMPLEX_LA(EIGENOP, VMLOP) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALL_LA(EIGENOP, vmc##VMLOP, scomplex, MKL_Complex8) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALL_LA(EIGENOP, vmz##VMLOP, dcomplex, MKL_Complex16) - -#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(EIGENOP, VMLOP) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL_LA(EIGENOP, VMLOP) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALLS_COMPLEX_LA(EIGENOP, VMLOP) - - -EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(sin, Sin) -EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(asin, Asin) -EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(cos, Cos) -EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(acos, Acos) -EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(tan, Tan) -//EIGEN_MKL_VML_DECLARE_UNARY_CALLS(abs, Abs) -EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(exp, Exp) -EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(log, Ln) -EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(sqrt, Sqrt) - -EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(square, Sqr) - -// The vm*powx functions are not avaibale in the windows version of MKL. -#ifndef _WIN32 -EIGEN_MKL_VML_DECLARE_POW_CALL(pow, vmspowx_, float, float) -EIGEN_MKL_VML_DECLARE_POW_CALL(pow, vmdpowx_, double, double) -EIGEN_MKL_VML_DECLARE_POW_CALL(pow, vmcpowx_, scomplex, MKL_Complex8) -EIGEN_MKL_VML_DECLARE_POW_CALL(pow, vmzpowx_, dcomplex, MKL_Complex16) -#endif + +EIGEN_MKL_VML_DECLARE_POW_CALL(pow, vmsPowx, float, float, LA) +EIGEN_MKL_VML_DECLARE_POW_CALL(pow, vmdPowx, double, double, LA) +EIGEN_MKL_VML_DECLARE_POW_CALL(pow, vmcPowx, scomplex, MKL_Complex8, LA) +EIGEN_MKL_VML_DECLARE_POW_CALL(pow, vmzPowx, dcomplex, MKL_Complex16, LA) } // end namespace internal diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/BandMatrix.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/BandMatrix.h index ffd7fe8b..4978c914 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/BandMatrix.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/BandMatrix.h @@ -32,7 +32,7 @@ class BandMatrixBase : public EigenBase }; typedef typename internal::traits::Scalar Scalar; typedef Matrix DenseMatrixType; - typedef typename DenseMatrixType::Index Index; + typedef typename DenseMatrixType::StorageIndex StorageIndex; typedef typename internal::traits::CoefficientsType CoefficientsType; typedef EigenBase Base; @@ -161,15 +161,15 @@ class BandMatrixBase : public EigenBase * * \brief Represents a rectangular matrix with a banded storage * - * \param _Scalar Numeric type, i.e. float, double, int - * \param Rows Number of rows, or \b Dynamic - * \param Cols Number of columns, or \b Dynamic - * \param Supers Number of super diagonal - * \param Subs Number of sub diagonal - * \param _Options A combination of either \b #RowMajor or \b #ColMajor, and of \b #SelfAdjoint - * The former controls \ref TopicStorageOrders "storage order", and defaults to - * column-major. The latter controls whether the matrix represents a selfadjoint - * matrix in which case either Supers of Subs have to be null. + * \tparam _Scalar Numeric type, i.e. float, double, int + * \tparam _Rows Number of rows, or \b Dynamic + * \tparam _Cols Number of columns, or \b Dynamic + * \tparam _Supers Number of super diagonal + * \tparam _Subs Number of sub diagonal + * \tparam _Options A combination of either \b #RowMajor or \b #ColMajor, and of \b #SelfAdjoint + * The former controls \ref TopicStorageOrders "storage order", and defaults to + * column-major. The latter controls whether the matrix represents a selfadjoint + * matrix in which case either Supers of Subs have to be null. * * \sa class TridiagonalMatrix */ @@ -179,7 +179,7 @@ struct traits > { typedef _Scalar Scalar; typedef Dense StorageKind; - typedef DenseIndex Index; + typedef Eigen::Index StorageIndex; enum { CoeffReadCost = NumTraits::ReadCost, RowsAtCompileTime = _Rows, @@ -201,10 +201,10 @@ class BandMatrix : public BandMatrixBase::Scalar Scalar; - typedef typename internal::traits::Index Index; + typedef typename internal::traits::StorageIndex StorageIndex; typedef typename internal::traits::CoefficientsType CoefficientsType; - inline BandMatrix(Index rows=Rows, Index cols=Cols, Index supers=Supers, Index subs=Subs) + explicit inline BandMatrix(Index rows=Rows, Index cols=Cols, Index supers=Supers, Index subs=Subs) : m_coeffs(1+supers+subs,cols), m_rows(rows), m_supers(supers), m_subs(subs) { @@ -241,7 +241,7 @@ struct traits::CoeffReadCost, RowsAtCompileTime = _Rows, @@ -264,9 +264,9 @@ class BandMatrixWrapper : public BandMatrixBase::Scalar Scalar; typedef typename internal::traits::CoefficientsType CoefficientsType; - typedef typename internal::traits::Index Index; + typedef typename internal::traits::StorageIndex StorageIndex; - inline BandMatrixWrapper(const CoefficientsType& coeffs, Index rows=_Rows, Index cols=_Cols, Index supers=_Supers, Index subs=_Subs) + explicit inline BandMatrixWrapper(const CoefficientsType& coeffs, Index rows=_Rows, Index cols=_Cols, Index supers=_Supers, Index subs=_Subs) : m_coeffs(coeffs), m_rows(rows), m_supers(supers), m_subs(subs) { @@ -302,9 +302,9 @@ class BandMatrixWrapper : public BandMatrixBase class TridiagonalMatrix : public BandMatrix { typedef BandMatrix Base; - typedef typename Base::Index Index; + typedef typename Base::StorageIndex StorageIndex; public: - TridiagonalMatrix(Index size = Size) : Base(size,size,Options&SelfAdjoint?0:1,1) {} + explicit TridiagonalMatrix(Index size = Size) : Base(size,size,Options&SelfAdjoint?0:1,1) {} inline typename Base::template DiagonalIntReturnType<1>::Type super() { return Base::template diagonal<1>(); } @@ -327,6 +327,25 @@ class TridiagonalMatrix : public BandMatrix +struct evaluator_traits > + : public evaluator_traits_base > +{ + typedef BandShape Shape; +}; + +template +struct evaluator_traits > + : public evaluator_traits_base > +{ + typedef BandShape Shape; +}; + +template<> struct AssignmentKind { typedef EigenBase2EigenBase Kind; }; + } // end namespace internal } // end namespace Eigen diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/Block.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/Block.h index 87bedfa4..11de45c2 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/Block.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/Block.h @@ -13,14 +13,70 @@ namespace Eigen { +namespace internal { +template +struct traits > : traits +{ + typedef typename traits::Scalar Scalar; + typedef typename traits::StorageKind StorageKind; + typedef typename traits::XprKind XprKind; + typedef typename ref_selector::type XprTypeNested; + typedef typename remove_reference::type _XprTypeNested; + enum{ + MatrixRows = traits::RowsAtCompileTime, + MatrixCols = traits::ColsAtCompileTime, + RowsAtCompileTime = MatrixRows == 0 ? 0 : BlockRows, + ColsAtCompileTime = MatrixCols == 0 ? 0 : BlockCols, + MaxRowsAtCompileTime = BlockRows==0 ? 0 + : RowsAtCompileTime != Dynamic ? int(RowsAtCompileTime) + : int(traits::MaxRowsAtCompileTime), + MaxColsAtCompileTime = BlockCols==0 ? 0 + : ColsAtCompileTime != Dynamic ? int(ColsAtCompileTime) + : int(traits::MaxColsAtCompileTime), + + XprTypeIsRowMajor = (int(traits::Flags)&RowMajorBit) != 0, + IsRowMajor = (MaxRowsAtCompileTime==1&&MaxColsAtCompileTime!=1) ? 1 + : (MaxColsAtCompileTime==1&&MaxRowsAtCompileTime!=1) ? 0 + : XprTypeIsRowMajor, + HasSameStorageOrderAsXprType = (IsRowMajor == XprTypeIsRowMajor), + InnerSize = IsRowMajor ? int(ColsAtCompileTime) : int(RowsAtCompileTime), + InnerStrideAtCompileTime = HasSameStorageOrderAsXprType + ? int(inner_stride_at_compile_time::ret) + : int(outer_stride_at_compile_time::ret), + OuterStrideAtCompileTime = HasSameStorageOrderAsXprType + ? int(outer_stride_at_compile_time::ret) + : int(inner_stride_at_compile_time::ret), + + // FIXME, this traits is rather specialized for dense object and it needs to be cleaned further + FlagsLvalueBit = is_lvalue::value ? LvalueBit : 0, + FlagsRowMajorBit = IsRowMajor ? RowMajorBit : 0, + Flags = (traits::Flags & (DirectAccessBit | (InnerPanel?CompressedAccessBit:0))) | FlagsLvalueBit | FlagsRowMajorBit, + // FIXME DirectAccessBit should not be handled by expressions + // + // Alignment is needed by MapBase's assertions + // We can sefely set it to false here. Internal alignment errors will be detected by an eigen_internal_assert in the respective evaluator + Alignment = 0 + }; +}; + +template::ret> class BlockImpl_dense; + +} // end namespace internal + +template class BlockImpl; + /** \class Block * \ingroup Core_Module * * \brief Expression of a fixed-size or dynamic-size block * - * \param XprType the type of the expression in which we are taking a block - * \param BlockRows the number of rows of the block we are taking at compile time (optional) - * \param BlockCols the number of columns of the block we are taking at compile time (optional) + * \tparam XprType the type of the expression in which we are taking a block + * \tparam BlockRows the number of rows of the block we are taking at compile time (optional) + * \tparam BlockCols the number of columns of the block we are taking at compile time (optional) + * \tparam InnerPanel is true, if the block maps to a set of rows of a row major matrix or + * to set of columns of a column major matrix (optional). The parameter allows to determine + * at compile time whether aligned access is possible on the block expression. * * This class represents an expression of either a fixed-size or dynamic-size block. It is the return * type of DenseBase::block(Index,Index,Index,Index) and DenseBase::block(Index,Index) and @@ -44,61 +100,6 @@ namespace Eigen { * * \sa DenseBase::block(Index,Index,Index,Index), DenseBase::block(Index,Index), class VectorBlock */ - -namespace internal { -template -struct traits > : traits -{ - typedef typename traits::Scalar Scalar; - typedef typename traits::StorageKind StorageKind; - typedef typename traits::XprKind XprKind; - typedef typename nested::type XprTypeNested; - typedef typename remove_reference::type _XprTypeNested; - enum{ - MatrixRows = traits::RowsAtCompileTime, - MatrixCols = traits::ColsAtCompileTime, - RowsAtCompileTime = MatrixRows == 0 ? 0 : BlockRows, - ColsAtCompileTime = MatrixCols == 0 ? 0 : BlockCols, - MaxRowsAtCompileTime = BlockRows==0 ? 0 - : RowsAtCompileTime != Dynamic ? int(RowsAtCompileTime) - : int(traits::MaxRowsAtCompileTime), - MaxColsAtCompileTime = BlockCols==0 ? 0 - : ColsAtCompileTime != Dynamic ? int(ColsAtCompileTime) - : int(traits::MaxColsAtCompileTime), - XprTypeIsRowMajor = (int(traits::Flags)&RowMajorBit) != 0, - IsRowMajor = (MaxRowsAtCompileTime==1&&MaxColsAtCompileTime!=1) ? 1 - : (MaxColsAtCompileTime==1&&MaxRowsAtCompileTime!=1) ? 0 - : XprTypeIsRowMajor, - HasSameStorageOrderAsXprType = (IsRowMajor == XprTypeIsRowMajor), - InnerSize = IsRowMajor ? int(ColsAtCompileTime) : int(RowsAtCompileTime), - InnerStrideAtCompileTime = HasSameStorageOrderAsXprType - ? int(inner_stride_at_compile_time::ret) - : int(outer_stride_at_compile_time::ret), - OuterStrideAtCompileTime = HasSameStorageOrderAsXprType - ? int(outer_stride_at_compile_time::ret) - : int(inner_stride_at_compile_time::ret), - MaskPacketAccessBit = (InnerSize == Dynamic || (InnerSize % packet_traits::size) == 0) - && (InnerStrideAtCompileTime == 1) - ? PacketAccessBit : 0, - MaskAlignedBit = (InnerPanel && (OuterStrideAtCompileTime!=Dynamic) && (((OuterStrideAtCompileTime * int(sizeof(Scalar))) % 16) == 0)) ? AlignedBit : 0, - FlagsLinearAccessBit = (RowsAtCompileTime == 1 || ColsAtCompileTime == 1 || (InnerPanel && (traits::Flags&LinearAccessBit))) ? LinearAccessBit : 0, - FlagsLvalueBit = is_lvalue::value ? LvalueBit : 0, - FlagsRowMajorBit = IsRowMajor ? RowMajorBit : 0, - Flags0 = traits::Flags & ( (HereditaryBits & ~RowMajorBit) | - DirectAccessBit | - MaskPacketAccessBit | - MaskAlignedBit), - Flags = Flags0 | FlagsLinearAccessBit | FlagsLvalueBit | FlagsRowMajorBit - }; -}; - -template::ret> class BlockImpl_dense; - -} // end namespace internal - -template class BlockImpl; - template class Block : public BlockImpl::StorageKind> { @@ -108,9 +109,12 @@ template class typedef Impl Base; EIGEN_GENERIC_PUBLIC_INTERFACE(Block) EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Block) + + typedef typename internal::remove_all::type NestedExpression; /** Column or Row constructor */ + EIGEN_DEVICE_FUNC inline Block(XprType& xpr, Index i) : Impl(xpr,i) { eigen_assert( (i>=0) && ( @@ -120,25 +124,27 @@ template class /** Fixed-size constructor */ - inline Block(XprType& xpr, Index a_startRow, Index a_startCol) - : Impl(xpr, a_startRow, a_startCol) + EIGEN_DEVICE_FUNC + inline Block(XprType& xpr, Index startRow, Index startCol) + : Impl(xpr, startRow, startCol) { EIGEN_STATIC_ASSERT(RowsAtCompileTime!=Dynamic && ColsAtCompileTime!=Dynamic,THIS_METHOD_IS_ONLY_FOR_FIXED_SIZE) - eigen_assert(a_startRow >= 0 && BlockRows >= 1 && a_startRow + BlockRows <= xpr.rows() - && a_startCol >= 0 && BlockCols >= 1 && a_startCol + BlockCols <= xpr.cols()); + eigen_assert(startRow >= 0 && BlockRows >= 0 && startRow + BlockRows <= xpr.rows() + && startCol >= 0 && BlockCols >= 0 && startCol + BlockCols <= xpr.cols()); } /** Dynamic-size constructor */ + EIGEN_DEVICE_FUNC inline Block(XprType& xpr, - Index a_startRow, Index a_startCol, + Index startRow, Index startCol, Index blockRows, Index blockCols) - : Impl(xpr, a_startRow, a_startCol, blockRows, blockCols) + : Impl(xpr, startRow, startCol, blockRows, blockCols) { eigen_assert((RowsAtCompileTime==Dynamic || RowsAtCompileTime==blockRows) && (ColsAtCompileTime==Dynamic || ColsAtCompileTime==blockCols)); - eigen_assert(a_startRow >= 0 && blockRows >= 0 && a_startRow <= xpr.rows() - blockRows - && a_startCol >= 0 && blockCols >= 0 && a_startCol <= xpr.cols() - blockCols); + eigen_assert(startRow >= 0 && blockRows >= 0 && startRow <= xpr.rows() - blockRows + && startCol >= 0 && blockCols >= 0 && startCol <= xpr.cols() - blockCols); } }; @@ -149,14 +155,15 @@ class BlockImpl : public internal::BlockImpl_dense { typedef internal::BlockImpl_dense Impl; - typedef typename XprType::Index Index; + typedef typename XprType::StorageIndex StorageIndex; public: typedef Impl Base; EIGEN_INHERIT_ASSIGNMENT_OPERATORS(BlockImpl) - inline BlockImpl(XprType& xpr, Index i) : Impl(xpr,i) {} - inline BlockImpl(XprType& xpr, Index a_startRow, Index a_startCol) : Impl(xpr, a_startRow, a_startCol) {} - inline BlockImpl(XprType& xpr, Index a_startRow, Index a_startCol, Index blockRows, Index blockCols) - : Impl(xpr, a_startRow, a_startCol, blockRows, blockCols) {} + EIGEN_DEVICE_FUNC inline BlockImpl(XprType& xpr, Index i) : Impl(xpr,i) {} + EIGEN_DEVICE_FUNC inline BlockImpl(XprType& xpr, Index startRow, Index startCol) : Impl(xpr, startRow, startCol) {} + EIGEN_DEVICE_FUNC + inline BlockImpl(XprType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols) + : Impl(xpr, startRow, startCol, blockRows, blockCols) {} }; namespace internal { @@ -166,16 +173,18 @@ template >::type { typedef Block BlockType; + typedef typename internal::ref_selector::non_const_type XprTypeNested; public: typedef typename internal::dense_xpr_base::type Base; EIGEN_DENSE_PUBLIC_INTERFACE(BlockType) EIGEN_INHERIT_ASSIGNMENT_OPERATORS(BlockImpl_dense) - class InnerIterator; + // class InnerIterator; // FIXME apparently never used /** Column or Row constructor */ + EIGEN_DEVICE_FUNC inline BlockImpl_dense(XprType& xpr, Index i) : m_xpr(xpr), // It is a row if and only if BlockRows==1 and BlockCols==XprType::ColsAtCompileTime, @@ -190,75 +199,76 @@ template inline PacketScalar packet(Index rowId, Index colId) const { - return m_xpr.template packet - (rowId + m_startRow.value(), colId + m_startCol.value()); + return m_xpr.template packet(rowId + m_startRow.value(), colId + m_startCol.value()); } template inline void writePacket(Index rowId, Index colId, const PacketScalar& val) { - m_xpr.const_cast_derived().template writePacket - (rowId + m_startRow.value(), colId + m_startCol.value(), val); + m_xpr.template writePacket(rowId + m_startRow.value(), colId + m_startCol.value(), val); } template @@ -272,40 +282,46 @@ template inline void writePacket(Index index, const PacketScalar& val) { - m_xpr.const_cast_derived().template writePacket + m_xpr.template writePacket (m_startRow.value() + (RowsAtCompileTime == 1 ? 0 : index), m_startCol.value() + (RowsAtCompileTime == 1 ? index : 0), val); } #ifdef EIGEN_PARSED_BY_DOXYGEN /** \sa MapBase::data() */ - inline const Scalar* data() const; - inline Index innerStride() const; - inline Index outerStride() const; + EIGEN_DEVICE_FUNC inline const Scalar* data() const; + EIGEN_DEVICE_FUNC inline Index innerStride() const; + EIGEN_DEVICE_FUNC inline Index outerStride() const; #endif - const typename internal::remove_all::type& nestedExpression() const + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& nestedExpression() const { return m_xpr; } + + EIGEN_DEVICE_FUNC + XprType& nestedExpression() { return m_xpr; } - Index startRow() const + EIGEN_DEVICE_FUNC + StorageIndex startRow() const { return m_startRow.value(); } - Index startCol() const + EIGEN_DEVICE_FUNC + StorageIndex startCol() const { return m_startCol.value(); } protected: - const typename XprType::Nested m_xpr; - const internal::variable_if_dynamic m_startRow; - const internal::variable_if_dynamic m_startCol; - const internal::variable_if_dynamic m_blockRows; - const internal::variable_if_dynamic m_blockCols; + XprTypeNested m_xpr; + const internal::variable_if_dynamic m_startRow; + const internal::variable_if_dynamic m_startCol; + const internal::variable_if_dynamic m_blockRows; + const internal::variable_if_dynamic m_blockCols; }; /** \internal Internal implementation of dense Blocks in the direct access case.*/ @@ -314,6 +330,10 @@ class BlockImpl_dense : public MapBase > { typedef Block BlockType; + typedef typename internal::ref_selector::non_const_type XprTypeNested; + enum { + XprTypeIsRowMajor = (int(traits::Flags)&RowMajorBit) != 0 + }; public: typedef MapBase Base; @@ -322,42 +342,52 @@ class BlockImpl_dense /** Column or Row constructor */ + EIGEN_DEVICE_FUNC inline BlockImpl_dense(XprType& xpr, Index i) - : Base(internal::const_cast_ptr(&xpr.coeffRef( - (BlockRows==1) && (BlockCols==XprType::ColsAtCompileTime) ? i : 0, - (BlockRows==XprType::RowsAtCompileTime) && (BlockCols==1) ? i : 0)), + : Base(xpr.data() + i * ( ((BlockRows==1) && (BlockCols==XprType::ColsAtCompileTime) && (!XprTypeIsRowMajor)) + || ((BlockRows==XprType::RowsAtCompileTime) && (BlockCols==1) && ( XprTypeIsRowMajor)) ? xpr.innerStride() : xpr.outerStride()), BlockRows==1 ? 1 : xpr.rows(), BlockCols==1 ? 1 : xpr.cols()), - m_xpr(xpr) + m_xpr(xpr), + m_startRow( (BlockRows==1) && (BlockCols==XprType::ColsAtCompileTime) ? i : 0), + m_startCol( (BlockRows==XprType::RowsAtCompileTime) && (BlockCols==1) ? i : 0) { init(); } /** Fixed-size constructor */ + EIGEN_DEVICE_FUNC inline BlockImpl_dense(XprType& xpr, Index startRow, Index startCol) - : Base(internal::const_cast_ptr(&xpr.coeffRef(startRow,startCol))), m_xpr(xpr) + : Base(xpr.data()+xpr.innerStride()*(XprTypeIsRowMajor?startCol:startRow) + xpr.outerStride()*(XprTypeIsRowMajor?startRow:startCol)), + m_xpr(xpr), m_startRow(startRow), m_startCol(startCol) { init(); } /** Dynamic-size constructor */ + EIGEN_DEVICE_FUNC inline BlockImpl_dense(XprType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols) - : Base(internal::const_cast_ptr(&xpr.coeffRef(startRow,startCol)), blockRows, blockCols), - m_xpr(xpr) + : Base(xpr.data()+xpr.innerStride()*(XprTypeIsRowMajor?startCol:startRow) + xpr.outerStride()*(XprTypeIsRowMajor?startRow:startCol), blockRows, blockCols), + m_xpr(xpr), m_startRow(startRow), m_startCol(startCol) { init(); } - const typename internal::remove_all::type& nestedExpression() const + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& nestedExpression() const { return m_xpr; } + + EIGEN_DEVICE_FUNC + XprType& nestedExpression() { return m_xpr; } /** \sa MapBase::innerStride() */ + EIGEN_DEVICE_FUNC inline Index innerStride() const { return internal::traits::HasSameStorageOrderAsXprType @@ -366,11 +396,24 @@ class BlockImpl_dense } /** \sa MapBase::outerStride() */ + EIGEN_DEVICE_FUNC inline Index outerStride() const { return m_outerStride; } + EIGEN_DEVICE_FUNC + StorageIndex startRow() const + { + return m_startRow.value(); + } + + EIGEN_DEVICE_FUNC + StorageIndex startCol() const + { + return m_startCol.value(); + } + #ifndef __SUNPRO_CC // FIXME sunstudio is not friendly with the above friend... // META-FIXME there is no 'friend' keyword around here. Is this obsolete? @@ -379,6 +422,7 @@ class BlockImpl_dense #ifndef EIGEN_PARSED_BY_DOXYGEN /** \internal used by allowAligned() */ + EIGEN_DEVICE_FUNC inline BlockImpl_dense(XprType& xpr, const Scalar* data, Index blockRows, Index blockCols) : Base(data, blockRows, blockCols), m_xpr(xpr) { @@ -387,6 +431,7 @@ class BlockImpl_dense #endif protected: + EIGEN_DEVICE_FUNC void init() { m_outerStride = internal::traits::HasSameStorageOrderAsXprType @@ -394,7 +439,9 @@ class BlockImpl_dense : m_xpr.innerStride(); } - typename XprType::Nested m_xpr; + XprTypeNested m_xpr; + const internal::variable_if_dynamic m_startRow; + const internal::variable_if_dynamic m_startCol; Index m_outerStride; }; diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/BooleanRedux.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/BooleanRedux.h index be9f48a8..ccf51906 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/BooleanRedux.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/BooleanRedux.h @@ -14,54 +14,54 @@ namespace Eigen { namespace internal { -template +template struct all_unroller { enum { - col = (UnrollCount-1) / Derived::RowsAtCompileTime, - row = (UnrollCount-1) % Derived::RowsAtCompileTime + col = (UnrollCount-1) / Rows, + row = (UnrollCount-1) % Rows }; static inline bool run(const Derived &mat) { - return all_unroller::run(mat) && mat.coeff(row, col); + return all_unroller::run(mat) && mat.coeff(row, col); } }; -template -struct all_unroller +template +struct all_unroller { static inline bool run(const Derived &/*mat*/) { return true; } }; -template -struct all_unroller +template +struct all_unroller { static inline bool run(const Derived &) { return false; } }; -template +template struct any_unroller { enum { - col = (UnrollCount-1) / Derived::RowsAtCompileTime, - row = (UnrollCount-1) % Derived::RowsAtCompileTime + col = (UnrollCount-1) / Rows, + row = (UnrollCount-1) % Rows }; - + static inline bool run(const Derived &mat) { - return any_unroller::run(mat) || mat.coeff(row, col); + return any_unroller::run(mat) || mat.coeff(row, col); } }; -template -struct any_unroller +template +struct any_unroller { static inline bool run(const Derived & /*mat*/) { return false; } }; -template -struct any_unroller +template +struct any_unroller { static inline bool run(const Derived &) { return false; } }; @@ -76,21 +76,21 @@ struct any_unroller * \sa any(), Cwise::operator<() */ template -inline bool DenseBase::all() const +EIGEN_DEVICE_FUNC inline bool DenseBase::all() const { + typedef internal::evaluator Evaluator; enum { unroll = SizeAtCompileTime != Dynamic - && CoeffReadCost != Dynamic - && NumTraits::AddCost != Dynamic - && SizeAtCompileTime * (CoeffReadCost + NumTraits::AddCost) <= EIGEN_UNROLLING_LIMIT + && SizeAtCompileTime * (Evaluator::CoeffReadCost + NumTraits::AddCost) <= EIGEN_UNROLLING_LIMIT }; + Evaluator evaluator(derived()); if(unroll) - return internal::all_unroller::run(derived()); + return internal::all_unroller::RowsAtCompileTime>::run(evaluator); else { for(Index j = 0; j < cols(); ++j) for(Index i = 0; i < rows(); ++i) - if (!coeff(i, j)) return false; + if (!evaluator.coeff(i, j)) return false; return true; } } @@ -100,21 +100,21 @@ inline bool DenseBase::all() const * \sa all() */ template -inline bool DenseBase::any() const +EIGEN_DEVICE_FUNC inline bool DenseBase::any() const { + typedef internal::evaluator Evaluator; enum { unroll = SizeAtCompileTime != Dynamic - && CoeffReadCost != Dynamic - && NumTraits::AddCost != Dynamic - && SizeAtCompileTime * (CoeffReadCost + NumTraits::AddCost) <= EIGEN_UNROLLING_LIMIT + && SizeAtCompileTime * (Evaluator::CoeffReadCost + NumTraits::AddCost) <= EIGEN_UNROLLING_LIMIT }; + Evaluator evaluator(derived()); if(unroll) - return internal::any_unroller::run(derived()); + return internal::any_unroller::RowsAtCompileTime>::run(evaluator); else { for(Index j = 0; j < cols(); ++j) for(Index i = 0; i < rows(); ++i) - if (coeff(i, j)) return true; + if (evaluator.coeff(i, j)) return true; return false; } } @@ -124,7 +124,7 @@ inline bool DenseBase::any() const * \sa all(), any() */ template -inline typename DenseBase::Index DenseBase::count() const +EIGEN_DEVICE_FUNC inline Eigen::Index DenseBase::count() const { return derived().template cast().template cast().sum(); } @@ -136,7 +136,11 @@ inline typename DenseBase::Index DenseBase::count() const template inline bool DenseBase::hasNaN() const { +#if EIGEN_COMP_MSVC || (defined __FAST_MATH__) + return derived().array().isNaN().any(); +#else return !((derived().array()==derived().array()).all()); +#endif } /** \returns true if \c *this contains only finite numbers, i.e., no NaN and no +/-INF values. @@ -146,7 +150,11 @@ inline bool DenseBase::hasNaN() const template inline bool DenseBase::allFinite() const { +#if EIGEN_COMP_MSVC || (defined __FAST_MATH__) + return derived().array().isFinite().all(); +#else return !((derived()-derived()).hasNaN()); +#endif } } // end namespace Eigen diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/CMakeLists.txt b/testbed/nanogui/ext/eigen/Eigen/src/Core/CMakeLists.txt deleted file mode 100644 index 2346fc2b..00000000 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/CMakeLists.txt +++ /dev/null @@ -1,10 +0,0 @@ -FILE(GLOB Eigen_Core_SRCS "*.h") - -INSTALL(FILES - ${Eigen_Core_SRCS} - DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen/src/Core COMPONENT Devel - ) - -ADD_SUBDIRECTORY(products) -ADD_SUBDIRECTORY(util) -ADD_SUBDIRECTORY(arch) diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/CommaInitializer.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/CommaInitializer.h index a036d8c3..35fdbb81 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/CommaInitializer.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/CommaInitializer.h @@ -22,14 +22,14 @@ namespace Eigen { * the return type of MatrixBase::operator<<, and most of the time this is the only * way it is used. * - * \sa \ref MatrixBaseCommaInitRef "MatrixBase::operator<<", CommaInitializer::finished() + * \sa \blank \ref MatrixBaseCommaInitRef "MatrixBase::operator<<", CommaInitializer::finished() */ template struct CommaInitializer { typedef typename XprType::Scalar Scalar; - typedef typename XprType::Index Index; + EIGEN_DEVICE_FUNC inline CommaInitializer(XprType& xpr, const Scalar& s) : m_xpr(xpr), m_row(0), m_col(1), m_currentBlockRows(1) { @@ -37,6 +37,7 @@ struct CommaInitializer } template + EIGEN_DEVICE_FUNC inline CommaInitializer(XprType& xpr, const DenseBase& other) : m_xpr(xpr), m_row(0), m_col(other.cols()), m_currentBlockRows(other.rows()) { @@ -46,6 +47,7 @@ struct CommaInitializer /* Copy/Move constructor which transfers ownership. This is crucial in * absence of return value optimization to avoid assertions during destruction. */ // FIXME in C++11 mode this could be replaced by a proper RValue constructor + EIGEN_DEVICE_FUNC inline CommaInitializer(const CommaInitializer& o) : m_xpr(o.m_xpr), m_row(o.m_row), m_col(o.m_col), m_currentBlockRows(o.m_currentBlockRows) { // Mark original object as finished. In absence of R-value references we need to const_cast: @@ -55,6 +57,7 @@ struct CommaInitializer } /* inserts a scalar value in the target matrix */ + EIGEN_DEVICE_FUNC CommaInitializer& operator,(const Scalar& s) { if (m_col==m_xpr.cols()) @@ -74,11 +77,10 @@ struct CommaInitializer /* inserts a matrix expression in the target matrix */ template + EIGEN_DEVICE_FUNC CommaInitializer& operator,(const DenseBase& other) { - if(other.cols()==0 || other.rows()==0) - return *this; - if (m_col==m_xpr.cols()) + if (m_col==m_xpr.cols() && (other.cols()!=0 || other.rows()!=m_currentBlockRows)) { m_row+=m_currentBlockRows; m_col = 0; @@ -86,24 +88,22 @@ struct CommaInitializer eigen_assert(m_row+m_currentBlockRows<=m_xpr.rows() && "Too many rows passed to comma initializer (operator<<)"); } - eigen_assert(m_col - (m_row, m_col) = other; - else - m_xpr.block(m_row, m_col, other.rows(), other.cols()) = other; + m_xpr.template block + (m_row, m_col, other.rows(), other.cols()) = other; m_col += other.cols(); return *this; } + EIGEN_DEVICE_FUNC inline ~CommaInitializer() +#if defined VERIFY_RAISES_ASSERT && (!defined EIGEN_NO_ASSERTION_CHECKING) && defined EIGEN_EXCEPTIONS + EIGEN_EXCEPTION_SPEC(Eigen::eigen_assert_exception) +#endif { - eigen_assert((m_row+m_currentBlockRows) == m_xpr.rows() - && m_col == m_xpr.cols() - && "Too few coefficients passed to comma initializer (operator<<)"); + finished(); } /** \returns the built matrix once all its coefficients have been set. @@ -113,9 +113,15 @@ struct CommaInitializer * quaternion.fromRotationMatrix((Matrix3f() << axis0, axis1, axis2).finished()); * \endcode */ - inline XprType& finished() { return m_xpr; } + EIGEN_DEVICE_FUNC + inline XprType& finished() { + eigen_assert(((m_row+m_currentBlockRows) == m_xpr.rows() || m_xpr.cols() == 0) + && m_col == m_xpr.cols() + && "Too few coefficients passed to comma initializer (operator<<)"); + return m_xpr; + } - XprType& m_xpr; // target expression + XprType& m_xpr; // target expression Index m_row; // current row id Index m_col; // current col id Index m_currentBlockRows; // current block height @@ -135,7 +141,7 @@ struct CommaInitializer * \sa CommaInitializer::finished(), class CommaInitializer */ template -inline CommaInitializer DenseBase::operator<< (const Scalar& s) +EIGEN_DEVICE_FUNC inline CommaInitializer DenseBase::operator<< (const Scalar& s) { return CommaInitializer(*static_cast(this), s); } @@ -143,7 +149,7 @@ inline CommaInitializer DenseBase::operator<< (const Scalar& s /** \sa operator<<(const Scalar&) */ template template -inline CommaInitializer +EIGEN_DEVICE_FUNC inline CommaInitializer DenseBase::operator<<(const DenseBase& other) { return CommaInitializer(*static_cast(this), other); diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/ConditionEstimator.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/ConditionEstimator.h new file mode 100644 index 00000000..aa7efdc7 --- /dev/null +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/ConditionEstimator.h @@ -0,0 +1,175 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2016 Rasmus Munk Larsen (rmlarsen@google.com) +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CONDITIONESTIMATOR_H +#define EIGEN_CONDITIONESTIMATOR_H + +namespace Eigen { + +namespace internal { + +template +struct rcond_compute_sign { + static inline Vector run(const Vector& v) { + const RealVector v_abs = v.cwiseAbs(); + return (v_abs.array() == static_cast(0)) + .select(Vector::Ones(v.size()), v.cwiseQuotient(v_abs)); + } +}; + +// Partial specialization to avoid elementwise division for real vectors. +template +struct rcond_compute_sign { + static inline Vector run(const Vector& v) { + return (v.array() < static_cast(0)) + .select(-Vector::Ones(v.size()), Vector::Ones(v.size())); + } +}; + +/** + * \returns an estimate of ||inv(matrix)||_1 given a decomposition of + * \a matrix that implements .solve() and .adjoint().solve() methods. + * + * This function implements Algorithms 4.1 and 5.1 from + * http://www.maths.manchester.ac.uk/~higham/narep/narep135.pdf + * which also forms the basis for the condition number estimators in + * LAPACK. Since at most 10 calls to the solve method of dec are + * performed, the total cost is O(dims^2), as opposed to O(dims^3) + * needed to compute the inverse matrix explicitly. + * + * The most common usage is in estimating the condition number + * ||matrix||_1 * ||inv(matrix)||_1. The first term ||matrix||_1 can be + * computed directly in O(n^2) operations. + * + * Supports the following decompositions: FullPivLU, PartialPivLU, LDLT, and + * LLT. + * + * \sa FullPivLU, PartialPivLU, LDLT, LLT. + */ +template +typename Decomposition::RealScalar rcond_invmatrix_L1_norm_estimate(const Decomposition& dec) +{ + typedef typename Decomposition::MatrixType MatrixType; + typedef typename Decomposition::Scalar Scalar; + typedef typename Decomposition::RealScalar RealScalar; + typedef typename internal::plain_col_type::type Vector; + typedef typename internal::plain_col_type::type RealVector; + const bool is_complex = (NumTraits::IsComplex != 0); + + eigen_assert(dec.rows() == dec.cols()); + const Index n = dec.rows(); + if (n == 0) + return 0; + + // Disable Index to float conversion warning +#ifdef __INTEL_COMPILER + #pragma warning push + #pragma warning ( disable : 2259 ) +#endif + Vector v = dec.solve(Vector::Ones(n) / Scalar(n)); +#ifdef __INTEL_COMPILER + #pragma warning pop +#endif + + // lower_bound is a lower bound on + // ||inv(matrix)||_1 = sup_v ||inv(matrix) v||_1 / ||v||_1 + // and is the objective maximized by the ("super-") gradient ascent + // algorithm below. + RealScalar lower_bound = v.template lpNorm<1>(); + if (n == 1) + return lower_bound; + + // Gradient ascent algorithm follows: We know that the optimum is achieved at + // one of the simplices v = e_i, so in each iteration we follow a + // super-gradient to move towards the optimal one. + RealScalar old_lower_bound = lower_bound; + Vector sign_vector(n); + Vector old_sign_vector; + Index v_max_abs_index = -1; + Index old_v_max_abs_index = v_max_abs_index; + for (int k = 0; k < 4; ++k) + { + sign_vector = internal::rcond_compute_sign::run(v); + if (k > 0 && !is_complex && sign_vector == old_sign_vector) { + // Break if the solution stagnated. + break; + } + // v_max_abs_index = argmax |real( inv(matrix)^T * sign_vector )| + v = dec.adjoint().solve(sign_vector); + v.real().cwiseAbs().maxCoeff(&v_max_abs_index); + if (v_max_abs_index == old_v_max_abs_index) { + // Break if the solution stagnated. + break; + } + // Move to the new simplex e_j, where j = v_max_abs_index. + v = dec.solve(Vector::Unit(n, v_max_abs_index)); // v = inv(matrix) * e_j. + lower_bound = v.template lpNorm<1>(); + if (lower_bound <= old_lower_bound) { + // Break if the gradient step did not increase the lower_bound. + break; + } + if (!is_complex) { + old_sign_vector = sign_vector; + } + old_v_max_abs_index = v_max_abs_index; + old_lower_bound = lower_bound; + } + // The following calculates an independent estimate of ||matrix||_1 by + // multiplying matrix by a vector with entries of slowly increasing + // magnitude and alternating sign: + // v_i = (-1)^{i} (1 + (i / (dim-1))), i = 0,...,dim-1. + // This improvement to Hager's algorithm above is due to Higham. It was + // added to make the algorithm more robust in certain corner cases where + // large elements in the matrix might otherwise escape detection due to + // exact cancellation (especially when op and op_adjoint correspond to a + // sequence of backsubstitutions and permutations), which could cause + // Hager's algorithm to vastly underestimate ||matrix||_1. + Scalar alternating_sign(RealScalar(1)); + for (Index i = 0; i < n; ++i) { + // The static_cast is needed when Scalar is a complex and RealScalar implements expression templates + v[i] = alternating_sign * static_cast(RealScalar(1) + (RealScalar(i) / (RealScalar(n - 1)))); + alternating_sign = -alternating_sign; + } + v = dec.solve(v); + const RealScalar alternate_lower_bound = (2 * v.template lpNorm<1>()) / (3 * RealScalar(n)); + return numext::maxi(lower_bound, alternate_lower_bound); +} + +/** \brief Reciprocal condition number estimator. + * + * Computing a decomposition of a dense matrix takes O(n^3) operations, while + * this method estimates the condition number quickly and reliably in O(n^2) + * operations. + * + * \returns an estimate of the reciprocal condition number + * (1 / (||matrix||_1 * ||inv(matrix)||_1)) of matrix, given ||matrix||_1 and + * its decomposition. Supports the following decompositions: FullPivLU, + * PartialPivLU, LDLT, and LLT. + * + * \sa FullPivLU, PartialPivLU, LDLT, LLT. + */ +template +typename Decomposition::RealScalar +rcond_estimate_helper(typename Decomposition::RealScalar matrix_norm, const Decomposition& dec) +{ + typedef typename Decomposition::RealScalar RealScalar; + eigen_assert(dec.rows() == dec.cols()); + if (dec.rows() == 0) return RealScalar(1); + if (matrix_norm == RealScalar(0)) return RealScalar(0); + if (dec.rows() == 1) return RealScalar(1); + const RealScalar inverse_matrix_norm = rcond_invmatrix_L1_norm_estimate(dec); + return (inverse_matrix_norm == RealScalar(0) ? RealScalar(0) + : (RealScalar(1) / inverse_matrix_norm) / matrix_norm); +} + +} // namespace internal + +} // namespace Eigen + +#endif diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/CoreEvaluators.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/CoreEvaluators.h new file mode 100644 index 00000000..15b361b3 --- /dev/null +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/CoreEvaluators.h @@ -0,0 +1,1728 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Benoit Jacob +// Copyright (C) 2011-2014 Gael Guennebaud +// Copyright (C) 2011-2012 Jitse Niesen +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + + +#ifndef EIGEN_COREEVALUATORS_H +#define EIGEN_COREEVALUATORS_H + +namespace Eigen { + +namespace internal { + +// This class returns the evaluator kind from the expression storage kind. +// Default assumes index based accessors +template +struct storage_kind_to_evaluator_kind { + typedef IndexBased Kind; +}; + +// This class returns the evaluator shape from the expression storage kind. +// It can be Dense, Sparse, Triangular, Diagonal, SelfAdjoint, Band, etc. +template struct storage_kind_to_shape; + +template<> struct storage_kind_to_shape { typedef DenseShape Shape; }; +template<> struct storage_kind_to_shape { typedef SolverShape Shape; }; +template<> struct storage_kind_to_shape { typedef PermutationShape Shape; }; +template<> struct storage_kind_to_shape { typedef TranspositionsShape Shape; }; + +// Evaluators have to be specialized with respect to various criteria such as: +// - storage/structure/shape +// - scalar type +// - etc. +// Therefore, we need specialization of evaluator providing additional template arguments for each kind of evaluators. +// We currently distinguish the following kind of evaluators: +// - unary_evaluator for expressions taking only one arguments (CwiseUnaryOp, CwiseUnaryView, Transpose, MatrixWrapper, ArrayWrapper, Reverse, Replicate) +// - binary_evaluator for expression taking two arguments (CwiseBinaryOp) +// - ternary_evaluator for expression taking three arguments (CwiseTernaryOp) +// - product_evaluator for linear algebra products (Product); special case of binary_evaluator because it requires additional tags for dispatching. +// - mapbase_evaluator for Map, Block, Ref +// - block_evaluator for Block (special dispatching to a mapbase_evaluator or unary_evaluator) + +template< typename T, + typename Arg1Kind = typename evaluator_traits::Kind, + typename Arg2Kind = typename evaluator_traits::Kind, + typename Arg3Kind = typename evaluator_traits::Kind, + typename Arg1Scalar = typename traits::Scalar, + typename Arg2Scalar = typename traits::Scalar, + typename Arg3Scalar = typename traits::Scalar> struct ternary_evaluator; + +template< typename T, + typename LhsKind = typename evaluator_traits::Kind, + typename RhsKind = typename evaluator_traits::Kind, + typename LhsScalar = typename traits::Scalar, + typename RhsScalar = typename traits::Scalar> struct binary_evaluator; + +template< typename T, + typename Kind = typename evaluator_traits::Kind, + typename Scalar = typename T::Scalar> struct unary_evaluator; + +// evaluator_traits contains traits for evaluator + +template +struct evaluator_traits_base +{ + // by default, get evaluator kind and shape from storage + typedef typename storage_kind_to_evaluator_kind::StorageKind>::Kind Kind; + typedef typename storage_kind_to_shape::StorageKind>::Shape Shape; +}; + +// Default evaluator traits +template +struct evaluator_traits : public evaluator_traits_base +{ +}; + +template::Shape > +struct evaluator_assume_aliasing { + static const bool value = false; +}; + +// By default, we assume a unary expression: +template +struct evaluator : public unary_evaluator +{ + typedef unary_evaluator Base; + EIGEN_DEVICE_FUNC explicit evaluator(const T& xpr) : Base(xpr) {} +}; + + +// TODO: Think about const-correctness +template +struct evaluator + : evaluator +{ + EIGEN_DEVICE_FUNC + explicit evaluator(const T& xpr) : evaluator(xpr) {} +}; + +// ---------- base class for all evaluators ---------- + +template +struct evaluator_base +{ + // TODO that's not very nice to have to propagate all these traits. They are currently only needed to handle outer,inner indices. + typedef traits ExpressionTraits; + + enum { + Alignment = 0 + }; + // noncopyable: + // Don't make this class inherit noncopyable as this kills EBO (Empty Base Optimization) + // and make complex evaluator much larger than then should do. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE evaluator_base() {} + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ~evaluator_base() {} +private: + EIGEN_DEVICE_FUNC evaluator_base(const evaluator_base&); + EIGEN_DEVICE_FUNC const evaluator_base& operator=(const evaluator_base&); +}; + +// -------------------- Matrix and Array -------------------- +// +// evaluator is a common base class for the +// Matrix and Array evaluators. +// Here we directly specialize evaluator. This is not really a unary expression, and it is, by definition, dense, +// so no need for more sophisticated dispatching. + +// this helper permits to completely eliminate m_outerStride if it is known at compiletime. +template class plainobjectbase_evaluator_data { +public: + EIGEN_DEVICE_FUNC plainobjectbase_evaluator_data(const Scalar* ptr, Index outerStride) : data(ptr) + { + EIGEN_ONLY_USED_FOR_DEBUG(outerStride); + eigen_internal_assert(outerStride==OuterStride); + } + EIGEN_DEVICE_FUNC Index outerStride() const { return OuterStride; } + const Scalar *data; +}; + +template class plainobjectbase_evaluator_data { +public: + EIGEN_DEVICE_FUNC plainobjectbase_evaluator_data(const Scalar* ptr, Index outerStride) : data(ptr), m_outerStride(outerStride) {} + EIGEN_DEVICE_FUNC Index outerStride() const { return m_outerStride; } + const Scalar *data; +protected: + Index m_outerStride; +}; + +template +struct evaluator > + : evaluator_base +{ + typedef PlainObjectBase PlainObjectType; + typedef typename PlainObjectType::Scalar Scalar; + typedef typename PlainObjectType::CoeffReturnType CoeffReturnType; + + enum { + IsRowMajor = PlainObjectType::IsRowMajor, + IsVectorAtCompileTime = PlainObjectType::IsVectorAtCompileTime, + RowsAtCompileTime = PlainObjectType::RowsAtCompileTime, + ColsAtCompileTime = PlainObjectType::ColsAtCompileTime, + + CoeffReadCost = NumTraits::ReadCost, + Flags = traits::EvaluatorFlags, + Alignment = traits::Alignment + }; + enum { + // We do not need to know the outer stride for vectors + OuterStrideAtCompileTime = IsVectorAtCompileTime ? 0 + : int(IsRowMajor) ? ColsAtCompileTime + : RowsAtCompileTime + }; + + EIGEN_DEVICE_FUNC evaluator() + : m_d(0,OuterStrideAtCompileTime) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + EIGEN_DEVICE_FUNC explicit evaluator(const PlainObjectType& m) + : m_d(m.data(),IsVectorAtCompileTime ? 0 : m.outerStride()) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + if (IsRowMajor) + return m_d.data[row * m_d.outerStride() + col]; + else + return m_d.data[row + col * m_d.outerStride()]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return m_d.data[index]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index row, Index col) + { + if (IsRowMajor) + return const_cast(m_d.data)[row * m_d.outerStride() + col]; + else + return const_cast(m_d.data)[row + col * m_d.outerStride()]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index index) + { + return const_cast(m_d.data)[index]; + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index row, Index col) const + { + if (IsRowMajor) + return ploadt(m_d.data + row * m_d.outerStride() + col); + else + return ploadt(m_d.data + row + col * m_d.outerStride()); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index index) const + { + return ploadt(m_d.data + index); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index row, Index col, const PacketType& x) + { + if (IsRowMajor) + return pstoret + (const_cast(m_d.data) + row * m_d.outerStride() + col, x); + else + return pstoret + (const_cast(m_d.data) + row + col * m_d.outerStride(), x); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketType& x) + { + return pstoret(const_cast(m_d.data) + index, x); + } + +protected: + + plainobjectbase_evaluator_data m_d; +}; + +template +struct evaluator > + : evaluator > > +{ + typedef Matrix XprType; + + EIGEN_DEVICE_FUNC evaluator() {} + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& m) + : evaluator >(m) + { } +}; + +template +struct evaluator > + : evaluator > > +{ + typedef Array XprType; + + EIGEN_DEVICE_FUNC evaluator() {} + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& m) + : evaluator >(m) + { } +}; + +// -------------------- Transpose -------------------- + +template +struct unary_evaluator, IndexBased> + : evaluator_base > +{ + typedef Transpose XprType; + + enum { + CoeffReadCost = evaluator::CoeffReadCost, + Flags = evaluator::Flags ^ RowMajorBit, + Alignment = evaluator::Alignment + }; + + EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& t) : m_argImpl(t.nestedExpression()) {} + + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + return m_argImpl.coeff(col, row); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return m_argImpl.coeff(index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index row, Index col) + { + return m_argImpl.coeffRef(col, row); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + typename XprType::Scalar& coeffRef(Index index) + { + return m_argImpl.coeffRef(index); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index row, Index col) const + { + return m_argImpl.template packet(col, row); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index index) const + { + return m_argImpl.template packet(index); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index row, Index col, const PacketType& x) + { + m_argImpl.template writePacket(col, row, x); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketType& x) + { + m_argImpl.template writePacket(index, x); + } + +protected: + evaluator m_argImpl; +}; + +// -------------------- CwiseNullaryOp -------------------- +// Like Matrix and Array, this is not really a unary expression, so we directly specialize evaluator. +// Likewise, there is not need to more sophisticated dispatching here. + +template::value, + bool has_unary = has_unary_operator::value, + bool has_binary = has_binary_operator::value> +struct nullary_wrapper +{ + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar operator()(const NullaryOp& op, IndexType i, IndexType j) const { return op(i,j); } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar operator()(const NullaryOp& op, IndexType i) const { return op(i); } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T packetOp(const NullaryOp& op, IndexType i, IndexType j) const { return op.template packetOp(i,j); } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T packetOp(const NullaryOp& op, IndexType i) const { return op.template packetOp(i); } +}; + +template +struct nullary_wrapper +{ + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar operator()(const NullaryOp& op, IndexType=0, IndexType=0) const { return op(); } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T packetOp(const NullaryOp& op, IndexType=0, IndexType=0) const { return op.template packetOp(); } +}; + +template +struct nullary_wrapper +{ + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar operator()(const NullaryOp& op, IndexType i, IndexType j=0) const { return op(i,j); } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T packetOp(const NullaryOp& op, IndexType i, IndexType j=0) const { return op.template packetOp(i,j); } +}; + +// We need the following specialization for vector-only functors assigned to a runtime vector, +// for instance, using linspace and assigning a RowVectorXd to a MatrixXd or even a row of a MatrixXd. +// In this case, i==0 and j is used for the actual iteration. +template +struct nullary_wrapper +{ + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar operator()(const NullaryOp& op, IndexType i, IndexType j) const { + eigen_assert(i==0 || j==0); + return op(i+j); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T packetOp(const NullaryOp& op, IndexType i, IndexType j) const { + eigen_assert(i==0 || j==0); + return op.template packetOp(i+j); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar operator()(const NullaryOp& op, IndexType i) const { return op(i); } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T packetOp(const NullaryOp& op, IndexType i) const { return op.template packetOp(i); } +}; + +template +struct nullary_wrapper {}; + +#if 0 && EIGEN_COMP_MSVC>0 +// Disable this ugly workaround. This is now handled in traits::match, +// but this piece of code might still become handly if some other weird compilation +// erros pop up again. + +// MSVC exhibits a weird compilation error when +// compiling: +// Eigen::MatrixXf A = MatrixXf::Random(3,3); +// Ref R = 2.f*A; +// and that has_*ary_operator> have not been instantiated yet. +// The "problem" is that evaluator<2.f*A> is instantiated by traits::match<2.f*A> +// and at that time has_*ary_operator returns true regardless of T. +// Then nullary_wrapper is badly instantiated as nullary_wrapper<.,.,true,true,true>. +// The trick is thus to defer the proper instantiation of nullary_wrapper when coeff(), +// and packet() are really instantiated as implemented below: + +// This is a simple wrapper around Index to enforce the re-instantiation of +// has_*ary_operator when needed. +template struct nullary_wrapper_workaround_msvc { + nullary_wrapper_workaround_msvc(const T&); + operator T()const; +}; + +template +struct nullary_wrapper +{ + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar operator()(const NullaryOp& op, IndexType i, IndexType j) const { + return nullary_wrapper >::value, + has_unary_operator >::value, + has_binary_operator >::value>().operator()(op,i,j); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar operator()(const NullaryOp& op, IndexType i) const { + return nullary_wrapper >::value, + has_unary_operator >::value, + has_binary_operator >::value>().operator()(op,i); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T packetOp(const NullaryOp& op, IndexType i, IndexType j) const { + return nullary_wrapper >::value, + has_unary_operator >::value, + has_binary_operator >::value>().template packetOp(op,i,j); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T packetOp(const NullaryOp& op, IndexType i) const { + return nullary_wrapper >::value, + has_unary_operator >::value, + has_binary_operator >::value>().template packetOp(op,i); + } +}; +#endif // MSVC workaround + +template +struct evaluator > + : evaluator_base > +{ + typedef CwiseNullaryOp XprType; + typedef typename internal::remove_all::type PlainObjectTypeCleaned; + + enum { + CoeffReadCost = internal::functor_traits::Cost, + + Flags = (evaluator::Flags + & ( HereditaryBits + | (functor_has_linear_access::ret ? LinearAccessBit : 0) + | (functor_traits::PacketAccess ? PacketAccessBit : 0))) + | (functor_traits::IsRepeatable ? 0 : EvalBeforeNestingBit), + Alignment = AlignedMax + }; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& n) + : m_functor(n.functor()), m_wrapper() + { + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + typedef typename XprType::CoeffReturnType CoeffReturnType; + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(IndexType row, IndexType col) const + { + return m_wrapper(m_functor, row, col); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(IndexType index) const + { + return m_wrapper(m_functor,index); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(IndexType row, IndexType col) const + { + return m_wrapper.template packetOp(m_functor, row, col); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(IndexType index) const + { + return m_wrapper.template packetOp(m_functor, index); + } + +protected: + const NullaryOp m_functor; + const internal::nullary_wrapper m_wrapper; +}; + +// -------------------- CwiseUnaryOp -------------------- + +template +struct unary_evaluator, IndexBased > + : evaluator_base > +{ + typedef CwiseUnaryOp XprType; + + enum { + CoeffReadCost = evaluator::CoeffReadCost + functor_traits::Cost, + + Flags = evaluator::Flags + & (HereditaryBits | LinearAccessBit | (functor_traits::PacketAccess ? PacketAccessBit : 0)), + Alignment = evaluator::Alignment + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit unary_evaluator(const XprType& op) : m_d(op) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits::Cost); + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + typedef typename XprType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + return m_d.func()(m_d.argImpl.coeff(row, col)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return m_d.func()(m_d.argImpl.coeff(index)); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index row, Index col) const + { + return m_d.func().packetOp(m_d.argImpl.template packet(row, col)); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index index) const + { + return m_d.func().packetOp(m_d.argImpl.template packet(index)); + } + +protected: + + // this helper permits to completely eliminate the functor if it is empty + class Data : private UnaryOp + { + public: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Data(const XprType& xpr) : UnaryOp(xpr.functor()), argImpl(xpr.nestedExpression()) {} + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const UnaryOp& func() const { return static_cast(*this); } + evaluator argImpl; + }; + + Data m_d; +}; + +// -------------------- CwiseTernaryOp -------------------- + +// this is a ternary expression +template +struct evaluator > + : public ternary_evaluator > +{ + typedef CwiseTernaryOp XprType; + typedef ternary_evaluator > Base; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) : Base(xpr) {} +}; + +template +struct ternary_evaluator, IndexBased, IndexBased> + : evaluator_base > +{ + typedef CwiseTernaryOp XprType; + + enum { + CoeffReadCost = evaluator::CoeffReadCost + evaluator::CoeffReadCost + evaluator::CoeffReadCost + functor_traits::Cost, + + Arg1Flags = evaluator::Flags, + Arg2Flags = evaluator::Flags, + Arg3Flags = evaluator::Flags, + SameType = is_same::value && is_same::value, + StorageOrdersAgree = (int(Arg1Flags)&RowMajorBit)==(int(Arg2Flags)&RowMajorBit) && (int(Arg1Flags)&RowMajorBit)==(int(Arg3Flags)&RowMajorBit), + Flags0 = (int(Arg1Flags) | int(Arg2Flags) | int(Arg3Flags)) & ( + HereditaryBits + | (int(Arg1Flags) & int(Arg2Flags) & int(Arg3Flags) & + ( (StorageOrdersAgree ? LinearAccessBit : 0) + | (functor_traits::PacketAccess && StorageOrdersAgree && SameType ? PacketAccessBit : 0) + ) + ) + ), + Flags = (Flags0 & ~RowMajorBit) | (Arg1Flags & RowMajorBit), + Alignment = EIGEN_PLAIN_ENUM_MIN( + EIGEN_PLAIN_ENUM_MIN(evaluator::Alignment, evaluator::Alignment), + evaluator::Alignment) + }; + + EIGEN_DEVICE_FUNC explicit ternary_evaluator(const XprType& xpr) : m_d(xpr) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits::Cost); + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + typedef typename XprType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + return m_d.func()(m_d.arg1Impl.coeff(row, col), m_d.arg2Impl.coeff(row, col), m_d.arg3Impl.coeff(row, col)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return m_d.func()(m_d.arg1Impl.coeff(index), m_d.arg2Impl.coeff(index), m_d.arg3Impl.coeff(index)); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index row, Index col) const + { + return m_d.func().packetOp(m_d.arg1Impl.template packet(row, col), + m_d.arg2Impl.template packet(row, col), + m_d.arg3Impl.template packet(row, col)); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index index) const + { + return m_d.func().packetOp(m_d.arg1Impl.template packet(index), + m_d.arg2Impl.template packet(index), + m_d.arg3Impl.template packet(index)); + } + +protected: + // this helper permits to completely eliminate the functor if it is empty + struct Data : private TernaryOp + { + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Data(const XprType& xpr) : TernaryOp(xpr.functor()), arg1Impl(xpr.arg1()), arg2Impl(xpr.arg2()), arg3Impl(xpr.arg3()) {} + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TernaryOp& func() const { return static_cast(*this); } + evaluator arg1Impl; + evaluator arg2Impl; + evaluator arg3Impl; + }; + + Data m_d; +}; + +// -------------------- CwiseBinaryOp -------------------- + +// this is a binary expression +template +struct evaluator > + : public binary_evaluator > +{ + typedef CwiseBinaryOp XprType; + typedef binary_evaluator > Base; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) : Base(xpr) {} +}; + +template +struct binary_evaluator, IndexBased, IndexBased> + : evaluator_base > +{ + typedef CwiseBinaryOp XprType; + + enum { + CoeffReadCost = evaluator::CoeffReadCost + evaluator::CoeffReadCost + functor_traits::Cost, + + LhsFlags = evaluator::Flags, + RhsFlags = evaluator::Flags, + SameType = is_same::value, + StorageOrdersAgree = (int(LhsFlags)&RowMajorBit)==(int(RhsFlags)&RowMajorBit), + Flags0 = (int(LhsFlags) | int(RhsFlags)) & ( + HereditaryBits + | (int(LhsFlags) & int(RhsFlags) & + ( (StorageOrdersAgree ? LinearAccessBit : 0) + | (functor_traits::PacketAccess && StorageOrdersAgree && SameType ? PacketAccessBit : 0) + ) + ) + ), + Flags = (Flags0 & ~RowMajorBit) | (LhsFlags & RowMajorBit), + Alignment = EIGEN_PLAIN_ENUM_MIN(evaluator::Alignment,evaluator::Alignment) + }; + + EIGEN_DEVICE_FUNC explicit binary_evaluator(const XprType& xpr) : m_d(xpr) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits::Cost); + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + typedef typename XprType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + return m_d.func()(m_d.lhsImpl.coeff(row, col), m_d.rhsImpl.coeff(row, col)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return m_d.func()(m_d.lhsImpl.coeff(index), m_d.rhsImpl.coeff(index)); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index row, Index col) const + { + return m_d.func().packetOp(m_d.lhsImpl.template packet(row, col), + m_d.rhsImpl.template packet(row, col)); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index index) const + { + return m_d.func().packetOp(m_d.lhsImpl.template packet(index), + m_d.rhsImpl.template packet(index)); + } + +protected: + + // this helper permits to completely eliminate the functor if it is empty + struct Data : private BinaryOp + { + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Data(const XprType& xpr) : BinaryOp(xpr.functor()), lhsImpl(xpr.lhs()), rhsImpl(xpr.rhs()) {} + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const BinaryOp& func() const { return static_cast(*this); } + evaluator lhsImpl; + evaluator rhsImpl; + }; + + Data m_d; +}; + +// -------------------- CwiseUnaryView -------------------- + +template +struct unary_evaluator, IndexBased> + : evaluator_base > +{ + typedef CwiseUnaryView XprType; + + enum { + CoeffReadCost = evaluator::CoeffReadCost + functor_traits::Cost, + + Flags = (evaluator::Flags & (HereditaryBits | LinearAccessBit | DirectAccessBit)), + + Alignment = 0 // FIXME it is not very clear why alignment is necessarily lost... + }; + + EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& op) : m_d(op) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits::Cost); + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + return m_d.func()(m_d.argImpl.coeff(row, col)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return m_d.func()(m_d.argImpl.coeff(index)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index row, Index col) + { + return m_d.func()(m_d.argImpl.coeffRef(row, col)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index index) + { + return m_d.func()(m_d.argImpl.coeffRef(index)); + } + +protected: + + // this helper permits to completely eliminate the functor if it is empty + struct Data : private UnaryOp + { + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Data(const XprType& xpr) : UnaryOp(xpr.functor()), argImpl(xpr.nestedExpression()) {} + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const UnaryOp& func() const { return static_cast(*this); } + evaluator argImpl; + }; + + Data m_d; +}; + +// -------------------- Map -------------------- + +// FIXME perhaps the PlainObjectType could be provided by Derived::PlainObject ? +// but that might complicate template specialization +template +struct mapbase_evaluator; + +template +struct mapbase_evaluator : evaluator_base +{ + typedef Derived XprType; + typedef typename XprType::PointerType PointerType; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + + enum { + IsRowMajor = XprType::RowsAtCompileTime, + ColsAtCompileTime = XprType::ColsAtCompileTime, + CoeffReadCost = NumTraits::ReadCost + }; + + EIGEN_DEVICE_FUNC explicit mapbase_evaluator(const XprType& map) + : m_data(const_cast(map.data())), + m_innerStride(map.innerStride()), + m_outerStride(map.outerStride()) + { + EIGEN_STATIC_ASSERT(EIGEN_IMPLIES(evaluator::Flags&PacketAccessBit, internal::inner_stride_at_compile_time::ret==1), + PACKET_ACCESS_REQUIRES_TO_HAVE_INNER_STRIDE_FIXED_TO_1); + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + return m_data[col * colStride() + row * rowStride()]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return m_data[index * m_innerStride.value()]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index row, Index col) + { + return m_data[col * colStride() + row * rowStride()]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index index) + { + return m_data[index * m_innerStride.value()]; + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index row, Index col) const + { + PointerType ptr = m_data + row * rowStride() + col * colStride(); + return internal::ploadt(ptr); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index index) const + { + return internal::ploadt(m_data + index * m_innerStride.value()); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index row, Index col, const PacketType& x) + { + PointerType ptr = m_data + row * rowStride() + col * colStride(); + return internal::pstoret(ptr, x); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketType& x) + { + internal::pstoret(m_data + index * m_innerStride.value(), x); + } +protected: + EIGEN_DEVICE_FUNC + inline Index rowStride() const { return XprType::IsRowMajor ? m_outerStride.value() : m_innerStride.value(); } + EIGEN_DEVICE_FUNC + inline Index colStride() const { return XprType::IsRowMajor ? m_innerStride.value() : m_outerStride.value(); } + + PointerType m_data; + const internal::variable_if_dynamic m_innerStride; + const internal::variable_if_dynamic m_outerStride; +}; + +template +struct evaluator > + : public mapbase_evaluator, PlainObjectType> +{ + typedef Map XprType; + typedef typename XprType::Scalar Scalar; + // TODO: should check for smaller packet types once we can handle multi-sized packet types + typedef typename packet_traits::type PacketScalar; + + enum { + InnerStrideAtCompileTime = StrideType::InnerStrideAtCompileTime == 0 + ? int(PlainObjectType::InnerStrideAtCompileTime) + : int(StrideType::InnerStrideAtCompileTime), + OuterStrideAtCompileTime = StrideType::OuterStrideAtCompileTime == 0 + ? int(PlainObjectType::OuterStrideAtCompileTime) + : int(StrideType::OuterStrideAtCompileTime), + HasNoInnerStride = InnerStrideAtCompileTime == 1, + HasNoOuterStride = StrideType::OuterStrideAtCompileTime == 0, + HasNoStride = HasNoInnerStride && HasNoOuterStride, + IsDynamicSize = PlainObjectType::SizeAtCompileTime==Dynamic, + + PacketAccessMask = bool(HasNoInnerStride) ? ~int(0) : ~int(PacketAccessBit), + LinearAccessMask = bool(HasNoStride) || bool(PlainObjectType::IsVectorAtCompileTime) ? ~int(0) : ~int(LinearAccessBit), + Flags = int( evaluator::Flags) & (LinearAccessMask&PacketAccessMask), + + Alignment = int(MapOptions)&int(AlignedMask) + }; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& map) + : mapbase_evaluator(map) + { } +}; + +// -------------------- Ref -------------------- + +template +struct evaluator > + : public mapbase_evaluator, PlainObjectType> +{ + typedef Ref XprType; + + enum { + Flags = evaluator >::Flags, + Alignment = evaluator >::Alignment + }; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& ref) + : mapbase_evaluator(ref) + { } +}; + +// -------------------- Block -------------------- + +template::ret> struct block_evaluator; + +template +struct evaluator > + : block_evaluator +{ + typedef Block XprType; + typedef typename XprType::Scalar Scalar; + // TODO: should check for smaller packet types once we can handle multi-sized packet types + typedef typename packet_traits::type PacketScalar; + + enum { + CoeffReadCost = evaluator::CoeffReadCost, + + RowsAtCompileTime = traits::RowsAtCompileTime, + ColsAtCompileTime = traits::ColsAtCompileTime, + MaxRowsAtCompileTime = traits::MaxRowsAtCompileTime, + MaxColsAtCompileTime = traits::MaxColsAtCompileTime, + + ArgTypeIsRowMajor = (int(evaluator::Flags)&RowMajorBit) != 0, + IsRowMajor = (MaxRowsAtCompileTime==1 && MaxColsAtCompileTime!=1) ? 1 + : (MaxColsAtCompileTime==1 && MaxRowsAtCompileTime!=1) ? 0 + : ArgTypeIsRowMajor, + HasSameStorageOrderAsArgType = (IsRowMajor == ArgTypeIsRowMajor), + InnerSize = IsRowMajor ? int(ColsAtCompileTime) : int(RowsAtCompileTime), + InnerStrideAtCompileTime = HasSameStorageOrderAsArgType + ? int(inner_stride_at_compile_time::ret) + : int(outer_stride_at_compile_time::ret), + OuterStrideAtCompileTime = HasSameStorageOrderAsArgType + ? int(outer_stride_at_compile_time::ret) + : int(inner_stride_at_compile_time::ret), + MaskPacketAccessBit = (InnerStrideAtCompileTime == 1) ? PacketAccessBit : 0, + + FlagsLinearAccessBit = (RowsAtCompileTime == 1 || ColsAtCompileTime == 1 || (InnerPanel && (evaluator::Flags&LinearAccessBit))) ? LinearAccessBit : 0, + FlagsRowMajorBit = XprType::Flags&RowMajorBit, + Flags0 = evaluator::Flags & ( (HereditaryBits & ~RowMajorBit) | + DirectAccessBit | + MaskPacketAccessBit), + Flags = Flags0 | FlagsLinearAccessBit | FlagsRowMajorBit, + + PacketAlignment = unpacket_traits::alignment, + Alignment0 = (InnerPanel && (OuterStrideAtCompileTime!=Dynamic) && (((OuterStrideAtCompileTime * int(sizeof(Scalar))) % int(PacketAlignment)) == 0)) ? int(PacketAlignment) : 0, + Alignment = EIGEN_PLAIN_ENUM_MIN(evaluator::Alignment, Alignment0) + }; + typedef block_evaluator block_evaluator_type; + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& block) : block_evaluator_type(block) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } +}; + +// no direct-access => dispatch to a unary evaluator +template +struct block_evaluator + : unary_evaluator > +{ + typedef Block XprType; + + EIGEN_DEVICE_FUNC explicit block_evaluator(const XprType& block) + : unary_evaluator(block) + {} +}; + +template +struct unary_evaluator, IndexBased> + : evaluator_base > +{ + typedef Block XprType; + + EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& block) + : m_argImpl(block.nestedExpression()), + m_startRow(block.startRow()), + m_startCol(block.startCol()) + { } + + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + + enum { + RowsAtCompileTime = XprType::RowsAtCompileTime + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + return m_argImpl.coeff(m_startRow.value() + row, m_startCol.value() + col); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return coeff(RowsAtCompileTime == 1 ? 0 : index, RowsAtCompileTime == 1 ? index : 0); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index row, Index col) + { + return m_argImpl.coeffRef(m_startRow.value() + row, m_startCol.value() + col); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index index) + { + return coeffRef(RowsAtCompileTime == 1 ? 0 : index, RowsAtCompileTime == 1 ? index : 0); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index row, Index col) const + { + return m_argImpl.template packet(m_startRow.value() + row, m_startCol.value() + col); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index index) const + { + return packet(RowsAtCompileTime == 1 ? 0 : index, + RowsAtCompileTime == 1 ? index : 0); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index row, Index col, const PacketType& x) + { + return m_argImpl.template writePacket(m_startRow.value() + row, m_startCol.value() + col, x); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketType& x) + { + return writePacket(RowsAtCompileTime == 1 ? 0 : index, + RowsAtCompileTime == 1 ? index : 0, + x); + } + +protected: + evaluator m_argImpl; + const variable_if_dynamic m_startRow; + const variable_if_dynamic m_startCol; +}; + +// TODO: This evaluator does not actually use the child evaluator; +// all action is via the data() as returned by the Block expression. + +template +struct block_evaluator + : mapbase_evaluator, + typename Block::PlainObject> +{ + typedef Block XprType; + typedef typename XprType::Scalar Scalar; + + EIGEN_DEVICE_FUNC explicit block_evaluator(const XprType& block) + : mapbase_evaluator(block) + { + // TODO: for the 3.3 release, this should be turned to an internal assertion, but let's keep it as is for the beta lifetime + eigen_assert(((internal::UIntPtr(block.data()) % EIGEN_PLAIN_ENUM_MAX(1,evaluator::Alignment)) == 0) && "data is not aligned"); + } +}; + + +// -------------------- Select -------------------- +// NOTE shall we introduce a ternary_evaluator? + +// TODO enable vectorization for Select +template +struct evaluator > + : evaluator_base > +{ + typedef Select XprType; + enum { + CoeffReadCost = evaluator::CoeffReadCost + + EIGEN_PLAIN_ENUM_MAX(evaluator::CoeffReadCost, + evaluator::CoeffReadCost), + + Flags = (unsigned int)evaluator::Flags & evaluator::Flags & HereditaryBits, + + Alignment = EIGEN_PLAIN_ENUM_MIN(evaluator::Alignment, evaluator::Alignment) + }; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& select) + : m_conditionImpl(select.conditionMatrix()), + m_thenImpl(select.thenMatrix()), + m_elseImpl(select.elseMatrix()) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + typedef typename XprType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + if (m_conditionImpl.coeff(row, col)) + return m_thenImpl.coeff(row, col); + else + return m_elseImpl.coeff(row, col); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + if (m_conditionImpl.coeff(index)) + return m_thenImpl.coeff(index); + else + return m_elseImpl.coeff(index); + } + +protected: + evaluator m_conditionImpl; + evaluator m_thenImpl; + evaluator m_elseImpl; +}; + + +// -------------------- Replicate -------------------- + +template +struct unary_evaluator > + : evaluator_base > +{ + typedef Replicate XprType; + typedef typename XprType::CoeffReturnType CoeffReturnType; + enum { + Factor = (RowFactor==Dynamic || ColFactor==Dynamic) ? Dynamic : RowFactor*ColFactor + }; + typedef typename internal::nested_eval::type ArgTypeNested; + typedef typename internal::remove_all::type ArgTypeNestedCleaned; + + enum { + CoeffReadCost = evaluator::CoeffReadCost, + LinearAccessMask = XprType::IsVectorAtCompileTime ? LinearAccessBit : 0, + Flags = (evaluator::Flags & (HereditaryBits|LinearAccessMask) & ~RowMajorBit) | (traits::Flags & RowMajorBit), + + Alignment = evaluator::Alignment + }; + + EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& replicate) + : m_arg(replicate.nestedExpression()), + m_argImpl(m_arg), + m_rows(replicate.nestedExpression().rows()), + m_cols(replicate.nestedExpression().cols()) + {} + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + // try to avoid using modulo; this is a pure optimization strategy + const Index actual_row = internal::traits::RowsAtCompileTime==1 ? 0 + : RowFactor==1 ? row + : row % m_rows.value(); + const Index actual_col = internal::traits::ColsAtCompileTime==1 ? 0 + : ColFactor==1 ? col + : col % m_cols.value(); + + return m_argImpl.coeff(actual_row, actual_col); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + // try to avoid using modulo; this is a pure optimization strategy + const Index actual_index = internal::traits::RowsAtCompileTime==1 + ? (ColFactor==1 ? index : index%m_cols.value()) + : (RowFactor==1 ? index : index%m_rows.value()); + + return m_argImpl.coeff(actual_index); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index row, Index col) const + { + const Index actual_row = internal::traits::RowsAtCompileTime==1 ? 0 + : RowFactor==1 ? row + : row % m_rows.value(); + const Index actual_col = internal::traits::ColsAtCompileTime==1 ? 0 + : ColFactor==1 ? col + : col % m_cols.value(); + + return m_argImpl.template packet(actual_row, actual_col); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index index) const + { + const Index actual_index = internal::traits::RowsAtCompileTime==1 + ? (ColFactor==1 ? index : index%m_cols.value()) + : (RowFactor==1 ? index : index%m_rows.value()); + + return m_argImpl.template packet(actual_index); + } + +protected: + const ArgTypeNested m_arg; + evaluator m_argImpl; + const variable_if_dynamic m_rows; + const variable_if_dynamic m_cols; +}; + + +// -------------------- PartialReduxExpr -------------------- + +template< typename ArgType, typename MemberOp, int Direction> +struct evaluator > + : evaluator_base > +{ + typedef PartialReduxExpr XprType; + typedef typename internal::nested_eval::type ArgTypeNested; + typedef typename internal::remove_all::type ArgTypeNestedCleaned; + typedef typename ArgType::Scalar InputScalar; + typedef typename XprType::Scalar Scalar; + enum { + TraversalSize = Direction==int(Vertical) ? int(ArgType::RowsAtCompileTime) : int(ArgType::ColsAtCompileTime) + }; + typedef typename MemberOp::template Cost CostOpType; + enum { + CoeffReadCost = TraversalSize==Dynamic ? HugeCost + : TraversalSize * evaluator::CoeffReadCost + int(CostOpType::value), + + Flags = (traits::Flags&RowMajorBit) | (evaluator::Flags&(HereditaryBits&(~RowMajorBit))) | LinearAccessBit, + + Alignment = 0 // FIXME this will need to be improved once PartialReduxExpr is vectorized + }; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType xpr) + : m_arg(xpr.nestedExpression()), m_functor(xpr.functor()) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(TraversalSize==Dynamic ? HugeCost : int(CostOpType::value)); + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + typedef typename XprType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const Scalar coeff(Index i, Index j) const + { + if (Direction==Vertical) + return m_functor(m_arg.col(j)); + else + return m_functor(m_arg.row(i)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const Scalar coeff(Index index) const + { + if (Direction==Vertical) + return m_functor(m_arg.col(index)); + else + return m_functor(m_arg.row(index)); + } + +protected: + typename internal::add_const_on_value_type::type m_arg; + const MemberOp m_functor; +}; + + +// -------------------- MatrixWrapper and ArrayWrapper -------------------- +// +// evaluator_wrapper_base is a common base class for the +// MatrixWrapper and ArrayWrapper evaluators. + +template +struct evaluator_wrapper_base + : evaluator_base +{ + typedef typename remove_all::type ArgType; + enum { + CoeffReadCost = evaluator::CoeffReadCost, + Flags = evaluator::Flags, + Alignment = evaluator::Alignment + }; + + EIGEN_DEVICE_FUNC explicit evaluator_wrapper_base(const ArgType& arg) : m_argImpl(arg) {} + + typedef typename ArgType::Scalar Scalar; + typedef typename ArgType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + return m_argImpl.coeff(row, col); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return m_argImpl.coeff(index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index row, Index col) + { + return m_argImpl.coeffRef(row, col); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index index) + { + return m_argImpl.coeffRef(index); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index row, Index col) const + { + return m_argImpl.template packet(row, col); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index index) const + { + return m_argImpl.template packet(index); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index row, Index col, const PacketType& x) + { + m_argImpl.template writePacket(row, col, x); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketType& x) + { + m_argImpl.template writePacket(index, x); + } + +protected: + evaluator m_argImpl; +}; + +template +struct unary_evaluator > + : evaluator_wrapper_base > +{ + typedef MatrixWrapper XprType; + + EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& wrapper) + : evaluator_wrapper_base >(wrapper.nestedExpression()) + { } +}; + +template +struct unary_evaluator > + : evaluator_wrapper_base > +{ + typedef ArrayWrapper XprType; + + EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& wrapper) + : evaluator_wrapper_base >(wrapper.nestedExpression()) + { } +}; + + +// -------------------- Reverse -------------------- + +// defined in Reverse.h: +template struct reverse_packet_cond; + +template +struct unary_evaluator > + : evaluator_base > +{ + typedef Reverse XprType; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + + enum { + IsRowMajor = XprType::IsRowMajor, + IsColMajor = !IsRowMajor, + ReverseRow = (Direction == Vertical) || (Direction == BothDirections), + ReverseCol = (Direction == Horizontal) || (Direction == BothDirections), + ReversePacket = (Direction == BothDirections) + || ((Direction == Vertical) && IsColMajor) + || ((Direction == Horizontal) && IsRowMajor), + + CoeffReadCost = evaluator::CoeffReadCost, + + // let's enable LinearAccess only with vectorization because of the product overhead + // FIXME enable DirectAccess with negative strides? + Flags0 = evaluator::Flags, + LinearAccess = ( (Direction==BothDirections) && (int(Flags0)&PacketAccessBit) ) + || ((ReverseRow && XprType::ColsAtCompileTime==1) || (ReverseCol && XprType::RowsAtCompileTime==1)) + ? LinearAccessBit : 0, + + Flags = int(Flags0) & (HereditaryBits | PacketAccessBit | LinearAccess), + + Alignment = 0 // FIXME in some rare cases, Alignment could be preserved, like a Vector4f. + }; + + EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& reverse) + : m_argImpl(reverse.nestedExpression()), + m_rows(ReverseRow ? reverse.nestedExpression().rows() : 1), + m_cols(ReverseCol ? reverse.nestedExpression().cols() : 1) + { } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + return m_argImpl.coeff(ReverseRow ? m_rows.value() - row - 1 : row, + ReverseCol ? m_cols.value() - col - 1 : col); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return m_argImpl.coeff(m_rows.value() * m_cols.value() - index - 1); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index row, Index col) + { + return m_argImpl.coeffRef(ReverseRow ? m_rows.value() - row - 1 : row, + ReverseCol ? m_cols.value() - col - 1 : col); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index index) + { + return m_argImpl.coeffRef(m_rows.value() * m_cols.value() - index - 1); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index row, Index col) const + { + enum { + PacketSize = unpacket_traits::size, + OffsetRow = ReverseRow && IsColMajor ? PacketSize : 1, + OffsetCol = ReverseCol && IsRowMajor ? PacketSize : 1 + }; + typedef internal::reverse_packet_cond reverse_packet; + return reverse_packet::run(m_argImpl.template packet( + ReverseRow ? m_rows.value() - row - OffsetRow : row, + ReverseCol ? m_cols.value() - col - OffsetCol : col)); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index index) const + { + enum { PacketSize = unpacket_traits::size }; + return preverse(m_argImpl.template packet(m_rows.value() * m_cols.value() - index - PacketSize)); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index row, Index col, const PacketType& x) + { + // FIXME we could factorize some code with packet(i,j) + enum { + PacketSize = unpacket_traits::size, + OffsetRow = ReverseRow && IsColMajor ? PacketSize : 1, + OffsetCol = ReverseCol && IsRowMajor ? PacketSize : 1 + }; + typedef internal::reverse_packet_cond reverse_packet; + m_argImpl.template writePacket( + ReverseRow ? m_rows.value() - row - OffsetRow : row, + ReverseCol ? m_cols.value() - col - OffsetCol : col, + reverse_packet::run(x)); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketType& x) + { + enum { PacketSize = unpacket_traits::size }; + m_argImpl.template writePacket + (m_rows.value() * m_cols.value() - index - PacketSize, preverse(x)); + } + +protected: + evaluator m_argImpl; + + // If we do not reverse rows, then we do not need to know the number of rows; same for columns + // Nonetheless, in this case it is important to set to 1 such that the coeff(index) method works fine for vectors. + const variable_if_dynamic m_rows; + const variable_if_dynamic m_cols; +}; + + +// -------------------- Diagonal -------------------- + +template +struct evaluator > + : evaluator_base > +{ + typedef Diagonal XprType; + + enum { + CoeffReadCost = evaluator::CoeffReadCost, + + Flags = (unsigned int)(evaluator::Flags & (HereditaryBits | DirectAccessBit) & ~RowMajorBit) | LinearAccessBit, + + Alignment = 0 + }; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& diagonal) + : m_argImpl(diagonal.nestedExpression()), + m_index(diagonal.index()) + { } + + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index) const + { + return m_argImpl.coeff(row + rowOffset(), row + colOffset()); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return m_argImpl.coeff(index + rowOffset(), index + colOffset()); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index row, Index) + { + return m_argImpl.coeffRef(row + rowOffset(), row + colOffset()); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index index) + { + return m_argImpl.coeffRef(index + rowOffset(), index + colOffset()); + } + +protected: + evaluator m_argImpl; + const internal::variable_if_dynamicindex m_index; + +private: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rowOffset() const { return m_index.value() > 0 ? 0 : -m_index.value(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index colOffset() const { return m_index.value() > 0 ? m_index.value() : 0; } +}; + + +//---------------------------------------------------------------------- +// deprecated code +//---------------------------------------------------------------------- + +// -------------------- EvalToTemp -------------------- + +// expression class for evaluating nested expression to a temporary + +template class EvalToTemp; + +template +struct traits > + : public traits +{ }; + +template +class EvalToTemp + : public dense_xpr_base >::type +{ + public: + + typedef typename dense_xpr_base::type Base; + EIGEN_GENERIC_PUBLIC_INTERFACE(EvalToTemp) + + explicit EvalToTemp(const ArgType& arg) + : m_arg(arg) + { } + + const ArgType& arg() const + { + return m_arg; + } + + Index rows() const + { + return m_arg.rows(); + } + + Index cols() const + { + return m_arg.cols(); + } + + private: + const ArgType& m_arg; +}; + +template +struct evaluator > + : public evaluator +{ + typedef EvalToTemp XprType; + typedef typename ArgType::PlainObject PlainObject; + typedef evaluator Base; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) + : m_result(xpr.arg()) + { + ::new (static_cast(this)) Base(m_result); + } + + // This constructor is used when nesting an EvalTo evaluator in another evaluator + EIGEN_DEVICE_FUNC evaluator(const ArgType& arg) + : m_result(arg) + { + ::new (static_cast(this)) Base(m_result); + } + +protected: + PlainObject m_result; +}; + +} // namespace internal + +} // end namespace Eigen + +#endif // EIGEN_COREEVALUATORS_H diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/CoreIterators.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/CoreIterators.h index 6da4683d..b9671968 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/CoreIterators.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/CoreIterators.h @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2008-2010 Gael Guennebaud +// Copyright (C) 2008-2014 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -15,47 +15,118 @@ namespace Eigen { /* This file contains the respective InnerIterator definition of the expressions defined in Eigen/Core */ -/** \ingroup SparseCore_Module - * \class InnerIterator - * \brief An InnerIterator allows to loop over the element of a sparse (or dense) matrix or expression - * - * todo +namespace internal { + +template +class inner_iterator_selector; + +} + +/** \class InnerIterator + * \brief An InnerIterator allows to loop over the element of any matrix expression. + * + * \warning To be used with care because an evaluator is constructed every time an InnerIterator iterator is constructed. + * + * TODO: add a usage example */ - -// generic version for dense matrix and expressions -template class DenseBase::InnerIterator +template +class InnerIterator { - protected: - typedef typename Derived::Scalar Scalar; - typedef typename Derived::Index Index; +protected: + typedef internal::inner_iterator_selector::Kind> IteratorType; + typedef internal::evaluator EvaluatorType; + typedef typename internal::traits::Scalar Scalar; +public: + /** Construct an iterator over the \a outerId -th row or column of \a xpr */ + InnerIterator(const XprType &xpr, const Index &outerId) + : m_eval(xpr), m_iter(m_eval, outerId, xpr.innerSize()) + {} + + /// \returns the value of the current coefficient. + EIGEN_STRONG_INLINE Scalar value() const { return m_iter.value(); } + /** Increment the iterator \c *this to the next non-zero coefficient. + * Explicit zeros are not skipped over. To skip explicit zeros, see class SparseView + */ + EIGEN_STRONG_INLINE InnerIterator& operator++() { m_iter.operator++(); return *this; } + EIGEN_STRONG_INLINE InnerIterator& operator+=(Index i) { m_iter.operator+=(i); return *this; } + EIGEN_STRONG_INLINE InnerIterator operator+(Index i) + { InnerIterator result(*this); result+=i; return result; } + - enum { IsRowMajor = (Derived::Flags&RowMajorBit)==RowMajorBit }; - public: - EIGEN_STRONG_INLINE InnerIterator(const Derived& expr, Index outer) - : m_expression(expr), m_inner(0), m_outer(outer), m_end(expr.innerSize()) - {} - - EIGEN_STRONG_INLINE Scalar value() const - { - return (IsRowMajor) ? m_expression.coeff(m_outer, m_inner) - : m_expression.coeff(m_inner, m_outer); - } - - EIGEN_STRONG_INLINE InnerIterator& operator++() { m_inner++; return *this; } - - EIGEN_STRONG_INLINE Index index() const { return m_inner; } - inline Index row() const { return IsRowMajor ? m_outer : index(); } - inline Index col() const { return IsRowMajor ? index() : m_outer; } - - EIGEN_STRONG_INLINE operator bool() const { return m_inner < m_end && m_inner>=0; } - - protected: - const Derived& m_expression; - Index m_inner; - const Index m_outer; - const Index m_end; + /// \returns the column or row index of the current coefficient. + EIGEN_STRONG_INLINE Index index() const { return m_iter.index(); } + /// \returns the row index of the current coefficient. + EIGEN_STRONG_INLINE Index row() const { return m_iter.row(); } + /// \returns the column index of the current coefficient. + EIGEN_STRONG_INLINE Index col() const { return m_iter.col(); } + /// \returns \c true if the iterator \c *this still references a valid coefficient. + EIGEN_STRONG_INLINE operator bool() const { return m_iter; } + +protected: + EvaluatorType m_eval; + IteratorType m_iter; +private: + // If you get here, then you're not using the right InnerIterator type, e.g.: + // SparseMatrix A; + // SparseMatrix::InnerIterator it(A,0); + template InnerIterator(const EigenBase&,Index outer); }; +namespace internal { + +// Generic inner iterator implementation for dense objects +template +class inner_iterator_selector +{ +protected: + typedef evaluator EvaluatorType; + typedef typename traits::Scalar Scalar; + enum { IsRowMajor = (XprType::Flags&RowMajorBit)==RowMajorBit }; + +public: + EIGEN_STRONG_INLINE inner_iterator_selector(const EvaluatorType &eval, const Index &outerId, const Index &innerSize) + : m_eval(eval), m_inner(0), m_outer(outerId), m_end(innerSize) + {} + + EIGEN_STRONG_INLINE Scalar value() const + { + return (IsRowMajor) ? m_eval.coeff(m_outer, m_inner) + : m_eval.coeff(m_inner, m_outer); + } + + EIGEN_STRONG_INLINE inner_iterator_selector& operator++() { m_inner++; return *this; } + + EIGEN_STRONG_INLINE Index index() const { return m_inner; } + inline Index row() const { return IsRowMajor ? m_outer : index(); } + inline Index col() const { return IsRowMajor ? index() : m_outer; } + + EIGEN_STRONG_INLINE operator bool() const { return m_inner < m_end && m_inner>=0; } + +protected: + const EvaluatorType& m_eval; + Index m_inner; + const Index m_outer; + const Index m_end; +}; + +// For iterator-based evaluator, inner-iterator is already implemented as +// evaluator<>::InnerIterator +template +class inner_iterator_selector + : public evaluator::InnerIterator +{ +protected: + typedef typename evaluator::InnerIterator Base; + typedef evaluator EvaluatorType; + +public: + EIGEN_STRONG_INLINE inner_iterator_selector(const EvaluatorType &eval, const Index &outerId, const Index &/*innerSize*/) + : Base(eval, outerId) + {} +}; + +} // end namespace internal + } // end namespace Eigen #endif // EIGEN_COREITERATORS_H diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/CwiseBinaryOp.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/CwiseBinaryOp.h index 586f77aa..bf2632d9 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/CwiseBinaryOp.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/CwiseBinaryOp.h @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2008-2009 Gael Guennebaud +// Copyright (C) 2008-2014 Gael Guennebaud // Copyright (C) 2006-2008 Benoit Jacob // // This Source Code Form is subject to the terms of the Mozilla @@ -13,26 +13,6 @@ namespace Eigen { -/** \class CwiseBinaryOp - * \ingroup Core_Module - * - * \brief Generic expression where a coefficient-wise binary operator is applied to two expressions - * - * \param BinaryOp template functor implementing the operator - * \param Lhs the type of the left-hand side - * \param Rhs the type of the right-hand side - * - * This class represents an expression where a coefficient-wise binary operator is applied to two expressions. - * It is the return type of binary operators, by which we mean only those binary operators where - * both the left-hand side and the right-hand side are Eigen expressions. - * For example, the return type of matrix1+matrix2 is a CwiseBinaryOp. - * - * Most of the time, this is the only way that it is used, so you typically don't have to name - * CwiseBinaryOp types explicitly. - * - * \sa MatrixBase::binaryExpr(const MatrixBase &,const CustomBinaryOp &) const, class CwiseUnaryOp, class CwiseNullaryOp - */ - namespace internal { template struct traits > @@ -52,76 +32,75 @@ struct traits > // we still want to handle the case when the result type is different. typedef typename result_of< BinaryOp( - typename Lhs::Scalar, - typename Rhs::Scalar + const typename Lhs::Scalar&, + const typename Rhs::Scalar& ) >::type Scalar; - typedef typename promote_storage_type::StorageKind, - typename traits::StorageKind>::ret StorageKind; - typedef typename promote_index_type::Index, - typename traits::Index>::type Index; + typedef typename cwise_promote_storage_type::StorageKind, + typename traits::StorageKind, + BinaryOp>::ret StorageKind; + typedef typename promote_index_type::StorageIndex, + typename traits::StorageIndex>::type StorageIndex; typedef typename Lhs::Nested LhsNested; typedef typename Rhs::Nested RhsNested; typedef typename remove_reference::type _LhsNested; typedef typename remove_reference::type _RhsNested; enum { - LhsCoeffReadCost = _LhsNested::CoeffReadCost, - RhsCoeffReadCost = _RhsNested::CoeffReadCost, - LhsFlags = _LhsNested::Flags, - RhsFlags = _RhsNested::Flags, - SameType = is_same::value, - StorageOrdersAgree = (int(Lhs::Flags)&RowMajorBit)==(int(Rhs::Flags)&RowMajorBit), - Flags0 = (int(LhsFlags) | int(RhsFlags)) & ( - HereditaryBits - | (int(LhsFlags) & int(RhsFlags) & - ( AlignedBit - | (StorageOrdersAgree ? LinearAccessBit : 0) - | (functor_traits::PacketAccess && StorageOrdersAgree && SameType ? PacketAccessBit : 0) - ) - ) - ), - Flags = (Flags0 & ~RowMajorBit) | (LhsFlags & RowMajorBit), - CoeffReadCost = LhsCoeffReadCost + RhsCoeffReadCost + functor_traits::Cost + Flags = cwise_promote_storage_order::StorageKind,typename traits::StorageKind,_LhsNested::Flags & RowMajorBit,_RhsNested::Flags & RowMajorBit>::value }; }; } // end namespace internal -// we require Lhs and Rhs to have the same scalar type. Currently there is no example of a binary functor -// that would take two operands of different types. If there were such an example, then this check should be -// moved to the BinaryOp functors, on a per-case basis. This would however require a change in the BinaryOp functors, as -// currently they take only one typename Scalar template parameter. -// It is tempting to always allow mixing different types but remember that this is often impossible in the vectorized paths. -// So allowing mixing different types gives very unexpected errors when enabling vectorization, when the user tries to -// add together a float matrix and a double matrix. -#define EIGEN_CHECK_BINARY_COMPATIBILIY(BINOP,LHS,RHS) \ - EIGEN_STATIC_ASSERT((internal::functor_is_product_like::ret \ - ? int(internal::scalar_product_traits::Defined) \ - : int(internal::is_same::value)), \ - YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) - template class CwiseBinaryOpImpl; -template -class CwiseBinaryOp : internal::no_assignment_operator, +/** \class CwiseBinaryOp + * \ingroup Core_Module + * + * \brief Generic expression where a coefficient-wise binary operator is applied to two expressions + * + * \tparam BinaryOp template functor implementing the operator + * \tparam LhsType the type of the left-hand side + * \tparam RhsType the type of the right-hand side + * + * This class represents an expression where a coefficient-wise binary operator is applied to two expressions. + * It is the return type of binary operators, by which we mean only those binary operators where + * both the left-hand side and the right-hand side are Eigen expressions. + * For example, the return type of matrix1+matrix2 is a CwiseBinaryOp. + * + * Most of the time, this is the only way that it is used, so you typically don't have to name + * CwiseBinaryOp types explicitly. + * + * \sa MatrixBase::binaryExpr(const MatrixBase &,const CustomBinaryOp &) const, class CwiseUnaryOp, class CwiseNullaryOp + */ +template +class CwiseBinaryOp : public CwiseBinaryOpImpl< - BinaryOp, Lhs, Rhs, - typename internal::promote_storage_type::StorageKind, - typename internal::traits::StorageKind>::ret> + BinaryOp, LhsType, RhsType, + typename internal::cwise_promote_storage_type::StorageKind, + typename internal::traits::StorageKind, + BinaryOp>::ret>, + internal::no_assignment_operator { public: + + typedef typename internal::remove_all::type Functor; + typedef typename internal::remove_all::type Lhs; + typedef typename internal::remove_all::type Rhs; typedef typename CwiseBinaryOpImpl< - BinaryOp, Lhs, Rhs, - typename internal::promote_storage_type::StorageKind, - typename internal::traits::StorageKind>::ret>::Base Base; + BinaryOp, LhsType, RhsType, + typename internal::cwise_promote_storage_type::StorageKind, + typename internal::traits::StorageKind, + BinaryOp>::ret>::Base Base; EIGEN_GENERIC_PUBLIC_INTERFACE(CwiseBinaryOp) - typedef typename internal::nested::type LhsNested; - typedef typename internal::nested::type RhsNested; + typedef typename internal::ref_selector::type LhsNested; + typedef typename internal::ref_selector::type RhsNested; typedef typename internal::remove_reference::type _LhsNested; typedef typename internal::remove_reference::type _RhsNested; + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CwiseBinaryOp(const Lhs& aLhs, const Rhs& aRhs, const BinaryOp& func = BinaryOp()) : m_lhs(aLhs), m_rhs(aRhs), m_functor(func) { @@ -131,6 +110,7 @@ class CwiseBinaryOp : internal::no_assignment_operator, eigen_assert(aLhs.rows() == aRhs.rows() && aLhs.cols() == aRhs.cols()); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rows() const { // return the fixed size type if available to enable compile time optimizations if (internal::traits::type>::RowsAtCompileTime==Dynamic) @@ -138,6 +118,7 @@ class CwiseBinaryOp : internal::no_assignment_operator, else return m_lhs.rows(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index cols() const { // return the fixed size type if available to enable compile time optimizations if (internal::traits::type>::ColsAtCompileTime==Dynamic) @@ -147,10 +128,13 @@ class CwiseBinaryOp : internal::no_assignment_operator, } /** \returns the left hand side nested expression */ + EIGEN_DEVICE_FUNC const _LhsNested& lhs() const { return m_lhs; } /** \returns the right hand side nested expression */ + EIGEN_DEVICE_FUNC const _RhsNested& rhs() const { return m_rhs; } /** \returns the functor representing the binary operation */ + EIGEN_DEVICE_FUNC const BinaryOp& functor() const { return m_functor; } protected: @@ -159,41 +143,13 @@ class CwiseBinaryOp : internal::no_assignment_operator, const BinaryOp m_functor; }; -template -class CwiseBinaryOpImpl - : public internal::dense_xpr_base >::type +// Generic API dispatcher +template +class CwiseBinaryOpImpl + : public internal::generic_xpr_base >::type { - typedef CwiseBinaryOp Derived; - public: - - typedef typename internal::dense_xpr_base >::type Base; - EIGEN_DENSE_PUBLIC_INTERFACE( Derived ) - - EIGEN_STRONG_INLINE const Scalar coeff(Index rowId, Index colId) const - { - return derived().functor()(derived().lhs().coeff(rowId, colId), - derived().rhs().coeff(rowId, colId)); - } - - template - EIGEN_STRONG_INLINE PacketScalar packet(Index rowId, Index colId) const - { - return derived().functor().packetOp(derived().lhs().template packet(rowId, colId), - derived().rhs().template packet(rowId, colId)); - } - - EIGEN_STRONG_INLINE const Scalar coeff(Index index) const - { - return derived().functor()(derived().lhs().coeff(index), - derived().rhs().coeff(index)); - } - - template - EIGEN_STRONG_INLINE PacketScalar packet(Index index) const - { - return derived().functor().packetOp(derived().lhs().template packet(index), - derived().rhs().template packet(index)); - } +public: + typedef typename internal::generic_xpr_base >::type Base; }; /** replaces \c *this by \c *this - \a other. @@ -202,11 +158,10 @@ class CwiseBinaryOpImpl */ template template -EIGEN_STRONG_INLINE Derived & +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived & MatrixBase::operator-=(const MatrixBase &other) { - SelfCwiseBinaryOp, Derived, OtherDerived> tmp(derived()); - tmp = other.derived(); + call_assignment(derived(), other.derived(), internal::sub_assign_op()); return derived(); } @@ -216,11 +171,10 @@ MatrixBase::operator-=(const MatrixBase &other) */ template template -EIGEN_STRONG_INLINE Derived & +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived & MatrixBase::operator+=(const MatrixBase& other) { - SelfCwiseBinaryOp, Derived, OtherDerived> tmp(derived()); - tmp = other.derived(); + call_assignment(derived(), other.derived(), internal::add_assign_op()); return derived(); } diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/CwiseNullaryOp.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/CwiseNullaryOp.h index a93bab2d..144608ec 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/CwiseNullaryOp.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/CwiseNullaryOp.h @@ -12,13 +12,24 @@ namespace Eigen { +namespace internal { +template +struct traits > : traits +{ + enum { + Flags = traits::Flags & RowMajorBit + }; +}; + +} // namespace internal + /** \class CwiseNullaryOp * \ingroup Core_Module * * \brief Generic expression of a matrix where all coefficients are defined by a functor * - * \param NullaryOp template functor implementing the operator - * \param PlainObjectType the underlying plain matrix/array type + * \tparam NullaryOp template functor implementing the operator + * \tparam PlainObjectType the underlying plain matrix/array type * * This class represents an expression of a generic nullary operator. * It is the return type of the Ones(), Zero(), Constant(), Identity() and Random() methods, @@ -27,68 +38,49 @@ namespace Eigen { * However, if you want to write a function returning such an expression, you * will need to use this class. * - * \sa class CwiseUnaryOp, class CwiseBinaryOp, DenseBase::NullaryExpr() + * The functor NullaryOp must expose one of the following method: + + + + +
\c operator()() if the procedural generation does not depend on the coefficient entries (e.g., random numbers)
\c operator()(Index i)if the procedural generation makes sense for vectors only and that it depends on the coefficient index \c i (e.g., linspace)
\c operator()(Index i,Index j)if the procedural generation depends on the matrix coordinates \c i, \c j (e.g., to generate a checkerboard with 0 and 1)
+ * It is also possible to expose the last two operators if the generation makes sense for matrices but can be optimized for vectors. + * + * See DenseBase::NullaryExpr(Index,const CustomNullaryOp&) for an example binding + * C++11 random number generators. + * + * A nullary expression can also be used to implement custom sophisticated matrix manipulations + * that cannot be covered by the existing set of natively supported matrix manipulations. + * See this \ref TopicCustomizing_NullaryExpr "page" for some examples and additional explanations + * on the behavior of CwiseNullaryOp. + * + * \sa class CwiseUnaryOp, class CwiseBinaryOp, DenseBase::NullaryExpr */ - -namespace internal { template -struct traits > : traits -{ - enum { - Flags = (traits::Flags - & ( HereditaryBits - | (functor_has_linear_access::ret ? LinearAccessBit : 0) - | (functor_traits::PacketAccess ? PacketAccessBit : 0))) - | (functor_traits::IsRepeatable ? 0 : EvalBeforeNestingBit), - CoeffReadCost = functor_traits::Cost - }; -}; -} - -template -class CwiseNullaryOp : internal::no_assignment_operator, - public internal::dense_xpr_base< CwiseNullaryOp >::type +class CwiseNullaryOp : public internal::dense_xpr_base< CwiseNullaryOp >::type, internal::no_assignment_operator { public: typedef typename internal::dense_xpr_base::type Base; EIGEN_DENSE_PUBLIC_INTERFACE(CwiseNullaryOp) - CwiseNullaryOp(Index nbRows, Index nbCols, const NullaryOp& func = NullaryOp()) - : m_rows(nbRows), m_cols(nbCols), m_functor(func) + EIGEN_DEVICE_FUNC + CwiseNullaryOp(Index rows, Index cols, const NullaryOp& func = NullaryOp()) + : m_rows(rows), m_cols(cols), m_functor(func) { - eigen_assert(nbRows >= 0 - && (RowsAtCompileTime == Dynamic || RowsAtCompileTime == nbRows) - && nbCols >= 0 - && (ColsAtCompileTime == Dynamic || ColsAtCompileTime == nbCols)); + eigen_assert(rows >= 0 + && (RowsAtCompileTime == Dynamic || RowsAtCompileTime == rows) + && cols >= 0 + && (ColsAtCompileTime == Dynamic || ColsAtCompileTime == cols)); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rows() const { return m_rows.value(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index cols() const { return m_cols.value(); } - EIGEN_STRONG_INLINE const Scalar coeff(Index rowId, Index colId) const - { - return m_functor(rowId, colId); - } - - template - EIGEN_STRONG_INLINE PacketScalar packet(Index rowId, Index colId) const - { - return m_functor.packetOp(rowId, colId); - } - - EIGEN_STRONG_INLINE const Scalar coeff(Index index) const - { - return m_functor(index); - } - - template - EIGEN_STRONG_INLINE PacketScalar packet(Index index) const - { - return m_functor.packetOp(index); - } - /** \returns the functor representing the nullary operation */ + EIGEN_DEVICE_FUNC const NullaryOp& functor() const { return m_functor; } protected: @@ -113,10 +105,10 @@ class CwiseNullaryOp : internal::no_assignment_operator, */ template template -EIGEN_STRONG_INLINE const CwiseNullaryOp +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const CwiseNullaryOp::PlainObject> DenseBase::NullaryExpr(Index rows, Index cols, const CustomNullaryOp& func) { - return CwiseNullaryOp(rows, cols, func); + return CwiseNullaryOp(rows, cols, func); } /** \returns an expression of a matrix defined by a custom functor \a func @@ -132,16 +124,19 @@ DenseBase::NullaryExpr(Index rows, Index cols, const CustomNullaryOp& f * * The template parameter \a CustomNullaryOp is the type of the functor. * + * Here is an example with C++11 random generators: \include random_cpp11.cpp + * Output: \verbinclude random_cpp11.out + * * \sa class CwiseNullaryOp */ template template -EIGEN_STRONG_INLINE const CwiseNullaryOp +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const CwiseNullaryOp::PlainObject> DenseBase::NullaryExpr(Index size, const CustomNullaryOp& func) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) - if(RowsAtCompileTime == 1) return CwiseNullaryOp(1, size, func); - else return CwiseNullaryOp(size, 1, func); + if(RowsAtCompileTime == 1) return CwiseNullaryOp(1, size, func); + else return CwiseNullaryOp(size, 1, func); } /** \returns an expression of a matrix defined by a custom functor \a func @@ -155,19 +150,19 @@ DenseBase::NullaryExpr(Index size, const CustomNullaryOp& func) */ template template -EIGEN_STRONG_INLINE const CwiseNullaryOp +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const CwiseNullaryOp::PlainObject> DenseBase::NullaryExpr(const CustomNullaryOp& func) { - return CwiseNullaryOp(RowsAtCompileTime, ColsAtCompileTime, func); + return CwiseNullaryOp(RowsAtCompileTime, ColsAtCompileTime, func); } /** \returns an expression of a constant matrix of value \a value * - * The parameters \a nbRows and \a nbCols are the number of rows and of columns of + * The parameters \a rows and \a cols are the number of rows and of columns of * the returned matrix. Must be compatible with this DenseBase type. * * This variant is meant to be used for dynamic-size matrix types. For fixed-size types, - * it is redundant to pass \a nbRows and \a nbCols as arguments, so Zero() should be used + * it is redundant to pass \a rows and \a cols as arguments, so Zero() should be used * instead. * * The template parameter \a CustomNullaryOp is the type of the functor. @@ -175,10 +170,10 @@ DenseBase::NullaryExpr(const CustomNullaryOp& func) * \sa class CwiseNullaryOp */ template -EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType -DenseBase::Constant(Index nbRows, Index nbCols, const Scalar& value) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType +DenseBase::Constant(Index rows, Index cols, const Scalar& value) { - return DenseBase::NullaryExpr(nbRows, nbCols, internal::scalar_constant_op(value)); + return DenseBase::NullaryExpr(rows, cols, internal::scalar_constant_op(value)); } /** \returns an expression of a constant matrix of value \a value @@ -197,7 +192,7 @@ DenseBase::Constant(Index nbRows, Index nbCols, const Scalar& value) * \sa class CwiseNullaryOp */ template -EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType DenseBase::Constant(Index size, const Scalar& value) { return DenseBase::NullaryExpr(size, internal::scalar_constant_op(value)); @@ -213,53 +208,40 @@ DenseBase::Constant(Index size, const Scalar& value) * \sa class CwiseNullaryOp */ template -EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType DenseBase::Constant(const Scalar& value) { EIGEN_STATIC_ASSERT_FIXED_SIZE(Derived) return DenseBase::NullaryExpr(RowsAtCompileTime, ColsAtCompileTime, internal::scalar_constant_op(value)); } -/** - * \brief Sets a linearly space vector. +/** \deprecated because of accuracy loss. In Eigen 3.3, it is an alias for LinSpaced(Index,const Scalar&,const Scalar&) * - * The function generates 'size' equally spaced values in the closed interval [low,high]. - * This particular version of LinSpaced() uses sequential access, i.e. vector access is - * assumed to be a(0), a(1), ..., a(size). This assumption allows for better vectorization - * and yields faster code than the random access version. - * - * When size is set to 1, a vector of length 1 containing 'high' is returned. - * - * \only_for_vectors - * - * Example: \include DenseBase_LinSpaced_seq.cpp - * Output: \verbinclude DenseBase_LinSpaced_seq.out - * - * \sa setLinSpaced(Index,const Scalar&,const Scalar&), LinSpaced(Index,Scalar,Scalar), CwiseNullaryOp + * \sa LinSpaced(Index,Scalar,Scalar), setLinSpaced(Index,const Scalar&,const Scalar&) */ template -EIGEN_STRONG_INLINE const typename DenseBase::SequentialLinSpacedReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::RandomAccessLinSpacedReturnType DenseBase::LinSpaced(Sequential_t, Index size, const Scalar& low, const Scalar& high) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) - return DenseBase::NullaryExpr(size, internal::linspaced_op(low,high,size)); + return DenseBase::NullaryExpr(size, internal::linspaced_op(low,high,size)); } -/** - * \copydoc DenseBase::LinSpaced(Sequential_t, Index, const Scalar&, const Scalar&) - * Special version for fixed size types which does not require the size parameter. +/** \deprecated because of accuracy loss. In Eigen 3.3, it is an alias for LinSpaced(const Scalar&,const Scalar&) + * + * \sa LinSpaced(Scalar,Scalar) */ template -EIGEN_STRONG_INLINE const typename DenseBase::SequentialLinSpacedReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::RandomAccessLinSpacedReturnType DenseBase::LinSpaced(Sequential_t, const Scalar& low, const Scalar& high) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) EIGEN_STATIC_ASSERT_FIXED_SIZE(Derived) - return DenseBase::NullaryExpr(Derived::SizeAtCompileTime, internal::linspaced_op(low,high,Derived::SizeAtCompileTime)); + return DenseBase::NullaryExpr(Derived::SizeAtCompileTime, internal::linspaced_op(low,high,Derived::SizeAtCompileTime)); } /** - * \brief Sets a linearly space vector. + * \brief Sets a linearly spaced vector. * * The function generates 'size' equally spaced values in the closed interval [low,high]. * When size is set to 1, a vector of length 1 containing 'high' is returned. @@ -269,14 +251,24 @@ DenseBase::LinSpaced(Sequential_t, const Scalar& low, const Scalar& hig * Example: \include DenseBase_LinSpaced.cpp * Output: \verbinclude DenseBase_LinSpaced.out * - * \sa setLinSpaced(Index,const Scalar&,const Scalar&), LinSpaced(Sequential_t,Index,const Scalar&,const Scalar&,Index), CwiseNullaryOp + * For integer scalar types, an even spacing is possible if and only if the length of the range, + * i.e., \c high-low is a scalar multiple of \c size-1, or if \c size is a scalar multiple of the + * number of values \c high-low+1 (meaning each value can be repeated the same number of time). + * If one of these two considions is not satisfied, then \c high is lowered to the largest value + * satisfying one of this constraint. + * Here are some examples: + * + * Example: \include DenseBase_LinSpacedInt.cpp + * Output: \verbinclude DenseBase_LinSpacedInt.out + * + * \sa setLinSpaced(Index,const Scalar&,const Scalar&), CwiseNullaryOp */ template -EIGEN_STRONG_INLINE const typename DenseBase::RandomAccessLinSpacedReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::RandomAccessLinSpacedReturnType DenseBase::LinSpaced(Index size, const Scalar& low, const Scalar& high) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) - return DenseBase::NullaryExpr(size, internal::linspaced_op(low,high,size)); + return DenseBase::NullaryExpr(size, internal::linspaced_op(low,high,size)); } /** @@ -284,22 +276,23 @@ DenseBase::LinSpaced(Index size, const Scalar& low, const Scalar& high) * Special version for fixed size types which does not require the size parameter. */ template -EIGEN_STRONG_INLINE const typename DenseBase::RandomAccessLinSpacedReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::RandomAccessLinSpacedReturnType DenseBase::LinSpaced(const Scalar& low, const Scalar& high) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) EIGEN_STATIC_ASSERT_FIXED_SIZE(Derived) - return DenseBase::NullaryExpr(Derived::SizeAtCompileTime, internal::linspaced_op(low,high,Derived::SizeAtCompileTime)); + return DenseBase::NullaryExpr(Derived::SizeAtCompileTime, internal::linspaced_op(low,high,Derived::SizeAtCompileTime)); } /** \returns true if all coefficients in this matrix are approximately equal to \a val, to within precision \a prec */ template -bool DenseBase::isApproxToConstant +EIGEN_DEVICE_FUNC bool DenseBase::isApproxToConstant (const Scalar& val, const RealScalar& prec) const { + typename internal::nested_eval::type self(derived()); for(Index j = 0; j < cols(); ++j) for(Index i = 0; i < rows(); ++i) - if(!internal::isApprox(this->coeff(i, j), val, prec)) + if(!internal::isApprox(self.coeff(i, j), val, prec)) return false; return true; } @@ -308,7 +301,7 @@ bool DenseBase::isApproxToConstant * * \returns true if all coefficients in this matrix are approximately equal to \a value, to within precision \a prec */ template -bool DenseBase::isConstant +EIGEN_DEVICE_FUNC bool DenseBase::isConstant (const Scalar& val, const RealScalar& prec) const { return isApproxToConstant(val, prec); @@ -319,22 +312,22 @@ bool DenseBase::isConstant * \sa setConstant(), Constant(), class CwiseNullaryOp */ template -EIGEN_STRONG_INLINE void DenseBase::fill(const Scalar& val) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void DenseBase::fill(const Scalar& val) { setConstant(val); } -/** Sets all coefficients in this expression to \a value. +/** Sets all coefficients in this expression to value \a val. * * \sa fill(), setConstant(Index,const Scalar&), setConstant(Index,Index,const Scalar&), setZero(), setOnes(), Constant(), class CwiseNullaryOp, setZero(), setOnes() */ template -EIGEN_STRONG_INLINE Derived& DenseBase::setConstant(const Scalar& val) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& DenseBase::setConstant(const Scalar& val) { return derived() = Constant(rows(), cols(), val); } -/** Resizes to the given \a size, and sets all coefficients in this expression to the given \a value. +/** Resizes to the given \a size, and sets all coefficients in this expression to the given value \a val. * * \only_for_vectors * @@ -344,17 +337,17 @@ EIGEN_STRONG_INLINE Derived& DenseBase::setConstant(const Scalar& val) * \sa MatrixBase::setConstant(const Scalar&), setConstant(Index,Index,const Scalar&), class CwiseNullaryOp, MatrixBase::Constant(const Scalar&) */ template -EIGEN_STRONG_INLINE Derived& +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& PlainObjectBase::setConstant(Index size, const Scalar& val) { resize(size); return setConstant(val); } -/** Resizes to the given size, and sets all coefficients in this expression to the given \a value. +/** Resizes to the given size, and sets all coefficients in this expression to the given value \a val. * - * \param nbRows the new number of rows - * \param nbCols the new number of columns + * \param rows the new number of rows + * \param cols the new number of columns * \param val the value to which all coefficients are set * * Example: \include Matrix_setConstant_int_int.cpp @@ -363,15 +356,15 @@ PlainObjectBase::setConstant(Index size, const Scalar& val) * \sa MatrixBase::setConstant(const Scalar&), setConstant(Index,const Scalar&), class CwiseNullaryOp, MatrixBase::Constant(const Scalar&) */ template -EIGEN_STRONG_INLINE Derived& -PlainObjectBase::setConstant(Index nbRows, Index nbCols, const Scalar& val) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& +PlainObjectBase::setConstant(Index rows, Index cols, const Scalar& val) { - resize(nbRows, nbCols); + resize(rows, cols); return setConstant(val); } /** - * \brief Sets a linearly space vector. + * \brief Sets a linearly spaced vector. * * The function generates 'size' equally spaced values in the closed interval [low,high]. * When size is set to 1, a vector of length 1 containing 'high' is returned. @@ -381,27 +374,33 @@ PlainObjectBase::setConstant(Index nbRows, Index nbCols, const Scalar& * Example: \include DenseBase_setLinSpaced.cpp * Output: \verbinclude DenseBase_setLinSpaced.out * - * \sa CwiseNullaryOp + * For integer scalar types, do not miss the explanations on the definition + * of \link LinSpaced(Index,const Scalar&,const Scalar&) even spacing \endlink. + * + * \sa LinSpaced(Index,const Scalar&,const Scalar&), CwiseNullaryOp */ template -EIGEN_STRONG_INLINE Derived& DenseBase::setLinSpaced(Index newSize, const Scalar& low, const Scalar& high) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& DenseBase::setLinSpaced(Index newSize, const Scalar& low, const Scalar& high) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) - return derived() = Derived::NullaryExpr(newSize, internal::linspaced_op(low,high,newSize)); + return derived() = Derived::NullaryExpr(newSize, internal::linspaced_op(low,high,newSize)); } /** - * \brief Sets a linearly space vector. + * \brief Sets a linearly spaced vector. * - * The function fill *this with equally spaced values in the closed interval [low,high]. + * The function fills \c *this with equally spaced values in the closed interval [low,high]. * When size is set to 1, a vector of length 1 containing 'high' is returned. * * \only_for_vectors * - * \sa setLinSpaced(Index, const Scalar&, const Scalar&), CwiseNullaryOp + * For integer scalar types, do not miss the explanations on the definition + * of \link LinSpaced(Index,const Scalar&,const Scalar&) even spacing \endlink. + * + * \sa LinSpaced(Index,const Scalar&,const Scalar&), setLinSpaced(Index, const Scalar&, const Scalar&), CwiseNullaryOp */ template -EIGEN_STRONG_INLINE Derived& DenseBase::setLinSpaced(const Scalar& low, const Scalar& high) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& DenseBase::setLinSpaced(const Scalar& low, const Scalar& high) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) return setLinSpaced(size(), low, high); @@ -424,10 +423,10 @@ EIGEN_STRONG_INLINE Derived& DenseBase::setLinSpaced(const Scalar& low, * \sa Zero(), Zero(Index) */ template -EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType -DenseBase::Zero(Index nbRows, Index nbCols) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType +DenseBase::Zero(Index rows, Index cols) { - return Constant(nbRows, nbCols, Scalar(0)); + return Constant(rows, cols, Scalar(0)); } /** \returns an expression of a zero vector. @@ -447,7 +446,7 @@ DenseBase::Zero(Index nbRows, Index nbCols) * \sa Zero(), Zero(Index,Index) */ template -EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType DenseBase::Zero(Index size) { return Constant(size, Scalar(0)); @@ -464,7 +463,7 @@ DenseBase::Zero(Index size) * \sa Zero(Index), Zero(Index,Index) */ template -EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType DenseBase::Zero() { return Constant(Scalar(0)); @@ -479,11 +478,12 @@ DenseBase::Zero() * \sa class CwiseNullaryOp, Zero() */ template -bool DenseBase::isZero(const RealScalar& prec) const +EIGEN_DEVICE_FUNC bool DenseBase::isZero(const RealScalar& prec) const { + typename internal::nested_eval::type self(derived()); for(Index j = 0; j < cols(); ++j) for(Index i = 0; i < rows(); ++i) - if(!internal::isMuchSmallerThan(this->coeff(i, j), static_cast(1), prec)) + if(!internal::isMuchSmallerThan(self.coeff(i, j), static_cast(1), prec)) return false; return true; } @@ -496,7 +496,7 @@ bool DenseBase::isZero(const RealScalar& prec) const * \sa class CwiseNullaryOp, Zero() */ template -EIGEN_STRONG_INLINE Derived& DenseBase::setZero() +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& DenseBase::setZero() { return setConstant(Scalar(0)); } @@ -511,7 +511,7 @@ EIGEN_STRONG_INLINE Derived& DenseBase::setZero() * \sa DenseBase::setZero(), setZero(Index,Index), class CwiseNullaryOp, DenseBase::Zero() */ template -EIGEN_STRONG_INLINE Derived& +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& PlainObjectBase::setZero(Index newSize) { resize(newSize); @@ -520,8 +520,8 @@ PlainObjectBase::setZero(Index newSize) /** Resizes to the given size, and sets all coefficients in this expression to zero. * - * \param nbRows the new number of rows - * \param nbCols the new number of columns + * \param rows the new number of rows + * \param cols the new number of columns * * Example: \include Matrix_setZero_int_int.cpp * Output: \verbinclude Matrix_setZero_int_int.out @@ -529,10 +529,10 @@ PlainObjectBase::setZero(Index newSize) * \sa DenseBase::setZero(), setZero(Index), class CwiseNullaryOp, DenseBase::Zero() */ template -EIGEN_STRONG_INLINE Derived& -PlainObjectBase::setZero(Index nbRows, Index nbCols) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& +PlainObjectBase::setZero(Index rows, Index cols) { - resize(nbRows, nbCols); + resize(rows, cols); return setConstant(Scalar(0)); } @@ -540,7 +540,7 @@ PlainObjectBase::setZero(Index nbRows, Index nbCols) /** \returns an expression of a matrix where all coefficients equal one. * - * The parameters \a nbRows and \a nbCols are the number of rows and of columns of + * The parameters \a rows and \a cols are the number of rows and of columns of * the returned matrix. Must be compatible with this MatrixBase type. * * This variant is meant to be used for dynamic-size matrix types. For fixed-size types, @@ -553,10 +553,10 @@ PlainObjectBase::setZero(Index nbRows, Index nbCols) * \sa Ones(), Ones(Index), isOnes(), class Ones */ template -EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType -DenseBase::Ones(Index nbRows, Index nbCols) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType +DenseBase::Ones(Index rows, Index cols) { - return Constant(nbRows, nbCols, Scalar(1)); + return Constant(rows, cols, Scalar(1)); } /** \returns an expression of a vector where all coefficients equal one. @@ -576,7 +576,7 @@ DenseBase::Ones(Index nbRows, Index nbCols) * \sa Ones(), Ones(Index,Index), isOnes(), class Ones */ template -EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType DenseBase::Ones(Index newSize) { return Constant(newSize, Scalar(1)); @@ -593,7 +593,7 @@ DenseBase::Ones(Index newSize) * \sa Ones(Index), Ones(Index,Index), isOnes(), class Ones */ template -EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType DenseBase::Ones() { return Constant(Scalar(1)); @@ -608,7 +608,7 @@ DenseBase::Ones() * \sa class CwiseNullaryOp, Ones() */ template -bool DenseBase::isOnes +EIGEN_DEVICE_FUNC bool DenseBase::isOnes (const RealScalar& prec) const { return isApproxToConstant(Scalar(1), prec); @@ -622,7 +622,7 @@ bool DenseBase::isOnes * \sa class CwiseNullaryOp, Ones() */ template -EIGEN_STRONG_INLINE Derived& DenseBase::setOnes() +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& DenseBase::setOnes() { return setConstant(Scalar(1)); } @@ -637,7 +637,7 @@ EIGEN_STRONG_INLINE Derived& DenseBase::setOnes() * \sa MatrixBase::setOnes(), setOnes(Index,Index), class CwiseNullaryOp, MatrixBase::Ones() */ template -EIGEN_STRONG_INLINE Derived& +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& PlainObjectBase::setOnes(Index newSize) { resize(newSize); @@ -646,8 +646,8 @@ PlainObjectBase::setOnes(Index newSize) /** Resizes to the given size, and sets all coefficients in this expression to one. * - * \param nbRows the new number of rows - * \param nbCols the new number of columns + * \param rows the new number of rows + * \param cols the new number of columns * * Example: \include Matrix_setOnes_int_int.cpp * Output: \verbinclude Matrix_setOnes_int_int.out @@ -655,10 +655,10 @@ PlainObjectBase::setOnes(Index newSize) * \sa MatrixBase::setOnes(), setOnes(Index), class CwiseNullaryOp, MatrixBase::Ones() */ template -EIGEN_STRONG_INLINE Derived& -PlainObjectBase::setOnes(Index nbRows, Index nbCols) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& +PlainObjectBase::setOnes(Index rows, Index cols) { - resize(nbRows, nbCols); + resize(rows, cols); return setConstant(Scalar(1)); } @@ -666,7 +666,7 @@ PlainObjectBase::setOnes(Index nbRows, Index nbCols) /** \returns an expression of the identity matrix (not necessarily square). * - * The parameters \a nbRows and \a nbCols are the number of rows and of columns of + * The parameters \a rows and \a cols are the number of rows and of columns of * the returned matrix. Must be compatible with this MatrixBase type. * * This variant is meant to be used for dynamic-size matrix types. For fixed-size types, @@ -679,10 +679,10 @@ PlainObjectBase::setOnes(Index nbRows, Index nbCols) * \sa Identity(), setIdentity(), isIdentity() */ template -EIGEN_STRONG_INLINE const typename MatrixBase::IdentityReturnType -MatrixBase::Identity(Index nbRows, Index nbCols) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename MatrixBase::IdentityReturnType +MatrixBase::Identity(Index rows, Index cols) { - return DenseBase::NullaryExpr(nbRows, nbCols, internal::scalar_identity_op()); + return DenseBase::NullaryExpr(rows, cols, internal::scalar_identity_op()); } /** \returns an expression of the identity matrix (not necessarily square). @@ -696,7 +696,7 @@ MatrixBase::Identity(Index nbRows, Index nbCols) * \sa Identity(Index,Index), setIdentity(), isIdentity() */ template -EIGEN_STRONG_INLINE const typename MatrixBase::IdentityReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename MatrixBase::IdentityReturnType MatrixBase::Identity() { EIGEN_STATIC_ASSERT_FIXED_SIZE(Derived) @@ -716,18 +716,19 @@ template bool MatrixBase::isIdentity (const RealScalar& prec) const { + typename internal::nested_eval::type self(derived()); for(Index j = 0; j < cols(); ++j) { for(Index i = 0; i < rows(); ++i) { if(i == j) { - if(!internal::isApprox(this->coeff(i, j), static_cast(1), prec)) + if(!internal::isApprox(self.coeff(i, j), static_cast(1), prec)) return false; } else { - if(!internal::isMuchSmallerThan(this->coeff(i, j), static_cast(1), prec)) + if(!internal::isMuchSmallerThan(self.coeff(i, j), static_cast(1), prec)) return false; } } @@ -740,6 +741,7 @@ namespace internal { template=16)> struct setIdentity_impl { + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Derived& run(Derived& m) { return m = Derived::Identity(m.rows(), m.cols()); @@ -749,11 +751,11 @@ struct setIdentity_impl template struct setIdentity_impl { - typedef typename Derived::Index Index; + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Derived& run(Derived& m) { m.setZero(); - const Index size = (std::min)(m.rows(), m.cols()); + const Index size = numext::mini(m.rows(), m.cols()); for(Index i = 0; i < size; ++i) m.coeffRef(i,i) = typename Derived::Scalar(1); return m; } @@ -769,15 +771,15 @@ struct setIdentity_impl * \sa class CwiseNullaryOp, Identity(), Identity(Index,Index), isIdentity() */ template -EIGEN_STRONG_INLINE Derived& MatrixBase::setIdentity() +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& MatrixBase::setIdentity() { return internal::setIdentity_impl::run(derived()); } /** \brief Resizes to the given size, and writes the identity expression (not necessarily square) into *this. * - * \param nbRows the new number of rows - * \param nbCols the new number of columns + * \param rows the new number of rows + * \param cols the new number of columns * * Example: \include Matrix_setIdentity_int_int.cpp * Output: \verbinclude Matrix_setIdentity_int_int.out @@ -785,9 +787,9 @@ EIGEN_STRONG_INLINE Derived& MatrixBase::setIdentity() * \sa MatrixBase::setIdentity(), class CwiseNullaryOp, MatrixBase::Identity() */ template -EIGEN_STRONG_INLINE Derived& MatrixBase::setIdentity(Index nbRows, Index nbCols) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& MatrixBase::setIdentity(Index rows, Index cols) { - derived().resize(nbRows, nbCols); + derived().resize(rows, cols); return setIdentity(); } @@ -798,7 +800,7 @@ EIGEN_STRONG_INLINE Derived& MatrixBase::setIdentity(Index nbRows, Inde * \sa MatrixBase::Unit(Index), MatrixBase::UnitX(), MatrixBase::UnitY(), MatrixBase::UnitZ(), MatrixBase::UnitW() */ template -EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::Unit(Index newSize, Index i) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::Unit(Index newSize, Index i) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) return BasisReturnType(SquareMatrixType::Identity(newSize,newSize), i); @@ -813,7 +815,7 @@ EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBa * \sa MatrixBase::Unit(Index,Index), MatrixBase::UnitX(), MatrixBase::UnitY(), MatrixBase::UnitZ(), MatrixBase::UnitW() */ template -EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::Unit(Index i) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::Unit(Index i) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) return BasisReturnType(SquareMatrixType::Identity(),i); @@ -826,7 +828,7 @@ EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBa * \sa MatrixBase::Unit(Index,Index), MatrixBase::Unit(Index), MatrixBase::UnitY(), MatrixBase::UnitZ(), MatrixBase::UnitW() */ template -EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::UnitX() +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::UnitX() { return Derived::Unit(0); } /** \returns an expression of the Y axis unit vector (0,1{,0}^*) @@ -836,7 +838,7 @@ EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBa * \sa MatrixBase::Unit(Index,Index), MatrixBase::Unit(Index), MatrixBase::UnitY(), MatrixBase::UnitZ(), MatrixBase::UnitW() */ template -EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::UnitY() +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::UnitY() { return Derived::Unit(1); } /** \returns an expression of the Z axis unit vector (0,0,1{,0}^*) @@ -846,7 +848,7 @@ EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBa * \sa MatrixBase::Unit(Index,Index), MatrixBase::Unit(Index), MatrixBase::UnitY(), MatrixBase::UnitZ(), MatrixBase::UnitW() */ template -EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::UnitZ() +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::UnitZ() { return Derived::Unit(2); } /** \returns an expression of the W axis unit vector (0,0,0,1) @@ -856,7 +858,7 @@ EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBa * \sa MatrixBase::Unit(Index,Index), MatrixBase::Unit(Index), MatrixBase::UnitY(), MatrixBase::UnitZ(), MatrixBase::UnitW() */ template -EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::UnitW() +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::UnitW() { return Derived::Unit(3); } } // end namespace Eigen diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/CwiseTernaryOp.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/CwiseTernaryOp.h new file mode 100644 index 00000000..9f3576fe --- /dev/null +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/CwiseTernaryOp.h @@ -0,0 +1,197 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2008-2014 Gael Guennebaud +// Copyright (C) 2006-2008 Benoit Jacob +// Copyright (C) 2016 Eugene Brevdo +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CWISE_TERNARY_OP_H +#define EIGEN_CWISE_TERNARY_OP_H + +namespace Eigen { + +namespace internal { +template +struct traits > { + // we must not inherit from traits since it has + // the potential to cause problems with MSVC + typedef typename remove_all::type Ancestor; + typedef typename traits::XprKind XprKind; + enum { + RowsAtCompileTime = traits::RowsAtCompileTime, + ColsAtCompileTime = traits::ColsAtCompileTime, + MaxRowsAtCompileTime = traits::MaxRowsAtCompileTime, + MaxColsAtCompileTime = traits::MaxColsAtCompileTime + }; + + // even though we require Arg1, Arg2, and Arg3 to have the same scalar type + // (see CwiseTernaryOp constructor), + // we still want to handle the case when the result type is different. + typedef typename result_of::type Scalar; + + typedef typename internal::traits::StorageKind StorageKind; + typedef typename internal::traits::StorageIndex StorageIndex; + + typedef typename Arg1::Nested Arg1Nested; + typedef typename Arg2::Nested Arg2Nested; + typedef typename Arg3::Nested Arg3Nested; + typedef typename remove_reference::type _Arg1Nested; + typedef typename remove_reference::type _Arg2Nested; + typedef typename remove_reference::type _Arg3Nested; + enum { Flags = _Arg1Nested::Flags & RowMajorBit }; +}; +} // end namespace internal + +template +class CwiseTernaryOpImpl; + +/** \class CwiseTernaryOp + * \ingroup Core_Module + * + * \brief Generic expression where a coefficient-wise ternary operator is + * applied to two expressions + * + * \tparam TernaryOp template functor implementing the operator + * \tparam Arg1Type the type of the first argument + * \tparam Arg2Type the type of the second argument + * \tparam Arg3Type the type of the third argument + * + * This class represents an expression where a coefficient-wise ternary + * operator is applied to three expressions. + * It is the return type of ternary operators, by which we mean only those + * ternary operators where + * all three arguments are Eigen expressions. + * For example, the return type of betainc(matrix1, matrix2, matrix3) is a + * CwiseTernaryOp. + * + * Most of the time, this is the only way that it is used, so you typically + * don't have to name + * CwiseTernaryOp types explicitly. + * + * \sa MatrixBase::ternaryExpr(const MatrixBase &, const + * MatrixBase &, const CustomTernaryOp &) const, class CwiseBinaryOp, + * class CwiseUnaryOp, class CwiseNullaryOp + */ +template +class CwiseTernaryOp : public CwiseTernaryOpImpl< + TernaryOp, Arg1Type, Arg2Type, Arg3Type, + typename internal::traits::StorageKind>, + internal::no_assignment_operator +{ + public: + typedef typename internal::remove_all::type Arg1; + typedef typename internal::remove_all::type Arg2; + typedef typename internal::remove_all::type Arg3; + + typedef typename CwiseTernaryOpImpl< + TernaryOp, Arg1Type, Arg2Type, Arg3Type, + typename internal::traits::StorageKind>::Base Base; + EIGEN_GENERIC_PUBLIC_INTERFACE(CwiseTernaryOp) + + typedef typename internal::ref_selector::type Arg1Nested; + typedef typename internal::ref_selector::type Arg2Nested; + typedef typename internal::ref_selector::type Arg3Nested; + typedef typename internal::remove_reference::type _Arg1Nested; + typedef typename internal::remove_reference::type _Arg2Nested; + typedef typename internal::remove_reference::type _Arg3Nested; + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE CwiseTernaryOp(const Arg1& a1, const Arg2& a2, + const Arg3& a3, + const TernaryOp& func = TernaryOp()) + : m_arg1(a1), m_arg2(a2), m_arg3(a3), m_functor(func) { + // require the sizes to match + EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Arg1, Arg2) + EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Arg1, Arg3) + + // The index types should match + EIGEN_STATIC_ASSERT((internal::is_same< + typename internal::traits::StorageKind, + typename internal::traits::StorageKind>::value), + STORAGE_KIND_MUST_MATCH) + EIGEN_STATIC_ASSERT((internal::is_same< + typename internal::traits::StorageKind, + typename internal::traits::StorageKind>::value), + STORAGE_KIND_MUST_MATCH) + + eigen_assert(a1.rows() == a2.rows() && a1.cols() == a2.cols() && + a1.rows() == a3.rows() && a1.cols() == a3.cols()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Index rows() const { + // return the fixed size type if available to enable compile time + // optimizations + if (internal::traits::type>:: + RowsAtCompileTime == Dynamic && + internal::traits::type>:: + RowsAtCompileTime == Dynamic) + return m_arg3.rows(); + else if (internal::traits::type>:: + RowsAtCompileTime == Dynamic && + internal::traits::type>:: + RowsAtCompileTime == Dynamic) + return m_arg2.rows(); + else + return m_arg1.rows(); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Index cols() const { + // return the fixed size type if available to enable compile time + // optimizations + if (internal::traits::type>:: + ColsAtCompileTime == Dynamic && + internal::traits::type>:: + ColsAtCompileTime == Dynamic) + return m_arg3.cols(); + else if (internal::traits::type>:: + ColsAtCompileTime == Dynamic && + internal::traits::type>:: + ColsAtCompileTime == Dynamic) + return m_arg2.cols(); + else + return m_arg1.cols(); + } + + /** \returns the first argument nested expression */ + EIGEN_DEVICE_FUNC + const _Arg1Nested& arg1() const { return m_arg1; } + /** \returns the first argument nested expression */ + EIGEN_DEVICE_FUNC + const _Arg2Nested& arg2() const { return m_arg2; } + /** \returns the third argument nested expression */ + EIGEN_DEVICE_FUNC + const _Arg3Nested& arg3() const { return m_arg3; } + /** \returns the functor representing the ternary operation */ + EIGEN_DEVICE_FUNC + const TernaryOp& functor() const { return m_functor; } + + protected: + Arg1Nested m_arg1; + Arg2Nested m_arg2; + Arg3Nested m_arg3; + const TernaryOp m_functor; +}; + +// Generic API dispatcher +template +class CwiseTernaryOpImpl + : public internal::generic_xpr_base< + CwiseTernaryOp >::type { + public: + typedef typename internal::generic_xpr_base< + CwiseTernaryOp >::type Base; +}; + +} // end namespace Eigen + +#endif // EIGEN_CWISE_TERNARY_OP_H diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/CwiseUnaryOp.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/CwiseUnaryOp.h index f2de749f..1d2dd19f 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/CwiseUnaryOp.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/CwiseUnaryOp.h @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2008-2010 Gael Guennebaud +// Copyright (C) 2008-2014 Gael Guennebaud // Copyright (C) 2006-2008 Benoit Jacob // // This Source Code Form is subject to the terms of the Mozilla @@ -13,13 +13,32 @@ namespace Eigen { +namespace internal { +template +struct traits > + : traits +{ + typedef typename result_of< + UnaryOp(const typename XprType::Scalar&) + >::type Scalar; + typedef typename XprType::Nested XprTypeNested; + typedef typename remove_reference::type _XprTypeNested; + enum { + Flags = _XprTypeNested::Flags & RowMajorBit + }; +}; +} + +template +class CwiseUnaryOpImpl; + /** \class CwiseUnaryOp * \ingroup Core_Module * * \brief Generic expression where a coefficient-wise unary operator is applied to an expression * - * \param UnaryOp template functor implementing the operator - * \param XprType the type of the expression to which we are applying the unary operator + * \tparam UnaryOp template functor implementing the operator + * \tparam XprType the type of the expression to which we are applying the unary operator * * This class represents an expression where a unary operator is applied to an expression. * It is the return type of all operations taking exactly 1 input expression, regardless of the @@ -32,93 +51,51 @@ namespace Eigen { * * \sa MatrixBase::unaryExpr(const CustomUnaryOp &) const, class CwiseBinaryOp, class CwiseNullaryOp */ - -namespace internal { template -struct traits > - : traits -{ - typedef typename result_of< - UnaryOp(typename XprType::Scalar) - >::type Scalar; - typedef typename XprType::Nested XprTypeNested; - typedef typename remove_reference::type _XprTypeNested; - enum { - Flags = _XprTypeNested::Flags & ( - HereditaryBits | LinearAccessBit | AlignedBit - | (functor_traits::PacketAccess ? PacketAccessBit : 0)), - CoeffReadCost = _XprTypeNested::CoeffReadCost + functor_traits::Cost - }; -}; -} - -template -class CwiseUnaryOpImpl; - -template -class CwiseUnaryOp : internal::no_assignment_operator, - public CwiseUnaryOpImpl::StorageKind> +class CwiseUnaryOp : public CwiseUnaryOpImpl::StorageKind>, internal::no_assignment_operator { public: typedef typename CwiseUnaryOpImpl::StorageKind>::Base Base; EIGEN_GENERIC_PUBLIC_INTERFACE(CwiseUnaryOp) + typedef typename internal::ref_selector::type XprTypeNested; + typedef typename internal::remove_all::type NestedExpression; - inline CwiseUnaryOp(const XprType& xpr, const UnaryOp& func = UnaryOp()) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit CwiseUnaryOp(const XprType& xpr, const UnaryOp& func = UnaryOp()) : m_xpr(xpr), m_functor(func) {} - EIGEN_STRONG_INLINE Index rows() const { return m_xpr.rows(); } - EIGEN_STRONG_INLINE Index cols() const { return m_xpr.cols(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Index rows() const { return m_xpr.rows(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Index cols() const { return m_xpr.cols(); } /** \returns the functor representing the unary operation */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const UnaryOp& functor() const { return m_functor; } /** \returns the nested expression */ - const typename internal::remove_all::type& + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const typename internal::remove_all::type& nestedExpression() const { return m_xpr; } /** \returns the nested expression */ - typename internal::remove_all::type& - nestedExpression() { return m_xpr.const_cast_derived(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + typename internal::remove_all::type& + nestedExpression() { return m_xpr; } protected: - typename XprType::Nested m_xpr; + XprTypeNested m_xpr; const UnaryOp m_functor; }; -// This is the generic implementation for dense storage. -// It can be used for any expression types implementing the dense concept. -template -class CwiseUnaryOpImpl - : public internal::dense_xpr_base >::type +// Generic API dispatcher +template +class CwiseUnaryOpImpl + : public internal::generic_xpr_base >::type { - public: - - typedef CwiseUnaryOp Derived; - typedef typename internal::dense_xpr_base >::type Base; - EIGEN_DENSE_PUBLIC_INTERFACE(Derived) - - EIGEN_STRONG_INLINE const Scalar coeff(Index rowId, Index colId) const - { - return derived().functor()(derived().nestedExpression().coeff(rowId, colId)); - } - - template - EIGEN_STRONG_INLINE PacketScalar packet(Index rowId, Index colId) const - { - return derived().functor().packetOp(derived().nestedExpression().template packet(rowId, colId)); - } - - EIGEN_STRONG_INLINE const Scalar coeff(Index index) const - { - return derived().functor()(derived().nestedExpression().coeff(index)); - } - - template - EIGEN_STRONG_INLINE PacketScalar packet(Index index) const - { - return derived().functor().packetOp(derived().nestedExpression().template packet(index)); - } +public: + typedef typename internal::generic_xpr_base >::type Base; }; } // end namespace Eigen diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/CwiseUnaryView.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/CwiseUnaryView.h index b2638d32..27103305 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/CwiseUnaryView.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/CwiseUnaryView.h @@ -12,33 +12,19 @@ namespace Eigen { -/** \class CwiseUnaryView - * \ingroup Core_Module - * - * \brief Generic lvalue expression of a coefficient-wise unary operator of a matrix or a vector - * - * \param ViewOp template functor implementing the view - * \param MatrixType the type of the matrix we are applying the unary operator - * - * This class represents a lvalue expression of a generic unary view operator of a matrix or a vector. - * It is the return type of real() and imag(), and most of the time this is the only way it is used. - * - * \sa MatrixBase::unaryViewExpr(const CustomUnaryOp &) const, class CwiseUnaryOp - */ - namespace internal { template struct traits > : traits { typedef typename result_of< - ViewOp(typename traits::Scalar) + ViewOp(const typename traits::Scalar&) >::type Scalar; typedef typename MatrixType::Nested MatrixTypeNested; typedef typename remove_all::type _MatrixTypeNested; enum { - Flags = (traits<_MatrixTypeNested>::Flags & (HereditaryBits | LvalueBit | LinearAccessBit | DirectAccessBit)), - CoeffReadCost = traits<_MatrixTypeNested>::CoeffReadCost + functor_traits::Cost, + FlagsLvalueBit = is_lvalue::value ? LvalueBit : 0, + Flags = traits<_MatrixTypeNested>::Flags & (RowMajorBit | FlagsLvalueBit | DirectAccessBit), // FIXME DirectAccessBit should not be handled by expressions MatrixTypeInnerStride = inner_stride_at_compile_time::ret, // need to cast the sizeof's from size_t to int explicitly, otherwise: // "error: no integral type can represent all of the enumerator values @@ -55,6 +41,19 @@ struct traits > template class CwiseUnaryViewImpl; +/** \class CwiseUnaryView + * \ingroup Core_Module + * + * \brief Generic lvalue expression of a coefficient-wise unary operator of a matrix or a vector + * + * \tparam ViewOp template functor implementing the view + * \tparam MatrixType the type of the matrix we are applying the unary operator + * + * This class represents a lvalue expression of a generic unary view operator of a matrix or a vector. + * It is the return type of real() and imag(), and most of the time this is the only way it is used. + * + * \sa MatrixBase::unaryViewExpr(const CustomUnaryOp &) const, class CwiseUnaryOp + */ template class CwiseUnaryView : public CwiseUnaryViewImpl::StorageKind> { @@ -62,8 +61,10 @@ class CwiseUnaryView : public CwiseUnaryViewImpl::StorageKind>::Base Base; EIGEN_GENERIC_PUBLIC_INTERFACE(CwiseUnaryView) + typedef typename internal::ref_selector::non_const_type MatrixTypeNested; + typedef typename internal::remove_all::type NestedExpression; - inline CwiseUnaryView(const MatrixType& mat, const ViewOp& func = ViewOp()) + explicit inline CwiseUnaryView(MatrixType& mat, const ViewOp& func = ViewOp()) : m_matrix(mat), m_functor(func) {} EIGEN_INHERIT_ASSIGNMENT_OPERATORS(CwiseUnaryView) @@ -75,19 +76,27 @@ class CwiseUnaryView : public CwiseUnaryViewImpl::type& + const typename internal::remove_all::type& nestedExpression() const { return m_matrix; } /** \returns the nested expression */ - typename internal::remove_all::type& + typename internal::remove_reference::type& nestedExpression() { return m_matrix.const_cast_derived(); } protected: - // FIXME changed from MatrixType::Nested because of a weird compilation error with sun CC - typename internal::nested::type m_matrix; + MatrixTypeNested m_matrix; ViewOp m_functor; }; +// Generic API dispatcher +template +class CwiseUnaryViewImpl + : public internal::generic_xpr_base >::type +{ +public: + typedef typename internal::generic_xpr_base >::type Base; +}; + template class CwiseUnaryViewImpl : public internal::dense_xpr_base< CwiseUnaryView >::type @@ -100,38 +109,18 @@ class CwiseUnaryViewImpl EIGEN_DENSE_PUBLIC_INTERFACE(Derived) EIGEN_INHERIT_ASSIGNMENT_OPERATORS(CwiseUnaryViewImpl) - inline Scalar* data() { return &coeffRef(0); } - inline const Scalar* data() const { return &coeff(0); } + EIGEN_DEVICE_FUNC inline Scalar* data() { return &(this->coeffRef(0)); } + EIGEN_DEVICE_FUNC inline const Scalar* data() const { return &(this->coeff(0)); } - inline Index innerStride() const + EIGEN_DEVICE_FUNC inline Index innerStride() const { return derived().nestedExpression().innerStride() * sizeof(typename internal::traits::Scalar) / sizeof(Scalar); } - inline Index outerStride() const + EIGEN_DEVICE_FUNC inline Index outerStride() const { return derived().nestedExpression().outerStride() * sizeof(typename internal::traits::Scalar) / sizeof(Scalar); } - - EIGEN_STRONG_INLINE CoeffReturnType coeff(Index row, Index col) const - { - return derived().functor()(derived().nestedExpression().coeff(row, col)); - } - - EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const - { - return derived().functor()(derived().nestedExpression().coeff(index)); - } - - EIGEN_STRONG_INLINE Scalar& coeffRef(Index row, Index col) - { - return derived().functor()(const_cast_derived().nestedExpression().coeffRef(row, col)); - } - - EIGEN_STRONG_INLINE Scalar& coeffRef(Index index) - { - return derived().functor()(const_cast_derived().nestedExpression().coeffRef(index)); - } }; } // end namespace Eigen diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/DenseBase.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/DenseBase.h index 04862f37..fd933eed 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/DenseBase.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/DenseBase.h @@ -34,37 +34,45 @@ static inline void check_DenseIndex_is_signed() { * \tparam Derived is the derived type, e.g., a matrix type or an expression. * * This class can be extended with the help of the plugin mechanism described on the page - * \ref TopicCustomizingEigen by defining the preprocessor symbol \c EIGEN_DENSEBASE_PLUGIN. + * \ref TopicCustomizing_Plugins by defining the preprocessor symbol \c EIGEN_DENSEBASE_PLUGIN. * - * \sa \ref TopicClassHierarchy + * \sa \blank \ref TopicClassHierarchy */ template class DenseBase #ifndef EIGEN_PARSED_BY_DOXYGEN - : public internal::special_scalar_op_base::Scalar, - typename NumTraits::Scalar>::Real> -#else : public DenseCoeffsBase +#else + : public DenseCoeffsBase #endif // not EIGEN_PARSED_BY_DOXYGEN { public: - using internal::special_scalar_op_base::Scalar, - typename NumTraits::Scalar>::Real>::operator*; - class InnerIterator; + /** Inner iterator type to iterate over the coefficients of a row or column. + * \sa class InnerIterator + */ + typedef Eigen::InnerIterator InnerIterator; typedef typename internal::traits::StorageKind StorageKind; - /** \brief The type of indices - * \details To change this, \c \#define the preprocessor symbol \c EIGEN_DEFAULT_DENSE_INDEX_TYPE. - * \sa \ref TopicPreprocessorDirectives. - */ - typedef typename internal::traits::Index Index; + /** + * \brief The type used to store indices + * \details This typedef is relevant for types that store multiple indices such as + * PermutationMatrix or Transpositions, otherwise it defaults to Eigen::Index + * \sa \blank \ref TopicPreprocessorDirectives, Eigen::Index, SparseMatrixBase. + */ + typedef typename internal::traits::StorageIndex StorageIndex; + /** The numeric type of the expression' coefficients, e.g. float, double, int or std::complex, etc. */ typedef typename internal::traits::Scalar Scalar; - typedef typename internal::packet_traits::type PacketScalar; + + /** The numeric type of the expression' coefficients, e.g. float, double, int or std::complex, etc. + * + * It is an alias for the Scalar type */ + typedef Scalar value_type; + typedef typename NumTraits::Real RealScalar; - typedef DenseCoeffsBase Base; + using Base::derived; using Base::const_cast_derived; using Base::rows; @@ -74,16 +82,6 @@ template class DenseBase using Base::colIndexByOuterInner; using Base::coeff; using Base::coeffByOuterInner; - using Base::packet; - using Base::packetByOuterInner; - using Base::writePacket; - using Base::writePacketByOuterInner; - using Base::coeffRef; - using Base::coeffRefByOuterInner; - using Base::copyCoeff; - using Base::copyCoeffByOuterInner; - using Base::copyPacket; - using Base::copyPacketByOuterInner; using Base::operator(); using Base::operator[]; using Base::x; @@ -169,30 +167,54 @@ template class DenseBase InnerSizeAtCompileTime = int(IsVectorAtCompileTime) ? int(SizeAtCompileTime) : int(IsRowMajor) ? int(ColsAtCompileTime) : int(RowsAtCompileTime), - CoeffReadCost = internal::traits::CoeffReadCost, - /**< This is a rough measure of how expensive it is to read one coefficient from - * this expression. - */ - InnerStrideAtCompileTime = internal::inner_stride_at_compile_time::ret, OuterStrideAtCompileTime = internal::outer_stride_at_compile_time::ret }; + + typedef typename internal::find_best_packet::type PacketScalar; - enum { ThisConstantIsPrivateInPlainObjectBase }; + enum { IsPlainObjectBase = 0 }; + + /** The plain matrix type corresponding to this expression. + * \sa PlainObject */ + typedef Matrix::Scalar, + internal::traits::RowsAtCompileTime, + internal::traits::ColsAtCompileTime, + AutoAlign | (internal::traits::Flags&RowMajorBit ? RowMajor : ColMajor), + internal::traits::MaxRowsAtCompileTime, + internal::traits::MaxColsAtCompileTime + > PlainMatrix; + + /** The plain array type corresponding to this expression. + * \sa PlainObject */ + typedef Array::Scalar, + internal::traits::RowsAtCompileTime, + internal::traits::ColsAtCompileTime, + AutoAlign | (internal::traits::Flags&RowMajorBit ? RowMajor : ColMajor), + internal::traits::MaxRowsAtCompileTime, + internal::traits::MaxColsAtCompileTime + > PlainArray; + + /** \brief The plain matrix or array type corresponding to this expression. + * + * This is not necessarily exactly the return type of eval(). In the case of plain matrices, + * the return type of eval() is a const reference to a matrix, not a matrix! It is however guaranteed + * that the return type of eval() is either PlainObject or const PlainObject&. + */ + typedef typename internal::conditional::XprKind,MatrixXpr >::value, + PlainMatrix, PlainArray>::type PlainObject; /** \returns the number of nonzero coefficients which is in practice the number * of stored coefficients. */ + EIGEN_DEVICE_FUNC inline Index nonZeros() const { return size(); } - /** \returns true if either the number of rows or the number of columns is equal to 1. - * In other words, this function returns - * \code rows()==1 || cols()==1 \endcode - * \sa rows(), cols(), IsVectorAtCompileTime. */ /** \returns the outer size. * * \note For a vector, this returns just 1. For a matrix (non-vector), this is the major dimension * with respect to the \ref TopicStorageOrders "storage order", i.e., the number of columns for a * column-major matrix, and the number of rows for a row-major matrix. */ + EIGEN_DEVICE_FUNC Index outerSize() const { return IsVectorAtCompileTime ? 1 @@ -204,6 +226,7 @@ template class DenseBase * \note For a vector, this is just the size. For a matrix (non-vector), this is the minor dimension * with respect to the \ref TopicStorageOrders "storage order", i.e., the number of rows for a * column-major matrix, and the number of columns for a row-major matrix. */ + EIGEN_DEVICE_FUNC Index innerSize() const { return IsVectorAtCompileTime ? this->size() @@ -214,6 +237,7 @@ template class DenseBase * Matrix::resize() and Array::resize(). The present method only asserts that the new size equals the old size, and does * nothing else. */ + EIGEN_DEVICE_FUNC void resize(Index newSize) { EIGEN_ONLY_USED_FOR_DEBUG(newSize); @@ -224,22 +248,22 @@ template class DenseBase * Matrix::resize() and Array::resize(). The present method only asserts that the new size equals the old size, and does * nothing else. */ - void resize(Index nbRows, Index nbCols) + EIGEN_DEVICE_FUNC + void resize(Index rows, Index cols) { - EIGEN_ONLY_USED_FOR_DEBUG(nbRows); - EIGEN_ONLY_USED_FOR_DEBUG(nbCols); - eigen_assert(nbRows == this->rows() && nbCols == this->cols() + EIGEN_ONLY_USED_FOR_DEBUG(rows); + EIGEN_ONLY_USED_FOR_DEBUG(cols); + eigen_assert(rows == this->rows() && cols == this->cols() && "DenseBase::resize() does not actually allow to resize."); } #ifndef EIGEN_PARSED_BY_DOXYGEN - /** \internal Represents a matrix with all coefficients equal to one another*/ - typedef CwiseNullaryOp,Derived> ConstantReturnType; - /** \internal Represents a vector with linearly spaced coefficients that allows sequential access only. */ - typedef CwiseNullaryOp,Derived> SequentialLinSpacedReturnType; + typedef CwiseNullaryOp,PlainObject> ConstantReturnType; + /** \internal \deprecated Represents a vector with linearly spaced coefficients that allows sequential access only. */ + typedef CwiseNullaryOp,PlainObject> SequentialLinSpacedReturnType; /** \internal Represents a vector with linearly spaced coefficients that allows random access. */ - typedef CwiseNullaryOp,Derived> RandomAccessLinSpacedReturnType; + typedef CwiseNullaryOp,PlainObject> RandomAccessLinSpacedReturnType; /** \internal the return type of MatrixBase::eigenvalues() */ typedef Matrix::Scalar>::Real, internal::traits::ColsAtCompileTime, 1> EigenvaluesReturnType; @@ -247,118 +271,133 @@ template class DenseBase /** Copies \a other into *this. \returns a reference to *this. */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const DenseBase& other); /** Special case of the template operator=, in order to prevent the compiler * from generating a default operator= (issue hit with g++ 4.1) */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const DenseBase& other); template + EIGEN_DEVICE_FUNC Derived& operator=(const EigenBase &other); template + EIGEN_DEVICE_FUNC Derived& operator+=(const EigenBase &other); template + EIGEN_DEVICE_FUNC Derived& operator-=(const EigenBase &other); template + EIGEN_DEVICE_FUNC Derived& operator=(const ReturnByValue& func); -#ifndef EIGEN_PARSED_BY_DOXYGEN - /** Copies \a other into *this without evaluating other. \returns a reference to *this. */ + /** \internal + * Copies \a other into *this without evaluating other. \returns a reference to *this. + * \deprecated */ template + EIGEN_DEVICE_FUNC Derived& lazyAssign(const DenseBase& other); -#endif // not EIGEN_PARSED_BY_DOXYGEN + EIGEN_DEVICE_FUNC CommaInitializer operator<< (const Scalar& s); + /** \deprecated it now returns \c *this */ template - const Flagged flagged() const; + EIGEN_DEPRECATED + const Derived& flagged() const + { return derived(); } template + EIGEN_DEVICE_FUNC CommaInitializer operator<< (const DenseBase& other); - Eigen::Transpose transpose(); - typedef typename internal::add_const >::type ConstTransposeReturnType; + typedef Transpose TransposeReturnType; + EIGEN_DEVICE_FUNC + TransposeReturnType transpose(); + typedef typename internal::add_const >::type ConstTransposeReturnType; + EIGEN_DEVICE_FUNC ConstTransposeReturnType transpose() const; + EIGEN_DEVICE_FUNC void transposeInPlace(); -#ifndef EIGEN_NO_DEBUG - protected: - template - void checkTransposeAliasing(const OtherDerived& other) const; - public: -#endif - - static const ConstantReturnType + EIGEN_DEVICE_FUNC static const ConstantReturnType Constant(Index rows, Index cols, const Scalar& value); - static const ConstantReturnType + EIGEN_DEVICE_FUNC static const ConstantReturnType Constant(Index size, const Scalar& value); - static const ConstantReturnType + EIGEN_DEVICE_FUNC static const ConstantReturnType Constant(const Scalar& value); - static const SequentialLinSpacedReturnType + EIGEN_DEVICE_FUNC static const SequentialLinSpacedReturnType LinSpaced(Sequential_t, Index size, const Scalar& low, const Scalar& high); - static const RandomAccessLinSpacedReturnType + EIGEN_DEVICE_FUNC static const RandomAccessLinSpacedReturnType LinSpaced(Index size, const Scalar& low, const Scalar& high); - static const SequentialLinSpacedReturnType + EIGEN_DEVICE_FUNC static const SequentialLinSpacedReturnType LinSpaced(Sequential_t, const Scalar& low, const Scalar& high); - static const RandomAccessLinSpacedReturnType + EIGEN_DEVICE_FUNC static const RandomAccessLinSpacedReturnType LinSpaced(const Scalar& low, const Scalar& high); - template - static const CwiseNullaryOp + template EIGEN_DEVICE_FUNC + static const CwiseNullaryOp NullaryExpr(Index rows, Index cols, const CustomNullaryOp& func); - template - static const CwiseNullaryOp + template EIGEN_DEVICE_FUNC + static const CwiseNullaryOp NullaryExpr(Index size, const CustomNullaryOp& func); - template - static const CwiseNullaryOp + template EIGEN_DEVICE_FUNC + static const CwiseNullaryOp NullaryExpr(const CustomNullaryOp& func); - static const ConstantReturnType Zero(Index rows, Index cols); - static const ConstantReturnType Zero(Index size); - static const ConstantReturnType Zero(); - static const ConstantReturnType Ones(Index rows, Index cols); - static const ConstantReturnType Ones(Index size); - static const ConstantReturnType Ones(); + EIGEN_DEVICE_FUNC static const ConstantReturnType Zero(Index rows, Index cols); + EIGEN_DEVICE_FUNC static const ConstantReturnType Zero(Index size); + EIGEN_DEVICE_FUNC static const ConstantReturnType Zero(); + EIGEN_DEVICE_FUNC static const ConstantReturnType Ones(Index rows, Index cols); + EIGEN_DEVICE_FUNC static const ConstantReturnType Ones(Index size); + EIGEN_DEVICE_FUNC static const ConstantReturnType Ones(); - void fill(const Scalar& value); - Derived& setConstant(const Scalar& value); - Derived& setLinSpaced(Index size, const Scalar& low, const Scalar& high); - Derived& setLinSpaced(const Scalar& low, const Scalar& high); - Derived& setZero(); - Derived& setOnes(); - Derived& setRandom(); + EIGEN_DEVICE_FUNC void fill(const Scalar& value); + EIGEN_DEVICE_FUNC Derived& setConstant(const Scalar& value); + EIGEN_DEVICE_FUNC Derived& setLinSpaced(Index size, const Scalar& low, const Scalar& high); + EIGEN_DEVICE_FUNC Derived& setLinSpaced(const Scalar& low, const Scalar& high); + EIGEN_DEVICE_FUNC Derived& setZero(); + EIGEN_DEVICE_FUNC Derived& setOnes(); + EIGEN_DEVICE_FUNC Derived& setRandom(); - template + template EIGEN_DEVICE_FUNC bool isApprox(const DenseBase& other, const RealScalar& prec = NumTraits::dummy_precision()) const; + EIGEN_DEVICE_FUNC bool isMuchSmallerThan(const RealScalar& other, const RealScalar& prec = NumTraits::dummy_precision()) const; - template + template EIGEN_DEVICE_FUNC bool isMuchSmallerThan(const DenseBase& other, const RealScalar& prec = NumTraits::dummy_precision()) const; - bool isApproxToConstant(const Scalar& value, const RealScalar& prec = NumTraits::dummy_precision()) const; - bool isConstant(const Scalar& value, const RealScalar& prec = NumTraits::dummy_precision()) const; - bool isZero(const RealScalar& prec = NumTraits::dummy_precision()) const; - bool isOnes(const RealScalar& prec = NumTraits::dummy_precision()) const; + EIGEN_DEVICE_FUNC bool isApproxToConstant(const Scalar& value, const RealScalar& prec = NumTraits::dummy_precision()) const; + EIGEN_DEVICE_FUNC bool isConstant(const Scalar& value, const RealScalar& prec = NumTraits::dummy_precision()) const; + EIGEN_DEVICE_FUNC bool isZero(const RealScalar& prec = NumTraits::dummy_precision()) const; + EIGEN_DEVICE_FUNC bool isOnes(const RealScalar& prec = NumTraits::dummy_precision()) const; inline bool hasNaN() const; inline bool allFinite() const; - inline Derived& operator*=(const Scalar& other); - inline Derived& operator/=(const Scalar& other); + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Derived& operator*=(const Scalar& other); + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Derived& operator/=(const Scalar& other); typedef typename internal::add_const_on_value_type::type>::type EvalReturnType; /** \returns the matrix or vector obtained by evaluating this expression. * * Notice that in the case of a plain matrix or vector (not an expression) this function just returns * a const reference, in order to avoid a useless copy. + * + * \warning Be carefull with eval() and the auto C++ keyword, as detailed in this \link TopicPitfalls_auto_keyword page \endlink. */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EvalReturnType eval() const { // Even though MSVC does not honor strong inlining when the return type @@ -366,61 +405,78 @@ template class DenseBase // size types on MSVC. return typename internal::eval::type(derived()); } - + /** swaps *this with the expression \a other. * */ template - void swap(const DenseBase& other, - int = OtherDerived::ThisConstantIsPrivateInPlainObjectBase) + EIGEN_DEVICE_FUNC + void swap(const DenseBase& other) { - SwapWrapper(derived()).lazyAssign(other.derived()); + EIGEN_STATIC_ASSERT(!OtherDerived::IsPlainObjectBase,THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY); + eigen_assert(rows()==other.rows() && cols()==other.cols()); + call_assignment(derived(), other.const_cast_derived(), internal::swap_assign_op()); } /** swaps *this with the matrix or array \a other. * */ template + EIGEN_DEVICE_FUNC void swap(PlainObjectBase& other) { - SwapWrapper(derived()).lazyAssign(other.derived()); + eigen_assert(rows()==other.rows() && cols()==other.cols()); + call_assignment(derived(), other.derived(), internal::swap_assign_op()); } + EIGEN_DEVICE_FUNC inline const NestByValue nestByValue() const; + EIGEN_DEVICE_FUNC inline const ForceAlignedAccess forceAlignedAccess() const; + EIGEN_DEVICE_FUNC inline ForceAlignedAccess forceAlignedAccess(); + template EIGEN_DEVICE_FUNC + inline const typename internal::conditional,Derived&>::type forceAlignedAccessIf() const; + template EIGEN_DEVICE_FUNC + inline typename internal::conditional,Derived&>::type forceAlignedAccessIf(); - inline const NestByValue nestByValue() const; - inline const ForceAlignedAccess forceAlignedAccess() const; - inline ForceAlignedAccess forceAlignedAccess(); - template inline const typename internal::conditional,Derived&>::type forceAlignedAccessIf() const; - template inline typename internal::conditional,Derived&>::type forceAlignedAccessIf(); + EIGEN_DEVICE_FUNC Scalar sum() const; + EIGEN_DEVICE_FUNC Scalar mean() const; + EIGEN_DEVICE_FUNC Scalar trace() const; - Scalar sum() const; - Scalar mean() const; - Scalar trace() const; + EIGEN_DEVICE_FUNC Scalar prod() const; - Scalar prod() const; + EIGEN_DEVICE_FUNC typename internal::traits::Scalar minCoeff() const; + EIGEN_DEVICE_FUNC typename internal::traits::Scalar maxCoeff() const; - typename internal::traits::Scalar minCoeff() const; - typename internal::traits::Scalar maxCoeff() const; - - template + template EIGEN_DEVICE_FUNC typename internal::traits::Scalar minCoeff(IndexType* row, IndexType* col) const; - template + template EIGEN_DEVICE_FUNC typename internal::traits::Scalar maxCoeff(IndexType* row, IndexType* col) const; - template + template EIGEN_DEVICE_FUNC typename internal::traits::Scalar minCoeff(IndexType* index) const; - template + template EIGEN_DEVICE_FUNC typename internal::traits::Scalar maxCoeff(IndexType* index) const; template - typename internal::result_of::Scalar)>::type - redux(const BinaryOp& func) const; + EIGEN_DEVICE_FUNC + Scalar redux(const BinaryOp& func) const; template + EIGEN_DEVICE_FUNC void visit(Visitor& func) const; - inline const WithFormat format(const IOFormat& fmt) const; + /** \returns a WithFormat proxy object allowing to print a matrix the with given + * format \a fmt. + * + * See class IOFormat for some examples. + * + * \sa class IOFormat, class WithFormat + */ + inline const WithFormat format(const IOFormat& fmt) const + { + return WithFormat(derived(), fmt); + } /** \returns the unique coefficient of a 1x1 expression */ + EIGEN_DEVICE_FUNC CoeffReturnType value() const { EIGEN_STATIC_ASSERT_SIZE_1x1(Derived) @@ -428,23 +484,44 @@ template class DenseBase return derived().coeff(0,0); } - bool all(void) const; - bool any(void) const; - Index count() const; + EIGEN_DEVICE_FUNC bool all() const; + EIGEN_DEVICE_FUNC bool any() const; + EIGEN_DEVICE_FUNC Index count() const; typedef VectorwiseOp RowwiseReturnType; typedef const VectorwiseOp ConstRowwiseReturnType; typedef VectorwiseOp ColwiseReturnType; typedef const VectorwiseOp ConstColwiseReturnType; - ConstRowwiseReturnType rowwise() const; - RowwiseReturnType rowwise(); - ConstColwiseReturnType colwise() const; - ColwiseReturnType colwise(); + /** \returns a VectorwiseOp wrapper of *this providing additional partial reduction operations + * + * Example: \include MatrixBase_rowwise.cpp + * Output: \verbinclude MatrixBase_rowwise.out + * + * \sa colwise(), class VectorwiseOp, \ref TutorialReductionsVisitorsBroadcasting + */ + //Code moved here due to a CUDA compiler bug + EIGEN_DEVICE_FUNC inline ConstRowwiseReturnType rowwise() const { + return ConstRowwiseReturnType(derived()); + } + EIGEN_DEVICE_FUNC RowwiseReturnType rowwise(); - static const CwiseNullaryOp,Derived> Random(Index rows, Index cols); - static const CwiseNullaryOp,Derived> Random(Index size); - static const CwiseNullaryOp,Derived> Random(); + /** \returns a VectorwiseOp wrapper of *this providing additional partial reduction operations + * + * Example: \include MatrixBase_colwise.cpp + * Output: \verbinclude MatrixBase_colwise.out + * + * \sa rowwise(), class VectorwiseOp, \ref TutorialReductionsVisitorsBroadcasting + */ + EIGEN_DEVICE_FUNC inline ConstColwiseReturnType colwise() const { + return ConstColwiseReturnType(derived()); + } + EIGEN_DEVICE_FUNC ColwiseReturnType colwise(); + + typedef CwiseNullaryOp,PlainObject> RandomReturnType; + static const RandomReturnType Random(Index rows, Index cols); + static const RandomReturnType Random(Index size); + static const RandomReturnType Random(); template const Select @@ -462,45 +539,60 @@ template class DenseBase template RealScalar lpNorm() const; template - inline const Replicate replicate() const; - - typedef Replicate ReplicateReturnType; - inline const ReplicateReturnType replicate(Index rowFacor,Index colFactor) const; + EIGEN_DEVICE_FUNC + const Replicate replicate() const; + /** + * \return an expression of the replication of \c *this + * + * Example: \include MatrixBase_replicate_int_int.cpp + * Output: \verbinclude MatrixBase_replicate_int_int.out + * + * \sa VectorwiseOp::replicate(), DenseBase::replicate(), class Replicate + */ + //Code moved here due to a CUDA compiler bug + EIGEN_DEVICE_FUNC + const Replicate replicate(Index rowFactor, Index colFactor) const + { + return Replicate(derived(), rowFactor, colFactor); + } typedef Reverse ReverseReturnType; typedef const Reverse ConstReverseReturnType; - ReverseReturnType reverse(); - ConstReverseReturnType reverse() const; - void reverseInPlace(); + EIGEN_DEVICE_FUNC ReverseReturnType reverse(); + /** This is the const version of reverse(). */ + //Code moved here due to a CUDA compiler bug + EIGEN_DEVICE_FUNC ConstReverseReturnType reverse() const + { + return ConstReverseReturnType(derived()); + } + EIGEN_DEVICE_FUNC void reverseInPlace(); #define EIGEN_CURRENT_STORAGE_BASE_CLASS Eigen::DenseBase +#define EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL +#define EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(COND) +#define EIGEN_DOC_UNARY_ADDONS(X,Y) +# include "../plugins/CommonCwiseUnaryOps.h" # include "../plugins/BlockMethods.h" +# include "../plugins/IndexedViewMethods.h" # ifdef EIGEN_DENSEBASE_PLUGIN # include EIGEN_DENSEBASE_PLUGIN # endif #undef EIGEN_CURRENT_STORAGE_BASE_CLASS - -#ifdef EIGEN2_SUPPORT - - Block corner(CornerType type, Index cRows, Index cCols); - const Block corner(CornerType type, Index cRows, Index cCols) const; - template - Block corner(CornerType type); - template - const Block corner(CornerType type) const; - -#endif // EIGEN2_SUPPORT - +#undef EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL +#undef EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF +#undef EIGEN_DOC_UNARY_ADDONS // disable the use of evalTo for dense objects with a nice compilation error - template inline void evalTo(Dest& ) const + template + EIGEN_DEVICE_FUNC + inline void evalTo(Dest& ) const { EIGEN_STATIC_ASSERT((internal::is_same::value),THE_EVAL_EVALTO_FUNCTION_SHOULD_NEVER_BE_CALLED_FOR_DENSE_OBJECTS); } protected: /** Default constructor. Do nothing. */ - DenseBase() + EIGEN_DEVICE_FUNC DenseBase() { /* Just checks for self-consistency of the flags. * Only do it when debugging Eigen, as this borders on paranoiac and could slow compilation down @@ -513,9 +605,9 @@ template class DenseBase } private: - explicit DenseBase(int); - DenseBase(int,int); - template explicit DenseBase(const DenseBase&); + EIGEN_DEVICE_FUNC explicit DenseBase(int); + EIGEN_DEVICE_FUNC DenseBase(int,int); + template EIGEN_DEVICE_FUNC explicit DenseBase(const DenseBase&); }; } // end namespace Eigen diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/DenseCoeffsBase.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/DenseCoeffsBase.h index 3c890f21..c4af48ab 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/DenseCoeffsBase.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/DenseCoeffsBase.h @@ -35,7 +35,6 @@ class DenseCoeffsBase : public EigenBase { public: typedef typename internal::traits::StorageKind StorageKind; - typedef typename internal::traits::Index Index; typedef typename internal::traits::Scalar Scalar; typedef typename internal::packet_traits::type PacketScalar; @@ -61,6 +60,7 @@ class DenseCoeffsBase : public EigenBase using Base::size; using Base::derived; + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rowIndexByOuterInner(Index outer, Index inner) const { return int(Derived::RowsAtCompileTime) == 1 ? 0 @@ -69,6 +69,7 @@ class DenseCoeffsBase : public EigenBase : inner; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index colIndexByOuterInner(Index outer, Index inner) const { return int(Derived::ColsAtCompileTime) == 1 ? 0 @@ -91,13 +92,15 @@ class DenseCoeffsBase : public EigenBase * * \sa operator()(Index,Index) const, coeffRef(Index,Index), coeff(Index) const */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index row, Index col) const { eigen_internal_assert(row >= 0 && row < rows() - && col >= 0 && col < cols()); - return derived().coeff(row, col); + && col >= 0 && col < cols()); + return internal::evaluator(derived()).coeff(row,col); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeffByOuterInner(Index outer, Index inner) const { return coeff(rowIndexByOuterInner(outer, inner), @@ -108,11 +111,12 @@ class DenseCoeffsBase : public EigenBase * * \sa operator()(Index,Index), operator[](Index) */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType operator()(Index row, Index col) const { eigen_assert(row >= 0 && row < rows() && col >= 0 && col < cols()); - return derived().coeff(row, col); + return coeff(row, col); } /** Short version: don't use this function, use @@ -130,11 +134,14 @@ class DenseCoeffsBase : public EigenBase * \sa operator[](Index) const, coeffRef(Index), coeff(Index,Index) const */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const { + EIGEN_STATIC_ASSERT(internal::evaluator::Flags & LinearAccessBit, + THIS_COEFFICIENT_ACCESSOR_TAKING_ONE_ACCESS_IS_ONLY_FOR_EXPRESSIONS_ALLOWING_LINEAR_ACCESS) eigen_internal_assert(index >= 0 && index < size()); - return derived().coeff(index); + return internal::evaluator(derived()).coeff(index); } @@ -146,15 +153,14 @@ class DenseCoeffsBase : public EigenBase * z() const, w() const */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType operator[](Index index) const { - #ifndef EIGEN2_SUPPORT EIGEN_STATIC_ASSERT(Derived::IsVectorAtCompileTime, THE_BRACKET_OPERATOR_IS_ONLY_FOR_VECTORS__USE_THE_PARENTHESIS_OPERATOR_INSTEAD) - #endif eigen_assert(index >= 0 && index < size()); - return derived().coeff(index); + return coeff(index); } /** \returns the coefficient at given index. @@ -167,32 +173,49 @@ class DenseCoeffsBase : public EigenBase * z() const, w() const */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType operator()(Index index) const { eigen_assert(index >= 0 && index < size()); - return derived().coeff(index); + return coeff(index); } /** equivalent to operator[](0). */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType x() const { return (*this)[0]; } /** equivalent to operator[](1). */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType - y() const { return (*this)[1]; } + y() const + { + EIGEN_STATIC_ASSERT(Derived::SizeAtCompileTime==-1 || Derived::SizeAtCompileTime>=2, OUT_OF_RANGE_ACCESS); + return (*this)[1]; + } /** equivalent to operator[](2). */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType - z() const { return (*this)[2]; } + z() const + { + EIGEN_STATIC_ASSERT(Derived::SizeAtCompileTime==-1 || Derived::SizeAtCompileTime>=3, OUT_OF_RANGE_ACCESS); + return (*this)[2]; + } /** equivalent to operator[](3). */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType - w() const { return (*this)[3]; } + w() const + { + EIGEN_STATIC_ASSERT(Derived::SizeAtCompileTime==-1 || Derived::SizeAtCompileTime>=4, OUT_OF_RANGE_ACCESS); + return (*this)[3]; + } /** \internal * \returns the packet of coefficients starting at the given row and column. It is your responsibility @@ -207,9 +230,9 @@ class DenseCoeffsBase : public EigenBase template EIGEN_STRONG_INLINE PacketReturnType packet(Index row, Index col) const { - eigen_internal_assert(row >= 0 && row < rows() - && col >= 0 && col < cols()); - return derived().template packet(row,col); + typedef typename internal::packet_traits::type DefaultPacketType; + eigen_internal_assert(row >= 0 && row < rows() && col >= 0 && col < cols()); + return internal::evaluator(derived()).template packet(row,col); } @@ -234,8 +257,11 @@ class DenseCoeffsBase : public EigenBase template EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const { + EIGEN_STATIC_ASSERT(internal::evaluator::Flags & LinearAccessBit, + THIS_COEFFICIENT_ACCESSOR_TAKING_ONE_ACCESS_IS_ONLY_FOR_EXPRESSIONS_ALLOWING_LINEAR_ACCESS) + typedef typename internal::packet_traits::type DefaultPacketType; eigen_internal_assert(index >= 0 && index < size()); - return derived().template packet(index); + return internal::evaluator(derived()).template packet(index); } protected: @@ -278,7 +304,6 @@ class DenseCoeffsBase : public DenseCoeffsBase Base; typedef typename internal::traits::StorageKind StorageKind; - typedef typename internal::traits::Index Index; typedef typename internal::traits::Scalar Scalar; typedef typename internal::packet_traits::type PacketScalar; typedef typename NumTraits::Real RealScalar; @@ -311,13 +336,15 @@ class DenseCoeffsBase : public DenseCoeffsBase= 0 && row < rows() - && col >= 0 && col < cols()); - return derived().coeffRef(row, col); + && col >= 0 && col < cols()); + return internal::evaluator(derived()).coeffRef(row,col); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRefByOuterInner(Index outer, Index inner) { @@ -330,12 +357,13 @@ class DenseCoeffsBase : public DenseCoeffsBase= 0 && row < rows() && col >= 0 && col < cols()); - return derived().coeffRef(row, col); + return coeffRef(row, col); } @@ -354,11 +382,14 @@ class DenseCoeffsBase : public DenseCoeffsBase::Flags & LinearAccessBit, + THIS_COEFFICIENT_ACCESSOR_TAKING_ONE_ACCESS_IS_ONLY_FOR_EXPRESSIONS_ALLOWING_LINEAR_ACCESS) eigen_internal_assert(index >= 0 && index < size()); - return derived().coeffRef(index); + return internal::evaluator(derived()).coeffRef(index); } /** \returns a reference to the coefficient at given index. @@ -368,15 +399,14 @@ class DenseCoeffsBase : public DenseCoeffsBase= 0 && index < size()); - return derived().coeffRef(index); + return coeffRef(index); } /** \returns a reference to the coefficient at given index. @@ -388,167 +418,49 @@ class DenseCoeffsBase : public DenseCoeffsBase= 0 && index < size()); - return derived().coeffRef(index); + return coeffRef(index); } /** equivalent to operator[](0). */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& x() { return (*this)[0]; } /** equivalent to operator[](1). */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& - y() { return (*this)[1]; } + y() + { + EIGEN_STATIC_ASSERT(Derived::SizeAtCompileTime==-1 || Derived::SizeAtCompileTime>=2, OUT_OF_RANGE_ACCESS); + return (*this)[1]; + } /** equivalent to operator[](2). */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& - z() { return (*this)[2]; } + z() + { + EIGEN_STATIC_ASSERT(Derived::SizeAtCompileTime==-1 || Derived::SizeAtCompileTime>=3, OUT_OF_RANGE_ACCESS); + return (*this)[2]; + } /** equivalent to operator[](3). */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& - w() { return (*this)[3]; } - - /** \internal - * Stores the given packet of coefficients, at the given row and column of this expression. It is your responsibility - * to ensure that a packet really starts there. This method is only available on expressions having the - * PacketAccessBit. - * - * The \a LoadMode parameter may have the value \a #Aligned or \a #Unaligned. Its effect is to select - * the appropriate vectorization instruction. Aligned access is faster, but is only possible for packets - * starting at an address which is a multiple of the packet size. - */ - - template - EIGEN_STRONG_INLINE void writePacket - (Index row, Index col, const typename internal::packet_traits::type& val) + w() { - eigen_internal_assert(row >= 0 && row < rows() - && col >= 0 && col < cols()); - derived().template writePacket(row,col,val); + EIGEN_STATIC_ASSERT(Derived::SizeAtCompileTime==-1 || Derived::SizeAtCompileTime>=4, OUT_OF_RANGE_ACCESS); + return (*this)[3]; } - - - /** \internal */ - template - EIGEN_STRONG_INLINE void writePacketByOuterInner - (Index outer, Index inner, const typename internal::packet_traits::type& val) - { - writePacket(rowIndexByOuterInner(outer, inner), - colIndexByOuterInner(outer, inner), - val); - } - - /** \internal - * Stores the given packet of coefficients, at the given index in this expression. It is your responsibility - * to ensure that a packet really starts there. This method is only available on expressions having the - * PacketAccessBit and the LinearAccessBit. - * - * The \a LoadMode parameter may have the value \a Aligned or \a Unaligned. Its effect is to select - * the appropriate vectorization instruction. Aligned access is faster, but is only possible for packets - * starting at an address which is a multiple of the packet size. - */ - template - EIGEN_STRONG_INLINE void writePacket - (Index index, const typename internal::packet_traits::type& val) - { - eigen_internal_assert(index >= 0 && index < size()); - derived().template writePacket(index,val); - } - -#ifndef EIGEN_PARSED_BY_DOXYGEN - - /** \internal Copies the coefficient at position (row,col) of other into *this. - * - * This method is overridden in SwapWrapper, allowing swap() assignments to share 99% of their code - * with usual assignments. - * - * Outside of this internal usage, this method has probably no usefulness. It is hidden in the public API dox. - */ - - template - EIGEN_STRONG_INLINE void copyCoeff(Index row, Index col, const DenseBase& other) - { - eigen_internal_assert(row >= 0 && row < rows() - && col >= 0 && col < cols()); - derived().coeffRef(row, col) = other.derived().coeff(row, col); - } - - /** \internal Copies the coefficient at the given index of other into *this. - * - * This method is overridden in SwapWrapper, allowing swap() assignments to share 99% of their code - * with usual assignments. - * - * Outside of this internal usage, this method has probably no usefulness. It is hidden in the public API dox. - */ - - template - EIGEN_STRONG_INLINE void copyCoeff(Index index, const DenseBase& other) - { - eigen_internal_assert(index >= 0 && index < size()); - derived().coeffRef(index) = other.derived().coeff(index); - } - - - template - EIGEN_STRONG_INLINE void copyCoeffByOuterInner(Index outer, Index inner, const DenseBase& other) - { - const Index row = rowIndexByOuterInner(outer,inner); - const Index col = colIndexByOuterInner(outer,inner); - // derived() is important here: copyCoeff() may be reimplemented in Derived! - derived().copyCoeff(row, col, other); - } - - /** \internal Copies the packet at position (row,col) of other into *this. - * - * This method is overridden in SwapWrapper, allowing swap() assignments to share 99% of their code - * with usual assignments. - * - * Outside of this internal usage, this method has probably no usefulness. It is hidden in the public API dox. - */ - - template - EIGEN_STRONG_INLINE void copyPacket(Index row, Index col, const DenseBase& other) - { - eigen_internal_assert(row >= 0 && row < rows() - && col >= 0 && col < cols()); - derived().template writePacket(row, col, - other.derived().template packet(row, col)); - } - - /** \internal Copies the packet at the given index of other into *this. - * - * This method is overridden in SwapWrapper, allowing swap() assignments to share 99% of their code - * with usual assignments. - * - * Outside of this internal usage, this method has probably no usefulness. It is hidden in the public API dox. - */ - - template - EIGEN_STRONG_INLINE void copyPacket(Index index, const DenseBase& other) - { - eigen_internal_assert(index >= 0 && index < size()); - derived().template writePacket(index, - other.derived().template packet(index)); - } - - /** \internal */ - template - EIGEN_STRONG_INLINE void copyPacketByOuterInner(Index outer, Index inner, const DenseBase& other) - { - const Index row = rowIndexByOuterInner(outer,inner); - const Index col = colIndexByOuterInner(outer,inner); - // derived() is important here: copyCoeff() may be reimplemented in Derived! - derived().template copyPacket< OtherDerived, StoreMode, LoadMode>(row, col, other); - } -#endif - }; /** \brief Base class providing direct read-only coefficient access to matrices and arrays. @@ -560,7 +472,7 @@ class DenseCoeffsBase : public DenseCoeffsBase which defines functions to access entries read-only using * \c operator() . * - * \sa \ref TopicClassHierarchy + * \sa \blank \ref TopicClassHierarchy */ template class DenseCoeffsBase : public DenseCoeffsBase @@ -568,7 +480,6 @@ class DenseCoeffsBase : public DenseCoeffsBase Base; - typedef typename internal::traits::Index Index; typedef typename internal::traits::Scalar Scalar; typedef typename NumTraits::Real RealScalar; @@ -581,6 +492,7 @@ class DenseCoeffsBase : public DenseCoeffsBase : public DenseCoeffsBase : public DenseCoeffsBase : public DenseCoeffsBase : public DenseCoeffsBase which defines functions to access entries read/write using * \c operator(). * - * \sa \ref TopicClassHierarchy + * \sa \blank \ref TopicClassHierarchy */ template class DenseCoeffsBase @@ -639,7 +554,6 @@ class DenseCoeffsBase public: typedef DenseCoeffsBase Base; - typedef typename internal::traits::Index Index; typedef typename internal::traits::Scalar Scalar; typedef typename NumTraits::Real RealScalar; @@ -652,6 +566,7 @@ class DenseCoeffsBase * * \sa outerStride(), rowStride(), colStride() */ + EIGEN_DEVICE_FUNC inline Index innerStride() const { return derived().innerStride(); @@ -662,6 +577,7 @@ class DenseCoeffsBase * * \sa innerStride(), rowStride(), colStride() */ + EIGEN_DEVICE_FUNC inline Index outerStride() const { return derived().outerStride(); @@ -677,6 +593,7 @@ class DenseCoeffsBase * * \sa innerStride(), outerStride(), colStride() */ + EIGEN_DEVICE_FUNC inline Index rowStride() const { return Derived::IsRowMajor ? outerStride() : innerStride(); @@ -686,6 +603,7 @@ class DenseCoeffsBase * * \sa innerStride(), outerStride(), rowStride() */ + EIGEN_DEVICE_FUNC inline Index colStride() const { return Derived::IsRowMajor ? innerStride() : outerStride(); @@ -694,33 +612,42 @@ class DenseCoeffsBase namespace internal { -template +template struct first_aligned_impl { - static inline typename Derived::Index run(const Derived&) + static inline Index run(const Derived&) { return 0; } }; -template -struct first_aligned_impl +template +struct first_aligned_impl { - static inline typename Derived::Index run(const Derived& m) + static inline Index run(const Derived& m) { - return internal::first_aligned(&m.const_cast_derived().coeffRef(0,0), m.size()); + return internal::first_aligned(m.data(), m.size()); } }; -/** \internal \returns the index of the first element of the array that is well aligned for vectorization. +/** \internal \returns the index of the first element of the array stored by \a m that is properly aligned with respect to \a Alignment for vectorization. + * + * \tparam Alignment requested alignment in Bytes. * * There is also the variant first_aligned(const Scalar*, Integer) defined in Memory.h. See it for more * documentation. */ -template -static inline typename Derived::Index first_aligned(const Derived& m) +template +static inline Index first_aligned(const DenseBase& m) { - return first_aligned_impl - - ::run(m); + enum { ReturnZero = (int(evaluator::Alignment) >= Alignment) || !(Derived::Flags & DirectAccessBit) }; + return first_aligned_impl::run(m.derived()); +} + +template +static inline Index first_default_aligned(const DenseBase& m) +{ + typedef typename Derived::Scalar Scalar; + typedef typename packet_traits::type DefaultPacketType; + return internal::first_aligned::alignment),Derived>(m); } template::ret> diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/DenseStorage.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/DenseStorage.h index a72738e5..7958feeb 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/DenseStorage.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/DenseStorage.h @@ -3,7 +3,7 @@ // // Copyright (C) 2008 Gael Guennebaud // Copyright (C) 2006-2009 Benoit Jacob -// Copyright (C) 2010 Hauke Heibel +// Copyright (C) 2010-2013 Hauke Heibel // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -13,9 +13,9 @@ #define EIGEN_MATRIXSTORAGE_H #ifdef EIGEN_DENSE_STORAGE_CTOR_PLUGIN - #define EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN EIGEN_DENSE_STORAGE_CTOR_PLUGIN; + #define EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN(X) X; EIGEN_DENSE_STORAGE_CTOR_PLUGIN; #else - #define EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN + #define EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN(X) #endif namespace Eigen { @@ -24,7 +24,9 @@ namespace internal { struct constructor_without_unaligned_array_assert {}; -template void check_static_allocation_size() +template +EIGEN_DEVICE_FUNC +void check_static_allocation_size() { // if EIGEN_STACK_ALLOCATION_LIMIT is defined to 0, then no limit #if EIGEN_STACK_ALLOCATION_LIMIT @@ -38,18 +40,19 @@ template void check_static_allocation_size() */ template + : compute_default_alignment::value > struct plain_array { T array[Size]; - plain_array() + EIGEN_DEVICE_FUNC + plain_array() { check_static_allocation_size(); } - plain_array(constructor_without_unaligned_array_assert) + EIGEN_DEVICE_FUNC + plain_array(constructor_without_unaligned_array_assert) { check_static_allocation_size(); } @@ -64,29 +67,88 @@ struct plain_array template EIGEN_ALWAYS_INLINE PtrType eigen_unaligned_array_assert_workaround_gcc47(PtrType array) { return array; } #define EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(sizemask) \ - eigen_assert((reinterpret_cast(eigen_unaligned_array_assert_workaround_gcc47(array)) & sizemask) == 0 \ + eigen_assert((internal::UIntPtr(eigen_unaligned_array_assert_workaround_gcc47(array)) & (sizemask)) == 0 \ && "this assertion is explained here: " \ "http://eigen.tuxfamily.org/dox-devel/group__TopicUnalignedArrayAssert.html" \ " **** READ THIS WEB PAGE !!! ****"); #else #define EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(sizemask) \ - eigen_assert((reinterpret_cast(array) & sizemask) == 0 \ + eigen_assert((internal::UIntPtr(array) & (sizemask)) == 0 \ && "this assertion is explained here: " \ "http://eigen.tuxfamily.org/dox-devel/group__TopicUnalignedArrayAssert.html" \ " **** READ THIS WEB PAGE !!! ****"); #endif template -struct plain_array +struct plain_array { - EIGEN_USER_ALIGN16 T array[Size]; + EIGEN_ALIGN_TO_BOUNDARY(8) T array[Size]; + EIGEN_DEVICE_FUNC plain_array() - { - EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(0xf); + { + EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(7); check_static_allocation_size(); } + EIGEN_DEVICE_FUNC + plain_array(constructor_without_unaligned_array_assert) + { + check_static_allocation_size(); + } +}; + +template +struct plain_array +{ + EIGEN_ALIGN_TO_BOUNDARY(16) T array[Size]; + + EIGEN_DEVICE_FUNC + plain_array() + { + EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(15); + check_static_allocation_size(); + } + + EIGEN_DEVICE_FUNC + plain_array(constructor_without_unaligned_array_assert) + { + check_static_allocation_size(); + } +}; + +template +struct plain_array +{ + EIGEN_ALIGN_TO_BOUNDARY(32) T array[Size]; + + EIGEN_DEVICE_FUNC + plain_array() + { + EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(31); + check_static_allocation_size(); + } + + EIGEN_DEVICE_FUNC + plain_array(constructor_without_unaligned_array_assert) + { + check_static_allocation_size(); + } +}; + +template +struct plain_array +{ + EIGEN_ALIGN_TO_BOUNDARY(64) T array[Size]; + + EIGEN_DEVICE_FUNC + plain_array() + { + EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(63); + check_static_allocation_size(); + } + + EIGEN_DEVICE_FUNC plain_array(constructor_without_unaligned_array_assert) { check_static_allocation_size(); @@ -96,9 +158,9 @@ struct plain_array template struct plain_array { - EIGEN_USER_ALIGN16 T array[1]; - plain_array() {} - plain_array(constructor_without_unaligned_array_assert) {} + T array[1]; + EIGEN_DEVICE_FUNC plain_array() {} + EIGEN_DEVICE_FUNC plain_array(constructor_without_unaligned_array_assert) {} }; } // end namespace internal @@ -122,33 +184,54 @@ template class DenseSt { internal::plain_array m_data; public: - inline DenseStorage() {} - inline DenseStorage(internal::constructor_without_unaligned_array_assert) + EIGEN_DEVICE_FUNC DenseStorage() { + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN(Index size = Size) + } + EIGEN_DEVICE_FUNC + explicit DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(internal::constructor_without_unaligned_array_assert()) {} - inline DenseStorage(DenseIndex,DenseIndex,DenseIndex) {} - inline void swap(DenseStorage& other) { std::swap(m_data,other.m_data); } - static inline DenseIndex rows(void) {return _Rows;} - static inline DenseIndex cols(void) {return _Cols;} - inline void conservativeResize(DenseIndex,DenseIndex,DenseIndex) {} - inline void resize(DenseIndex,DenseIndex,DenseIndex) {} - inline const T *data() const { return m_data.array; } - inline T *data() { return m_data.array; } + EIGEN_DEVICE_FUNC + DenseStorage(const DenseStorage& other) : m_data(other.m_data) { + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN(Index size = Size) + } + EIGEN_DEVICE_FUNC + DenseStorage& operator=(const DenseStorage& other) + { + if (this != &other) m_data = other.m_data; + return *this; + } + EIGEN_DEVICE_FUNC DenseStorage(Index size, Index rows, Index cols) { + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN({}) + eigen_internal_assert(size==rows*cols && rows==_Rows && cols==_Cols); + EIGEN_UNUSED_VARIABLE(size); + EIGEN_UNUSED_VARIABLE(rows); + EIGEN_UNUSED_VARIABLE(cols); + } + EIGEN_DEVICE_FUNC void swap(DenseStorage& other) { std::swap(m_data,other.m_data); } + EIGEN_DEVICE_FUNC static Index rows(void) {return _Rows;} + EIGEN_DEVICE_FUNC static Index cols(void) {return _Cols;} + EIGEN_DEVICE_FUNC void conservativeResize(Index,Index,Index) {} + EIGEN_DEVICE_FUNC void resize(Index,Index,Index) {} + EIGEN_DEVICE_FUNC const T *data() const { return m_data.array; } + EIGEN_DEVICE_FUNC T *data() { return m_data.array; } }; // null matrix template class DenseStorage { public: - inline DenseStorage() {} - inline DenseStorage(internal::constructor_without_unaligned_array_assert) {} - inline DenseStorage(DenseIndex,DenseIndex,DenseIndex) {} - inline void swap(DenseStorage& ) {} - static inline DenseIndex rows(void) {return _Rows;} - static inline DenseIndex cols(void) {return _Cols;} - inline void conservativeResize(DenseIndex,DenseIndex,DenseIndex) {} - inline void resize(DenseIndex,DenseIndex,DenseIndex) {} - inline const T *data() const { return 0; } - inline T *data() { return 0; } + EIGEN_DEVICE_FUNC DenseStorage() {} + EIGEN_DEVICE_FUNC explicit DenseStorage(internal::constructor_without_unaligned_array_assert) {} + EIGEN_DEVICE_FUNC DenseStorage(const DenseStorage&) {} + EIGEN_DEVICE_FUNC DenseStorage& operator=(const DenseStorage&) { return *this; } + EIGEN_DEVICE_FUNC DenseStorage(Index,Index,Index) {} + EIGEN_DEVICE_FUNC void swap(DenseStorage& ) {} + EIGEN_DEVICE_FUNC static Index rows(void) {return _Rows;} + EIGEN_DEVICE_FUNC static Index cols(void) {return _Cols;} + EIGEN_DEVICE_FUNC void conservativeResize(Index,Index,Index) {} + EIGEN_DEVICE_FUNC void resize(Index,Index,Index) {} + EIGEN_DEVICE_FUNC const T *data() const { return 0; } + EIGEN_DEVICE_FUNC T *data() { return 0; } }; // more specializations for null matrices; these are necessary to resolve ambiguities @@ -165,86 +248,158 @@ template class DenseStorage class DenseStorage { internal::plain_array m_data; - DenseIndex m_rows; - DenseIndex m_cols; + Index m_rows; + Index m_cols; public: - inline DenseStorage() : m_rows(0), m_cols(0) {} - inline DenseStorage(internal::constructor_without_unaligned_array_assert) + EIGEN_DEVICE_FUNC DenseStorage() : m_rows(0), m_cols(0) {} + EIGEN_DEVICE_FUNC explicit DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(internal::constructor_without_unaligned_array_assert()), m_rows(0), m_cols(0) {} - inline DenseStorage(DenseIndex, DenseIndex nbRows, DenseIndex nbCols) : m_rows(nbRows), m_cols(nbCols) {} - inline void swap(DenseStorage& other) + EIGEN_DEVICE_FUNC DenseStorage(const DenseStorage& other) : m_data(other.m_data), m_rows(other.m_rows), m_cols(other.m_cols) {} + EIGEN_DEVICE_FUNC DenseStorage& operator=(const DenseStorage& other) + { + if (this != &other) + { + m_data = other.m_data; + m_rows = other.m_rows; + m_cols = other.m_cols; + } + return *this; + } + EIGEN_DEVICE_FUNC DenseStorage(Index, Index rows, Index cols) : m_rows(rows), m_cols(cols) {} + EIGEN_DEVICE_FUNC void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_rows,other.m_rows); std::swap(m_cols,other.m_cols); } - inline DenseIndex rows() const {return m_rows;} - inline DenseIndex cols() const {return m_cols;} - inline void conservativeResize(DenseIndex, DenseIndex nbRows, DenseIndex nbCols) { m_rows = nbRows; m_cols = nbCols; } - inline void resize(DenseIndex, DenseIndex nbRows, DenseIndex nbCols) { m_rows = nbRows; m_cols = nbCols; } - inline const T *data() const { return m_data.array; } - inline T *data() { return m_data.array; } + EIGEN_DEVICE_FUNC Index rows() const {return m_rows;} + EIGEN_DEVICE_FUNC Index cols() const {return m_cols;} + EIGEN_DEVICE_FUNC void conservativeResize(Index, Index rows, Index cols) { m_rows = rows; m_cols = cols; } + EIGEN_DEVICE_FUNC void resize(Index, Index rows, Index cols) { m_rows = rows; m_cols = cols; } + EIGEN_DEVICE_FUNC const T *data() const { return m_data.array; } + EIGEN_DEVICE_FUNC T *data() { return m_data.array; } }; // dynamic-size matrix with fixed-size storage and fixed width template class DenseStorage { internal::plain_array m_data; - DenseIndex m_rows; + Index m_rows; public: - inline DenseStorage() : m_rows(0) {} - inline DenseStorage(internal::constructor_without_unaligned_array_assert) + EIGEN_DEVICE_FUNC DenseStorage() : m_rows(0) {} + EIGEN_DEVICE_FUNC explicit DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(internal::constructor_without_unaligned_array_assert()), m_rows(0) {} - inline DenseStorage(DenseIndex, DenseIndex nbRows, DenseIndex) : m_rows(nbRows) {} - inline void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_rows,other.m_rows); } - inline DenseIndex rows(void) const {return m_rows;} - inline DenseIndex cols(void) const {return _Cols;} - inline void conservativeResize(DenseIndex, DenseIndex nbRows, DenseIndex) { m_rows = nbRows; } - inline void resize(DenseIndex, DenseIndex nbRows, DenseIndex) { m_rows = nbRows; } - inline const T *data() const { return m_data.array; } - inline T *data() { return m_data.array; } + EIGEN_DEVICE_FUNC DenseStorage(const DenseStorage& other) : m_data(other.m_data), m_rows(other.m_rows) {} + EIGEN_DEVICE_FUNC DenseStorage& operator=(const DenseStorage& other) + { + if (this != &other) + { + m_data = other.m_data; + m_rows = other.m_rows; + } + return *this; + } + EIGEN_DEVICE_FUNC DenseStorage(Index, Index rows, Index) : m_rows(rows) {} + EIGEN_DEVICE_FUNC void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_rows,other.m_rows); } + EIGEN_DEVICE_FUNC Index rows(void) const {return m_rows;} + EIGEN_DEVICE_FUNC Index cols(void) const {return _Cols;} + EIGEN_DEVICE_FUNC void conservativeResize(Index, Index rows, Index) { m_rows = rows; } + EIGEN_DEVICE_FUNC void resize(Index, Index rows, Index) { m_rows = rows; } + EIGEN_DEVICE_FUNC const T *data() const { return m_data.array; } + EIGEN_DEVICE_FUNC T *data() { return m_data.array; } }; // dynamic-size matrix with fixed-size storage and fixed height template class DenseStorage { internal::plain_array m_data; - DenseIndex m_cols; + Index m_cols; public: - inline DenseStorage() : m_cols(0) {} - inline DenseStorage(internal::constructor_without_unaligned_array_assert) + EIGEN_DEVICE_FUNC DenseStorage() : m_cols(0) {} + EIGEN_DEVICE_FUNC explicit DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(internal::constructor_without_unaligned_array_assert()), m_cols(0) {} - inline DenseStorage(DenseIndex, DenseIndex, DenseIndex nbCols) : m_cols(nbCols) {} - inline void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_cols,other.m_cols); } - inline DenseIndex rows(void) const {return _Rows;} - inline DenseIndex cols(void) const {return m_cols;} - inline void conservativeResize(DenseIndex, DenseIndex, DenseIndex nbCols) { m_cols = nbCols; } - inline void resize(DenseIndex, DenseIndex, DenseIndex nbCols) { m_cols = nbCols; } - inline const T *data() const { return m_data.array; } - inline T *data() { return m_data.array; } + EIGEN_DEVICE_FUNC DenseStorage(const DenseStorage& other) : m_data(other.m_data), m_cols(other.m_cols) {} + EIGEN_DEVICE_FUNC DenseStorage& operator=(const DenseStorage& other) + { + if (this != &other) + { + m_data = other.m_data; + m_cols = other.m_cols; + } + return *this; + } + EIGEN_DEVICE_FUNC DenseStorage(Index, Index, Index cols) : m_cols(cols) {} + EIGEN_DEVICE_FUNC void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_cols,other.m_cols); } + EIGEN_DEVICE_FUNC Index rows(void) const {return _Rows;} + EIGEN_DEVICE_FUNC Index cols(void) const {return m_cols;} + void conservativeResize(Index, Index, Index cols) { m_cols = cols; } + void resize(Index, Index, Index cols) { m_cols = cols; } + EIGEN_DEVICE_FUNC const T *data() const { return m_data.array; } + EIGEN_DEVICE_FUNC T *data() { return m_data.array; } }; // purely dynamic matrix. template class DenseStorage { T *m_data; - DenseIndex m_rows; - DenseIndex m_cols; + Index m_rows; + Index m_cols; public: - inline DenseStorage() : m_data(0), m_rows(0), m_cols(0) {} - inline DenseStorage(internal::constructor_without_unaligned_array_assert) + EIGEN_DEVICE_FUNC DenseStorage() : m_data(0), m_rows(0), m_cols(0) {} + EIGEN_DEVICE_FUNC explicit DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(0), m_rows(0), m_cols(0) {} - inline DenseStorage(DenseIndex size, DenseIndex nbRows, DenseIndex nbCols) - : m_data(internal::conditional_aligned_new_auto(size)), m_rows(nbRows), m_cols(nbCols) - { EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN } - inline ~DenseStorage() { internal::conditional_aligned_delete_auto(m_data, m_rows*m_cols); } - inline void swap(DenseStorage& other) + EIGEN_DEVICE_FUNC DenseStorage(Index size, Index rows, Index cols) + : m_data(internal::conditional_aligned_new_auto(size)), m_rows(rows), m_cols(cols) + { + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN({}) + eigen_internal_assert(size==rows*cols && rows>=0 && cols >=0); + } + EIGEN_DEVICE_FUNC DenseStorage(const DenseStorage& other) + : m_data(internal::conditional_aligned_new_auto(other.m_rows*other.m_cols)) + , m_rows(other.m_rows) + , m_cols(other.m_cols) + { + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN(Index size = m_rows*m_cols) + internal::smart_copy(other.m_data, other.m_data+other.m_rows*other.m_cols, m_data); + } + EIGEN_DEVICE_FUNC DenseStorage& operator=(const DenseStorage& other) + { + if (this != &other) + { + DenseStorage tmp(other); + this->swap(tmp); + } + return *this; + } +#if EIGEN_HAS_RVALUE_REFERENCES + EIGEN_DEVICE_FUNC + DenseStorage(DenseStorage&& other) EIGEN_NOEXCEPT + : m_data(std::move(other.m_data)) + , m_rows(std::move(other.m_rows)) + , m_cols(std::move(other.m_cols)) + { + other.m_data = nullptr; + other.m_rows = 0; + other.m_cols = 0; + } + EIGEN_DEVICE_FUNC + DenseStorage& operator=(DenseStorage&& other) EIGEN_NOEXCEPT + { + using std::swap; + swap(m_data, other.m_data); + swap(m_rows, other.m_rows); + swap(m_cols, other.m_cols); + return *this; + } +#endif + EIGEN_DEVICE_FUNC ~DenseStorage() { internal::conditional_aligned_delete_auto(m_data, m_rows*m_cols); } + EIGEN_DEVICE_FUNC void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_rows,other.m_rows); std::swap(m_cols,other.m_cols); } - inline DenseIndex rows(void) const {return m_rows;} - inline DenseIndex cols(void) const {return m_cols;} - inline void conservativeResize(DenseIndex size, DenseIndex nbRows, DenseIndex nbCols) + EIGEN_DEVICE_FUNC Index rows(void) const {return m_rows;} + EIGEN_DEVICE_FUNC Index cols(void) const {return m_cols;} + void conservativeResize(Index size, Index rows, Index cols) { m_data = internal::conditional_aligned_realloc_new_auto(m_data, size, m_rows*m_cols); - m_rows = nbRows; - m_cols = nbCols; + m_rows = rows; + m_cols = cols; } - void resize(DenseIndex size, DenseIndex nbRows, DenseIndex nbCols) + EIGEN_DEVICE_FUNC void resize(Index size, Index rows, Index cols) { if(size != m_rows*m_cols) { @@ -253,35 +408,73 @@ template class DenseStorage(size); else m_data = 0; - EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN({}) } - m_rows = nbRows; - m_cols = nbCols; + m_rows = rows; + m_cols = cols; } - inline const T *data() const { return m_data; } - inline T *data() { return m_data; } + EIGEN_DEVICE_FUNC const T *data() const { return m_data; } + EIGEN_DEVICE_FUNC T *data() { return m_data; } }; // matrix with dynamic width and fixed height (so that matrix has dynamic size). template class DenseStorage { T *m_data; - DenseIndex m_cols; + Index m_cols; public: - inline DenseStorage() : m_data(0), m_cols(0) {} - inline DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(0), m_cols(0) {} - inline DenseStorage(DenseIndex size, DenseIndex, DenseIndex nbCols) : m_data(internal::conditional_aligned_new_auto(size)), m_cols(nbCols) - { EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN } - inline ~DenseStorage() { internal::conditional_aligned_delete_auto(m_data, _Rows*m_cols); } - inline void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_cols,other.m_cols); } - static inline DenseIndex rows(void) {return _Rows;} - inline DenseIndex cols(void) const {return m_cols;} - inline void conservativeResize(DenseIndex size, DenseIndex, DenseIndex nbCols) + EIGEN_DEVICE_FUNC DenseStorage() : m_data(0), m_cols(0) {} + explicit DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(0), m_cols(0) {} + EIGEN_DEVICE_FUNC DenseStorage(Index size, Index rows, Index cols) : m_data(internal::conditional_aligned_new_auto(size)), m_cols(cols) + { + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN({}) + eigen_internal_assert(size==rows*cols && rows==_Rows && cols >=0); + EIGEN_UNUSED_VARIABLE(rows); + } + EIGEN_DEVICE_FUNC DenseStorage(const DenseStorage& other) + : m_data(internal::conditional_aligned_new_auto(_Rows*other.m_cols)) + , m_cols(other.m_cols) + { + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN(Index size = m_cols*_Rows) + internal::smart_copy(other.m_data, other.m_data+_Rows*m_cols, m_data); + } + EIGEN_DEVICE_FUNC DenseStorage& operator=(const DenseStorage& other) + { + if (this != &other) + { + DenseStorage tmp(other); + this->swap(tmp); + } + return *this; + } +#if EIGEN_HAS_RVALUE_REFERENCES + EIGEN_DEVICE_FUNC + DenseStorage(DenseStorage&& other) EIGEN_NOEXCEPT + : m_data(std::move(other.m_data)) + , m_cols(std::move(other.m_cols)) + { + other.m_data = nullptr; + other.m_cols = 0; + } + EIGEN_DEVICE_FUNC + DenseStorage& operator=(DenseStorage&& other) EIGEN_NOEXCEPT + { + using std::swap; + swap(m_data, other.m_data); + swap(m_cols, other.m_cols); + return *this; + } +#endif + EIGEN_DEVICE_FUNC ~DenseStorage() { internal::conditional_aligned_delete_auto(m_data, _Rows*m_cols); } + EIGEN_DEVICE_FUNC void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_cols,other.m_cols); } + EIGEN_DEVICE_FUNC static Index rows(void) {return _Rows;} + EIGEN_DEVICE_FUNC Index cols(void) const {return m_cols;} + EIGEN_DEVICE_FUNC void conservativeResize(Index size, Index, Index cols) { m_data = internal::conditional_aligned_realloc_new_auto(m_data, size, _Rows*m_cols); - m_cols = nbCols; + m_cols = cols; } - EIGEN_STRONG_INLINE void resize(DenseIndex size, DenseIndex, DenseIndex nbCols) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(Index size, Index, Index cols) { if(size != _Rows*m_cols) { @@ -290,34 +483,72 @@ template class DenseStorage(size); else m_data = 0; - EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN({}) } - m_cols = nbCols; + m_cols = cols; } - inline const T *data() const { return m_data; } - inline T *data() { return m_data; } + EIGEN_DEVICE_FUNC const T *data() const { return m_data; } + EIGEN_DEVICE_FUNC T *data() { return m_data; } }; // matrix with dynamic height and fixed width (so that matrix has dynamic size). template class DenseStorage { T *m_data; - DenseIndex m_rows; + Index m_rows; public: - inline DenseStorage() : m_data(0), m_rows(0) {} - inline DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(0), m_rows(0) {} - inline DenseStorage(DenseIndex size, DenseIndex nbRows, DenseIndex) : m_data(internal::conditional_aligned_new_auto(size)), m_rows(nbRows) - { EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN } - inline ~DenseStorage() { internal::conditional_aligned_delete_auto(m_data, _Cols*m_rows); } - inline void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_rows,other.m_rows); } - inline DenseIndex rows(void) const {return m_rows;} - static inline DenseIndex cols(void) {return _Cols;} - inline void conservativeResize(DenseIndex size, DenseIndex nbRows, DenseIndex) + EIGEN_DEVICE_FUNC DenseStorage() : m_data(0), m_rows(0) {} + explicit DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(0), m_rows(0) {} + EIGEN_DEVICE_FUNC DenseStorage(Index size, Index rows, Index cols) : m_data(internal::conditional_aligned_new_auto(size)), m_rows(rows) + { + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN({}) + eigen_internal_assert(size==rows*cols && rows>=0 && cols == _Cols); + EIGEN_UNUSED_VARIABLE(cols); + } + EIGEN_DEVICE_FUNC DenseStorage(const DenseStorage& other) + : m_data(internal::conditional_aligned_new_auto(other.m_rows*_Cols)) + , m_rows(other.m_rows) + { + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN(Index size = m_rows*_Cols) + internal::smart_copy(other.m_data, other.m_data+other.m_rows*_Cols, m_data); + } + EIGEN_DEVICE_FUNC DenseStorage& operator=(const DenseStorage& other) + { + if (this != &other) + { + DenseStorage tmp(other); + this->swap(tmp); + } + return *this; + } +#if EIGEN_HAS_RVALUE_REFERENCES + EIGEN_DEVICE_FUNC + DenseStorage(DenseStorage&& other) EIGEN_NOEXCEPT + : m_data(std::move(other.m_data)) + , m_rows(std::move(other.m_rows)) + { + other.m_data = nullptr; + other.m_rows = 0; + } + EIGEN_DEVICE_FUNC + DenseStorage& operator=(DenseStorage&& other) EIGEN_NOEXCEPT + { + using std::swap; + swap(m_data, other.m_data); + swap(m_rows, other.m_rows); + return *this; + } +#endif + EIGEN_DEVICE_FUNC ~DenseStorage() { internal::conditional_aligned_delete_auto(m_data, _Cols*m_rows); } + EIGEN_DEVICE_FUNC void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_rows,other.m_rows); } + EIGEN_DEVICE_FUNC Index rows(void) const {return m_rows;} + EIGEN_DEVICE_FUNC static Index cols(void) {return _Cols;} + void conservativeResize(Index size, Index rows, Index) { m_data = internal::conditional_aligned_realloc_new_auto(m_data, size, m_rows*_Cols); - m_rows = nbRows; + m_rows = rows; } - EIGEN_STRONG_INLINE void resize(DenseIndex size, DenseIndex nbRows, DenseIndex) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(Index size, Index rows, Index) { if(size != m_rows*_Cols) { @@ -326,12 +557,12 @@ template class DenseStorage(size); else m_data = 0; - EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN({}) } - m_rows = nbRows; + m_rows = rows; } - inline const T *data() const { return m_data; } - inline T *data() { return m_data; } + EIGEN_DEVICE_FUNC const T *data() const { return m_data; } + EIGEN_DEVICE_FUNC T *data() { return m_data; } }; } // end namespace Eigen diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/Diagonal.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/Diagonal.h index 68cf6d4b..c62f5ff2 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/Diagonal.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/Diagonal.h @@ -21,7 +21,7 @@ namespace Eigen { * \param MatrixType the type of the object in which we are taking a sub/main/super diagonal * \param DiagIndex the index of the sub/super diagonal. The default is 0 and it means the main diagonal. * A positive value means a superdiagonal, a negative value means a subdiagonal. - * You can also use Dynamic so the index can be set at runtime. + * You can also use DynamicIndex so the index can be set at runtime. * * The matrix is not required to be square. * @@ -37,7 +37,7 @@ template struct traits > : traits { - typedef typename nested::type MatrixTypeNested; + typedef typename ref_selector::type MatrixTypeNested; typedef typename remove_reference::type _MatrixTypeNested; typedef typename MatrixType::StorageKind StorageKind; enum { @@ -52,8 +52,7 @@ struct traits > MatrixType::MaxColsAtCompileTime - EIGEN_PLAIN_ENUM_MAX( DiagIndex, 0))), MaxColsAtCompileTime = 1, MaskLvalueBit = is_lvalue::value ? LvalueBit : 0, - Flags = (unsigned int)_MatrixTypeNested::Flags & (HereditaryBits | LinearAccessBit | MaskLvalueBit | DirectAccessBit) & ~RowMajorBit, - CoeffReadCost = _MatrixTypeNested::CoeffReadCost, + Flags = (unsigned int)_MatrixTypeNested::Flags & (RowMajorBit | MaskLvalueBit | DirectAccessBit) & ~RowMajorBit, // FIXME DirectAccessBit should not be handled by expressions MatrixTypeOuterStride = outer_stride_at_compile_time::ret, InnerStrideAtCompileTime = MatrixTypeOuterStride == Dynamic ? Dynamic : MatrixTypeOuterStride+1, OuterStrideAtCompileTime = 0 @@ -70,20 +69,28 @@ template class Diagonal typedef typename internal::dense_xpr_base::type Base; EIGEN_DENSE_PUBLIC_INTERFACE(Diagonal) - inline Diagonal(MatrixType& matrix, Index a_index = DiagIndex) : m_matrix(matrix), m_index(a_index) {} + EIGEN_DEVICE_FUNC + explicit inline Diagonal(MatrixType& matrix, Index a_index = DiagIndex) : m_matrix(matrix), m_index(a_index) {} EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Diagonal) + EIGEN_DEVICE_FUNC inline Index rows() const - { return m_index.value()<0 ? (std::min)(m_matrix.cols(),m_matrix.rows()+m_index.value()) : (std::min)(m_matrix.rows(),m_matrix.cols()-m_index.value()); } + { + return m_index.value()<0 ? numext::mini(m_matrix.cols(),m_matrix.rows()+m_index.value()) + : numext::mini(m_matrix.rows(),m_matrix.cols()-m_index.value()); + } + EIGEN_DEVICE_FUNC inline Index cols() const { return 1; } + EIGEN_DEVICE_FUNC inline Index innerStride() const { return m_matrix.outerStride() + 1; } + EIGEN_DEVICE_FUNC inline Index outerStride() const { return 0; @@ -95,62 +102,75 @@ template class Diagonal const Scalar >::type ScalarWithConstIfNotLvalue; - inline ScalarWithConstIfNotLvalue* data() { return &(m_matrix.const_cast_derived().coeffRef(rowOffset(), colOffset())); } - inline const Scalar* data() const { return &(m_matrix.const_cast_derived().coeffRef(rowOffset(), colOffset())); } + EIGEN_DEVICE_FUNC + inline ScalarWithConstIfNotLvalue* data() { return &(m_matrix.coeffRef(rowOffset(), colOffset())); } + EIGEN_DEVICE_FUNC + inline const Scalar* data() const { return &(m_matrix.coeffRef(rowOffset(), colOffset())); } + EIGEN_DEVICE_FUNC inline Scalar& coeffRef(Index row, Index) { EIGEN_STATIC_ASSERT_LVALUE(MatrixType) - return m_matrix.const_cast_derived().coeffRef(row+rowOffset(), row+colOffset()); + return m_matrix.coeffRef(row+rowOffset(), row+colOffset()); } + EIGEN_DEVICE_FUNC inline const Scalar& coeffRef(Index row, Index) const { - return m_matrix.const_cast_derived().coeffRef(row+rowOffset(), row+colOffset()); + return m_matrix.coeffRef(row+rowOffset(), row+colOffset()); } + EIGEN_DEVICE_FUNC inline CoeffReturnType coeff(Index row, Index) const { return m_matrix.coeff(row+rowOffset(), row+colOffset()); } + EIGEN_DEVICE_FUNC inline Scalar& coeffRef(Index idx) { EIGEN_STATIC_ASSERT_LVALUE(MatrixType) - return m_matrix.const_cast_derived().coeffRef(idx+rowOffset(), idx+colOffset()); + return m_matrix.coeffRef(idx+rowOffset(), idx+colOffset()); } + EIGEN_DEVICE_FUNC inline const Scalar& coeffRef(Index idx) const { - return m_matrix.const_cast_derived().coeffRef(idx+rowOffset(), idx+colOffset()); + return m_matrix.coeffRef(idx+rowOffset(), idx+colOffset()); } + EIGEN_DEVICE_FUNC inline CoeffReturnType coeff(Index idx) const { return m_matrix.coeff(idx+rowOffset(), idx+colOffset()); } - const typename internal::remove_all::type& + EIGEN_DEVICE_FUNC + inline const typename internal::remove_all::type& nestedExpression() const { return m_matrix; } - int index() const + EIGEN_DEVICE_FUNC + inline Index index() const { return m_index.value(); } protected: - typename MatrixType::Nested m_matrix; + typename internal::ref_selector::non_const_type m_matrix; const internal::variable_if_dynamicindex m_index; private: // some compilers may fail to optimize std::max etc in case of compile-time constants... + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index absDiagIndex() const { return m_index.value()>0 ? m_index.value() : -m_index.value(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rowOffset() const { return m_index.value()>0 ? 0 : -m_index.value(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index colOffset() const { return m_index.value()>0 ? m_index.value() : 0; } - // triger a compile time error is someone try to call packet + // trigger a compile-time error if someone try to call packet template typename MatrixType::PacketReturnType packet(Index) const; template typename MatrixType::PacketReturnType packet(Index,Index) const; }; @@ -164,15 +184,15 @@ template class Diagonal * * \sa class Diagonal */ template -inline typename MatrixBase::DiagonalReturnType +EIGEN_DEVICE_FUNC inline typename MatrixBase::DiagonalReturnType MatrixBase::diagonal() { - return derived(); + return DiagonalReturnType(derived()); } /** This is the const version of diagonal(). */ template -inline typename MatrixBase::ConstDiagonalReturnType +EIGEN_DEVICE_FUNC inline typename MatrixBase::ConstDiagonalReturnType MatrixBase::diagonal() const { return ConstDiagonalReturnType(derived()); @@ -190,7 +210,7 @@ MatrixBase::diagonal() const * * \sa MatrixBase::diagonal(), class Diagonal */ template -inline typename MatrixBase::DiagonalDynamicIndexReturnType +EIGEN_DEVICE_FUNC inline typename MatrixBase::DiagonalDynamicIndexReturnType MatrixBase::diagonal(Index index) { return DiagonalDynamicIndexReturnType(derived(), index); @@ -198,7 +218,7 @@ MatrixBase::diagonal(Index index) /** This is the const version of diagonal(Index). */ template -inline typename MatrixBase::ConstDiagonalDynamicIndexReturnType +EIGEN_DEVICE_FUNC inline typename MatrixBase::ConstDiagonalDynamicIndexReturnType MatrixBase::diagonal(Index index) const { return ConstDiagonalDynamicIndexReturnType(derived(), index); @@ -216,20 +236,22 @@ MatrixBase::diagonal(Index index) const * * \sa MatrixBase::diagonal(), class Diagonal */ template -template -inline typename MatrixBase::template DiagonalIndexReturnType::Type +template +EIGEN_DEVICE_FUNC +inline typename MatrixBase::template DiagonalIndexReturnType::Type MatrixBase::diagonal() { - return derived(); + return typename DiagonalIndexReturnType::Type(derived()); } /** This is the const version of diagonal(). */ template -template -inline typename MatrixBase::template ConstDiagonalIndexReturnType::Type +template +EIGEN_DEVICE_FUNC +inline typename MatrixBase::template ConstDiagonalIndexReturnType::Type MatrixBase::diagonal() const { - return derived(); + return typename ConstDiagonalIndexReturnType::Type(derived()); } } // end namespace Eigen diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/DiagonalMatrix.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/DiagonalMatrix.h index e6c220f4..4e8297ee 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/DiagonalMatrix.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/DiagonalMatrix.h @@ -22,7 +22,7 @@ class DiagonalBase : public EigenBase typedef typename DiagonalVectorType::Scalar Scalar; typedef typename DiagonalVectorType::RealScalar RealScalar; typedef typename internal::traits::StorageKind StorageKind; - typedef typename internal::traits::Index Index; + typedef typename internal::traits::StorageIndex StorageIndex; enum { RowsAtCompileTime = DiagonalVectorType::SizeAtCompileTime, @@ -30,79 +30,61 @@ class DiagonalBase : public EigenBase MaxRowsAtCompileTime = DiagonalVectorType::MaxSizeAtCompileTime, MaxColsAtCompileTime = DiagonalVectorType::MaxSizeAtCompileTime, IsVectorAtCompileTime = 0, - Flags = 0 + Flags = NoPreferredStorageOrderBit }; typedef Matrix DenseMatrixType; typedef DenseMatrixType DenseType; typedef DiagonalMatrix PlainObject; + EIGEN_DEVICE_FUNC inline const Derived& derived() const { return *static_cast(this); } + EIGEN_DEVICE_FUNC inline Derived& derived() { return *static_cast(this); } + EIGEN_DEVICE_FUNC DenseMatrixType toDenseMatrix() const { return derived(); } - template - void evalTo(MatrixBase &other) const; - template - void addTo(MatrixBase &other) const - { other.diagonal() += diagonal(); } - template - void subTo(MatrixBase &other) const - { other.diagonal() -= diagonal(); } + EIGEN_DEVICE_FUNC inline const DiagonalVectorType& diagonal() const { return derived().diagonal(); } + EIGEN_DEVICE_FUNC inline DiagonalVectorType& diagonal() { return derived().diagonal(); } + EIGEN_DEVICE_FUNC inline Index rows() const { return diagonal().size(); } + EIGEN_DEVICE_FUNC inline Index cols() const { return diagonal().size(); } - /** \returns the diagonal matrix product of \c *this by the matrix \a matrix. - */ template - const DiagonalProduct + EIGEN_DEVICE_FUNC + const Product operator*(const MatrixBase &matrix) const { - return DiagonalProduct(matrix.derived(), derived()); + return Product(derived(),matrix.derived()); } - inline const DiagonalWrapper, const DiagonalVectorType> > + typedef DiagonalWrapper, const DiagonalVectorType> > InverseReturnType; + EIGEN_DEVICE_FUNC + inline const InverseReturnType inverse() const { - return diagonal().cwiseInverse(); + return InverseReturnType(diagonal().cwiseInverse()); } - inline const DiagonalWrapper, const DiagonalVectorType> > + EIGEN_DEVICE_FUNC + inline const DiagonalWrapper operator*(const Scalar& scalar) const { - return diagonal() * scalar; + return DiagonalWrapper(diagonal() * scalar); } - friend inline const DiagonalWrapper, const DiagonalVectorType> > + EIGEN_DEVICE_FUNC + friend inline const DiagonalWrapper operator*(const Scalar& scalar, const DiagonalBase& other) { - return other.diagonal() * scalar; + return DiagonalWrapper(scalar * other.diagonal()); } - - #ifdef EIGEN2_SUPPORT - template - bool isApprox(const DiagonalBase& other, typename NumTraits::Real precision = NumTraits::dummy_precision()) const - { - return diagonal().isApprox(other.diagonal(), precision); - } - template - bool isApprox(const MatrixBase& other, typename NumTraits::Real precision = NumTraits::dummy_precision()) const - { - return toDenseMatrix().isApprox(other, precision); - } - #endif }; -template -template -void DiagonalBase::evalTo(MatrixBase &other) const -{ - other.setZero(); - other.diagonal() = diagonal(); -} #endif /** \class DiagonalMatrix @@ -124,10 +106,9 @@ struct traits > : traits > { typedef Matrix<_Scalar,SizeAtCompileTime,1,0,MaxSizeAtCompileTime,1> DiagonalVectorType; - typedef Dense StorageKind; - typedef DenseIndex Index; + typedef DiagonalShape StorageKind; enum { - Flags = LvalueBit + Flags = LvalueBit | NoPreferredStorageOrderBit }; }; } @@ -141,7 +122,7 @@ class DiagonalMatrix typedef const DiagonalMatrix& Nested; typedef _Scalar Scalar; typedef typename internal::traits::StorageKind StorageKind; - typedef typename internal::traits::Index Index; + typedef typename internal::traits::StorageIndex StorageIndex; #endif protected: @@ -151,24 +132,31 @@ class DiagonalMatrix public: /** const version of diagonal(). */ + EIGEN_DEVICE_FUNC inline const DiagonalVectorType& diagonal() const { return m_diagonal; } /** \returns a reference to the stored vector of diagonal coefficients. */ + EIGEN_DEVICE_FUNC inline DiagonalVectorType& diagonal() { return m_diagonal; } /** Default constructor without initialization */ + EIGEN_DEVICE_FUNC inline DiagonalMatrix() {} /** Constructs a diagonal matrix with given dimension */ - inline DiagonalMatrix(Index dim) : m_diagonal(dim) {} + EIGEN_DEVICE_FUNC + explicit inline DiagonalMatrix(Index dim) : m_diagonal(dim) {} /** 2D constructor. */ + EIGEN_DEVICE_FUNC inline DiagonalMatrix(const Scalar& x, const Scalar& y) : m_diagonal(x,y) {} /** 3D constructor. */ + EIGEN_DEVICE_FUNC inline DiagonalMatrix(const Scalar& x, const Scalar& y, const Scalar& z) : m_diagonal(x,y,z) {} /** Copy constructor. */ template + EIGEN_DEVICE_FUNC inline DiagonalMatrix(const DiagonalBase& other) : m_diagonal(other.diagonal()) {} #ifndef EIGEN_PARSED_BY_DOXYGEN @@ -178,11 +166,13 @@ class DiagonalMatrix /** generic constructor from expression of the diagonal coefficients */ template + EIGEN_DEVICE_FUNC explicit inline DiagonalMatrix(const MatrixBase& other) : m_diagonal(other) {} /** Copy operator. */ template + EIGEN_DEVICE_FUNC DiagonalMatrix& operator=(const DiagonalBase& other) { m_diagonal = other.diagonal(); @@ -193,6 +183,7 @@ class DiagonalMatrix /** This is a special case of the templated operator=. Its purpose is to * prevent a default operator= from hiding the templated operator=. */ + EIGEN_DEVICE_FUNC DiagonalMatrix& operator=(const DiagonalMatrix& other) { m_diagonal = other.diagonal(); @@ -201,14 +192,19 @@ class DiagonalMatrix #endif /** Resizes to given size. */ + EIGEN_DEVICE_FUNC inline void resize(Index size) { m_diagonal.resize(size); } /** Sets all coefficients to zero. */ + EIGEN_DEVICE_FUNC inline void setZero() { m_diagonal.setZero(); } /** Resizes and sets all coefficients to zero. */ + EIGEN_DEVICE_FUNC inline void setZero(Index size) { m_diagonal.setZero(size); } /** Sets this matrix to be the identity matrix of the current size. */ + EIGEN_DEVICE_FUNC inline void setIdentity() { m_diagonal.setOnes(); } /** Sets this matrix to be the identity matrix of the given size. */ + EIGEN_DEVICE_FUNC inline void setIdentity(Index size) { m_diagonal.setOnes(size); } }; @@ -232,14 +228,15 @@ struct traits > { typedef _DiagonalVectorType DiagonalVectorType; typedef typename DiagonalVectorType::Scalar Scalar; - typedef typename DiagonalVectorType::Index Index; - typedef typename DiagonalVectorType::StorageKind StorageKind; + typedef typename DiagonalVectorType::StorageIndex StorageIndex; + typedef DiagonalShape StorageKind; + typedef typename traits::XprKind XprKind; enum { RowsAtCompileTime = DiagonalVectorType::SizeAtCompileTime, ColsAtCompileTime = DiagonalVectorType::SizeAtCompileTime, - MaxRowsAtCompileTime = DiagonalVectorType::SizeAtCompileTime, - MaxColsAtCompileTime = DiagonalVectorType::SizeAtCompileTime, - Flags = traits::Flags & LvalueBit + MaxRowsAtCompileTime = DiagonalVectorType::MaxSizeAtCompileTime, + MaxColsAtCompileTime = DiagonalVectorType::MaxSizeAtCompileTime, + Flags = (traits::Flags & LvalueBit) | NoPreferredStorageOrderBit }; }; } @@ -255,9 +252,11 @@ class DiagonalWrapper #endif /** Constructor from expression of diagonal coefficients to wrap. */ - inline DiagonalWrapper(DiagonalVectorType& a_diagonal) : m_diagonal(a_diagonal) {} + EIGEN_DEVICE_FUNC + explicit inline DiagonalWrapper(DiagonalVectorType& a_diagonal) : m_diagonal(a_diagonal) {} /** \returns a const reference to the wrapped expression of diagonal coefficients. */ + EIGEN_DEVICE_FUNC const DiagonalVectorType& diagonal() const { return m_diagonal; } protected: @@ -274,10 +273,10 @@ class DiagonalWrapper * \sa class DiagonalWrapper, class DiagonalMatrix, diagonal(), isDiagonal() **/ template -inline const DiagonalWrapper +EIGEN_DEVICE_FUNC inline const DiagonalWrapper MatrixBase::asDiagonal() const { - return derived(); + return DiagonalWrapper(derived()); } /** \returns true if *this is approximately equal to a diagonal matrix, @@ -291,12 +290,11 @@ MatrixBase::asDiagonal() const template bool MatrixBase::isDiagonal(const RealScalar& prec) const { - using std::abs; if(cols() != rows()) return false; RealScalar maxAbsOnDiagonal = static_cast(-1); for(Index j = 0; j < cols(); ++j) { - RealScalar absOnDiagonal = abs(coeff(j,j)); + RealScalar absOnDiagonal = numext::abs(coeff(j,j)); if(absOnDiagonal > maxAbsOnDiagonal) maxAbsOnDiagonal = absOnDiagonal; } for(Index j = 0; j < cols(); ++j) @@ -308,6 +306,38 @@ bool MatrixBase::isDiagonal(const RealScalar& prec) const return true; } +namespace internal { + +template<> struct storage_kind_to_shape { typedef DiagonalShape Shape; }; + +struct Diagonal2Dense {}; + +template<> struct AssignmentKind { typedef Diagonal2Dense Kind; }; + +// Diagonal matrix to Dense assignment +template< typename DstXprType, typename SrcXprType, typename Functor> +struct Assignment +{ + static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op &/*func*/) + { + Index dstRows = src.rows(); + Index dstCols = src.cols(); + if((dst.rows()!=dstRows) || (dst.cols()!=dstCols)) + dst.resize(dstRows, dstCols); + + dst.setZero(); + dst.diagonal() = src.diagonal(); + } + + static void run(DstXprType &dst, const SrcXprType &src, const internal::add_assign_op &/*func*/) + { dst.diagonal() += src.diagonal(); } + + static void run(DstXprType &dst, const SrcXprType &src, const internal::sub_assign_op &/*func*/) + { dst.diagonal() -= src.diagonal(); } +}; + +} // namespace internal + } // end namespace Eigen #endif // EIGEN_DIAGONALMATRIX_H diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/DiagonalProduct.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/DiagonalProduct.h index c03a0c2e..7911d1cd 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/DiagonalProduct.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/DiagonalProduct.h @@ -13,116 +13,14 @@ namespace Eigen { -namespace internal { -template -struct traits > - : traits -{ - typedef typename scalar_product_traits::ReturnType Scalar; - enum { - RowsAtCompileTime = MatrixType::RowsAtCompileTime, - ColsAtCompileTime = MatrixType::ColsAtCompileTime, - MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime, - MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime, - - _StorageOrder = MatrixType::Flags & RowMajorBit ? RowMajor : ColMajor, - _ScalarAccessOnDiag = !((int(_StorageOrder) == ColMajor && int(ProductOrder) == OnTheLeft) - ||(int(_StorageOrder) == RowMajor && int(ProductOrder) == OnTheRight)), - _SameTypes = is_same::value, - // FIXME currently we need same types, but in the future the next rule should be the one - //_Vectorizable = bool(int(MatrixType::Flags)&PacketAccessBit) && ((!_PacketOnDiag) || (_SameTypes && bool(int(DiagonalType::DiagonalVectorType::Flags)&PacketAccessBit))), - _Vectorizable = bool(int(MatrixType::Flags)&PacketAccessBit) && _SameTypes && (_ScalarAccessOnDiag || (bool(int(DiagonalType::DiagonalVectorType::Flags)&PacketAccessBit))), - _LinearAccessMask = (RowsAtCompileTime==1 || ColsAtCompileTime==1) ? LinearAccessBit : 0, - - Flags = ((HereditaryBits|_LinearAccessMask) & (unsigned int)(MatrixType::Flags)) | (_Vectorizable ? PacketAccessBit : 0) | AlignedBit,//(int(MatrixType::Flags)&int(DiagonalType::DiagonalVectorType::Flags)&AlignedBit), - CoeffReadCost = NumTraits::MulCost + MatrixType::CoeffReadCost + DiagonalType::DiagonalVectorType::CoeffReadCost - }; -}; -} - -template -class DiagonalProduct : internal::no_assignment_operator, - public MatrixBase > -{ - public: - - typedef MatrixBase Base; - EIGEN_DENSE_PUBLIC_INTERFACE(DiagonalProduct) - - inline DiagonalProduct(const MatrixType& matrix, const DiagonalType& diagonal) - : m_matrix(matrix), m_diagonal(diagonal) - { - eigen_assert(diagonal.diagonal().size() == (ProductOrder == OnTheLeft ? matrix.rows() : matrix.cols())); - } - - EIGEN_STRONG_INLINE Index rows() const { return m_matrix.rows(); } - EIGEN_STRONG_INLINE Index cols() const { return m_matrix.cols(); } - - EIGEN_STRONG_INLINE const Scalar coeff(Index row, Index col) const - { - return m_diagonal.diagonal().coeff(ProductOrder == OnTheLeft ? row : col) * m_matrix.coeff(row, col); - } - - EIGEN_STRONG_INLINE const Scalar coeff(Index idx) const - { - enum { - StorageOrder = int(MatrixType::Flags) & RowMajorBit ? RowMajor : ColMajor - }; - return coeff(int(StorageOrder)==ColMajor?idx:0,int(StorageOrder)==ColMajor?0:idx); - } - - template - EIGEN_STRONG_INLINE PacketScalar packet(Index row, Index col) const - { - enum { - StorageOrder = Flags & RowMajorBit ? RowMajor : ColMajor - }; - const Index indexInDiagonalVector = ProductOrder == OnTheLeft ? row : col; - return packet_impl(row,col,indexInDiagonalVector,typename internal::conditional< - ((int(StorageOrder) == RowMajor && int(ProductOrder) == OnTheLeft) - ||(int(StorageOrder) == ColMajor && int(ProductOrder) == OnTheRight)), internal::true_type, internal::false_type>::type()); - } - - template - EIGEN_STRONG_INLINE PacketScalar packet(Index idx) const - { - enum { - StorageOrder = int(MatrixType::Flags) & RowMajorBit ? RowMajor : ColMajor - }; - return packet(int(StorageOrder)==ColMajor?idx:0,int(StorageOrder)==ColMajor?0:idx); - } - - protected: - template - EIGEN_STRONG_INLINE PacketScalar packet_impl(Index row, Index col, Index id, internal::true_type) const - { - return internal::pmul(m_matrix.template packet(row, col), - internal::pset1(m_diagonal.diagonal().coeff(id))); - } - - template - EIGEN_STRONG_INLINE PacketScalar packet_impl(Index row, Index col, Index id, internal::false_type) const - { - enum { - InnerSize = (MatrixType::Flags & RowMajorBit) ? MatrixType::ColsAtCompileTime : MatrixType::RowsAtCompileTime, - DiagonalVectorPacketLoadMode = (LoadMode == Aligned && (((InnerSize%16) == 0) || (int(DiagonalType::DiagonalVectorType::Flags)&AlignedBit)==AlignedBit) ? Aligned : Unaligned) - }; - return internal::pmul(m_matrix.template packet(row, col), - m_diagonal.diagonal().template packet(id)); - } - - typename MatrixType::Nested m_matrix; - typename DiagonalType::Nested m_diagonal; -}; - /** \returns the diagonal matrix product of \c *this by the diagonal matrix \a diagonal. */ template template -inline const DiagonalProduct +EIGEN_DEVICE_FUNC inline const Product MatrixBase::operator*(const DiagonalBase &a_diagonal) const { - return DiagonalProduct(derived(), a_diagonal.derived()); + return Product(derived(),a_diagonal.derived()); } } // end namespace Eigen diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/Dot.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/Dot.h index 9d7651f1..bb8e3fec 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/Dot.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/Dot.h @@ -28,26 +28,31 @@ template struct dot_nocheck { - typedef typename scalar_product_traits::Scalar,typename traits::Scalar>::ReturnType ResScalar; + typedef scalar_conj_product_op::Scalar,typename traits::Scalar> conj_prod; + typedef typename conj_prod::result_type ResScalar; + EIGEN_DEVICE_FUNC static inline ResScalar run(const MatrixBase& a, const MatrixBase& b) { - return a.template binaryExpr::Scalar,typename traits::Scalar> >(b).sum(); + return a.template binaryExpr(b).sum(); } }; template struct dot_nocheck { - typedef typename scalar_product_traits::Scalar,typename traits::Scalar>::ReturnType ResScalar; + typedef scalar_conj_product_op::Scalar,typename traits::Scalar> conj_prod; + typedef typename conj_prod::result_type ResScalar; + EIGEN_DEVICE_FUNC static inline ResScalar run(const MatrixBase& a, const MatrixBase& b) { - return a.transpose().template binaryExpr::Scalar,typename traits::Scalar> >(b).sum(); + return a.transpose().template binaryExpr(b).sum(); } }; } // end namespace internal -/** \returns the dot product of *this with other. +/** \fn MatrixBase::dot + * \returns the dot product of *this with other. * * \only_for_vectors * @@ -59,58 +64,33 @@ struct dot_nocheck */ template template -typename internal::scalar_product_traits::Scalar,typename internal::traits::Scalar>::ReturnType +EIGEN_DEVICE_FUNC +typename ScalarBinaryOpTraits::Scalar,typename internal::traits::Scalar>::ReturnType MatrixBase::dot(const MatrixBase& other) const { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived) EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Derived,OtherDerived) +#if !(defined(EIGEN_NO_STATIC_ASSERT) && defined(EIGEN_NO_DEBUG)) typedef internal::scalar_conj_product_op func; EIGEN_CHECK_BINARY_COMPATIBILIY(func,Scalar,typename OtherDerived::Scalar); - +#endif + eigen_assert(size() == other.size()); return internal::dot_nocheck::run(*this, other); } -#ifdef EIGEN2_SUPPORT -/** \returns the dot product of *this with other, with the Eigen2 convention that the dot product is linear in the first variable - * (conjugating the second variable). Of course this only makes a difference in the complex case. - * - * This method is only available in EIGEN2_SUPPORT mode. - * - * \only_for_vectors - * - * \sa dot() - */ -template -template -typename internal::traits::Scalar -MatrixBase::eigen2_dot(const MatrixBase& other) const -{ - EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) - EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived) - EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Derived,OtherDerived) - EIGEN_STATIC_ASSERT((internal::is_same::value), - YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) - - eigen_assert(size() == other.size()); - - return internal::dot_nocheck::run(other,*this); -} -#endif - - //---------- implementation of L2 norm and related functions ---------- /** \returns, for vectors, the squared \em l2 norm of \c *this, and for matrices the Frobenius norm. * In both cases, it consists in the sum of the square of all the matrix entries. * For vectors, this is also equals to the dot product of \c *this with itself. * - * \sa dot(), norm() + * \sa dot(), norm(), lpNorm() */ template -EIGEN_STRONG_INLINE typename NumTraits::Scalar>::Real MatrixBase::squaredNorm() const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename NumTraits::Scalar>::Real MatrixBase::squaredNorm() const { return numext::real((*this).cwiseAbs2().sum()); } @@ -119,41 +99,98 @@ EIGEN_STRONG_INLINE typename NumTraits::Scala * In both cases, it consists in the square root of the sum of the square of all the matrix entries. * For vectors, this is also equals to the square root of the dot product of \c *this with itself. * - * \sa dot(), squaredNorm() + * \sa lpNorm(), dot(), squaredNorm() */ template -inline typename NumTraits::Scalar>::Real MatrixBase::norm() const +EIGEN_DEVICE_FUNC inline typename NumTraits::Scalar>::Real MatrixBase::norm() const { - using std::sqrt; - return sqrt(squaredNorm()); + return numext::sqrt(squaredNorm()); } -/** \returns an expression of the quotient of *this by its own norm. +/** \returns an expression of the quotient of \c *this by its own norm. + * + * \warning If the input vector is too small (i.e., this->norm()==0), + * then this function returns a copy of the input. * * \only_for_vectors * * \sa norm(), normalize() */ template -inline const typename MatrixBase::PlainObject +EIGEN_DEVICE_FUNC inline const typename MatrixBase::PlainObject MatrixBase::normalized() const { - typedef typename internal::nested::type Nested; - typedef typename internal::remove_reference::type _Nested; + typedef typename internal::nested_eval::type _Nested; _Nested n(derived()); - return n / n.norm(); + RealScalar z = n.squaredNorm(); + // NOTE: after extensive benchmarking, this conditional does not impact performance, at least on recent x86 CPU + if(z>RealScalar(0)) + return n / numext::sqrt(z); + else + return n; } /** Normalizes the vector, i.e. divides it by its own norm. * * \only_for_vectors * + * \warning If the input vector is too small (i.e., this->norm()==0), then \c *this is left unchanged. + * * \sa norm(), normalized() */ template -inline void MatrixBase::normalize() +EIGEN_DEVICE_FUNC inline void MatrixBase::normalize() { - *this /= norm(); + RealScalar z = squaredNorm(); + // NOTE: after extensive benchmarking, this conditional does not impact performance, at least on recent x86 CPU + if(z>RealScalar(0)) + derived() /= numext::sqrt(z); +} + +/** \returns an expression of the quotient of \c *this by its own norm while avoiding underflow and overflow. + * + * \only_for_vectors + * + * This method is analogue to the normalized() method, but it reduces the risk of + * underflow and overflow when computing the norm. + * + * \warning If the input vector is too small (i.e., this->norm()==0), + * then this function returns a copy of the input. + * + * \sa stableNorm(), stableNormalize(), normalized() + */ +template +EIGEN_DEVICE_FUNC inline const typename MatrixBase::PlainObject +MatrixBase::stableNormalized() const +{ + typedef typename internal::nested_eval::type _Nested; + _Nested n(derived()); + RealScalar w = n.cwiseAbs().maxCoeff(); + RealScalar z = (n/w).squaredNorm(); + if(z>RealScalar(0)) + return n / (numext::sqrt(z)*w); + else + return n; +} + +/** Normalizes the vector while avoid underflow and overflow + * + * \only_for_vectors + * + * This method is analogue to the normalize() method, but it reduces the risk of + * underflow and overflow when computing the norm. + * + * \warning If the input vector is too small (i.e., this->norm()==0), then \c *this is left unchanged. + * + * \sa stableNorm(), stableNormalized(), normalize() + */ +template +EIGEN_DEVICE_FUNC inline void MatrixBase::stableNormalize() +{ + RealScalar w = cwiseAbs().maxCoeff(); + RealScalar z = (derived()/w).squaredNorm(); + if(z>RealScalar(0)) + derived() /= numext::sqrt(z)*w; } //---------- implementation of other norms ---------- @@ -164,9 +201,10 @@ template struct lpNorm_selector { typedef typename NumTraits::Scalar>::Real RealScalar; + EIGEN_DEVICE_FUNC static inline RealScalar run(const MatrixBase& m) { - using std::pow; + EIGEN_USING_STD_MATH(pow) return pow(m.cwiseAbs().array().pow(p).sum(), RealScalar(1)/p); } }; @@ -174,6 +212,7 @@ struct lpNorm_selector template struct lpNorm_selector { + EIGEN_DEVICE_FUNC static inline typename NumTraits::Scalar>::Real run(const MatrixBase& m) { return m.cwiseAbs().sum(); @@ -183,6 +222,7 @@ struct lpNorm_selector template struct lpNorm_selector { + EIGEN_DEVICE_FUNC static inline typename NumTraits::Scalar>::Real run(const MatrixBase& m) { return m.norm(); @@ -192,23 +232,35 @@ struct lpNorm_selector template struct lpNorm_selector { - static inline typename NumTraits::Scalar>::Real run(const MatrixBase& m) + typedef typename NumTraits::Scalar>::Real RealScalar; + EIGEN_DEVICE_FUNC + static inline RealScalar run(const MatrixBase& m) { + if(Derived::SizeAtCompileTime==0 || (Derived::SizeAtCompileTime==Dynamic && m.size()==0)) + return RealScalar(0); return m.cwiseAbs().maxCoeff(); } }; } // end namespace internal -/** \returns the \f$ \ell^p \f$ norm of *this, that is, returns the p-th root of the sum of the p-th powers of the absolute values - * of the coefficients of *this. If \a p is the special value \a Eigen::Infinity, this function returns the \f$ \ell^\infty \f$ - * norm, that is the maximum of the absolute values of the coefficients of *this. +/** \returns the \b coefficient-wise \f$ \ell^p \f$ norm of \c *this, that is, returns the p-th root of the sum of the p-th powers of the absolute values + * of the coefficients of \c *this. If \a p is the special value \a Eigen::Infinity, this function returns the \f$ \ell^\infty \f$ + * norm, that is the maximum of the absolute values of the coefficients of \c *this. + * + * In all cases, if \c *this is empty, then the value 0 is returned. + * + * \note For matrices, this function does not compute the operator-norm. That is, if \c *this is a matrix, then its coefficients are interpreted as a 1D vector. Nonetheless, you can easily compute the 1-norm and \f$\infty\f$-norm matrix operator norms using \link TutorialReductionsVisitorsBroadcastingReductionsNorm partial reductions \endlink. * * \sa norm() */ template template -inline typename NumTraits::Scalar>::Real +#ifndef EIGEN_PARSED_BY_DOXYGEN +EIGEN_DEVICE_FUNC inline typename NumTraits::Scalar>::Real +#else +EIGEN_DEVICE_FUNC MatrixBase::RealScalar +#endif MatrixBase::lpNorm() const { return internal::lpNorm_selector::run(*this); @@ -227,8 +279,8 @@ template bool MatrixBase::isOrthogonal (const MatrixBase& other, const RealScalar& prec) const { - typename internal::nested::type nested(derived()); - typename internal::nested::type otherNested(other.derived()); + typename internal::nested_eval::type nested(derived()); + typename internal::nested_eval::type otherNested(other.derived()); return numext::abs2(nested.dot(otherNested)) <= prec * prec * nested.squaredNorm() * otherNested.squaredNorm(); } @@ -246,13 +298,13 @@ bool MatrixBase::isOrthogonal template bool MatrixBase::isUnitary(const RealScalar& prec) const { - typename Derived::Nested nested(derived()); + typename internal::nested_eval::type self(derived()); for(Index i = 0; i < cols(); ++i) { - if(!internal::isApprox(nested.col(i).squaredNorm(), static_cast(1), prec)) + if(!internal::isApprox(self.col(i).squaredNorm(), static_cast(1), prec)) return false; for(Index j = 0; j < i; ++j) - if(!internal::isMuchSmallerThan(nested.col(i).dot(nested.col(j)), static_cast(1), prec)) + if(!internal::isMuchSmallerThan(self.col(i).dot(self.col(j)), static_cast(1), prec)) return false; } return true; diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/EigenBase.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/EigenBase.h index fadb4585..ccc122cf 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/EigenBase.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/EigenBase.h @@ -13,7 +13,9 @@ namespace Eigen { -/** Common base class for all classes T such that MatrixBase has an operator=(T) and a constructor MatrixBase(T). +/** \class EigenBase + * + * Common base class for all classes T such that MatrixBase has an operator=(T) and a constructor MatrixBase(T). * * In other words, an EigenBase object is an object that can be copied into a MatrixBase. * @@ -21,39 +23,57 @@ namespace Eigen { * * Notice that this class is trivial, it is only used to disambiguate overloaded functions. * - * \sa \ref TopicClassHierarchy + * \sa \blank \ref TopicClassHierarchy */ template struct EigenBase { // typedef typename internal::plain_matrix_type::type PlainObject; + + /** \brief The interface type of indices + * \details To change this, \c \#define the preprocessor symbol \c EIGEN_DEFAULT_DENSE_INDEX_TYPE. + * \deprecated Since Eigen 3.3, its usage is deprecated. Use Eigen::Index instead. + * \sa StorageIndex, \ref TopicPreprocessorDirectives. + */ + typedef Eigen::Index Index; + // FIXME is it needed? typedef typename internal::traits::StorageKind StorageKind; - typedef typename internal::traits::Index Index; /** \returns a reference to the derived object */ + EIGEN_DEVICE_FUNC Derived& derived() { return *static_cast(this); } /** \returns a const reference to the derived object */ + EIGEN_DEVICE_FUNC const Derived& derived() const { return *static_cast(this); } + EIGEN_DEVICE_FUNC inline Derived& const_cast_derived() const { return *static_cast(const_cast(this)); } + EIGEN_DEVICE_FUNC inline const Derived& const_derived() const { return *static_cast(this); } /** \returns the number of rows. \sa cols(), RowsAtCompileTime */ + EIGEN_DEVICE_FUNC inline Index rows() const { return derived().rows(); } /** \returns the number of columns. \sa rows(), ColsAtCompileTime*/ + EIGEN_DEVICE_FUNC inline Index cols() const { return derived().cols(); } /** \returns the number of coefficients, which is rows()*cols(). * \sa rows(), cols(), SizeAtCompileTime. */ + EIGEN_DEVICE_FUNC inline Index size() const { return rows() * cols(); } /** \internal Don't use it, but do the equivalent: \code dst = *this; \endcode */ - template inline void evalTo(Dest& dst) const + template + EIGEN_DEVICE_FUNC + inline void evalTo(Dest& dst) const { derived().evalTo(dst); } /** \internal Don't use it, but do the equivalent: \code dst += *this; \endcode */ - template inline void addTo(Dest& dst) const + template + EIGEN_DEVICE_FUNC + inline void addTo(Dest& dst) const { // This is the default implementation, // derived class can reimplement it in a more optimized way. @@ -63,7 +83,9 @@ template struct EigenBase } /** \internal Don't use it, but do the equivalent: \code dst -= *this; \endcode */ - template inline void subTo(Dest& dst) const + template + EIGEN_DEVICE_FUNC + inline void subTo(Dest& dst) const { // This is the default implementation, // derived class can reimplement it in a more optimized way. @@ -73,7 +95,8 @@ template struct EigenBase } /** \internal Don't use it, but do the equivalent: \code dst.applyOnTheRight(*this); \endcode */ - template inline void applyThisOnTheRight(Dest& dst) const + template + EIGEN_DEVICE_FUNC inline void applyThisOnTheRight(Dest& dst) const { // This is the default implementation, // derived class can reimplement it in a more optimized way. @@ -81,7 +104,8 @@ template struct EigenBase } /** \internal Don't use it, but do the equivalent: \code dst.applyOnTheLeft(*this); \endcode */ - template inline void applyThisOnTheLeft(Dest& dst) const + template + EIGEN_DEVICE_FUNC inline void applyThisOnTheLeft(Dest& dst) const { // This is the default implementation, // derived class can reimplement it in a more optimized way. @@ -104,25 +128,28 @@ template struct EigenBase */ template template +EIGEN_DEVICE_FUNC Derived& DenseBase::operator=(const EigenBase &other) { - other.derived().evalTo(derived()); + call_assignment(derived(), other.derived()); return derived(); } template template +EIGEN_DEVICE_FUNC Derived& DenseBase::operator+=(const EigenBase &other) { - other.derived().addTo(derived()); + call_assignment(derived(), other.derived(), internal::add_assign_op()); return derived(); } template template +EIGEN_DEVICE_FUNC Derived& DenseBase::operator-=(const EigenBase &other) { - other.derived().subTo(derived()); + call_assignment(derived(), other.derived(), internal::sub_assign_op()); return derived(); } diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/Flagged.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/Flagged.h deleted file mode 100644 index 1f2955fc..00000000 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/Flagged.h +++ /dev/null @@ -1,140 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#ifndef EIGEN_FLAGGED_H -#define EIGEN_FLAGGED_H - -namespace Eigen { - -/** \class Flagged - * \ingroup Core_Module - * - * \brief Expression with modified flags - * - * \param ExpressionType the type of the object of which we are modifying the flags - * \param Added the flags added to the expression - * \param Removed the flags removed from the expression (has priority over Added). - * - * This class represents an expression whose flags have been modified. - * It is the return type of MatrixBase::flagged() - * and most of the time this is the only way it is used. - * - * \sa MatrixBase::flagged() - */ - -namespace internal { -template -struct traits > : traits -{ - enum { Flags = (ExpressionType::Flags | Added) & ~Removed }; -}; -} - -template class Flagged - : public MatrixBase > -{ - public: - - typedef MatrixBase Base; - - EIGEN_DENSE_PUBLIC_INTERFACE(Flagged) - typedef typename internal::conditional::ret, - ExpressionType, const ExpressionType&>::type ExpressionTypeNested; - typedef typename ExpressionType::InnerIterator InnerIterator; - - inline Flagged(const ExpressionType& matrix) : m_matrix(matrix) {} - - inline Index rows() const { return m_matrix.rows(); } - inline Index cols() const { return m_matrix.cols(); } - inline Index outerStride() const { return m_matrix.outerStride(); } - inline Index innerStride() const { return m_matrix.innerStride(); } - - inline CoeffReturnType coeff(Index row, Index col) const - { - return m_matrix.coeff(row, col); - } - - inline CoeffReturnType coeff(Index index) const - { - return m_matrix.coeff(index); - } - - inline const Scalar& coeffRef(Index row, Index col) const - { - return m_matrix.const_cast_derived().coeffRef(row, col); - } - - inline const Scalar& coeffRef(Index index) const - { - return m_matrix.const_cast_derived().coeffRef(index); - } - - inline Scalar& coeffRef(Index row, Index col) - { - return m_matrix.const_cast_derived().coeffRef(row, col); - } - - inline Scalar& coeffRef(Index index) - { - return m_matrix.const_cast_derived().coeffRef(index); - } - - template - inline const PacketScalar packet(Index row, Index col) const - { - return m_matrix.template packet(row, col); - } - - template - inline void writePacket(Index row, Index col, const PacketScalar& x) - { - m_matrix.const_cast_derived().template writePacket(row, col, x); - } - - template - inline const PacketScalar packet(Index index) const - { - return m_matrix.template packet(index); - } - - template - inline void writePacket(Index index, const PacketScalar& x) - { - m_matrix.const_cast_derived().template writePacket(index, x); - } - - const ExpressionType& _expression() const { return m_matrix; } - - template - typename ExpressionType::PlainObject solveTriangular(const MatrixBase& other) const; - - template - void solveTriangularInPlace(const MatrixBase& other) const; - - protected: - ExpressionTypeNested m_matrix; -}; - -/** \returns an expression of *this with added and removed flags - * - * This is mostly for internal use. - * - * \sa class Flagged - */ -template -template -inline const Flagged -DenseBase::flagged() const -{ - return derived(); -} - -} // end namespace Eigen - -#endif // EIGEN_FLAGGED_H diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/ForceAlignedAccess.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/ForceAlignedAccess.h index 807c7a29..7b08b45e 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/ForceAlignedAccess.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/ForceAlignedAccess.h @@ -39,29 +39,29 @@ template class ForceAlignedAccess typedef typename internal::dense_xpr_base::type Base; EIGEN_DENSE_PUBLIC_INTERFACE(ForceAlignedAccess) - inline ForceAlignedAccess(const ExpressionType& matrix) : m_expression(matrix) {} + EIGEN_DEVICE_FUNC explicit inline ForceAlignedAccess(const ExpressionType& matrix) : m_expression(matrix) {} - inline Index rows() const { return m_expression.rows(); } - inline Index cols() const { return m_expression.cols(); } - inline Index outerStride() const { return m_expression.outerStride(); } - inline Index innerStride() const { return m_expression.innerStride(); } + EIGEN_DEVICE_FUNC inline Index rows() const { return m_expression.rows(); } + EIGEN_DEVICE_FUNC inline Index cols() const { return m_expression.cols(); } + EIGEN_DEVICE_FUNC inline Index outerStride() const { return m_expression.outerStride(); } + EIGEN_DEVICE_FUNC inline Index innerStride() const { return m_expression.innerStride(); } - inline const CoeffReturnType coeff(Index row, Index col) const + EIGEN_DEVICE_FUNC inline const CoeffReturnType coeff(Index row, Index col) const { return m_expression.coeff(row, col); } - inline Scalar& coeffRef(Index row, Index col) + EIGEN_DEVICE_FUNC inline Scalar& coeffRef(Index row, Index col) { return m_expression.const_cast_derived().coeffRef(row, col); } - inline const CoeffReturnType coeff(Index index) const + EIGEN_DEVICE_FUNC inline const CoeffReturnType coeff(Index index) const { return m_expression.coeff(index); } - inline Scalar& coeffRef(Index index) + EIGEN_DEVICE_FUNC inline Scalar& coeffRef(Index index) { return m_expression.const_cast_derived().coeffRef(index); } @@ -90,7 +90,7 @@ template class ForceAlignedAccess m_expression.const_cast_derived().template writePacket(index, x); } - operator const ExpressionType&() const { return m_expression; } + EIGEN_DEVICE_FUNC operator const ExpressionType&() const { return m_expression; } protected: const ExpressionType& m_expression; @@ -127,7 +127,7 @@ template inline typename internal::add_const_on_value_type,Derived&>::type>::type MatrixBase::forceAlignedAccessIf() const { - return derived(); + return derived(); // FIXME This should not work but apparently is never used } /** \returns an expression of *this with forced aligned access if \a Enable is true. @@ -138,7 +138,7 @@ template inline typename internal::conditional,Derived&>::type MatrixBase::forceAlignedAccessIf() { - return derived(); + return derived(); // FIXME This should not work but apparently is never used } } // end namespace Eigen diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/Functors.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/Functors.h deleted file mode 100644 index b08b967f..00000000 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/Functors.h +++ /dev/null @@ -1,985 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008-2010 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#ifndef EIGEN_FUNCTORS_H -#define EIGEN_FUNCTORS_H - -namespace Eigen { - -namespace internal { - -// associative functors: - -/** \internal - * \brief Template functor to compute the sum of two scalars - * - * \sa class CwiseBinaryOp, MatrixBase::operator+, class VectorwiseOp, MatrixBase::sum() - */ -template struct scalar_sum_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_sum_op) - EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a, const Scalar& b) const { return a + b; } - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const - { return internal::padd(a,b); } - template - EIGEN_STRONG_INLINE const Scalar predux(const Packet& a) const - { return internal::predux(a); } -}; -template -struct functor_traits > { - enum { - Cost = NumTraits::AddCost, - PacketAccess = packet_traits::HasAdd - }; -}; - -/** \internal - * \brief Template functor to compute the product of two scalars - * - * \sa class CwiseBinaryOp, Cwise::operator*(), class VectorwiseOp, MatrixBase::redux() - */ -template struct scalar_product_op { - enum { - // TODO vectorize mixed product - Vectorizable = is_same::value && packet_traits::HasMul && packet_traits::HasMul - }; - typedef typename scalar_product_traits::ReturnType result_type; - EIGEN_EMPTY_STRUCT_CTOR(scalar_product_op) - EIGEN_STRONG_INLINE const result_type operator() (const LhsScalar& a, const RhsScalar& b) const { return a * b; } - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const - { return internal::pmul(a,b); } - template - EIGEN_STRONG_INLINE const result_type predux(const Packet& a) const - { return internal::predux_mul(a); } -}; -template -struct functor_traits > { - enum { - Cost = (NumTraits::MulCost + NumTraits::MulCost)/2, // rough estimate! - PacketAccess = scalar_product_op::Vectorizable - }; -}; - -/** \internal - * \brief Template functor to compute the conjugate product of two scalars - * - * This is a short cut for conj(x) * y which is needed for optimization purpose; in Eigen2 support mode, this becomes x * conj(y) - */ -template struct scalar_conj_product_op { - - enum { - Conj = NumTraits::IsComplex - }; - - typedef typename scalar_product_traits::ReturnType result_type; - - EIGEN_EMPTY_STRUCT_CTOR(scalar_conj_product_op) - EIGEN_STRONG_INLINE const result_type operator() (const LhsScalar& a, const RhsScalar& b) const - { return conj_helper().pmul(a,b); } - - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const - { return conj_helper().pmul(a,b); } -}; -template -struct functor_traits > { - enum { - Cost = NumTraits::MulCost, - PacketAccess = internal::is_same::value && packet_traits::HasMul - }; -}; - -/** \internal - * \brief Template functor to compute the min of two scalars - * - * \sa class CwiseBinaryOp, MatrixBase::cwiseMin, class VectorwiseOp, MatrixBase::minCoeff() - */ -template struct scalar_min_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_min_op) - EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a, const Scalar& b) const { using std::min; return (min)(a, b); } - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const - { return internal::pmin(a,b); } - template - EIGEN_STRONG_INLINE const Scalar predux(const Packet& a) const - { return internal::predux_min(a); } -}; -template -struct functor_traits > { - enum { - Cost = NumTraits::AddCost, - PacketAccess = packet_traits::HasMin - }; -}; - -/** \internal - * \brief Template functor to compute the max of two scalars - * - * \sa class CwiseBinaryOp, MatrixBase::cwiseMax, class VectorwiseOp, MatrixBase::maxCoeff() - */ -template struct scalar_max_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_max_op) - EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a, const Scalar& b) const { using std::max; return (max)(a, b); } - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const - { return internal::pmax(a,b); } - template - EIGEN_STRONG_INLINE const Scalar predux(const Packet& a) const - { return internal::predux_max(a); } -}; -template -struct functor_traits > { - enum { - Cost = NumTraits::AddCost, - PacketAccess = packet_traits::HasMax - }; -}; - -/** \internal - * \brief Template functor to compute the hypot of two scalars - * - * \sa MatrixBase::stableNorm(), class Redux - */ -template struct scalar_hypot_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_hypot_op) -// typedef typename NumTraits::Real result_type; - EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& _x, const Scalar& _y) const - { - using std::max; - using std::min; - using std::sqrt; - Scalar p = (max)(_x, _y); - Scalar q = (min)(_x, _y); - Scalar qp = q/p; - return p * sqrt(Scalar(1) + qp*qp); - } -}; -template -struct functor_traits > { - enum { Cost = 5 * NumTraits::MulCost, PacketAccess=0 }; -}; - -/** \internal - * \brief Template functor to compute the pow of two scalars - */ -template struct scalar_binary_pow_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_binary_pow_op) - inline Scalar operator() (const Scalar& a, const OtherScalar& b) const { return numext::pow(a, b); } -}; -template -struct functor_traits > { - enum { Cost = 5 * NumTraits::MulCost, PacketAccess = false }; -}; - -// other binary functors: - -/** \internal - * \brief Template functor to compute the difference of two scalars - * - * \sa class CwiseBinaryOp, MatrixBase::operator- - */ -template struct scalar_difference_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_difference_op) - EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a, const Scalar& b) const { return a - b; } - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const - { return internal::psub(a,b); } -}; -template -struct functor_traits > { - enum { - Cost = NumTraits::AddCost, - PacketAccess = packet_traits::HasSub - }; -}; - -/** \internal - * \brief Template functor to compute the quotient of two scalars - * - * \sa class CwiseBinaryOp, Cwise::operator/() - */ -template struct scalar_quotient_op { - enum { - // TODO vectorize mixed product - Vectorizable = is_same::value && packet_traits::HasDiv && packet_traits::HasDiv - }; - typedef typename scalar_product_traits::ReturnType result_type; - EIGEN_EMPTY_STRUCT_CTOR(scalar_quotient_op) - EIGEN_STRONG_INLINE const result_type operator() (const LhsScalar& a, const RhsScalar& b) const { return a / b; } - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const - { return internal::pdiv(a,b); } -}; -template -struct functor_traits > { - enum { - Cost = (NumTraits::MulCost + NumTraits::MulCost), // rough estimate! - PacketAccess = scalar_quotient_op::Vectorizable - }; -}; - - - -/** \internal - * \brief Template functor to compute the and of two booleans - * - * \sa class CwiseBinaryOp, ArrayBase::operator&& - */ -struct scalar_boolean_and_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_boolean_and_op) - EIGEN_STRONG_INLINE bool operator() (const bool& a, const bool& b) const { return a && b; } -}; -template<> struct functor_traits { - enum { - Cost = NumTraits::AddCost, - PacketAccess = false - }; -}; - -/** \internal - * \brief Template functor to compute the or of two booleans - * - * \sa class CwiseBinaryOp, ArrayBase::operator|| - */ -struct scalar_boolean_or_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_boolean_or_op) - EIGEN_STRONG_INLINE bool operator() (const bool& a, const bool& b) const { return a || b; } -}; -template<> struct functor_traits { - enum { - Cost = NumTraits::AddCost, - PacketAccess = false - }; -}; - -// unary functors: - -/** \internal - * \brief Template functor to compute the opposite of a scalar - * - * \sa class CwiseUnaryOp, MatrixBase::operator- - */ -template struct scalar_opposite_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_opposite_op) - EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a) const { return -a; } - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a) const - { return internal::pnegate(a); } -}; -template -struct functor_traits > -{ enum { - Cost = NumTraits::AddCost, - PacketAccess = packet_traits::HasNegate }; -}; - -/** \internal - * \brief Template functor to compute the absolute value of a scalar - * - * \sa class CwiseUnaryOp, Cwise::abs - */ -template struct scalar_abs_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_abs_op) - typedef typename NumTraits::Real result_type; - EIGEN_STRONG_INLINE const result_type operator() (const Scalar& a) const { using std::abs; return abs(a); } - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a) const - { return internal::pabs(a); } -}; -template -struct functor_traits > -{ - enum { - Cost = NumTraits::AddCost, - PacketAccess = packet_traits::HasAbs - }; -}; - -/** \internal - * \brief Template functor to compute the squared absolute value of a scalar - * - * \sa class CwiseUnaryOp, Cwise::abs2 - */ -template struct scalar_abs2_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_abs2_op) - typedef typename NumTraits::Real result_type; - EIGEN_STRONG_INLINE const result_type operator() (const Scalar& a) const { return numext::abs2(a); } - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a) const - { return internal::pmul(a,a); } -}; -template -struct functor_traits > -{ enum { Cost = NumTraits::MulCost, PacketAccess = packet_traits::HasAbs2 }; }; - -/** \internal - * \brief Template functor to compute the conjugate of a complex value - * - * \sa class CwiseUnaryOp, MatrixBase::conjugate() - */ -template struct scalar_conjugate_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_conjugate_op) - EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a) const { using numext::conj; return conj(a); } - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a) const { return internal::pconj(a); } -}; -template -struct functor_traits > -{ - enum { - Cost = NumTraits::IsComplex ? NumTraits::AddCost : 0, - PacketAccess = packet_traits::HasConj - }; -}; - -/** \internal - * \brief Template functor to cast a scalar to another type - * - * \sa class CwiseUnaryOp, MatrixBase::cast() - */ -template -struct scalar_cast_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_cast_op) - typedef NewType result_type; - EIGEN_STRONG_INLINE const NewType operator() (const Scalar& a) const { return cast(a); } -}; -template -struct functor_traits > -{ enum { Cost = is_same::value ? 0 : NumTraits::AddCost, PacketAccess = false }; }; - -/** \internal - * \brief Template functor to extract the real part of a complex - * - * \sa class CwiseUnaryOp, MatrixBase::real() - */ -template -struct scalar_real_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_real_op) - typedef typename NumTraits::Real result_type; - EIGEN_STRONG_INLINE result_type operator() (const Scalar& a) const { return numext::real(a); } -}; -template -struct functor_traits > -{ enum { Cost = 0, PacketAccess = false }; }; - -/** \internal - * \brief Template functor to extract the imaginary part of a complex - * - * \sa class CwiseUnaryOp, MatrixBase::imag() - */ -template -struct scalar_imag_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_imag_op) - typedef typename NumTraits::Real result_type; - EIGEN_STRONG_INLINE result_type operator() (const Scalar& a) const { return numext::imag(a); } -}; -template -struct functor_traits > -{ enum { Cost = 0, PacketAccess = false }; }; - -/** \internal - * \brief Template functor to extract the real part of a complex as a reference - * - * \sa class CwiseUnaryOp, MatrixBase::real() - */ -template -struct scalar_real_ref_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_real_ref_op) - typedef typename NumTraits::Real result_type; - EIGEN_STRONG_INLINE result_type& operator() (const Scalar& a) const { return numext::real_ref(*const_cast(&a)); } -}; -template -struct functor_traits > -{ enum { Cost = 0, PacketAccess = false }; }; - -/** \internal - * \brief Template functor to extract the imaginary part of a complex as a reference - * - * \sa class CwiseUnaryOp, MatrixBase::imag() - */ -template -struct scalar_imag_ref_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_imag_ref_op) - typedef typename NumTraits::Real result_type; - EIGEN_STRONG_INLINE result_type& operator() (const Scalar& a) const { return numext::imag_ref(*const_cast(&a)); } -}; -template -struct functor_traits > -{ enum { Cost = 0, PacketAccess = false }; }; - -/** \internal - * - * \brief Template functor to compute the exponential of a scalar - * - * \sa class CwiseUnaryOp, Cwise::exp() - */ -template struct scalar_exp_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_exp_op) - inline const Scalar operator() (const Scalar& a) const { using std::exp; return exp(a); } - typedef typename packet_traits::type Packet; - inline Packet packetOp(const Packet& a) const { return internal::pexp(a); } -}; -template -struct functor_traits > -{ enum { Cost = 5 * NumTraits::MulCost, PacketAccess = packet_traits::HasExp }; }; - -/** \internal - * - * \brief Template functor to compute the logarithm of a scalar - * - * \sa class CwiseUnaryOp, Cwise::log() - */ -template struct scalar_log_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_log_op) - inline const Scalar operator() (const Scalar& a) const { using std::log; return log(a); } - typedef typename packet_traits::type Packet; - inline Packet packetOp(const Packet& a) const { return internal::plog(a); } -}; -template -struct functor_traits > -{ enum { Cost = 5 * NumTraits::MulCost, PacketAccess = packet_traits::HasLog }; }; - -/** \internal - * \brief Template functor to multiply a scalar by a fixed other one - * - * \sa class CwiseUnaryOp, MatrixBase::operator*, MatrixBase::operator/ - */ -/* NOTE why doing the pset1() in packetOp *is* an optimization ? - * indeed it seems better to declare m_other as a Packet and do the pset1() once - * in the constructor. However, in practice: - * - GCC does not like m_other as a Packet and generate a load every time it needs it - * - on the other hand GCC is able to moves the pset1() outside the loop :) - * - simpler code ;) - * (ICC and gcc 4.4 seems to perform well in both cases, the issue is visible with y = a*x + b*y) - */ -template -struct scalar_multiple_op { - typedef typename packet_traits::type Packet; - // FIXME default copy constructors seems bugged with std::complex<> - EIGEN_STRONG_INLINE scalar_multiple_op(const scalar_multiple_op& other) : m_other(other.m_other) { } - EIGEN_STRONG_INLINE scalar_multiple_op(const Scalar& other) : m_other(other) { } - EIGEN_STRONG_INLINE Scalar operator() (const Scalar& a) const { return a * m_other; } - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a) const - { return internal::pmul(a, pset1(m_other)); } - typename add_const_on_value_type::Nested>::type m_other; -}; -template -struct functor_traits > -{ enum { Cost = NumTraits::MulCost, PacketAccess = packet_traits::HasMul }; }; - -template -struct scalar_multiple2_op { - typedef typename scalar_product_traits::ReturnType result_type; - EIGEN_STRONG_INLINE scalar_multiple2_op(const scalar_multiple2_op& other) : m_other(other.m_other) { } - EIGEN_STRONG_INLINE scalar_multiple2_op(const Scalar2& other) : m_other(other) { } - EIGEN_STRONG_INLINE result_type operator() (const Scalar1& a) const { return a * m_other; } - typename add_const_on_value_type::Nested>::type m_other; -}; -template -struct functor_traits > -{ enum { Cost = NumTraits::MulCost, PacketAccess = false }; }; - -/** \internal - * \brief Template functor to divide a scalar by a fixed other one - * - * This functor is used to implement the quotient of a matrix by - * a scalar where the scalar type is not necessarily a floating point type. - * - * \sa class CwiseUnaryOp, MatrixBase::operator/ - */ -template -struct scalar_quotient1_op { - typedef typename packet_traits::type Packet; - // FIXME default copy constructors seems bugged with std::complex<> - EIGEN_STRONG_INLINE scalar_quotient1_op(const scalar_quotient1_op& other) : m_other(other.m_other) { } - EIGEN_STRONG_INLINE scalar_quotient1_op(const Scalar& other) : m_other(other) {} - EIGEN_STRONG_INLINE Scalar operator() (const Scalar& a) const { return a / m_other; } - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a) const - { return internal::pdiv(a, pset1(m_other)); } - typename add_const_on_value_type::Nested>::type m_other; -}; -template -struct functor_traits > -{ enum { Cost = 2 * NumTraits::MulCost, PacketAccess = packet_traits::HasDiv }; }; - -// nullary functors - -template -struct scalar_constant_op { - typedef typename packet_traits::type Packet; - EIGEN_STRONG_INLINE scalar_constant_op(const scalar_constant_op& other) : m_other(other.m_other) { } - EIGEN_STRONG_INLINE scalar_constant_op(const Scalar& other) : m_other(other) { } - template - EIGEN_STRONG_INLINE const Scalar operator() (Index, Index = 0) const { return m_other; } - template - EIGEN_STRONG_INLINE const Packet packetOp(Index, Index = 0) const { return internal::pset1(m_other); } - const Scalar m_other; -}; -template -struct functor_traits > -// FIXME replace this packet test by a safe one -{ enum { Cost = 1, PacketAccess = packet_traits::Vectorizable, IsRepeatable = true }; }; - -template struct scalar_identity_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_identity_op) - template - EIGEN_STRONG_INLINE const Scalar operator() (Index row, Index col) const { return row==col ? Scalar(1) : Scalar(0); } -}; -template -struct functor_traits > -{ enum { Cost = NumTraits::AddCost, PacketAccess = false, IsRepeatable = true }; }; - -template struct linspaced_op_impl; - -// linear access for packet ops: -// 1) initialization -// base = [low, ..., low] + ([step, ..., step] * [-size, ..., 0]) -// 2) each step (where size is 1 for coeff access or PacketSize for packet access) -// base += [size*step, ..., size*step] -// -// TODO: Perhaps it's better to initialize lazily (so not in the constructor but in packetOp) -// in order to avoid the padd() in operator() ? -template -struct linspaced_op_impl -{ - typedef typename packet_traits::type Packet; - - linspaced_op_impl(const Scalar& low, const Scalar& step) : - m_low(low), m_step(step), - m_packetStep(pset1(packet_traits::size*step)), - m_base(padd(pset1(low), pmul(pset1(step),plset(-packet_traits::size)))) {} - - template - EIGEN_STRONG_INLINE const Scalar operator() (Index i) const - { - m_base = padd(m_base, pset1(m_step)); - return m_low+Scalar(i)*m_step; - } - - template - EIGEN_STRONG_INLINE const Packet packetOp(Index) const { return m_base = padd(m_base,m_packetStep); } - - const Scalar m_low; - const Scalar m_step; - const Packet m_packetStep; - mutable Packet m_base; -}; - -// random access for packet ops: -// 1) each step -// [low, ..., low] + ( [step, ..., step] * ( [i, ..., i] + [0, ..., size] ) ) -template -struct linspaced_op_impl -{ - typedef typename packet_traits::type Packet; - - linspaced_op_impl(const Scalar& low, const Scalar& step) : - m_low(low), m_step(step), - m_lowPacket(pset1(m_low)), m_stepPacket(pset1(m_step)), m_interPacket(plset(0)) {} - - template - EIGEN_STRONG_INLINE const Scalar operator() (Index i) const { return m_low+i*m_step; } - - template - EIGEN_STRONG_INLINE const Packet packetOp(Index i) const - { return internal::padd(m_lowPacket, pmul(m_stepPacket, padd(pset1(Scalar(i)),m_interPacket))); } - - const Scalar m_low; - const Scalar m_step; - const Packet m_lowPacket; - const Packet m_stepPacket; - const Packet m_interPacket; -}; - -// ----- Linspace functor ---------------------------------------------------------------- - -// Forward declaration (we default to random access which does not really give -// us a speed gain when using packet access but it allows to use the functor in -// nested expressions). -template struct linspaced_op; -template struct functor_traits< linspaced_op > -{ enum { Cost = 1, PacketAccess = packet_traits::HasSetLinear, IsRepeatable = true }; }; -template struct linspaced_op -{ - typedef typename packet_traits::type Packet; - linspaced_op(const Scalar& low, const Scalar& high, DenseIndex num_steps) : impl((num_steps==1 ? high : low), (num_steps==1 ? Scalar() : (high-low)/Scalar(num_steps-1))) {} - - template - EIGEN_STRONG_INLINE const Scalar operator() (Index i) const { return impl(i); } - - // We need this function when assigning e.g. a RowVectorXd to a MatrixXd since - // there row==0 and col is used for the actual iteration. - template - EIGEN_STRONG_INLINE const Scalar operator() (Index row, Index col) const - { - eigen_assert(col==0 || row==0); - return impl(col + row); - } - - template - EIGEN_STRONG_INLINE const Packet packetOp(Index i) const { return impl.packetOp(i); } - - // We need this function when assigning e.g. a RowVectorXd to a MatrixXd since - // there row==0 and col is used for the actual iteration. - template - EIGEN_STRONG_INLINE const Packet packetOp(Index row, Index col) const - { - eigen_assert(col==0 || row==0); - return impl.packetOp(col + row); - } - - // This proxy object handles the actual required temporaries, the different - // implementations (random vs. sequential access) as well as the - // correct piping to size 2/4 packet operations. - const linspaced_op_impl impl; -}; - -// all functors allow linear access, except scalar_identity_op. So we fix here a quick meta -// to indicate whether a functor allows linear access, just always answering 'yes' except for -// scalar_identity_op. -// FIXME move this to functor_traits adding a functor_default -template struct functor_has_linear_access { enum { ret = 1 }; }; -template struct functor_has_linear_access > { enum { ret = 0 }; }; - -// In Eigen, any binary op (Product, CwiseBinaryOp) require the Lhs and Rhs to have the same scalar type, except for multiplication -// where the mixing of different types is handled by scalar_product_traits -// In particular, real * complex is allowed. -// FIXME move this to functor_traits adding a functor_default -template struct functor_is_product_like { enum { ret = 0 }; }; -template struct functor_is_product_like > { enum { ret = 1 }; }; -template struct functor_is_product_like > { enum { ret = 1 }; }; -template struct functor_is_product_like > { enum { ret = 1 }; }; - - -/** \internal - * \brief Template functor to add a scalar to a fixed other one - * \sa class CwiseUnaryOp, Array::operator+ - */ -/* If you wonder why doing the pset1() in packetOp() is an optimization check scalar_multiple_op */ -template -struct scalar_add_op { - typedef typename packet_traits::type Packet; - // FIXME default copy constructors seems bugged with std::complex<> - inline scalar_add_op(const scalar_add_op& other) : m_other(other.m_other) { } - inline scalar_add_op(const Scalar& other) : m_other(other) { } - inline Scalar operator() (const Scalar& a) const { return a + m_other; } - inline const Packet packetOp(const Packet& a) const - { return internal::padd(a, pset1(m_other)); } - const Scalar m_other; -}; -template -struct functor_traits > -{ enum { Cost = NumTraits::AddCost, PacketAccess = packet_traits::HasAdd }; }; - -/** \internal - * \brief Template functor to compute the square root of a scalar - * \sa class CwiseUnaryOp, Cwise::sqrt() - */ -template struct scalar_sqrt_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_sqrt_op) - inline const Scalar operator() (const Scalar& a) const { using std::sqrt; return sqrt(a); } - typedef typename packet_traits::type Packet; - inline Packet packetOp(const Packet& a) const { return internal::psqrt(a); } -}; -template -struct functor_traits > -{ enum { - Cost = 5 * NumTraits::MulCost, - PacketAccess = packet_traits::HasSqrt - }; -}; - -/** \internal - * \brief Template functor to compute the cosine of a scalar - * \sa class CwiseUnaryOp, ArrayBase::cos() - */ -template struct scalar_cos_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_cos_op) - inline Scalar operator() (const Scalar& a) const { using std::cos; return cos(a); } - typedef typename packet_traits::type Packet; - inline Packet packetOp(const Packet& a) const { return internal::pcos(a); } -}; -template -struct functor_traits > -{ - enum { - Cost = 5 * NumTraits::MulCost, - PacketAccess = packet_traits::HasCos - }; -}; - -/** \internal - * \brief Template functor to compute the sine of a scalar - * \sa class CwiseUnaryOp, ArrayBase::sin() - */ -template struct scalar_sin_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_sin_op) - inline const Scalar operator() (const Scalar& a) const { using std::sin; return sin(a); } - typedef typename packet_traits::type Packet; - inline Packet packetOp(const Packet& a) const { return internal::psin(a); } -}; -template -struct functor_traits > -{ - enum { - Cost = 5 * NumTraits::MulCost, - PacketAccess = packet_traits::HasSin - }; -}; - - -/** \internal - * \brief Template functor to compute the tan of a scalar - * \sa class CwiseUnaryOp, ArrayBase::tan() - */ -template struct scalar_tan_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_tan_op) - inline const Scalar operator() (const Scalar& a) const { using std::tan; return tan(a); } - typedef typename packet_traits::type Packet; - inline Packet packetOp(const Packet& a) const { return internal::ptan(a); } -}; -template -struct functor_traits > -{ - enum { - Cost = 5 * NumTraits::MulCost, - PacketAccess = packet_traits::HasTan - }; -}; - -/** \internal - * \brief Template functor to compute the arc cosine of a scalar - * \sa class CwiseUnaryOp, ArrayBase::acos() - */ -template struct scalar_acos_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_acos_op) - inline const Scalar operator() (const Scalar& a) const { using std::acos; return acos(a); } - typedef typename packet_traits::type Packet; - inline Packet packetOp(const Packet& a) const { return internal::pacos(a); } -}; -template -struct functor_traits > -{ - enum { - Cost = 5 * NumTraits::MulCost, - PacketAccess = packet_traits::HasACos - }; -}; - -/** \internal - * \brief Template functor to compute the arc sine of a scalar - * \sa class CwiseUnaryOp, ArrayBase::asin() - */ -template struct scalar_asin_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_asin_op) - inline const Scalar operator() (const Scalar& a) const { using std::asin; return asin(a); } - typedef typename packet_traits::type Packet; - inline Packet packetOp(const Packet& a) const { return internal::pasin(a); } -}; -template -struct functor_traits > -{ - enum { - Cost = 5 * NumTraits::MulCost, - PacketAccess = packet_traits::HasASin - }; -}; - -/** \internal - * \brief Template functor to raise a scalar to a power - * \sa class CwiseUnaryOp, Cwise::pow - */ -template -struct scalar_pow_op { - // FIXME default copy constructors seems bugged with std::complex<> - inline scalar_pow_op(const scalar_pow_op& other) : m_exponent(other.m_exponent) { } - inline scalar_pow_op(const Scalar& exponent) : m_exponent(exponent) {} - inline Scalar operator() (const Scalar& a) const { return numext::pow(a, m_exponent); } - const Scalar m_exponent; -}; -template -struct functor_traits > -{ enum { Cost = 5 * NumTraits::MulCost, PacketAccess = false }; }; - -/** \internal - * \brief Template functor to compute the quotient between a scalar and array entries. - * \sa class CwiseUnaryOp, Cwise::inverse() - */ -template -struct scalar_inverse_mult_op { - scalar_inverse_mult_op(const Scalar& other) : m_other(other) {} - inline Scalar operator() (const Scalar& a) const { return m_other / a; } - template - inline const Packet packetOp(const Packet& a) const - { return internal::pdiv(pset1(m_other),a); } - Scalar m_other; -}; - -/** \internal - * \brief Template functor to compute the inverse of a scalar - * \sa class CwiseUnaryOp, Cwise::inverse() - */ -template -struct scalar_inverse_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_inverse_op) - inline Scalar operator() (const Scalar& a) const { return Scalar(1)/a; } - template - inline const Packet packetOp(const Packet& a) const - { return internal::pdiv(pset1(Scalar(1)),a); } -}; -template -struct functor_traits > -{ enum { Cost = NumTraits::MulCost, PacketAccess = packet_traits::HasDiv }; }; - -/** \internal - * \brief Template functor to compute the square of a scalar - * \sa class CwiseUnaryOp, Cwise::square() - */ -template -struct scalar_square_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_square_op) - inline Scalar operator() (const Scalar& a) const { return a*a; } - template - inline const Packet packetOp(const Packet& a) const - { return internal::pmul(a,a); } -}; -template -struct functor_traits > -{ enum { Cost = NumTraits::MulCost, PacketAccess = packet_traits::HasMul }; }; - -/** \internal - * \brief Template functor to compute the cube of a scalar - * \sa class CwiseUnaryOp, Cwise::cube() - */ -template -struct scalar_cube_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_cube_op) - inline Scalar operator() (const Scalar& a) const { return a*a*a; } - template - inline const Packet packetOp(const Packet& a) const - { return internal::pmul(a,pmul(a,a)); } -}; -template -struct functor_traits > -{ enum { Cost = 2*NumTraits::MulCost, PacketAccess = packet_traits::HasMul }; }; - -// default functor traits for STL functors: - -template -struct functor_traits > -{ enum { Cost = NumTraits::MulCost, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = NumTraits::MulCost, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = NumTraits::AddCost, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = NumTraits::AddCost, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = NumTraits::AddCost, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = functor_traits::Cost, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = functor_traits::Cost, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1 + functor_traits::Cost, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1 + functor_traits::Cost, PacketAccess = false }; }; - -#ifdef EIGEN_STDEXT_SUPPORT - -template -struct functor_traits > -{ enum { Cost = 0, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 0, PacketAccess = false }; }; - -template -struct functor_traits > > -{ enum { Cost = 0, PacketAccess = false }; }; - -template -struct functor_traits > > -{ enum { Cost = 0, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = functor_traits::Cost + functor_traits::Cost, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = functor_traits::Cost + functor_traits::Cost + functor_traits::Cost, PacketAccess = false }; }; - -#endif // EIGEN_STDEXT_SUPPORT - -// allow to add new functors and specializations of functor_traits from outside Eigen. -// this macro is really needed because functor_traits must be specialized after it is declared but before it is used... -#ifdef EIGEN_FUNCTORS_PLUGIN -#include EIGEN_FUNCTORS_PLUGIN -#endif - -} // end namespace internal - -} // end namespace Eigen - -#endif // EIGEN_FUNCTORS_H diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/Fuzzy.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/Fuzzy.h index fe63bd29..43aa49b2 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/Fuzzy.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/Fuzzy.h @@ -19,18 +19,19 @@ namespace internal template::IsInteger> struct isApprox_selector { + EIGEN_DEVICE_FUNC static bool run(const Derived& x, const OtherDerived& y, const typename Derived::RealScalar& prec) { - using std::min; - typename internal::nested::type nested(x); - typename internal::nested::type otherNested(y); - return (nested - otherNested).cwiseAbs2().sum() <= prec * prec * (min)(nested.cwiseAbs2().sum(), otherNested.cwiseAbs2().sum()); + typename internal::nested_eval::type nested(x); + typename internal::nested_eval::type otherNested(y); + return (nested - otherNested).cwiseAbs2().sum() <= prec * prec * numext::mini(nested.cwiseAbs2().sum(), otherNested.cwiseAbs2().sum()); } }; template struct isApprox_selector { + EIGEN_DEVICE_FUNC static bool run(const Derived& x, const OtherDerived& y, const typename Derived::RealScalar&) { return x.matrix() == y.matrix(); @@ -40,6 +41,7 @@ struct isApprox_selector template::IsInteger> struct isMuchSmallerThan_object_selector { + EIGEN_DEVICE_FUNC static bool run(const Derived& x, const OtherDerived& y, const typename Derived::RealScalar& prec) { return x.cwiseAbs2().sum() <= numext::abs2(prec) * y.cwiseAbs2().sum(); @@ -49,6 +51,7 @@ struct isMuchSmallerThan_object_selector template struct isMuchSmallerThan_object_selector { + EIGEN_DEVICE_FUNC static bool run(const Derived& x, const OtherDerived&, const typename Derived::RealScalar&) { return x.matrix() == Derived::Zero(x.rows(), x.cols()).matrix(); @@ -58,6 +61,7 @@ struct isMuchSmallerThan_object_selector template::IsInteger> struct isMuchSmallerThan_scalar_selector { + EIGEN_DEVICE_FUNC static bool run(const Derived& x, const typename Derived::RealScalar& y, const typename Derived::RealScalar& prec) { return x.cwiseAbs2().sum() <= numext::abs2(prec * y); @@ -67,6 +71,7 @@ struct isMuchSmallerThan_scalar_selector template struct isMuchSmallerThan_scalar_selector { + EIGEN_DEVICE_FUNC static bool run(const Derived& x, const typename Derived::RealScalar&, const typename Derived::RealScalar&) { return x.matrix() == Derived::Zero(x.rows(), x.cols()).matrix(); @@ -95,7 +100,7 @@ struct isMuchSmallerThan_scalar_selector */ template template -bool DenseBase::isApprox( +EIGEN_DEVICE_FUNC bool DenseBase::isApprox( const DenseBase& other, const RealScalar& prec ) const @@ -117,7 +122,7 @@ bool DenseBase::isApprox( * \sa isApprox(), isMuchSmallerThan(const DenseBase&, RealScalar) const */ template -bool DenseBase::isMuchSmallerThan( +EIGEN_DEVICE_FUNC bool DenseBase::isMuchSmallerThan( const typename NumTraits::Real& other, const RealScalar& prec ) const @@ -137,7 +142,7 @@ bool DenseBase::isMuchSmallerThan( */ template template -bool DenseBase::isMuchSmallerThan( +EIGEN_DEVICE_FUNC bool DenseBase::isMuchSmallerThan( const DenseBase& other, const RealScalar& prec ) const diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/GeneralProduct.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/GeneralProduct.h index 9e805a80..b206b0a7 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/GeneralProduct.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/GeneralProduct.h @@ -11,29 +11,7 @@ #ifndef EIGEN_GENERAL_PRODUCT_H #define EIGEN_GENERAL_PRODUCT_H -namespace Eigen { - -/** \class GeneralProduct - * \ingroup Core_Module - * - * \brief Expression of the product of two general matrices or vectors - * - * \param LhsNested the type used to store the left-hand side - * \param RhsNested the type used to store the right-hand side - * \param ProductMode the type of the product - * - * This class represents an expression of the product of two general matrices. - * We call a general matrix, a dense matrix with full storage. For instance, - * This excludes triangular, selfadjoint, and sparse matrices. - * It is the return type of the operator* between general matrices. Its template - * arguments are determined automatically by ProductReturnType. Therefore, - * GeneralProduct should never be used direclty. To determine the result type of a - * function which involves a matrix product, use ProductReturnType::Type. - * - * \sa ProductReturnType, MatrixBase::operator*(const MatrixBase&) - */ -template::value> -class GeneralProduct; +namespace Eigen { enum { Large = 2, @@ -47,7 +25,8 @@ template struct product_type_selector; template struct product_size_category { enum { is_large = MaxSize == Dynamic || - Size >= EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD, + Size >= EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD || + (Size==Dynamic && MaxSize>=EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD), value = is_large ? Large : Size == 1 ? 1 : Small @@ -59,15 +38,14 @@ template struct product_type typedef typename remove_all::type _Lhs; typedef typename remove_all::type _Rhs; enum { - MaxRows = _Lhs::MaxRowsAtCompileTime, - Rows = _Lhs::RowsAtCompileTime, - MaxCols = _Rhs::MaxColsAtCompileTime, - Cols = _Rhs::ColsAtCompileTime, - MaxDepth = EIGEN_SIZE_MIN_PREFER_FIXED(_Lhs::MaxColsAtCompileTime, - _Rhs::MaxRowsAtCompileTime), - Depth = EIGEN_SIZE_MIN_PREFER_FIXED(_Lhs::ColsAtCompileTime, - _Rhs::RowsAtCompileTime), - LargeThreshold = EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD + MaxRows = traits<_Lhs>::MaxRowsAtCompileTime, + Rows = traits<_Lhs>::RowsAtCompileTime, + MaxCols = traits<_Rhs>::MaxColsAtCompileTime, + Cols = traits<_Rhs>::ColsAtCompileTime, + MaxDepth = EIGEN_SIZE_MIN_PREFER_FIXED(traits<_Lhs>::MaxColsAtCompileTime, + traits<_Rhs>::MaxRowsAtCompileTime), + Depth = EIGEN_SIZE_MIN_PREFER_FIXED(traits<_Lhs>::ColsAtCompileTime, + traits<_Rhs>::RowsAtCompileTime) }; // the splitting into different lines of code here, introducing the _select enums and the typedef below, @@ -82,7 +60,8 @@ private: public: enum { - value = selector::ret + value = selector::ret, + ret = selector::ret }; #ifdef EIGEN_DEBUG_PRODUCT static void debug() @@ -98,12 +77,13 @@ public: #endif }; - /* The following allows to select the kind of product at compile time * based on the three dimensions of the product. * This is a compile time mapping from {1,Small,Large}^3 -> {product types} */ // FIXME I'm not sure the current mapping is the ideal one. template struct product_type_selector { enum { ret = OuterProduct }; }; +template struct product_type_selector { enum { ret = LazyCoeffBasedProductMode }; }; +template struct product_type_selector<1, N, 1> { enum { ret = LazyCoeffBasedProductMode }; }; template struct product_type_selector<1, 1, Depth> { enum { ret = InnerProduct }; }; template<> struct product_type_selector<1, 1, 1> { enum { ret = InnerProduct }; }; template<> struct product_type_selector { enum { ret = CoeffBasedProductMode }; }; @@ -122,60 +102,12 @@ template<> struct product_type_selector { enum template<> struct product_type_selector { enum { ret = GemmProduct }; }; template<> struct product_type_selector { enum { ret = GemmProduct }; }; template<> struct product_type_selector { enum { ret = GemmProduct }; }; -template<> struct product_type_selector { enum { ret = GemmProduct }; }; -template<> struct product_type_selector { enum { ret = GemmProduct }; }; +template<> struct product_type_selector { enum { ret = CoeffBasedProductMode }; }; +template<> struct product_type_selector { enum { ret = CoeffBasedProductMode }; }; template<> struct product_type_selector { enum { ret = GemmProduct }; }; } // end namespace internal -/** \class ProductReturnType - * \ingroup Core_Module - * - * \brief Helper class to get the correct and optimized returned type of operator* - * - * \param Lhs the type of the left-hand side - * \param Rhs the type of the right-hand side - * \param ProductMode the type of the product (determined automatically by internal::product_mode) - * - * This class defines the typename Type representing the optimized product expression - * between two matrix expressions. In practice, using ProductReturnType::Type - * is the recommended way to define the result type of a function returning an expression - * which involve a matrix product. The class Product should never be - * used directly. - * - * \sa class Product, MatrixBase::operator*(const MatrixBase&) - */ -template -struct ProductReturnType -{ - // TODO use the nested type to reduce instanciations ???? -// typedef typename internal::nested::type LhsNested; -// typedef typename internal::nested::type RhsNested; - - typedef GeneralProduct Type; -}; - -template -struct ProductReturnType -{ - typedef typename internal::nested::type >::type LhsNested; - typedef typename internal::nested::type >::type RhsNested; - typedef CoeffBasedProduct Type; -}; - -template -struct ProductReturnType -{ - typedef typename internal::nested::type >::type LhsNested; - typedef typename internal::nested::type >::type RhsNested; - typedef CoeffBasedProduct Type; -}; - -// this is a workaround for sun CC -template -struct LazyProductReturnType : public ProductReturnType -{}; - /*********************************************************************** * Implementation of Inner Vector Vector Product ***********************************************************************/ @@ -187,119 +119,10 @@ struct LazyProductReturnType : public ProductReturnType with: operator=(Scalar x); -namespace internal { - -template -struct traits > - : traits::ReturnType,1,1> > -{}; - -} - -template -class GeneralProduct - : internal::no_assignment_operator, - public Matrix::ReturnType,1,1> -{ - typedef Matrix::ReturnType,1,1> Base; - public: - GeneralProduct(const Lhs& lhs, const Rhs& rhs) - { - EIGEN_STATIC_ASSERT((internal::is_same::value), - YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) - - Base::coeffRef(0,0) = (lhs.transpose().cwiseProduct(rhs)).sum(); - } - - /** Convertion to scalar */ - operator const typename Base::Scalar() const { - return Base::coeff(0,0); - } -}; - /*********************************************************************** * Implementation of Outer Vector Vector Product ***********************************************************************/ -namespace internal { - -// Column major -template -EIGEN_DONT_INLINE void outer_product_selector_run(const ProductType& prod, Dest& dest, const Func& func, const false_type&) -{ - typedef typename Dest::Index Index; - // FIXME make sure lhs is sequentially stored - // FIXME not very good if rhs is real and lhs complex while alpha is real too - const Index cols = dest.cols(); - for (Index j=0; j -EIGEN_DONT_INLINE void outer_product_selector_run(const ProductType& prod, Dest& dest, const Func& func, const true_type&) { - typedef typename Dest::Index Index; - // FIXME make sure rhs is sequentially stored - // FIXME not very good if lhs is real and rhs complex while alpha is real too - const Index rows = dest.rows(); - for (Index i=0; i -struct traits > - : traits, Lhs, Rhs> > -{}; - -} - -template -class GeneralProduct - : public ProductBase, Lhs, Rhs> -{ - template struct IsRowMajor : internal::conditional<(int(T::Flags)&RowMajorBit), internal::true_type, internal::false_type>::type {}; - - public: - EIGEN_PRODUCT_PUBLIC_INTERFACE(GeneralProduct) - - GeneralProduct(const Lhs& lhs, const Rhs& rhs) : Base(lhs,rhs) - { - EIGEN_STATIC_ASSERT((internal::is_same::value), - YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) - } - - struct set { template void operator()(const Dst& dst, const Src& src) const { dst.const_cast_derived() = src; } }; - struct add { template void operator()(const Dst& dst, const Src& src) const { dst.const_cast_derived() += src; } }; - struct sub { template void operator()(const Dst& dst, const Src& src) const { dst.const_cast_derived() -= src; } }; - struct adds { - Scalar m_scale; - adds(const Scalar& s) : m_scale(s) {} - template void operator()(const Dst& dst, const Src& src) const { - dst.const_cast_derived() += m_scale * src; - } - }; - - template - inline void evalTo(Dest& dest) const { - internal::outer_product_selector_run(*this, dest, set(), IsRowMajor()); - } - - template - inline void addTo(Dest& dest) const { - internal::outer_product_selector_run(*this, dest, add(), IsRowMajor()); - } - - template - inline void subTo(Dest& dest) const { - internal::outer_product_selector_run(*this, dest, sub(), IsRowMajor()); - } - - template void scaleAndAddTo(Dest& dest, const Scalar& alpha) const - { - internal::outer_product_selector_run(*this, dest, adds(alpha), IsRowMajor()); - } -}; - /*********************************************************************** * Implementation of General Matrix Vector Product ***********************************************************************/ @@ -313,60 +136,13 @@ class GeneralProduct */ namespace internal { -template -struct traits > - : traits, Lhs, Rhs> > -{}; - template -struct gemv_selector; +struct gemv_dense_selector; } // end namespace internal -template -class GeneralProduct - : public ProductBase, Lhs, Rhs> -{ - public: - EIGEN_PRODUCT_PUBLIC_INTERFACE(GeneralProduct) - - typedef typename Lhs::Scalar LhsScalar; - typedef typename Rhs::Scalar RhsScalar; - - GeneralProduct(const Lhs& a_lhs, const Rhs& a_rhs) : Base(a_lhs,a_rhs) - { -// EIGEN_STATIC_ASSERT((internal::is_same::value), -// YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) - } - - enum { Side = Lhs::IsVectorAtCompileTime ? OnTheLeft : OnTheRight }; - typedef typename internal::conditional::type MatrixType; - - template void scaleAndAddTo(Dest& dst, const Scalar& alpha) const - { - eigen_assert(m_lhs.rows() == dst.rows() && m_rhs.cols() == dst.cols()); - internal::gemv_selector::HasUsableDirectAccess)>::run(*this, dst, alpha); - } -}; - namespace internal { -// The vector is on the left => transposition -template -struct gemv_selector -{ - template - static void run(const ProductType& prod, Dest& dest, const typename ProductType::Scalar& alpha) - { - Transpose destT(dest); - enum { OtherStorageOrder = StorageOrder == RowMajor ? ColMajor : RowMajor }; - gemv_selector - ::run(GeneralProduct,Transpose, GemvProduct> - (prod.rhs().transpose(), prod.lhs().transpose()), destT, alpha); - } -}; - template struct gemv_static_vector_if; template @@ -384,126 +160,161 @@ struct gemv_static_vector_if template struct gemv_static_vector_if { - #if EIGEN_ALIGN_STATICALLY - internal::plain_array m_data; - EIGEN_STRONG_INLINE Scalar* data() { return m_data.array; } - #else - // Some architectures cannot align on the stack, - // => let's manually enforce alignment by allocating more data and return the address of the first aligned element. enum { ForceAlignment = internal::packet_traits::Vectorizable, PacketSize = internal::packet_traits::size }; - internal::plain_array m_data; + #if EIGEN_MAX_STATIC_ALIGN_BYTES!=0 + internal::plain_array m_data; + EIGEN_STRONG_INLINE Scalar* data() { return m_data.array; } + #else + // Some architectures cannot align on the stack, + // => let's manually enforce alignment by allocating more data and return the address of the first aligned element. + internal::plain_array m_data; EIGEN_STRONG_INLINE Scalar* data() { return ForceAlignment - ? reinterpret_cast((reinterpret_cast(m_data.array) & ~(size_t(15))) + 16) + ? reinterpret_cast((internal::UIntPtr(m_data.array) & ~(std::size_t(EIGEN_MAX_ALIGN_BYTES-1))) + EIGEN_MAX_ALIGN_BYTES) : m_data.array; } #endif }; -template<> struct gemv_selector +// The vector is on the left => transposition +template +struct gemv_dense_selector { - template - static inline void run(const ProductType& prod, Dest& dest, const typename ProductType::Scalar& alpha) + template + static void run(const Lhs &lhs, const Rhs &rhs, Dest& dest, const typename Dest::Scalar& alpha) { - typedef typename ProductType::Index Index; - typedef typename ProductType::LhsScalar LhsScalar; - typedef typename ProductType::RhsScalar RhsScalar; - typedef typename ProductType::Scalar ResScalar; - typedef typename ProductType::RealScalar RealScalar; - typedef typename ProductType::ActualLhsType ActualLhsType; - typedef typename ProductType::ActualRhsType ActualRhsType; - typedef typename ProductType::LhsBlasTraits LhsBlasTraits; - typedef typename ProductType::RhsBlasTraits RhsBlasTraits; - typedef Map, Aligned> MappedDest; + Transpose destT(dest); + enum { OtherStorageOrder = StorageOrder == RowMajor ? ColMajor : RowMajor }; + gemv_dense_selector + ::run(rhs.transpose(), lhs.transpose(), destT, alpha); + } +}; - ActualLhsType actualLhs = LhsBlasTraits::extract(prod.lhs()); - ActualRhsType actualRhs = RhsBlasTraits::extract(prod.rhs()); +template<> struct gemv_dense_selector +{ + template + static inline void run(const Lhs &lhs, const Rhs &rhs, Dest& dest, const typename Dest::Scalar& alpha) + { + typedef typename Lhs::Scalar LhsScalar; + typedef typename Rhs::Scalar RhsScalar; + typedef typename Dest::Scalar ResScalar; + typedef typename Dest::RealScalar RealScalar; + + typedef internal::blas_traits LhsBlasTraits; + typedef typename LhsBlasTraits::DirectLinearAccessType ActualLhsType; + typedef internal::blas_traits RhsBlasTraits; + typedef typename RhsBlasTraits::DirectLinearAccessType ActualRhsType; + + typedef Map, EIGEN_PLAIN_ENUM_MIN(AlignedMax,internal::packet_traits::size)> MappedDest; - ResScalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(prod.lhs()) - * RhsBlasTraits::extractScalarFactor(prod.rhs()); + ActualLhsType actualLhs = LhsBlasTraits::extract(lhs); + ActualRhsType actualRhs = RhsBlasTraits::extract(rhs); + + ResScalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(lhs) + * RhsBlasTraits::extractScalarFactor(rhs); + + // make sure Dest is a compile-time vector type (bug 1166) + typedef typename conditional::type ActualDest; enum { // FIXME find a way to allow an inner stride on the result if packet_traits::size==1 // on, the other hand it is good for the cache to pack the vector anyways... - EvalToDestAtCompileTime = Dest::InnerStrideAtCompileTime==1, + EvalToDestAtCompileTime = (ActualDest::InnerStrideAtCompileTime==1), ComplexByReal = (NumTraits::IsComplex) && (!NumTraits::IsComplex), - MightCannotUseDest = (Dest::InnerStrideAtCompileTime!=1) || ComplexByReal + MightCannotUseDest = (!EvalToDestAtCompileTime) || ComplexByReal }; - gemv_static_vector_if static_dest; - - bool alphaIsCompatible = (!ComplexByReal) || (numext::imag(actualAlpha)==RealScalar(0)); - bool evalToDest = EvalToDestAtCompileTime && alphaIsCompatible; - + typedef const_blas_data_mapper LhsMapper; + typedef const_blas_data_mapper RhsMapper; RhsScalar compatibleAlpha = get_factor::run(actualAlpha); - ei_declare_aligned_stack_constructed_variable(ResScalar,actualDestPtr,dest.size(), - evalToDest ? dest.data() : static_dest.data()); - - if(!evalToDest) + if(!MightCannotUseDest) { - #ifdef EIGEN_DENSE_STORAGE_CTOR_PLUGIN - int size = dest.size(); - EIGEN_DENSE_STORAGE_CTOR_PLUGIN - #endif - if(!alphaIsCompatible) - { - MappedDest(actualDestPtr, dest.size()).setZero(); - compatibleAlpha = RhsScalar(1); - } - else - MappedDest(actualDestPtr, dest.size()) = dest; + // shortcut if we are sure to be able to use dest directly, + // this ease the compiler to generate cleaner and more optimzized code for most common cases + general_matrix_vector_product + ::run( + actualLhs.rows(), actualLhs.cols(), + LhsMapper(actualLhs.data(), actualLhs.outerStride()), + RhsMapper(actualRhs.data(), actualRhs.innerStride()), + dest.data(), 1, + compatibleAlpha); } - - general_matrix_vector_product - ::run( - actualLhs.rows(), actualLhs.cols(), - actualLhs.data(), actualLhs.outerStride(), - actualRhs.data(), actualRhs.innerStride(), - actualDestPtr, 1, - compatibleAlpha); - - if (!evalToDest) + else { - if(!alphaIsCompatible) - dest += actualAlpha * MappedDest(actualDestPtr, dest.size()); - else - dest = MappedDest(actualDestPtr, dest.size()); + gemv_static_vector_if static_dest; + + const bool alphaIsCompatible = (!ComplexByReal) || (numext::imag(actualAlpha)==RealScalar(0)); + const bool evalToDest = EvalToDestAtCompileTime && alphaIsCompatible; + + ei_declare_aligned_stack_constructed_variable(ResScalar,actualDestPtr,dest.size(), + evalToDest ? dest.data() : static_dest.data()); + + if(!evalToDest) + { + #ifdef EIGEN_DENSE_STORAGE_CTOR_PLUGIN + Index size = dest.size(); + EIGEN_DENSE_STORAGE_CTOR_PLUGIN + #endif + if(!alphaIsCompatible) + { + MappedDest(actualDestPtr, dest.size()).setZero(); + compatibleAlpha = RhsScalar(1); + } + else + MappedDest(actualDestPtr, dest.size()) = dest; + } + + general_matrix_vector_product + ::run( + actualLhs.rows(), actualLhs.cols(), + LhsMapper(actualLhs.data(), actualLhs.outerStride()), + RhsMapper(actualRhs.data(), actualRhs.innerStride()), + actualDestPtr, 1, + compatibleAlpha); + + if (!evalToDest) + { + if(!alphaIsCompatible) + dest.matrix() += actualAlpha * MappedDest(actualDestPtr, dest.size()); + else + dest = MappedDest(actualDestPtr, dest.size()); + } } } }; -template<> struct gemv_selector +template<> struct gemv_dense_selector { - template - static void run(const ProductType& prod, Dest& dest, const typename ProductType::Scalar& alpha) + template + static void run(const Lhs &lhs, const Rhs &rhs, Dest& dest, const typename Dest::Scalar& alpha) { - typedef typename ProductType::LhsScalar LhsScalar; - typedef typename ProductType::RhsScalar RhsScalar; - typedef typename ProductType::Scalar ResScalar; - typedef typename ProductType::Index Index; - typedef typename ProductType::ActualLhsType ActualLhsType; - typedef typename ProductType::ActualRhsType ActualRhsType; - typedef typename ProductType::_ActualRhsType _ActualRhsType; - typedef typename ProductType::LhsBlasTraits LhsBlasTraits; - typedef typename ProductType::RhsBlasTraits RhsBlasTraits; + typedef typename Lhs::Scalar LhsScalar; + typedef typename Rhs::Scalar RhsScalar; + typedef typename Dest::Scalar ResScalar; + + typedef internal::blas_traits LhsBlasTraits; + typedef typename LhsBlasTraits::DirectLinearAccessType ActualLhsType; + typedef internal::blas_traits RhsBlasTraits; + typedef typename RhsBlasTraits::DirectLinearAccessType ActualRhsType; + typedef typename internal::remove_all::type ActualRhsTypeCleaned; - typename add_const::type actualLhs = LhsBlasTraits::extract(prod.lhs()); - typename add_const::type actualRhs = RhsBlasTraits::extract(prod.rhs()); + typename add_const::type actualLhs = LhsBlasTraits::extract(lhs); + typename add_const::type actualRhs = RhsBlasTraits::extract(rhs); - ResScalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(prod.lhs()) - * RhsBlasTraits::extractScalarFactor(prod.rhs()); + ResScalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(lhs) + * RhsBlasTraits::extractScalarFactor(rhs); enum { // FIXME find a way to allow an inner stride on the result if packet_traits::size==1 // on, the other hand it is good for the cache to pack the vector anyways... - DirectlyUseRhs = _ActualRhsType::InnerStrideAtCompileTime==1 + DirectlyUseRhs = ActualRhsTypeCleaned::InnerStrideAtCompileTime==1 }; - gemv_static_vector_if static_rhs; + gemv_static_vector_if static_rhs; ei_declare_aligned_stack_constructed_variable(RhsScalar,actualRhsPtr,actualRhs.size(), DirectlyUseRhs ? const_cast(actualRhs.data()) : static_rhs.data()); @@ -511,45 +322,48 @@ template<> struct gemv_selector if(!DirectlyUseRhs) { #ifdef EIGEN_DENSE_STORAGE_CTOR_PLUGIN - int size = actualRhs.size(); + Index size = actualRhs.size(); EIGEN_DENSE_STORAGE_CTOR_PLUGIN #endif - Map(actualRhsPtr, actualRhs.size()) = actualRhs; + Map(actualRhsPtr, actualRhs.size()) = actualRhs; } + typedef const_blas_data_mapper LhsMapper; + typedef const_blas_data_mapper RhsMapper; general_matrix_vector_product - ::run( + ::run( actualLhs.rows(), actualLhs.cols(), - actualLhs.data(), actualLhs.outerStride(), - actualRhsPtr, 1, - dest.data(), dest.innerStride(), + LhsMapper(actualLhs.data(), actualLhs.outerStride()), + RhsMapper(actualRhsPtr, 1), + dest.data(), dest.col(0).innerStride(), //NOTE if dest is not a vector at compile-time, then dest.innerStride() might be wrong. (bug 1166) actualAlpha); } }; -template<> struct gemv_selector +template<> struct gemv_dense_selector { - template - static void run(const ProductType& prod, Dest& dest, const typename ProductType::Scalar& alpha) + template + static void run(const Lhs &lhs, const Rhs &rhs, Dest& dest, const typename Dest::Scalar& alpha) { - typedef typename Dest::Index Index; - // TODO makes sure dest is sequentially stored in memory, otherwise use a temp - const Index size = prod.rhs().rows(); + EIGEN_STATIC_ASSERT((!nested_eval::Evaluate),EIGEN_INTERNAL_COMPILATION_ERROR_OR_YOU_MADE_A_PROGRAMMING_MISTAKE); + // TODO if rhs is large enough it might be beneficial to make sure that dest is sequentially stored in memory, otherwise use a temp + typename nested_eval::type actual_rhs(rhs); + const Index size = rhs.rows(); for(Index k=0; k struct gemv_selector +template<> struct gemv_dense_selector { - template - static void run(const ProductType& prod, Dest& dest, const typename ProductType::Scalar& alpha) + template + static void run(const Lhs &lhs, const Rhs &rhs, Dest& dest, const typename Dest::Scalar& alpha) { - typedef typename Dest::Index Index; - // TODO makes sure rhs is sequentially stored in memory, otherwise use a temp - const Index rows = prod.rows(); + EIGEN_STATIC_ASSERT((!nested_eval::Evaluate),EIGEN_INTERNAL_COMPILATION_ERROR_OR_YOU_MADE_A_PROGRAMMING_MISTAKE); + typename nested_eval::type actual_rhs(rhs); + const Index rows = dest.rows(); for(Index i=0; i struct gemv_selector * * \sa lazyProduct(), operator*=(const MatrixBase&), Cwise::operator*() */ +#ifndef __CUDACC__ + template template -inline const typename ProductReturnType::Type +inline const Product MatrixBase::operator*(const MatrixBase &other) const { // A note regarding the function declaration: In MSVC, this function will sometimes @@ -592,9 +408,12 @@ MatrixBase::operator*(const MatrixBase &other) const #ifdef EIGEN_DEBUG_PRODUCT internal::product_type::debug(); #endif - return typename ProductReturnType::Type(derived(), other.derived()); + + return Product(derived(), other.derived()); } +#endif // __CUDACC__ + /** \returns an expression of the matrix product of \c *this and \a other without implicit evaluation. * * The returned product will behave like any other expressions: the coefficients of the product will be @@ -608,8 +427,8 @@ MatrixBase::operator*(const MatrixBase &other) const */ template template -const typename LazyProductReturnType::Type -MatrixBase::lazyProduct(const MatrixBase &other) const +const Product +EIGEN_DEVICE_FUNC MatrixBase::lazyProduct(const MatrixBase &other) const { enum { ProductIsValid = Derived::ColsAtCompileTime==Dynamic @@ -627,7 +446,7 @@ MatrixBase::lazyProduct(const MatrixBase &other) const INVALID_MATRIX_PRODUCT__IF_YOU_WANTED_A_COEFF_WISE_PRODUCT_YOU_MUST_USE_THE_EXPLICIT_FUNCTION) EIGEN_STATIC_ASSERT(ProductIsValid || SameSizes, INVALID_MATRIX_PRODUCT) - return typename LazyProductReturnType::Type(derived(), other.derived()); + return Product(derived(), other.derived()); } } // end namespace Eigen diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/GenericPacketMath.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/GenericPacketMath.h index 5f783ebe..d19d5bbd 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/GenericPacketMath.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/GenericPacketMath.h @@ -42,21 +42,29 @@ namespace internal { struct default_packet_traits { enum { + HasHalfPacket = 0, + HasAdd = 1, HasSub = 1, HasMul = 1, HasNegate = 1, HasAbs = 1, + HasArg = 0, HasAbs2 = 1, HasMin = 1, HasMax = 1, HasConj = 1, HasSetLinear = 1, + HasBlend = 0, HasDiv = 0, HasSqrt = 0, + HasRsqrt = 0, HasExp = 0, + HasExpm1 = 0, HasLog = 0, + HasLog1p = 0, + HasLog10 = 0, HasPow = 0, HasSin = 0, @@ -64,17 +72,37 @@ struct default_packet_traits HasTan = 0, HasASin = 0, HasACos = 0, - HasATan = 0 + HasATan = 0, + HasSinh = 0, + HasCosh = 0, + HasTanh = 0, + HasLGamma = 0, + HasDiGamma = 0, + HasZeta = 0, + HasPolygamma = 0, + HasErf = 0, + HasErfc = 0, + HasIGamma = 0, + HasIGammac = 0, + HasBetaInc = 0, + + HasRound = 0, + HasFloor = 0, + HasCeil = 0, + + HasSign = 0 }; }; template struct packet_traits : default_packet_traits { typedef T type; + typedef T half; enum { Vectorizable = 0, size = 1, - AlignedOnScalar = 0 + AlignedOnScalar = 0, + HasHalfPacket = 0 }; enum { HasAdd = 0, @@ -90,135 +118,239 @@ template struct packet_traits : default_packet_traits }; }; +template struct packet_traits : packet_traits { }; + +template struct type_casting_traits { + enum { + VectorizedCast = 0, + SrcCoeffRatio = 1, + TgtCoeffRatio = 1 + }; +}; + + +/** \internal \returns static_cast(a) (coeff-wise) */ +template +EIGEN_DEVICE_FUNC inline TgtPacket +pcast(const SrcPacket& a) { + return static_cast(a); +} +template +EIGEN_DEVICE_FUNC inline TgtPacket +pcast(const SrcPacket& a, const SrcPacket& /*b*/) { + return static_cast(a); +} + +template +EIGEN_DEVICE_FUNC inline TgtPacket +pcast(const SrcPacket& a, const SrcPacket& /*b*/, const SrcPacket& /*c*/, const SrcPacket& /*d*/) { + return static_cast(a); +} + /** \internal \returns a + b (coeff-wise) */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet padd(const Packet& a, const Packet& b) { return a+b; } /** \internal \returns a - b (coeff-wise) */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet psub(const Packet& a, const Packet& b) { return a-b; } /** \internal \returns -a (coeff-wise) */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pnegate(const Packet& a) { return -a; } /** \internal \returns conj(a) (coeff-wise) */ -template inline Packet + +template EIGEN_DEVICE_FUNC inline Packet pconj(const Packet& a) { return numext::conj(a); } /** \internal \returns a * b (coeff-wise) */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pmul(const Packet& a, const Packet& b) { return a*b; } /** \internal \returns a / b (coeff-wise) */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pdiv(const Packet& a, const Packet& b) { return a/b; } /** \internal \returns the min of \a a and \a b (coeff-wise) */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pmin(const Packet& a, - const Packet& b) { using std::min; return (min)(a, b); } + const Packet& b) { return numext::mini(a, b); } /** \internal \returns the max of \a a and \a b (coeff-wise) */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pmax(const Packet& a, - const Packet& b) { using std::max; return (max)(a, b); } + const Packet& b) { return numext::maxi(a, b); } /** \internal \returns the absolute value of \a a */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pabs(const Packet& a) { using std::abs; return abs(a); } +/** \internal \returns the phase angle of \a a */ +template EIGEN_DEVICE_FUNC inline Packet +parg(const Packet& a) { using numext::arg; return arg(a); } + /** \internal \returns the bitwise and of \a a and \a b */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pand(const Packet& a, const Packet& b) { return a & b; } /** \internal \returns the bitwise or of \a a and \a b */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet por(const Packet& a, const Packet& b) { return a | b; } /** \internal \returns the bitwise xor of \a a and \a b */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pxor(const Packet& a, const Packet& b) { return a ^ b; } /** \internal \returns the bitwise andnot of \a a and \a b */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pandnot(const Packet& a, const Packet& b) { return a & (!b); } /** \internal \returns a packet version of \a *from, from must be 16 bytes aligned */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pload(const typename unpacket_traits::type* from) { return *from; } /** \internal \returns a packet version of \a *from, (un-aligned load) */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet ploadu(const typename unpacket_traits::type* from) { return *from; } -/** \internal \returns a packet with elements of \a *from duplicated. - * For instance, for a packet of 8 elements, 4 scalar will be read from \a *from and - * duplicated to form: {from[0],from[0],from[1],from[1],,from[2],from[2],,from[3],from[3]} - * Currently, this function is only used for scalar * complex products. - */ -template inline Packet -ploaddup(const typename unpacket_traits::type* from) { return *from; } - /** \internal \returns a packet with constant coefficients \a a, e.g.: (a,a,a,a) */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pset1(const typename unpacket_traits::type& a) { return a; } +/** \internal \returns a packet with constant coefficients \a a[0], e.g.: (a[0],a[0],a[0],a[0]) */ +template EIGEN_DEVICE_FUNC inline Packet +pload1(const typename unpacket_traits::type *a) { return pset1(*a); } + +/** \internal \returns a packet with elements of \a *from duplicated. + * For instance, for a packet of 8 elements, 4 scalars will be read from \a *from and + * duplicated to form: {from[0],from[0],from[1],from[1],from[2],from[2],from[3],from[3]} + * Currently, this function is only used for scalar * complex products. + */ +template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet +ploaddup(const typename unpacket_traits::type* from) { return *from; } + +/** \internal \returns a packet with elements of \a *from quadrupled. + * For instance, for a packet of 8 elements, 2 scalars will be read from \a *from and + * replicated to form: {from[0],from[0],from[0],from[0],from[1],from[1],from[1],from[1]} + * Currently, this function is only used in matrix products. + * For packet-size smaller or equal to 4, this function is equivalent to pload1 + */ +template EIGEN_DEVICE_FUNC inline Packet +ploadquad(const typename unpacket_traits::type* from) +{ return pload1(from); } + +/** \internal equivalent to + * \code + * a0 = pload1(a+0); + * a1 = pload1(a+1); + * a2 = pload1(a+2); + * a3 = pload1(a+3); + * \endcode + * \sa pset1, pload1, ploaddup, pbroadcast2 + */ +template EIGEN_DEVICE_FUNC +inline void pbroadcast4(const typename unpacket_traits::type *a, + Packet& a0, Packet& a1, Packet& a2, Packet& a3) +{ + a0 = pload1(a+0); + a1 = pload1(a+1); + a2 = pload1(a+2); + a3 = pload1(a+3); +} + +/** \internal equivalent to + * \code + * a0 = pload1(a+0); + * a1 = pload1(a+1); + * \endcode + * \sa pset1, pload1, ploaddup, pbroadcast4 + */ +template EIGEN_DEVICE_FUNC +inline void pbroadcast2(const typename unpacket_traits::type *a, + Packet& a0, Packet& a1) +{ + a0 = pload1(a+0); + a1 = pload1(a+1); +} + /** \internal \brief Returns a packet with coefficients (a,a+1,...,a+packet_size-1). */ -template inline typename packet_traits::type -plset(const Scalar& a) { return a; } +template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet +plset(const typename unpacket_traits::type& a) { return a; } /** \internal copy the packet \a from to \a *to, \a to must be 16 bytes aligned */ -template inline void pstore(Scalar* to, const Packet& from) +template EIGEN_DEVICE_FUNC inline void pstore(Scalar* to, const Packet& from) { (*to) = from; } /** \internal copy the packet \a from to \a *to, (un-aligned store) */ -template inline void pstoreu(Scalar* to, const Packet& from) -{ (*to) = from; } +template EIGEN_DEVICE_FUNC inline void pstoreu(Scalar* to, const Packet& from) +{ (*to) = from; } + + template EIGEN_DEVICE_FUNC inline Packet pgather(const Scalar* from, Index /*stride*/) + { return ploadu(from); } + + template EIGEN_DEVICE_FUNC inline void pscatter(Scalar* to, const Packet& from, Index /*stride*/) + { pstore(to, from); } /** \internal tries to do cache prefetching of \a addr */ -template inline void prefetch(const Scalar* addr) +template EIGEN_DEVICE_FUNC inline void prefetch(const Scalar* addr) { -#if !defined(_MSC_VER) -__builtin_prefetch(addr); +#ifdef __CUDA_ARCH__ +#if defined(__LP64__) + // 64-bit pointer operand constraint for inlined asm + asm(" prefetch.L1 [ %1 ];" : "=l"(addr) : "l"(addr)); +#else + // 32-bit pointer operand constraint for inlined asm + asm(" prefetch.L1 [ %1 ];" : "=r"(addr) : "r"(addr)); +#endif +#elif (!EIGEN_COMP_MSVC) && (EIGEN_COMP_GNUC || EIGEN_COMP_CLANG || EIGEN_COMP_ICC) + __builtin_prefetch(addr); #endif } /** \internal \returns the first element of a packet */ -template inline typename unpacket_traits::type pfirst(const Packet& a) +template EIGEN_DEVICE_FUNC inline typename unpacket_traits::type pfirst(const Packet& a) { return a; } /** \internal \returns a packet where the element i contains the sum of the packet of \a vec[i] */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet preduxp(const Packet* vecs) { return vecs[0]; } /** \internal \returns the sum of the elements of \a a*/ -template inline typename unpacket_traits::type predux(const Packet& a) +template EIGEN_DEVICE_FUNC inline typename unpacket_traits::type predux(const Packet& a) +{ return a; } + +/** \internal \returns the sum of the elements of \a a by block of 4 elements. + * For a packet {a0, a1, a2, a3, a4, a5, a6, a7}, it returns a half packet {a0+a4, a1+a5, a2+a6, a3+a7} + * For packet-size smaller or equal to 4, this boils down to a noop. + */ +template EIGEN_DEVICE_FUNC inline +typename conditional<(unpacket_traits::size%8)==0,typename unpacket_traits::half,Packet>::type +predux_downto4(const Packet& a) { return a; } /** \internal \returns the product of the elements of \a a*/ -template inline typename unpacket_traits::type predux_mul(const Packet& a) +template EIGEN_DEVICE_FUNC inline typename unpacket_traits::type predux_mul(const Packet& a) { return a; } /** \internal \returns the min of the elements of \a a*/ -template inline typename unpacket_traits::type predux_min(const Packet& a) +template EIGEN_DEVICE_FUNC inline typename unpacket_traits::type predux_min(const Packet& a) { return a; } /** \internal \returns the max of the elements of \a a*/ -template inline typename unpacket_traits::type predux_max(const Packet& a) +template EIGEN_DEVICE_FUNC inline typename unpacket_traits::type predux_max(const Packet& a) { return a; } /** \internal \returns the reversed elements of \a a*/ -template inline Packet preverse(const Packet& a) +template EIGEN_DEVICE_FUNC inline Packet preverse(const Packet& a) { return a; } - /** \internal \returns \a a with real and imaginary part flipped (for complex type only) */ -template inline Packet pcplxflip(const Packet& a) +template EIGEN_DEVICE_FUNC inline Packet pcplxflip(const Packet& a) { // FIXME: uncomment the following in case we drop the internal imag and real functions. // using std::imag; @@ -250,18 +382,64 @@ Packet pasin(const Packet& a) { using std::asin; return asin(a); } template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS Packet pacos(const Packet& a) { using std::acos; return acos(a); } +/** \internal \returns the arc tangent of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet patan(const Packet& a) { using std::atan; return atan(a); } + +/** \internal \returns the hyperbolic sine of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet psinh(const Packet& a) { using std::sinh; return sinh(a); } + +/** \internal \returns the hyperbolic cosine of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet pcosh(const Packet& a) { using std::cosh; return cosh(a); } + +/** \internal \returns the hyperbolic tan of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet ptanh(const Packet& a) { using std::tanh; return tanh(a); } + /** \internal \returns the exp of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS Packet pexp(const Packet& a) { using std::exp; return exp(a); } +/** \internal \returns the expm1 of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet pexpm1(const Packet& a) { return numext::expm1(a); } + /** \internal \returns the log of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS Packet plog(const Packet& a) { using std::log; return log(a); } +/** \internal \returns the log1p of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet plog1p(const Packet& a) { return numext::log1p(a); } + +/** \internal \returns the log10 of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet plog10(const Packet& a) { using std::log10; return log10(a); } + /** \internal \returns the square-root of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS Packet psqrt(const Packet& a) { using std::sqrt; return sqrt(a); } +/** \internal \returns the reciprocal square-root of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet prsqrt(const Packet& a) { + return pdiv(pset1(1), psqrt(a)); +} + +/** \internal \returns the rounded value of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet pround(const Packet& a) { using numext::round; return round(a); } + +/** \internal \returns the floor of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet pfloor(const Packet& a) { using numext::floor; return floor(a); } + +/** \internal \returns the ceil of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet pceil(const Packet& a) { using numext::ceil; return ceil(a); } + /*************************************************************************** * The following functions might not have to be overwritten for vectorized types ***************************************************************************/ @@ -275,34 +453,45 @@ inline void pstore1(typename unpacket_traits::type* to, const typename u } /** \internal \returns a * b + c (coeff-wise) */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pmadd(const Packet& a, const Packet& b, const Packet& c) { return padd(pmul(a, b),c); } /** \internal \returns a packet version of \a *from. - * If LoadMode equals #Aligned, \a from must be 16 bytes aligned */ -template -inline Packet ploadt(const typename unpacket_traits::type* from) + * The pointer \a from must be aligned on a \a Alignment bytes boundary. */ +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Packet ploadt(const typename unpacket_traits::type* from) { - if(LoadMode == Aligned) + if(Alignment >= unpacket_traits::alignment) return pload(from); else return ploadu(from); } /** \internal copy the packet \a from to \a *to. - * If StoreMode equals #Aligned, \a to must be 16 bytes aligned */ -template -inline void pstoret(Scalar* to, const Packet& from) + * The pointer \a from must be aligned on a \a Alignment bytes boundary. */ +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void pstoret(Scalar* to, const Packet& from) { - if(LoadMode == Aligned) + if(Alignment >= unpacket_traits::alignment) pstore(to, from); else pstoreu(to, from); } +/** \internal \returns a packet version of \a *from. + * Unlike ploadt, ploadt_ro takes advantage of the read-only memory path on the + * hardware if available to speedup the loading of data that won't be modified + * by the current computation. + */ +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Packet ploadt_ro(const typename unpacket_traits::type* from) +{ + return ploadt(from); +} + /** \internal default implementation of palign() allowing partial specialization */ template struct palign_impl @@ -336,15 +525,74 @@ inline void palign(PacketType& first, const PacketType& second) * Fast complex products (GCC generates a function call which is very slow) ***************************************************************************/ +// Eigen+CUDA does not support complexes. +#ifndef __CUDACC__ + template<> inline std::complex pmul(const std::complex& a, const std::complex& b) { return std::complex(real(a)*real(b) - imag(a)*imag(b), imag(a)*real(b) + real(a)*imag(b)); } template<> inline std::complex pmul(const std::complex& a, const std::complex& b) { return std::complex(real(a)*real(b) - imag(a)*imag(b), imag(a)*real(b) + real(a)*imag(b)); } +#endif + + +/*************************************************************************** + * PacketBlock, that is a collection of N packets where the number of words + * in the packet is a multiple of N. +***************************************************************************/ +template ::size> struct PacketBlock { + Packet packet[N]; +}; + +template EIGEN_DEVICE_FUNC inline void +ptranspose(PacketBlock& /*kernel*/) { + // Nothing to do in the scalar case, i.e. a 1x1 matrix. +} + +/*************************************************************************** + * Selector, i.e. vector of N boolean values used to select (i.e. blend) + * words from 2 packets. +***************************************************************************/ +template struct Selector { + bool select[N]; +}; + +template EIGEN_DEVICE_FUNC inline Packet +pblend(const Selector::size>& ifPacket, const Packet& thenPacket, const Packet& elsePacket) { + return ifPacket.select[0] ? thenPacket : elsePacket; +} + +/** \internal \returns \a a with the first coefficient replaced by the scalar b */ +template EIGEN_DEVICE_FUNC inline Packet +pinsertfirst(const Packet& a, typename unpacket_traits::type b) +{ + // Default implementation based on pblend. + // It must be specialized for higher performance. + Selector::size> mask; + mask.select[0] = true; + // This for loop should be optimized away by the compiler. + for(Index i=1; i::size; ++i) + mask.select[i] = false; + return pblend(mask, pset1(b), a); +} + +/** \internal \returns \a a with the last coefficient replaced by the scalar b */ +template EIGEN_DEVICE_FUNC inline Packet +pinsertlast(const Packet& a, typename unpacket_traits::type b) +{ + // Default implementation based on pblend. + // It must be specialized for higher performance. + Selector::size> mask; + // This for loop should be optimized away by the compiler. + for(Index i=0; i::size-1; ++i) + mask.select[i] = false; + mask.select[unpacket_traits::size-1] = true; + return pblend(mask, pset1(b), a); +} + } // end namespace internal } // end namespace Eigen #endif // EIGEN_GENERIC_PACKET_MATH_H - diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/GlobalFunctions.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/GlobalFunctions.h index 2acf9772..12828a7c 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/GlobalFunctions.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/GlobalFunctions.h @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2010-2012 Gael Guennebaud +// Copyright (C) 2010-2016 Gael Guennebaud // Copyright (C) 2010 Benoit Jacob // // This Source Code Form is subject to the terms of the Mozilla @@ -11,13 +11,30 @@ #ifndef EIGEN_GLOBAL_FUNCTIONS_H #define EIGEN_GLOBAL_FUNCTIONS_H -#define EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(NAME,FUNCTOR) \ +#ifdef EIGEN_PARSED_BY_DOXYGEN + +#define EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(NAME,FUNCTOR,DOC_OP,DOC_DETAILS) \ + /** \returns an expression of the coefficient-wise DOC_OP of \a x + + DOC_DETAILS + + \sa Math functions, class CwiseUnaryOp + */ \ template \ inline const Eigen::CwiseUnaryOp, const Derived> \ - NAME(const Eigen::ArrayBase& x) { \ - return x.derived(); \ + NAME(const Eigen::ArrayBase& x); + +#else + +#define EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(NAME,FUNCTOR,DOC_OP,DOC_DETAILS) \ + template \ + inline const Eigen::CwiseUnaryOp, const Derived> \ + (NAME)(const Eigen::ArrayBase& x) { \ + return Eigen::CwiseUnaryOp, const Derived>(x.derived()); \ } +#endif // EIGEN_PARSED_BY_DOXYGEN + #define EIGEN_ARRAY_DECLARE_GLOBAL_EIGEN_UNARY(NAME,FUNCTOR) \ \ template \ @@ -30,55 +47,134 @@ { \ static inline typename NAME##_retval >::type run(const Eigen::ArrayBase& x) \ { \ - return x.derived(); \ + return typename NAME##_retval >::type(x.derived()); \ } \ }; - namespace Eigen { - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(real,scalar_real_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(imag,scalar_imag_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(conj,scalar_conjugate_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(sin,scalar_sin_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(cos,scalar_cos_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(asin,scalar_asin_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(acos,scalar_acos_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(tan,scalar_tan_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(exp,scalar_exp_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(log,scalar_log_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(abs,scalar_abs_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(sqrt,scalar_sqrt_op) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(real,scalar_real_op,real part,\sa ArrayBase::real) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(imag,scalar_imag_op,imaginary part,\sa ArrayBase::imag) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(conj,scalar_conjugate_op,complex conjugate,\sa ArrayBase::conjugate) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(inverse,scalar_inverse_op,inverse,\sa ArrayBase::inverse) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(sin,scalar_sin_op,sine,\sa ArrayBase::sin) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(cos,scalar_cos_op,cosine,\sa ArrayBase::cos) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(tan,scalar_tan_op,tangent,\sa ArrayBase::tan) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(atan,scalar_atan_op,arc-tangent,\sa ArrayBase::atan) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(asin,scalar_asin_op,arc-sine,\sa ArrayBase::asin) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(acos,scalar_acos_op,arc-consine,\sa ArrayBase::acos) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(sinh,scalar_sinh_op,hyperbolic sine,\sa ArrayBase::sinh) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(cosh,scalar_cosh_op,hyperbolic cosine,\sa ArrayBase::cosh) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(tanh,scalar_tanh_op,hyperbolic tangent,\sa ArrayBase::tanh) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(lgamma,scalar_lgamma_op,natural logarithm of the gamma function,\sa ArrayBase::lgamma) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(digamma,scalar_digamma_op,derivative of lgamma,\sa ArrayBase::digamma) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(erf,scalar_erf_op,error function,\sa ArrayBase::erf) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(erfc,scalar_erfc_op,complement error function,\sa ArrayBase::erfc) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(exp,scalar_exp_op,exponential,\sa ArrayBase::exp) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(expm1,scalar_expm1_op,exponential of a value minus 1,\sa ArrayBase::expm1) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(log,scalar_log_op,natural logarithm,\sa Eigen::log10 DOXCOMMA ArrayBase::log) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(log1p,scalar_log1p_op,natural logarithm of 1 plus the value,\sa ArrayBase::log1p) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(log10,scalar_log10_op,base 10 logarithm,\sa Eigen::log DOXCOMMA ArrayBase::log) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(abs,scalar_abs_op,absolute value,\sa ArrayBase::abs DOXCOMMA MatrixBase::cwiseAbs) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(abs2,scalar_abs2_op,squared absolute value,\sa ArrayBase::abs2 DOXCOMMA MatrixBase::cwiseAbs2) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(arg,scalar_arg_op,complex argument,\sa ArrayBase::arg) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(sqrt,scalar_sqrt_op,square root,\sa ArrayBase::sqrt DOXCOMMA MatrixBase::cwiseSqrt) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(rsqrt,scalar_rsqrt_op,reciprocal square root,\sa ArrayBase::rsqrt) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(square,scalar_square_op,square (power 2),\sa Eigen::abs2 DOXCOMMA Eigen::pow DOXCOMMA ArrayBase::square) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(cube,scalar_cube_op,cube (power 3),\sa Eigen::pow DOXCOMMA ArrayBase::cube) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(round,scalar_round_op,nearest integer,\sa Eigen::floor DOXCOMMA Eigen::ceil DOXCOMMA ArrayBase::round) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(floor,scalar_floor_op,nearest integer not greater than the giben value,\sa Eigen::ceil DOXCOMMA ArrayBase::floor) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(ceil,scalar_ceil_op,nearest integer not less than the giben value,\sa Eigen::floor DOXCOMMA ArrayBase::ceil) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(isnan,scalar_isnan_op,not-a-number test,\sa Eigen::isinf DOXCOMMA Eigen::isfinite DOXCOMMA ArrayBase::isnan) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(isinf,scalar_isinf_op,infinite value test,\sa Eigen::isnan DOXCOMMA Eigen::isfinite DOXCOMMA ArrayBase::isinf) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(isfinite,scalar_isfinite_op,finite value test,\sa Eigen::isinf DOXCOMMA Eigen::isnan DOXCOMMA ArrayBase::isfinite) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(sign,scalar_sign_op,sign (or 0),\sa ArrayBase::sign) - template - inline const Eigen::CwiseUnaryOp, const Derived> - pow(const Eigen::ArrayBase& x, const typename Derived::Scalar& exponent) { + /** \returns an expression of the coefficient-wise power of \a x to the given constant \a exponent. + * + * \tparam ScalarExponent is the scalar type of \a exponent. It must be compatible with the scalar type of the given expression (\c Derived::Scalar). + * + * \sa ArrayBase::pow() + * + * \relates ArrayBase + */ +#ifdef EIGEN_PARSED_BY_DOXYGEN + template + inline const CwiseBinaryOp,Derived,Constant > + pow(const Eigen::ArrayBase& x, const ScalarExponent& exponent); +#else + template + inline typename internal::enable_if< !(internal::is_same::value) && EIGEN_SCALAR_BINARY_SUPPORTED(pow,typename Derived::Scalar,ScalarExponent), + const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(Derived,ScalarExponent,pow) >::type + pow(const Eigen::ArrayBase& x, const ScalarExponent& exponent) { return x.derived().pow(exponent); } template - inline const Eigen::CwiseBinaryOp, const Derived, const Derived> - pow(const Eigen::ArrayBase& x, const Eigen::ArrayBase& exponents) + inline const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(Derived,typename Derived::Scalar,pow) + pow(const Eigen::ArrayBase& x, const typename Derived::Scalar& exponent) { + return x.derived().pow(exponent); + } +#endif + + /** \returns an expression of the coefficient-wise power of \a x to the given array of \a exponents. + * + * This function computes the coefficient-wise power. + * + * Example: \include Cwise_array_power_array.cpp + * Output: \verbinclude Cwise_array_power_array.out + * + * \sa ArrayBase::pow() + * + * \relates ArrayBase + */ + template + inline const Eigen::CwiseBinaryOp, const Derived, const ExponentDerived> + pow(const Eigen::ArrayBase& x, const Eigen::ArrayBase& exponents) { - return Eigen::CwiseBinaryOp, const Derived, const Derived>( + return Eigen::CwiseBinaryOp, const Derived, const ExponentDerived>( x.derived(), exponents.derived() ); } - /** - * \brief Component-wise division of a scalar by array elements. - **/ - template - inline const Eigen::CwiseUnaryOp, const Derived> - operator/(const typename Derived::Scalar& s, const Eigen::ArrayBase& a) + /** \returns an expression of the coefficient-wise power of the scalar \a x to the given array of \a exponents. + * + * This function computes the coefficient-wise power between a scalar and an array of exponents. + * + * \tparam Scalar is the scalar type of \a x. It must be compatible with the scalar type of the given array expression (\c Derived::Scalar). + * + * Example: \include Cwise_scalar_power_array.cpp + * Output: \verbinclude Cwise_scalar_power_array.out + * + * \sa ArrayBase::pow() + * + * \relates ArrayBase + */ +#ifdef EIGEN_PARSED_BY_DOXYGEN + template + inline const CwiseBinaryOp,Constant,Derived> + pow(const Scalar& x,const Eigen::ArrayBase& x); +#else + template + inline typename internal::enable_if< !(internal::is_same::value) && EIGEN_SCALAR_BINARY_SUPPORTED(pow,Scalar,typename Derived::Scalar), + const EIGEN_SCALAR_BINARYOP_EXPR_RETURN_TYPE(Scalar,Derived,pow) >::type + pow(const Scalar& x, const Eigen::ArrayBase& exponents) { - return Eigen::CwiseUnaryOp, const Derived>( - a.derived(), - Eigen::internal::scalar_inverse_mult_op(s) - ); + return EIGEN_SCALAR_BINARYOP_EXPR_RETURN_TYPE(Scalar,Derived,pow)( + typename internal::plain_constant_type::type(exponents.rows(), exponents.cols(), x), exponents.derived() ); } + template + inline const EIGEN_SCALAR_BINARYOP_EXPR_RETURN_TYPE(typename Derived::Scalar,Derived,pow) + pow(const typename Derived::Scalar& x, const Eigen::ArrayBase& exponents) + { + return EIGEN_SCALAR_BINARYOP_EXPR_RETURN_TYPE(typename Derived::Scalar,Derived,pow)( + typename internal::plain_constant_type::type(exponents.rows(), exponents.cols(), x), exponents.derived() ); + } +#endif + + namespace internal { EIGEN_ARRAY_DECLARE_GLOBAL_EIGEN_UNARY(real,scalar_real_op) diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/IO.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/IO.h index 8d4bc59e..da7fd6cc 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/IO.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/IO.h @@ -49,7 +49,7 @@ std::ostream & print_matrix(std::ostream & s, const Derived& _m, const IOFormat& */ struct IOFormat { - /** Default contructor, see class IOFormat for the meaning of the parameters */ + /** Default constructor, see class IOFormat for the meaning of the parameters */ IOFormat(int _precision = StreamPrecision, int _flags = 0, const std::string& _coeffSeparator = " ", const std::string& _rowSeparator = "\n", const std::string& _rowPrefix="", const std::string& _rowSuffix="", @@ -57,6 +57,10 @@ struct IOFormat : matPrefix(_matPrefix), matSuffix(_matSuffix), rowPrefix(_rowPrefix), rowSuffix(_rowSuffix), rowSeparator(_rowSeparator), rowSpacer(""), coeffSeparator(_coeffSeparator), precision(_precision), flags(_flags) { + // TODO check if rowPrefix, rowSuffix or rowSeparator contains a newline + // don't add rowSpacer if columns are not to be aligned + if((flags & DontAlignCols)) + return; int i = int(matSuffix.length())-1; while (i>=0 && matSuffix[i]!='\n') { @@ -76,7 +80,7 @@ struct IOFormat * * \brief Pseudo expression providing matrix output with given format * - * \param ExpressionType the type of the object on which IO stream operations are performed + * \tparam ExpressionType the type of the object on which IO stream operations are performed * * This class represents an expression with stream operators controlled by a given IOFormat. * It is the return type of DenseBase::format() @@ -101,51 +105,23 @@ class WithFormat } protected: - const typename ExpressionType::Nested m_matrix; + typename ExpressionType::Nested m_matrix; IOFormat m_format; }; -/** \returns a WithFormat proxy object allowing to print a matrix the with given - * format \a fmt. - * - * See class IOFormat for some examples. - * - * \sa class IOFormat, class WithFormat - */ -template -inline const WithFormat -DenseBase::format(const IOFormat& fmt) const -{ - return WithFormat(derived(), fmt); -} - namespace internal { -template -struct significant_decimals_default_impl -{ - typedef typename NumTraits::Real RealScalar; - static inline int run() - { - using std::ceil; - using std::log; - return cast(ceil(-log(NumTraits::epsilon())/log(RealScalar(10)))); - } -}; - -template -struct significant_decimals_default_impl -{ - static inline int run() - { - return 0; - } -}; - +// NOTE: This helper is kept for backward compatibility with previous code specializing +// this internal::significant_decimals_impl structure. In the future we should directly +// call digits10() which has been introduced in July 2016 in 3.3. template struct significant_decimals_impl - : significant_decimals_default_impl::IsInteger> -{}; +{ + static inline int run() + { + return NumTraits::digits10(); + } +}; /** \internal * print the matrix \a _m to the output stream \a s using the output format \a fmt */ @@ -160,7 +136,6 @@ std::ostream & print_matrix(std::ostream & s, const Derived& _m, const IOFormat& typename Derived::Nested m = _m; typedef typename Derived::Scalar Scalar; - typedef typename Derived::Index Index; Index width = 0; diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/IndexedView.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/IndexedView.h new file mode 100644 index 00000000..8c57a277 --- /dev/null +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/IndexedView.h @@ -0,0 +1,207 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2017 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_INDEXED_VIEW_H +#define EIGEN_INDEXED_VIEW_H + +namespace Eigen { + +namespace internal { + +template +struct traits > + : traits +{ + enum { + RowsAtCompileTime = int(array_size::value), + ColsAtCompileTime = int(array_size::value), + MaxRowsAtCompileTime = RowsAtCompileTime != Dynamic ? int(RowsAtCompileTime) : int(traits::MaxRowsAtCompileTime), + MaxColsAtCompileTime = ColsAtCompileTime != Dynamic ? int(ColsAtCompileTime) : int(traits::MaxColsAtCompileTime), + + XprTypeIsRowMajor = (int(traits::Flags)&RowMajorBit) != 0, + IsRowMajor = (MaxRowsAtCompileTime==1&&MaxColsAtCompileTime!=1) ? 1 + : (MaxColsAtCompileTime==1&&MaxRowsAtCompileTime!=1) ? 0 + : XprTypeIsRowMajor, + + RowIncr = int(get_compile_time_incr::value), + ColIncr = int(get_compile_time_incr::value), + InnerIncr = IsRowMajor ? ColIncr : RowIncr, + OuterIncr = IsRowMajor ? RowIncr : ColIncr, + + HasSameStorageOrderAsXprType = (IsRowMajor == XprTypeIsRowMajor), + XprInnerStride = HasSameStorageOrderAsXprType ? int(inner_stride_at_compile_time::ret) : int(outer_stride_at_compile_time::ret), + XprOuterstride = HasSameStorageOrderAsXprType ? int(outer_stride_at_compile_time::ret) : int(inner_stride_at_compile_time::ret), + + InnerSize = XprTypeIsRowMajor ? ColsAtCompileTime : RowsAtCompileTime, + IsBlockAlike = InnerIncr==1 && OuterIncr==1, + IsInnerPannel = HasSameStorageOrderAsXprType && is_same,typename conditional::type>::value, + + InnerStrideAtCompileTime = InnerIncr<0 || InnerIncr==DynamicIndex || XprInnerStride==Dynamic ? Dynamic : XprInnerStride * InnerIncr, + OuterStrideAtCompileTime = OuterIncr<0 || OuterIncr==DynamicIndex || XprOuterstride==Dynamic ? Dynamic : XprOuterstride * OuterIncr, + + ReturnAsScalar = is_same::value && is_same::value, + ReturnAsBlock = (!ReturnAsScalar) && IsBlockAlike, + ReturnAsIndexedView = (!ReturnAsScalar) && (!ReturnAsBlock), + + // FIXME we deal with compile-time strides if and only if we have DirectAccessBit flag, + // but this is too strict regarding negative strides... + DirectAccessMask = (int(InnerIncr)!=UndefinedIncr && int(OuterIncr)!=UndefinedIncr && InnerIncr>=0 && OuterIncr>=0) ? DirectAccessBit : 0, + FlagsRowMajorBit = IsRowMajor ? RowMajorBit : 0, + FlagsLvalueBit = is_lvalue::value ? LvalueBit : 0, + Flags = (traits::Flags & (HereditaryBits | DirectAccessMask)) | FlagsLvalueBit | FlagsRowMajorBit + }; + + typedef Block BlockType; +}; + +} + +template +class IndexedViewImpl; + + +/** \class IndexedView + * \ingroup Core_Module + * + * \brief Expression of a non-sequential sub-matrix defined by arbitrary sequences of row and column indices + * + * \tparam XprType the type of the expression in which we are taking the intersections of sub-rows and sub-columns + * \tparam RowIndices the type of the object defining the sequence of row indices + * \tparam ColIndices the type of the object defining the sequence of column indices + * + * This class represents an expression of a sub-matrix (or sub-vector) defined as the intersection + * of sub-sets of rows and columns, that are themself defined by generic sequences of row indices \f$ \{r_0,r_1,..r_{m-1}\} \f$ + * and column indices \f$ \{c_0,c_1,..c_{n-1} \}\f$. Let \f$ A \f$ be the nested matrix, then the resulting matrix \f$ B \f$ has \c m + * rows and \c n columns, and its entries are given by: \f$ B(i,j) = A(r_i,c_j) \f$. + * + * The \c RowIndices and \c ColIndices types must be compatible with the following API: + * \code + * operator[](Index) const; + * Index size() const; + * \endcode + * + * Typical supported types thus include: + * - std::vector + * - std::valarray + * - std::array + * - Plain C arrays: int[N] + * - Eigen::ArrayXi + * - decltype(ArrayXi::LinSpaced(...)) + * - Any view/expressions of the previous types + * - Eigen::ArithmeticSequence + * - Eigen::internal::AllRange (helper for Eigen::all) + * - Eigen::internal::SingleRange (helper for single index) + * - etc. + * + * In typical usages of %Eigen, this class should never be used directly. It is the return type of + * DenseBase::operator()(const RowIndices&, const ColIndices&). + * + * \sa class Block + */ +template +class IndexedView : public IndexedViewImpl::StorageKind> +{ +public: + typedef typename IndexedViewImpl::StorageKind>::Base Base; + EIGEN_GENERIC_PUBLIC_INTERFACE(IndexedView) + EIGEN_INHERIT_ASSIGNMENT_OPERATORS(IndexedView) + + typedef typename internal::ref_selector::non_const_type MatrixTypeNested; + typedef typename internal::remove_all::type NestedExpression; + + template + IndexedView(XprType& xpr, const T0& rowIndices, const T1& colIndices) + : m_xpr(xpr), m_rowIndices(rowIndices), m_colIndices(colIndices) + {} + + /** \returns number of rows */ + Index rows() const { return internal::size(m_rowIndices); } + + /** \returns number of columns */ + Index cols() const { return internal::size(m_colIndices); } + + /** \returns the nested expression */ + const typename internal::remove_all::type& + nestedExpression() const { return m_xpr; } + + /** \returns the nested expression */ + typename internal::remove_reference::type& + nestedExpression() { return m_xpr.const_cast_derived(); } + + /** \returns a const reference to the object storing/generating the row indices */ + const RowIndices& rowIndices() const { return m_rowIndices; } + + /** \returns a const reference to the object storing/generating the column indices */ + const ColIndices& colIndices() const { return m_colIndices; } + +protected: + MatrixTypeNested m_xpr; + RowIndices m_rowIndices; + ColIndices m_colIndices; +}; + + +// Generic API dispatcher +template +class IndexedViewImpl + : public internal::generic_xpr_base >::type +{ +public: + typedef typename internal::generic_xpr_base >::type Base; +}; + +namespace internal { + + +template +struct unary_evaluator, IndexBased> + : evaluator_base > +{ + typedef IndexedView XprType; + + enum { + CoeffReadCost = evaluator::CoeffReadCost /* TODO + cost of row/col index */, + + Flags = (evaluator::Flags & (HereditaryBits /*| LinearAccessBit | DirectAccessBit*/)), + + Alignment = 0 + }; + + EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& xpr) : m_argImpl(xpr.nestedExpression()), m_xpr(xpr) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + return m_argImpl.coeff(m_xpr.rowIndices()[row], m_xpr.colIndices()[col]); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index row, Index col) + { + return m_argImpl.coeffRef(m_xpr.rowIndices()[row], m_xpr.colIndices()[col]); + } + +protected: + + evaluator m_argImpl; + const XprType& m_xpr; + +}; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_INDEXED_VIEW_H diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/Inverse.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/Inverse.h new file mode 100644 index 00000000..b76f0439 --- /dev/null +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/Inverse.h @@ -0,0 +1,118 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_INVERSE_H +#define EIGEN_INVERSE_H + +namespace Eigen { + +template class InverseImpl; + +namespace internal { + +template +struct traits > + : traits +{ + typedef typename XprType::PlainObject PlainObject; + typedef traits BaseTraits; + enum { + Flags = BaseTraits::Flags & RowMajorBit + }; +}; + +} // end namespace internal + +/** \class Inverse + * + * \brief Expression of the inverse of another expression + * + * \tparam XprType the type of the expression we are taking the inverse + * + * This class represents an abstract expression of A.inverse() + * and most of the time this is the only way it is used. + * + */ +template +class Inverse : public InverseImpl::StorageKind> +{ +public: + typedef typename XprType::StorageIndex StorageIndex; + typedef typename XprType::PlainObject PlainObject; + typedef typename XprType::Scalar Scalar; + typedef typename internal::ref_selector::type XprTypeNested; + typedef typename internal::remove_all::type XprTypeNestedCleaned; + typedef typename internal::ref_selector::type Nested; + typedef typename internal::remove_all::type NestedExpression; + + explicit EIGEN_DEVICE_FUNC Inverse(const XprType &xpr) + : m_xpr(xpr) + {} + + EIGEN_DEVICE_FUNC Index rows() const { return m_xpr.rows(); } + EIGEN_DEVICE_FUNC Index cols() const { return m_xpr.cols(); } + + EIGEN_DEVICE_FUNC const XprTypeNestedCleaned& nestedExpression() const { return m_xpr; } + +protected: + XprTypeNested m_xpr; +}; + +// Generic API dispatcher +template +class InverseImpl + : public internal::generic_xpr_base >::type +{ +public: + typedef typename internal::generic_xpr_base >::type Base; + typedef typename XprType::Scalar Scalar; +private: + + Scalar coeff(Index row, Index col) const; + Scalar coeff(Index i) const; +}; + +namespace internal { + +/** \internal + * \brief Default evaluator for Inverse expression. + * + * This default evaluator for Inverse expression simply evaluate the inverse into a temporary + * by a call to internal::call_assignment_no_alias. + * Therefore, inverse implementers only have to specialize Assignment, ...> for + * there own nested expression. + * + * \sa class Inverse + */ +template +struct unary_evaluator > + : public evaluator::PlainObject> +{ + typedef Inverse InverseType; + typedef typename InverseType::PlainObject PlainObject; + typedef evaluator Base; + + enum { Flags = Base::Flags | EvalBeforeNestingBit }; + + unary_evaluator(const InverseType& inv_xpr) + : m_result(inv_xpr.rows(), inv_xpr.cols()) + { + ::new (static_cast(this)) Base(m_result); + internal::call_assignment_no_alias(m_result, inv_xpr); + } + +protected: + PlainObject m_result; +}; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_INVERSE_H diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/Map.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/Map.h index f804c89d..06d19670 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/Map.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/Map.h @@ -13,13 +13,35 @@ namespace Eigen { +namespace internal { +template +struct traits > + : public traits +{ + typedef traits TraitsBase; + enum { + InnerStrideAtCompileTime = StrideType::InnerStrideAtCompileTime == 0 + ? int(PlainObjectType::InnerStrideAtCompileTime) + : int(StrideType::InnerStrideAtCompileTime), + OuterStrideAtCompileTime = StrideType::OuterStrideAtCompileTime == 0 + ? int(PlainObjectType::OuterStrideAtCompileTime) + : int(StrideType::OuterStrideAtCompileTime), + Alignment = int(MapOptions)&int(AlignedMask), + Flags0 = TraitsBase::Flags & (~NestByRefBit), + Flags = is_lvalue::value ? int(Flags0) : (int(Flags0) & ~LvalueBit) + }; +private: + enum { Options }; // Expressions don't have Options +}; +} + /** \class Map * \ingroup Core_Module * * \brief A matrix or vector expression mapping an existing array of data. * * \tparam PlainObjectType the equivalent matrix type of the mapped data - * \tparam MapOptions specifies whether the pointer is \c #Aligned, or \c #Unaligned. + * \tparam MapOptions specifies the pointer alignment in bytes. It can be: \c #Aligned128, , \c #Aligned64, \c #Aligned32, \c #Aligned16, \c #Aligned8 or \c #Unaligned. * The default is \c #Unaligned. * \tparam StrideType optionally specifies strides. By default, Map assumes the memory layout * of an ordinary, contiguous array. This can be overridden by specifying strides. @@ -63,44 +85,6 @@ namespace Eigen { * * \sa PlainObjectBase::Map(), \ref TopicStorageOrders */ - -namespace internal { -template -struct traits > - : public traits -{ - typedef traits TraitsBase; - typedef typename PlainObjectType::Index Index; - typedef typename PlainObjectType::Scalar Scalar; - enum { - InnerStrideAtCompileTime = StrideType::InnerStrideAtCompileTime == 0 - ? int(PlainObjectType::InnerStrideAtCompileTime) - : int(StrideType::InnerStrideAtCompileTime), - OuterStrideAtCompileTime = StrideType::OuterStrideAtCompileTime == 0 - ? int(PlainObjectType::OuterStrideAtCompileTime) - : int(StrideType::OuterStrideAtCompileTime), - HasNoInnerStride = InnerStrideAtCompileTime == 1, - HasNoOuterStride = StrideType::OuterStrideAtCompileTime == 0, - HasNoStride = HasNoInnerStride && HasNoOuterStride, - IsAligned = bool(EIGEN_ALIGN) && ((int(MapOptions)&Aligned)==Aligned), - IsDynamicSize = PlainObjectType::SizeAtCompileTime==Dynamic, - KeepsPacketAccess = bool(HasNoInnerStride) - && ( bool(IsDynamicSize) - || HasNoOuterStride - || ( OuterStrideAtCompileTime!=Dynamic - && ((static_cast(sizeof(Scalar))*OuterStrideAtCompileTime)%16)==0 ) ), - Flags0 = TraitsBase::Flags & (~NestByRefBit), - Flags1 = IsAligned ? (int(Flags0) | AlignedBit) : (int(Flags0) & ~AlignedBit), - Flags2 = (bool(HasNoStride) || bool(PlainObjectType::IsVectorAtCompileTime)) - ? int(Flags1) : int(Flags1 & ~LinearAccessBit), - Flags3 = is_lvalue::value ? int(Flags2) : (int(Flags2) & ~LvalueBit), - Flags = KeepsPacketAccess ? int(Flags3) : (int(Flags3) & ~PacketAccessBit) - }; -private: - enum { Options }; // Expressions don't have Options -}; -} - template class Map : public MapBase > { @@ -110,19 +94,17 @@ template class Ma EIGEN_DENSE_PUBLIC_INTERFACE(Map) typedef typename Base::PointerType PointerType; -#if EIGEN2_SUPPORT_STAGE <= STAGE30_FULL_EIGEN3_API - typedef const Scalar* PointerArgType; - inline PointerType cast_to_pointer_type(PointerArgType ptr) { return const_cast(ptr); } -#else typedef PointerType PointerArgType; + EIGEN_DEVICE_FUNC inline PointerType cast_to_pointer_type(PointerArgType ptr) { return ptr; } -#endif + EIGEN_DEVICE_FUNC inline Index innerStride() const { return StrideType::InnerStrideAtCompileTime != 0 ? m_stride.inner() : 1; } + EIGEN_DEVICE_FUNC inline Index outerStride() const { return StrideType::OuterStrideAtCompileTime != 0 ? m_stride.outer() @@ -134,10 +116,11 @@ template class Ma /** Constructor in the fixed-size case. * * \param dataPtr pointer to the array to map - * \param a_stride optional Stride object, passing the strides. + * \param stride optional Stride object, passing the strides. */ - inline Map(PointerArgType dataPtr, const StrideType& a_stride = StrideType()) - : Base(cast_to_pointer_type(dataPtr)), m_stride(a_stride) + EIGEN_DEVICE_FUNC + explicit inline Map(PointerArgType dataPtr, const StrideType& stride = StrideType()) + : Base(cast_to_pointer_type(dataPtr)), m_stride(stride) { PlainObjectType::Base::_check_template_params(); } @@ -145,11 +128,12 @@ template class Ma /** Constructor in the dynamic-size vector case. * * \param dataPtr pointer to the array to map - * \param a_size the size of the vector expression - * \param a_stride optional Stride object, passing the strides. + * \param size the size of the vector expression + * \param stride optional Stride object, passing the strides. */ - inline Map(PointerArgType dataPtr, Index a_size, const StrideType& a_stride = StrideType()) - : Base(cast_to_pointer_type(dataPtr), a_size), m_stride(a_stride) + EIGEN_DEVICE_FUNC + inline Map(PointerArgType dataPtr, Index size, const StrideType& stride = StrideType()) + : Base(cast_to_pointer_type(dataPtr), size), m_stride(stride) { PlainObjectType::Base::_check_template_params(); } @@ -157,12 +141,13 @@ template class Ma /** Constructor in the dynamic-size matrix case. * * \param dataPtr pointer to the array to map - * \param nbRows the number of rows of the matrix expression - * \param nbCols the number of columns of the matrix expression - * \param a_stride optional Stride object, passing the strides. + * \param rows the number of rows of the matrix expression + * \param cols the number of columns of the matrix expression + * \param stride optional Stride object, passing the strides. */ - inline Map(PointerArgType dataPtr, Index nbRows, Index nbCols, const StrideType& a_stride = StrideType()) - : Base(cast_to_pointer_type(dataPtr), nbRows, nbCols), m_stride(a_stride) + EIGEN_DEVICE_FUNC + inline Map(PointerArgType dataPtr, Index rows, Index cols, const StrideType& stride = StrideType()) + : Base(cast_to_pointer_type(dataPtr), rows, cols), m_stride(stride) { PlainObjectType::Base::_check_template_params(); } @@ -173,19 +158,6 @@ template class Ma StrideType m_stride; }; -template -inline Array<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols> - ::Array(const Scalar *data) -{ - this->_set_noalias(Eigen::Map(data)); -} - -template -inline Matrix<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols> - ::Matrix(const Scalar *data) -{ - this->_set_noalias(Eigen::Map(data)); -} } // end namespace Eigen diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/MapBase.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/MapBase.h index cebed2bb..020f939a 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/MapBase.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/MapBase.h @@ -12,15 +12,25 @@ #define EIGEN_MAPBASE_H #define EIGEN_STATIC_ASSERT_INDEX_BASED_ACCESS(Derived) \ - EIGEN_STATIC_ASSERT((int(internal::traits::Flags) & LinearAccessBit) || Derived::IsVectorAtCompileTime, \ + EIGEN_STATIC_ASSERT((int(internal::evaluator::Flags) & LinearAccessBit) || Derived::IsVectorAtCompileTime, \ YOU_ARE_TRYING_TO_USE_AN_INDEX_BASED_ACCESSOR_ON_AN_EXPRESSION_THAT_DOES_NOT_SUPPORT_THAT) namespace Eigen { -/** \class MapBase - * \ingroup Core_Module +/** \ingroup Core_Module * - * \brief Base class for Map and Block expression with direct access + * \brief Base class for dense Map and Block expression with direct access + * + * This base class provides the const low-level accessors (e.g. coeff, coeffRef) of dense + * Map and Block objects with direct access. + * Typical users do not have to directly deal with this class. + * + * This class can be extended by through the macro plugin \c EIGEN_MAPBASE_PLUGIN. + * See \link TopicCustomizing_Plugins customizing Eigen \endlink for details. + * + * The \c Derived class has to provide the following two methods describing the memory layout: + * \code Index innerStride() const; \endcode + * \code Index outerStride() const; \endcode * * \sa class Map, class Block */ @@ -37,7 +47,6 @@ template class MapBase }; typedef typename internal::traits::StorageKind StorageKind; - typedef typename internal::traits::Index Index; typedef typename internal::traits::Scalar Scalar; typedef typename internal::packet_traits::type PacketScalar; typedef typename NumTraits::Real RealScalar; @@ -76,8 +85,10 @@ template class MapBase typedef typename Base::CoeffReturnType CoeffReturnType; - inline Index rows() const { return m_rows.value(); } - inline Index cols() const { return m_cols.value(); } + /** \copydoc DenseBase::rows() */ + EIGEN_DEVICE_FUNC inline Index rows() const { return m_rows.value(); } + /** \copydoc DenseBase::cols() */ + EIGEN_DEVICE_FUNC inline Index cols() const { return m_cols.value(); } /** Returns a pointer to the first coefficient of the matrix or vector. * @@ -85,30 +96,39 @@ template class MapBase * * \sa innerStride(), outerStride() */ - inline const Scalar* data() const { return m_data; } + EIGEN_DEVICE_FUNC inline const Scalar* data() const { return m_data; } + /** \copydoc PlainObjectBase::coeff(Index,Index) const */ + EIGEN_DEVICE_FUNC inline const Scalar& coeff(Index rowId, Index colId) const { return m_data[colId * colStride() + rowId * rowStride()]; } + /** \copydoc PlainObjectBase::coeff(Index) const */ + EIGEN_DEVICE_FUNC inline const Scalar& coeff(Index index) const { EIGEN_STATIC_ASSERT_INDEX_BASED_ACCESS(Derived) return m_data[index * innerStride()]; } + /** \copydoc PlainObjectBase::coeffRef(Index,Index) const */ + EIGEN_DEVICE_FUNC inline const Scalar& coeffRef(Index rowId, Index colId) const { return this->m_data[colId * colStride() + rowId * rowStride()]; } + /** \copydoc PlainObjectBase::coeffRef(Index) const */ + EIGEN_DEVICE_FUNC inline const Scalar& coeffRef(Index index) const { EIGEN_STATIC_ASSERT_INDEX_BASED_ACCESS(Derived) return this->m_data[index * innerStride()]; } + /** \internal */ template inline PacketScalar packet(Index rowId, Index colId) const { @@ -116,6 +136,7 @@ template class MapBase (m_data + (colId * colStride() + rowId * rowStride())); } + /** \internal */ template inline PacketScalar packet(Index index) const { @@ -123,12 +144,16 @@ template class MapBase return internal::ploadt(m_data + index * innerStride()); } - inline MapBase(PointerType dataPtr) : m_data(dataPtr), m_rows(RowsAtCompileTime), m_cols(ColsAtCompileTime) + /** \internal Constructor for fixed size matrices or vectors */ + EIGEN_DEVICE_FUNC + explicit inline MapBase(PointerType dataPtr) : m_data(dataPtr), m_rows(RowsAtCompileTime), m_cols(ColsAtCompileTime) { EIGEN_STATIC_ASSERT_FIXED_SIZE(Derived) - checkSanity(); + checkSanity(); } + /** \internal Constructor for dynamically sized vectors */ + EIGEN_DEVICE_FUNC inline MapBase(PointerType dataPtr, Index vecSize) : m_data(dataPtr), m_rows(RowsAtCompileTime == Dynamic ? vecSize : Index(RowsAtCompileTime)), @@ -137,34 +162,56 @@ template class MapBase EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) eigen_assert(vecSize >= 0); eigen_assert(dataPtr == 0 || SizeAtCompileTime == Dynamic || SizeAtCompileTime == vecSize); - checkSanity(); + checkSanity(); } - inline MapBase(PointerType dataPtr, Index nbRows, Index nbCols) - : m_data(dataPtr), m_rows(nbRows), m_cols(nbCols) + /** \internal Constructor for dynamically sized matrices */ + EIGEN_DEVICE_FUNC + inline MapBase(PointerType dataPtr, Index rows, Index cols) + : m_data(dataPtr), m_rows(rows), m_cols(cols) { eigen_assert( (dataPtr == 0) - || ( nbRows >= 0 && (RowsAtCompileTime == Dynamic || RowsAtCompileTime == nbRows) - && nbCols >= 0 && (ColsAtCompileTime == Dynamic || ColsAtCompileTime == nbCols))); - checkSanity(); + || ( rows >= 0 && (RowsAtCompileTime == Dynamic || RowsAtCompileTime == rows) + && cols >= 0 && (ColsAtCompileTime == Dynamic || ColsAtCompileTime == cols))); + checkSanity(); } + #ifdef EIGEN_MAPBASE_PLUGIN + #include EIGEN_MAPBASE_PLUGIN + #endif + protected: - void checkSanity() const + template + EIGEN_DEVICE_FUNC + void checkSanity(typename internal::enable_if<(internal::traits::Alignment>0),void*>::type = 0) const { - EIGEN_STATIC_ASSERT(EIGEN_IMPLIES(internal::traits::Flags&PacketAccessBit, - internal::inner_stride_at_compile_time::ret==1), - PACKET_ACCESS_REQUIRES_TO_HAVE_INNER_STRIDE_FIXED_TO_1); - eigen_assert(EIGEN_IMPLIES(internal::traits::Flags&AlignedBit, (size_t(m_data) % 16) == 0) - && "data is not aligned"); +#if EIGEN_MAX_ALIGN_BYTES>0 + eigen_assert(( ((internal::UIntPtr(m_data) % internal::traits::Alignment) == 0) + || (cols() * rows() * innerStride() * sizeof(Scalar)) < internal::traits::Alignment ) && "data is not aligned"); +#endif } + template + EIGEN_DEVICE_FUNC + void checkSanity(typename internal::enable_if::Alignment==0,void*>::type = 0) const + {} + PointerType m_data; const internal::variable_if_dynamic m_rows; const internal::variable_if_dynamic m_cols; }; +/** \ingroup Core_Module + * + * \brief Base class for non-const dense Map and Block expression with direct access + * + * This base class provides the non-const low-level accessors (e.g. coeff and coeffRef) of + * dense Map and Block objects with direct access. + * It inherits MapBase which defines the const variant for reading specific entries. + * + * \sa class Map, class Block + */ template class MapBase : public MapBase { @@ -175,7 +222,7 @@ template class MapBase typedef typename Base::Scalar Scalar; typedef typename Base::PacketScalar PacketScalar; - typedef typename Base::Index Index; + typedef typename Base::StorageIndex StorageIndex; typedef typename Base::PointerType PointerType; using Base::derived; @@ -196,14 +243,18 @@ template class MapBase const Scalar >::type ScalarWithConstIfNotLvalue; + EIGEN_DEVICE_FUNC inline const Scalar* data() const { return this->m_data; } + EIGEN_DEVICE_FUNC inline ScalarWithConstIfNotLvalue* data() { return this->m_data; } // no const-cast here so non-const-correct code will give a compile error + EIGEN_DEVICE_FUNC inline ScalarWithConstIfNotLvalue& coeffRef(Index row, Index col) { return this->m_data[col * colStride() + row * rowStride()]; } + EIGEN_DEVICE_FUNC inline ScalarWithConstIfNotLvalue& coeffRef(Index index) { EIGEN_STATIC_ASSERT_INDEX_BASED_ACCESS(Derived) @@ -225,10 +276,11 @@ template class MapBase (this->m_data + index * innerStride(), val); } - explicit inline MapBase(PointerType dataPtr) : Base(dataPtr) {} - inline MapBase(PointerType dataPtr, Index vecSize) : Base(dataPtr, vecSize) {} - inline MapBase(PointerType dataPtr, Index nbRows, Index nbCols) : Base(dataPtr, nbRows, nbCols) {} + EIGEN_DEVICE_FUNC explicit inline MapBase(PointerType dataPtr) : Base(dataPtr) {} + EIGEN_DEVICE_FUNC inline MapBase(PointerType dataPtr, Index vecSize) : Base(dataPtr, vecSize) {} + EIGEN_DEVICE_FUNC inline MapBase(PointerType dataPtr, Index rows, Index cols) : Base(dataPtr, rows, cols) {} + EIGEN_DEVICE_FUNC Derived& operator=(const MapBase& other) { ReadOnlyMapBase::Base::operator=(other); diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/MathFunctions.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/MathFunctions.h index 2bfc5ebd..5ec6c395 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/MathFunctions.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/MathFunctions.h @@ -10,11 +10,24 @@ #ifndef EIGEN_MATHFUNCTIONS_H #define EIGEN_MATHFUNCTIONS_H +// source: http://www.geom.uiuc.edu/~huberty/math5337/groupe/digits.html +// TODO this should better be moved to NumTraits +#define EIGEN_PI 3.141592653589793238462643383279502884197169399375105820974944592307816406L + namespace Eigen { +// On WINCE, std::abs is defined for int only, so let's defined our own overloads: +// This issue has been confirmed with MSVC 2008 only, but the issue might exist for more recent versions too. +#if EIGEN_OS_WINCE && EIGEN_COMP_MSVC && EIGEN_COMP_MSVC<=1500 +long abs(long x) { return (labs(x)); } +double abs(double x) { return (fabs(x)); } +float abs(float x) { return (fabsf(x)); } +long double abs(long double x) { return (fabsl(x)); } +#endif + namespace internal { -/** \internal \struct global_math_functions_filtering_base +/** \internal \class global_math_functions_filtering_base * * What it does: * Defines a typedef 'type' as follows: @@ -62,6 +75,7 @@ template::IsComplex> struct real_default_impl { typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC static inline RealScalar run(const Scalar& x) { return x; @@ -72,6 +86,7 @@ template struct real_default_impl { typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC static inline RealScalar run(const Scalar& x) { using std::real; @@ -81,13 +96,25 @@ struct real_default_impl template struct real_impl : real_default_impl {}; +#ifdef __CUDA_ARCH__ +template +struct real_impl > +{ + typedef T RealScalar; + EIGEN_DEVICE_FUNC + static inline T run(const std::complex& x) + { + return x.real(); + } +}; +#endif + template struct real_retval { typedef typename NumTraits::Real type; }; - /**************************************************************************** * Implementation of imag * ****************************************************************************/ @@ -96,6 +123,7 @@ template::IsComplex> struct imag_default_impl { typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC static inline RealScalar run(const Scalar&) { return RealScalar(0); @@ -106,6 +134,7 @@ template struct imag_default_impl { typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC static inline RealScalar run(const Scalar& x) { using std::imag; @@ -115,6 +144,19 @@ struct imag_default_impl template struct imag_impl : imag_default_impl {}; +#ifdef __CUDA_ARCH__ +template +struct imag_impl > +{ + typedef T RealScalar; + EIGEN_DEVICE_FUNC + static inline T run(const std::complex& x) + { + return x.imag(); + } +}; +#endif + template struct imag_retval { @@ -129,10 +171,12 @@ template struct real_ref_impl { typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC static inline RealScalar& run(Scalar& x) { return reinterpret_cast(&x)[0]; } + EIGEN_DEVICE_FUNC static inline const RealScalar& run(const Scalar& x) { return reinterpret_cast(&x)[0]; @@ -153,10 +197,12 @@ template struct imag_ref_default_impl { typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC static inline RealScalar& run(Scalar& x) { return reinterpret_cast(&x)[1]; } + EIGEN_DEVICE_FUNC static inline const RealScalar& run(const Scalar& x) { return reinterpret_cast(&x)[1]; @@ -166,10 +212,12 @@ struct imag_ref_default_impl template struct imag_ref_default_impl { + EIGEN_DEVICE_FUNC static inline Scalar run(Scalar&) { return Scalar(0); } + EIGEN_DEVICE_FUNC static inline const Scalar run(const Scalar&) { return Scalar(0); @@ -192,6 +240,7 @@ struct imag_ref_retval template::IsComplex> struct conj_impl { + EIGEN_DEVICE_FUNC static inline Scalar run(const Scalar& x) { return x; @@ -201,6 +250,7 @@ struct conj_impl template struct conj_impl { + EIGEN_DEVICE_FUNC static inline Scalar run(const Scalar& x) { using std::conj; @@ -218,25 +268,39 @@ struct conj_retval * Implementation of abs2 * ****************************************************************************/ -template -struct abs2_impl +template +struct abs2_impl_default { typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC static inline RealScalar run(const Scalar& x) { return x*x; } }; -template -struct abs2_impl > +template +struct abs2_impl_default // IsComplex { - static inline RealScalar run(const std::complex& x) + typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC + static inline RealScalar run(const Scalar& x) { return real(x)*real(x) + imag(x)*imag(x); } }; +template +struct abs2_impl +{ + typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC + static inline RealScalar run(const Scalar& x) + { + return abs2_impl_default::IsComplex>::run(x); + } +}; + template struct abs2_retval { @@ -251,9 +315,10 @@ template struct norm1_default_impl { typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC static inline RealScalar run(const Scalar& x) { - using std::abs; + EIGEN_USING_STD_MATH(abs); return abs(real(x)) + abs(imag(x)); } }; @@ -261,9 +326,10 @@ struct norm1_default_impl template struct norm1_default_impl { + EIGEN_DEVICE_FUNC static inline Scalar run(const Scalar& x) { - using std::abs; + EIGEN_USING_STD_MATH(abs); return abs(x); } }; @@ -287,16 +353,22 @@ struct hypot_impl typedef typename NumTraits::Real RealScalar; static inline RealScalar run(const Scalar& x, const Scalar& y) { - using std::max; - using std::min; - using std::abs; - using std::sqrt; + EIGEN_USING_STD_MATH(abs); + EIGEN_USING_STD_MATH(sqrt); RealScalar _x = abs(x); RealScalar _y = abs(y); - RealScalar p = (max)(_x, _y); - if(p==RealScalar(0)) return 0; - RealScalar q = (min)(_x, _y); - RealScalar qp = q/p; + Scalar p, qp; + if(_x>_y) + { + p = _x; + qp = _y / p; + } + else + { + p = _y; + qp = _x / p; + } + if(p==RealScalar(0)) return RealScalar(0); return p * sqrt(RealScalar(1) + qp*qp); } }; @@ -314,6 +386,7 @@ struct hypot_retval template struct cast_impl { + EIGEN_DEVICE_FUNC static inline NewType run(const OldType& x) { return static_cast(x); @@ -323,48 +396,173 @@ struct cast_impl // here, for once, we're plainly returning NewType: we don't want cast to do weird things. template +EIGEN_DEVICE_FUNC inline NewType cast(const OldType& x) { return cast_impl::run(x); } /**************************************************************************** -* Implementation of atanh2 * +* Implementation of round * ****************************************************************************/ -template -struct atanh2_default_impl -{ - typedef Scalar retval; - typedef typename NumTraits::Real RealScalar; - static inline Scalar run(const Scalar& x, const Scalar& y) +#if EIGEN_HAS_CXX11_MATH + template + struct round_impl { + static inline Scalar run(const Scalar& x) + { + EIGEN_STATIC_ASSERT((!NumTraits::IsComplex), NUMERIC_TYPE_MUST_BE_REAL) + EIGEN_USING_STD_MATH(round); + return round(x); + } + }; +#else + template + struct round_impl { - using std::abs; - using std::log; - using std::sqrt; - Scalar z = x / y; - if (y == Scalar(0) || abs(z) > sqrt(NumTraits::epsilon())) - return RealScalar(0.5) * log((y + x) / (y - x)); - else - return z + z*z*z / RealScalar(3); - } -}; + static inline Scalar run(const Scalar& x) + { + EIGEN_STATIC_ASSERT((!NumTraits::IsComplex), NUMERIC_TYPE_MUST_BE_REAL) + EIGEN_USING_STD_MATH(floor); + EIGEN_USING_STD_MATH(ceil); + return (x > Scalar(0)) ? floor(x + Scalar(0.5)) : ceil(x - Scalar(0.5)); + } + }; +#endif template -struct atanh2_default_impl +struct round_retval { - static inline Scalar run(const Scalar&, const Scalar&) + typedef Scalar type; +}; + +/**************************************************************************** +* Implementation of arg * +****************************************************************************/ + +#if EIGEN_HAS_CXX11_MATH + template + struct arg_impl { + static inline Scalar run(const Scalar& x) + { + EIGEN_USING_STD_MATH(arg); + return arg(x); + } + }; +#else + template::IsComplex> + struct arg_default_impl + { + typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC + static inline RealScalar run(const Scalar& x) + { + return (x < Scalar(0)) ? Scalar(EIGEN_PI) : Scalar(0); } + }; + + template + struct arg_default_impl + { + typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC + static inline RealScalar run(const Scalar& x) + { + EIGEN_USING_STD_MATH(arg); + return arg(x); + } + }; + + template struct arg_impl : arg_default_impl {}; +#endif + +template +struct arg_retval +{ + typedef typename NumTraits::Real type; +}; + +/**************************************************************************** +* Implementation of expm1 * +****************************************************************************/ + +// This implementation is based on GSL Math's expm1. +namespace std_fallback { + // fallback expm1 implementation in case there is no expm1(Scalar) function in namespace of Scalar, + // or that there is no suitable std::expm1 function available. Implementation + // attributed to Kahan. See: http://www.plunk.org/~hatch/rightway.php. + template + EIGEN_DEVICE_FUNC inline Scalar expm1(const Scalar& x) { + EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar) + typedef typename NumTraits::Real RealScalar; + + EIGEN_USING_STD_MATH(exp); + Scalar u = exp(x); + if (u == Scalar(1)) { + return x; + } + Scalar um1 = u - RealScalar(1); + if (um1 == Scalar(-1)) { + return RealScalar(-1); + } + + EIGEN_USING_STD_MATH(log); + return (u - RealScalar(1)) * x / log(u); + } +} + +template +struct expm1_impl { + EIGEN_DEVICE_FUNC static inline Scalar run(const Scalar& x) { EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar) - return Scalar(0); + #if EIGEN_HAS_CXX11_MATH + using std::expm1; + #endif + using std_fallback::expm1; + return expm1(x); } }; -template -struct atanh2_impl : atanh2_default_impl::IsInteger> {}; template -struct atanh2_retval +struct expm1_retval +{ + typedef Scalar type; +}; + +/**************************************************************************** +* Implementation of log1p * +****************************************************************************/ + +namespace std_fallback { + // fallback log1p implementation in case there is no log1p(Scalar) function in namespace of Scalar, + // or that there is no suitable std::log1p function available + template + EIGEN_DEVICE_FUNC inline Scalar log1p(const Scalar& x) { + EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar) + typedef typename NumTraits::Real RealScalar; + EIGEN_USING_STD_MATH(log); + Scalar x1p = RealScalar(1) + x; + return ( x1p == Scalar(1) ) ? x : x * ( log(x1p) / (x1p - RealScalar(1)) ); + } +} + +template +struct log1p_impl { + EIGEN_DEVICE_FUNC static inline Scalar run(const Scalar& x) + { + EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar) + #if EIGEN_HAS_CXX11_MATH + using std::log1p; + #endif + using std_fallback::log1p; + return log1p(x); + } +}; + + +template +struct log1p_retval { typedef Scalar type; }; @@ -373,24 +571,26 @@ struct atanh2_retval * Implementation of pow * ****************************************************************************/ -template -struct pow_default_impl +template::IsInteger&&NumTraits::IsInteger> +struct pow_impl { - typedef Scalar retval; - static inline Scalar run(const Scalar& x, const Scalar& y) + //typedef Scalar retval; + typedef typename ScalarBinaryOpTraits >::ReturnType result_type; + static EIGEN_DEVICE_FUNC inline result_type run(const ScalarX& x, const ScalarY& y) { - using std::pow; + EIGEN_USING_STD_MATH(pow); return pow(x, y); } }; -template -struct pow_default_impl +template +struct pow_impl { - static inline Scalar run(Scalar x, Scalar y) + typedef ScalarX result_type; + static EIGEN_DEVICE_FUNC inline ScalarX run(ScalarX x, ScalarY y) { - Scalar res(1); - eigen_assert(!NumTraits::IsSigned || y >= 0); + ScalarX res(1); + eigen_assert(!NumTraits::IsSigned || y >= 0); if(y & 1) res *= x; y >>= 1; while(y) @@ -403,15 +603,6 @@ struct pow_default_impl } }; -template -struct pow_impl : pow_default_impl::IsInteger> {}; - -template -struct pow_retval -{ - typedef Scalar type; -}; - /**************************************************************************** * Implementation of random * ****************************************************************************/ @@ -447,48 +638,48 @@ struct random_default_impl }; enum { - floor_log2_terminate, - floor_log2_move_up, - floor_log2_move_down, - floor_log2_bogus + meta_floor_log2_terminate, + meta_floor_log2_move_up, + meta_floor_log2_move_down, + meta_floor_log2_bogus }; -template struct floor_log2_selector +template struct meta_floor_log2_selector { enum { middle = (lower + upper) / 2, - value = (upper <= lower + 1) ? int(floor_log2_terminate) - : (n < (1 << middle)) ? int(floor_log2_move_down) - : (n==0) ? int(floor_log2_bogus) - : int(floor_log2_move_up) + value = (upper <= lower + 1) ? int(meta_floor_log2_terminate) + : (n < (1 << middle)) ? int(meta_floor_log2_move_down) + : (n==0) ? int(meta_floor_log2_bogus) + : int(meta_floor_log2_move_up) }; }; template::value> -struct floor_log2 {}; + int selector = meta_floor_log2_selector::value> +struct meta_floor_log2 {}; template -struct floor_log2 +struct meta_floor_log2 { - enum { value = floor_log2::middle>::value }; + enum { value = meta_floor_log2::middle>::value }; }; template -struct floor_log2 +struct meta_floor_log2 { - enum { value = floor_log2::middle, upper>::value }; + enum { value = meta_floor_log2::middle, upper>::value }; }; template -struct floor_log2 +struct meta_floor_log2 { enum { value = (n >= ((unsigned int)(1) << (lower+1))) ? lower+1 : lower }; }; template -struct floor_log2 +struct meta_floor_log2 { // no value, error at compile time }; @@ -496,11 +687,24 @@ struct floor_log2 template struct random_default_impl { - typedef typename NumTraits::NonInteger NonInteger; - static inline Scalar run(const Scalar& x, const Scalar& y) { - return x + Scalar((NonInteger(y)-x+1) * std::rand() / (RAND_MAX + NonInteger(1))); + typedef typename conditional::IsSigned,std::ptrdiff_t,std::size_t>::type ScalarX; + if(y=x the result converted to an unsigned long is still correct. + std::size_t range = ScalarX(y)-ScalarX(x); + std::size_t offset = 0; + // rejection sampling + std::size_t divisor = 1; + std::size_t multiplier = 1; + if(range range); + return Scalar(ScalarX(x) + offset); } static inline Scalar run() @@ -508,7 +712,7 @@ struct random_default_impl #ifdef EIGEN_MAKING_DOCS return run(Scalar(NumTraits::IsSigned ? -10 : 0), Scalar(10)); #else - enum { rand_bits = floor_log2<(unsigned int)(RAND_MAX)+1>::value, + enum { rand_bits = meta_floor_log2<(unsigned int)(RAND_MAX)+1>::value, scalar_bits = sizeof(Scalar) * CHAR_BIT, shift = EIGEN_PLAIN_ENUM_MAX(0, int(rand_bits) - int(scalar_bits)), offset = NumTraits::IsSigned ? (1 << (EIGEN_PLAIN_ENUM_MIN(rand_bits,scalar_bits)-1)) : 0 @@ -545,97 +749,789 @@ inline EIGEN_MATHFUNC_RETVAL(random, Scalar) random() return EIGEN_MATHFUNC_IMPL(random, Scalar)::run(); } +// Implementatin of is* functions + +// std::is* do not work with fast-math and gcc, std::is* are available on MSVC 2013 and newer, as well as in clang. +#if (EIGEN_HAS_CXX11_MATH && !(EIGEN_COMP_GNUC_STRICT && __FINITE_MATH_ONLY__)) || (EIGEN_COMP_MSVC>=1800) || (EIGEN_COMP_CLANG) +#define EIGEN_USE_STD_FPCLASSIFY 1 +#else +#define EIGEN_USE_STD_FPCLASSIFY 0 +#endif + +template +EIGEN_DEVICE_FUNC +typename internal::enable_if::value,bool>::type +isnan_impl(const T&) { return false; } + +template +EIGEN_DEVICE_FUNC +typename internal::enable_if::value,bool>::type +isinf_impl(const T&) { return false; } + +template +EIGEN_DEVICE_FUNC +typename internal::enable_if::value,bool>::type +isfinite_impl(const T&) { return true; } + +template +EIGEN_DEVICE_FUNC +typename internal::enable_if<(!internal::is_integral::value)&&(!NumTraits::IsComplex),bool>::type +isfinite_impl(const T& x) +{ + #ifdef __CUDA_ARCH__ + return (::isfinite)(x); + #elif EIGEN_USE_STD_FPCLASSIFY + using std::isfinite; + return isfinite EIGEN_NOT_A_MACRO (x); + #else + return x<=NumTraits::highest() && x>=NumTraits::lowest(); + #endif +} + +template +EIGEN_DEVICE_FUNC +typename internal::enable_if<(!internal::is_integral::value)&&(!NumTraits::IsComplex),bool>::type +isinf_impl(const T& x) +{ + #ifdef __CUDA_ARCH__ + return (::isinf)(x); + #elif EIGEN_USE_STD_FPCLASSIFY + using std::isinf; + return isinf EIGEN_NOT_A_MACRO (x); + #else + return x>NumTraits::highest() || x::lowest(); + #endif +} + +template +EIGEN_DEVICE_FUNC +typename internal::enable_if<(!internal::is_integral::value)&&(!NumTraits::IsComplex),bool>::type +isnan_impl(const T& x) +{ + #ifdef __CUDA_ARCH__ + return (::isnan)(x); + #elif EIGEN_USE_STD_FPCLASSIFY + using std::isnan; + return isnan EIGEN_NOT_A_MACRO (x); + #else + return x != x; + #endif +} + +#if (!EIGEN_USE_STD_FPCLASSIFY) + +#if EIGEN_COMP_MSVC + +template EIGEN_DEVICE_FUNC bool isinf_msvc_helper(T x) +{ + return _fpclass(x)==_FPCLASS_NINF || _fpclass(x)==_FPCLASS_PINF; +} + +//MSVC defines a _isnan builtin function, but for double only +EIGEN_DEVICE_FUNC inline bool isnan_impl(const long double& x) { return _isnan(x)!=0; } +EIGEN_DEVICE_FUNC inline bool isnan_impl(const double& x) { return _isnan(x)!=0; } +EIGEN_DEVICE_FUNC inline bool isnan_impl(const float& x) { return _isnan(x)!=0; } + +EIGEN_DEVICE_FUNC inline bool isinf_impl(const long double& x) { return isinf_msvc_helper(x); } +EIGEN_DEVICE_FUNC inline bool isinf_impl(const double& x) { return isinf_msvc_helper(x); } +EIGEN_DEVICE_FUNC inline bool isinf_impl(const float& x) { return isinf_msvc_helper(x); } + +#elif (defined __FINITE_MATH_ONLY__ && __FINITE_MATH_ONLY__ && EIGEN_COMP_GNUC) + +#if EIGEN_GNUC_AT_LEAST(5,0) + #define EIGEN_TMP_NOOPT_ATTRIB EIGEN_DEVICE_FUNC inline __attribute__((optimize("no-finite-math-only"))) +#else + // NOTE the inline qualifier and noinline attribute are both needed: the former is to avoid linking issue (duplicate symbol), + // while the second prevent too aggressive optimizations in fast-math mode: + #define EIGEN_TMP_NOOPT_ATTRIB EIGEN_DEVICE_FUNC inline __attribute__((noinline,optimize("no-finite-math-only"))) +#endif + +template<> EIGEN_TMP_NOOPT_ATTRIB bool isnan_impl(const long double& x) { return __builtin_isnan(x); } +template<> EIGEN_TMP_NOOPT_ATTRIB bool isnan_impl(const double& x) { return __builtin_isnan(x); } +template<> EIGEN_TMP_NOOPT_ATTRIB bool isnan_impl(const float& x) { return __builtin_isnan(x); } +template<> EIGEN_TMP_NOOPT_ATTRIB bool isinf_impl(const double& x) { return __builtin_isinf(x); } +template<> EIGEN_TMP_NOOPT_ATTRIB bool isinf_impl(const float& x) { return __builtin_isinf(x); } +template<> EIGEN_TMP_NOOPT_ATTRIB bool isinf_impl(const long double& x) { return __builtin_isinf(x); } + +#undef EIGEN_TMP_NOOPT_ATTRIB + +#endif + +#endif + +// The following overload are defined at the end of this file +template EIGEN_DEVICE_FUNC bool isfinite_impl(const std::complex& x); +template EIGEN_DEVICE_FUNC bool isnan_impl(const std::complex& x); +template EIGEN_DEVICE_FUNC bool isinf_impl(const std::complex& x); + +template T generic_fast_tanh_float(const T& a_x); + } // end namespace internal /**************************************************************************** -* Generic math function * +* Generic math functions * ****************************************************************************/ namespace numext { +#if !defined(__CUDA_ARCH__) && !defined(__SYCL_DEVICE_ONLY__) +template +EIGEN_DEVICE_FUNC +EIGEN_ALWAYS_INLINE T mini(const T& x, const T& y) +{ + EIGEN_USING_STD_MATH(min); + return min EIGEN_NOT_A_MACRO (x,y); +} + +template +EIGEN_DEVICE_FUNC +EIGEN_ALWAYS_INLINE T maxi(const T& x, const T& y) +{ + EIGEN_USING_STD_MATH(max); + return max EIGEN_NOT_A_MACRO (x,y); +} + + +#elif defined(__SYCL_DEVICE_ONLY__) +template +EIGEN_ALWAYS_INLINE T mini(const T& x, const T& y) +{ + + return y < x ? y : x; +} + +template +EIGEN_ALWAYS_INLINE T maxi(const T& x, const T& y) +{ + + return x < y ? y : x; +} + +EIGEN_ALWAYS_INLINE int mini(const int& x, const int& y) +{ + return cl::sycl::min(x,y); +} + +EIGEN_ALWAYS_INLINE int maxi(const int& x, const int& y) +{ + return cl::sycl::max(x,y); +} + +EIGEN_ALWAYS_INLINE unsigned int mini(const unsigned int& x, const unsigned int& y) +{ + return cl::sycl::min(x,y); +} + +EIGEN_ALWAYS_INLINE unsigned int maxi(const unsigned int& x, const unsigned int& y) +{ + return cl::sycl::max(x,y); +} + +EIGEN_ALWAYS_INLINE long mini(const long & x, const long & y) +{ + return cl::sycl::min(x,y); +} + +EIGEN_ALWAYS_INLINE long maxi(const long & x, const long & y) +{ + return cl::sycl::max(x,y); +} + +EIGEN_ALWAYS_INLINE unsigned long mini(const unsigned long& x, const unsigned long& y) +{ + return cl::sycl::min(x,y); +} + +EIGEN_ALWAYS_INLINE unsigned long maxi(const unsigned long& x, const unsigned long& y) +{ + return cl::sycl::max(x,y); +} + + +EIGEN_ALWAYS_INLINE float mini(const float& x, const float& y) +{ + return cl::sycl::fmin(x,y); +} + +EIGEN_ALWAYS_INLINE float maxi(const float& x, const float& y) +{ + return cl::sycl::fmax(x,y); +} + +EIGEN_ALWAYS_INLINE double mini(const double& x, const double& y) +{ + return cl::sycl::fmin(x,y); +} + +EIGEN_ALWAYS_INLINE double maxi(const double& x, const double& y) +{ + return cl::sycl::fmax(x,y); +} + +#else +template +EIGEN_DEVICE_FUNC +EIGEN_ALWAYS_INLINE T mini(const T& x, const T& y) +{ + return y < x ? y : x; +} +template<> +EIGEN_DEVICE_FUNC +EIGEN_ALWAYS_INLINE float mini(const float& x, const float& y) +{ + return fminf(x, y); +} +template +EIGEN_DEVICE_FUNC +EIGEN_ALWAYS_INLINE T maxi(const T& x, const T& y) +{ + return x < y ? y : x; +} +template<> +EIGEN_DEVICE_FUNC +EIGEN_ALWAYS_INLINE float maxi(const float& x, const float& y) +{ + return fmaxf(x, y); +} +#endif + + template +EIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(real, Scalar) real(const Scalar& x) { return EIGEN_MATHFUNC_IMPL(real, Scalar)::run(x); -} +} template +EIGEN_DEVICE_FUNC inline typename internal::add_const_on_value_type< EIGEN_MATHFUNC_RETVAL(real_ref, Scalar) >::type real_ref(const Scalar& x) { return internal::real_ref_impl::run(x); } template +EIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(real_ref, Scalar) real_ref(Scalar& x) { return EIGEN_MATHFUNC_IMPL(real_ref, Scalar)::run(x); } template +EIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(imag, Scalar) imag(const Scalar& x) { return EIGEN_MATHFUNC_IMPL(imag, Scalar)::run(x); } template +EIGEN_DEVICE_FUNC +inline EIGEN_MATHFUNC_RETVAL(arg, Scalar) arg(const Scalar& x) +{ + return EIGEN_MATHFUNC_IMPL(arg, Scalar)::run(x); +} + +template +EIGEN_DEVICE_FUNC inline typename internal::add_const_on_value_type< EIGEN_MATHFUNC_RETVAL(imag_ref, Scalar) >::type imag_ref(const Scalar& x) { return internal::imag_ref_impl::run(x); } template +EIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(imag_ref, Scalar) imag_ref(Scalar& x) { return EIGEN_MATHFUNC_IMPL(imag_ref, Scalar)::run(x); } template +EIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(conj, Scalar) conj(const Scalar& x) { return EIGEN_MATHFUNC_IMPL(conj, Scalar)::run(x); } template +EIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(abs2, Scalar) abs2(const Scalar& x) { return EIGEN_MATHFUNC_IMPL(abs2, Scalar)::run(x); } template +EIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(norm1, Scalar) norm1(const Scalar& x) { return EIGEN_MATHFUNC_IMPL(norm1, Scalar)::run(x); } template +EIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(hypot, Scalar) hypot(const Scalar& x, const Scalar& y) { return EIGEN_MATHFUNC_IMPL(hypot, Scalar)::run(x, y); } template -inline EIGEN_MATHFUNC_RETVAL(atanh2, Scalar) atanh2(const Scalar& x, const Scalar& y) +EIGEN_DEVICE_FUNC +inline EIGEN_MATHFUNC_RETVAL(log1p, Scalar) log1p(const Scalar& x) { - return EIGEN_MATHFUNC_IMPL(atanh2, Scalar)::run(x, y); + return EIGEN_MATHFUNC_IMPL(log1p, Scalar)::run(x); } +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float log1p(float x) { return cl::sycl::log1p(x); } +EIGEN_ALWAYS_INLINE double log1p(double x) { return cl::sycl::log1p(x); } +#endif // defined(__SYCL_DEVICE_ONLY__) + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float log1p(const float &x) { return ::log1pf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double log1p(const double &x) { return ::log1p(x); } +#endif + +template +EIGEN_DEVICE_FUNC +inline typename internal::pow_impl::result_type pow(const ScalarX& x, const ScalarY& y) +{ + return internal::pow_impl::run(x, y); +} + +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float pow(float x, float y) { return cl::sycl::pow(x, y); } +EIGEN_ALWAYS_INLINE double pow(double x, double y) { return cl::sycl::pow(x, y); } +#endif // defined(__SYCL_DEVICE_ONLY__) + +template EIGEN_DEVICE_FUNC bool (isnan) (const T &x) { return internal::isnan_impl(x); } +template EIGEN_DEVICE_FUNC bool (isinf) (const T &x) { return internal::isinf_impl(x); } +template EIGEN_DEVICE_FUNC bool (isfinite)(const T &x) { return internal::isfinite_impl(x); } + +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float isnan(float x) { return cl::sycl::isnan(x); } +EIGEN_ALWAYS_INLINE double isnan(double x) { return cl::sycl::isnan(x); } +EIGEN_ALWAYS_INLINE float isinf(float x) { return cl::sycl::isinf(x); } +EIGEN_ALWAYS_INLINE double isinf(double x) { return cl::sycl::isinf(x); } +EIGEN_ALWAYS_INLINE float isfinite(float x) { return cl::sycl::isfinite(x); } +EIGEN_ALWAYS_INLINE double isfinite(double x) { return cl::sycl::isfinite(x); } +#endif // defined(__SYCL_DEVICE_ONLY__) + template -inline EIGEN_MATHFUNC_RETVAL(pow, Scalar) pow(const Scalar& x, const Scalar& y) +EIGEN_DEVICE_FUNC +inline EIGEN_MATHFUNC_RETVAL(round, Scalar) round(const Scalar& x) { - return EIGEN_MATHFUNC_IMPL(pow, Scalar)::run(x, y); + return EIGEN_MATHFUNC_IMPL(round, Scalar)::run(x); } -// std::isfinite is non standard, so let's define our own version, -// even though it is not very efficient. -template bool (isfinite)(const T& x) +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float round(float x) { return cl::sycl::round(x); } +EIGEN_ALWAYS_INLINE double round(double x) { return cl::sycl::round(x); } +#endif // defined(__SYCL_DEVICE_ONLY__) + +template +EIGEN_DEVICE_FUNC +T (floor)(const T& x) { - return x::highest() && x>NumTraits::lowest(); + EIGEN_USING_STD_MATH(floor); + return floor(x); } +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float floor(float x) { return cl::sycl::floor(x); } +EIGEN_ALWAYS_INLINE double floor(double x) { return cl::sycl::floor(x); } +#endif // defined(__SYCL_DEVICE_ONLY__) + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float floor(const float &x) { return ::floorf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double floor(const double &x) { return ::floor(x); } +#endif + +template +EIGEN_DEVICE_FUNC +T (ceil)(const T& x) +{ + EIGEN_USING_STD_MATH(ceil); + return ceil(x); +} + +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float ceil(float x) { return cl::sycl::ceil(x); } +EIGEN_ALWAYS_INLINE double ceil(double x) { return cl::sycl::ceil(x); } +#endif // defined(__SYCL_DEVICE_ONLY__) + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float ceil(const float &x) { return ::ceilf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double ceil(const double &x) { return ::ceil(x); } +#endif + + +/** Log base 2 for 32 bits positive integers. + * Conveniently returns 0 for x==0. */ +inline int log2(int x) +{ + eigen_assert(x>=0); + unsigned int v(x); + static const int table[32] = { 0, 9, 1, 10, 13, 21, 2, 29, 11, 14, 16, 18, 22, 25, 3, 30, 8, 12, 20, 28, 15, 17, 24, 7, 19, 27, 23, 6, 26, 5, 4, 31 }; + v |= v >> 1; + v |= v >> 2; + v |= v >> 4; + v |= v >> 8; + v |= v >> 16; + return table[(v * 0x07C4ACDDU) >> 27]; +} + +/** \returns the square root of \a x. + * + * It is essentially equivalent to \code using std::sqrt; return sqrt(x); \endcode, + * but slightly faster for float/double and some compilers (e.g., gcc), thanks to + * specializations when SSE is enabled. + * + * It's usage is justified in performance critical functions, like norm/normalize. + */ +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T sqrt(const T &x) +{ + EIGEN_USING_STD_MATH(sqrt); + return sqrt(x); +} + +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float sqrt(float x) { return cl::sycl::sqrt(x); } +EIGEN_ALWAYS_INLINE double sqrt(double x) { return cl::sycl::sqrt(x); } +#endif // defined(__SYCL_DEVICE_ONLY__) + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T log(const T &x) { + EIGEN_USING_STD_MATH(log); + return log(x); +} + +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float log(float x) { return cl::sycl::log(x); } +EIGEN_ALWAYS_INLINE double log(double x) { return cl::sycl::log(x); } +#endif // defined(__SYCL_DEVICE_ONLY__) + + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float log(const float &x) { return ::logf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double log(const double &x) { return ::log(x); } +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +typename NumTraits::Real abs(const T &x) { + EIGEN_USING_STD_MATH(abs); + return abs(x); +} + +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float abs(float x) { return cl::sycl::fabs(x); } +EIGEN_ALWAYS_INLINE double abs(double x) { return cl::sycl::fabs(x); } +#endif // defined(__SYCL_DEVICE_ONLY__) + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float abs(const float &x) { return ::fabsf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double abs(const double &x) { return ::fabs(x); } + +template <> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float abs(const std::complex& x) { + return ::hypotf(x.real(), x.imag()); +} + +template <> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double abs(const std::complex& x) { + return ::hypot(x.real(), x.imag()); +} +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T exp(const T &x) { + EIGEN_USING_STD_MATH(exp); + return exp(x); +} + +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float exp(float x) { return cl::sycl::exp(x); } +EIGEN_ALWAYS_INLINE double exp(double x) { return cl::sycl::exp(x); } +#endif // defined(__SYCL_DEVICE_ONLY__) + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float exp(const float &x) { return ::expf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double exp(const double &x) { return ::exp(x); } +#endif + +template +EIGEN_DEVICE_FUNC +inline EIGEN_MATHFUNC_RETVAL(expm1, Scalar) expm1(const Scalar& x) +{ + return EIGEN_MATHFUNC_IMPL(expm1, Scalar)::run(x); +} + +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float expm1(float x) { return cl::sycl::expm1(x); } +EIGEN_ALWAYS_INLINE double expm1(double x) { return cl::sycl::expm1(x); } +#endif // defined(__SYCL_DEVICE_ONLY__) + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float expm1(const float &x) { return ::expm1f(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double expm1(const double &x) { return ::expm1(x); } +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T cos(const T &x) { + EIGEN_USING_STD_MATH(cos); + return cos(x); +} + +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float cos(float x) { return cl::sycl::cos(x); } +EIGEN_ALWAYS_INLINE double cos(double x) { return cl::sycl::cos(x); } +#endif // defined(__SYCL_DEVICE_ONLY__) + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float cos(const float &x) { return ::cosf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double cos(const double &x) { return ::cos(x); } +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T sin(const T &x) { + EIGEN_USING_STD_MATH(sin); + return sin(x); +} + +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float sin(float x) { return cl::sycl::sin(x); } +EIGEN_ALWAYS_INLINE double sin(double x) { return cl::sycl::sin(x); } +#endif // defined(__SYCL_DEVICE_ONLY__) + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float sin(const float &x) { return ::sinf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double sin(const double &x) { return ::sin(x); } +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T tan(const T &x) { + EIGEN_USING_STD_MATH(tan); + return tan(x); +} + +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float tan(float x) { return cl::sycl::tan(x); } +EIGEN_ALWAYS_INLINE double tan(double x) { return cl::sycl::tan(x); } +#endif // defined(__SYCL_DEVICE_ONLY__) + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float tan(const float &x) { return ::tanf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double tan(const double &x) { return ::tan(x); } +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T acos(const T &x) { + EIGEN_USING_STD_MATH(acos); + return acos(x); +} + +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float acos(float x) { return cl::sycl::acos(x); } +EIGEN_ALWAYS_INLINE double acos(double x) { return cl::sycl::acos(x); } +#endif // defined(__SYCL_DEVICE_ONLY__) + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float acos(const float &x) { return ::acosf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double acos(const double &x) { return ::acos(x); } +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T asin(const T &x) { + EIGEN_USING_STD_MATH(asin); + return asin(x); +} + +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float asin(float x) { return cl::sycl::asin(x); } +EIGEN_ALWAYS_INLINE double asin(double x) { return cl::sycl::asin(x); } +#endif // defined(__SYCL_DEVICE_ONLY__) + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float asin(const float &x) { return ::asinf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double asin(const double &x) { return ::asin(x); } +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T atan(const T &x) { + EIGEN_USING_STD_MATH(atan); + return atan(x); +} + +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float atan(float x) { return cl::sycl::atan(x); } +EIGEN_ALWAYS_INLINE double atan(double x) { return cl::sycl::atan(x); } +#endif // defined(__SYCL_DEVICE_ONLY__) + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float atan(const float &x) { return ::atanf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double atan(const double &x) { return ::atan(x); } +#endif + + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T cosh(const T &x) { + EIGEN_USING_STD_MATH(cosh); + return cosh(x); +} + +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float cosh(float x) { return cl::sycl::cosh(x); } +EIGEN_ALWAYS_INLINE double cosh(double x) { return cl::sycl::cosh(x); } +#endif // defined(__SYCL_DEVICE_ONLY__) + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float cosh(const float &x) { return ::coshf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double cosh(const double &x) { return ::cosh(x); } +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T sinh(const T &x) { + EIGEN_USING_STD_MATH(sinh); + return sinh(x); +} + +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float sinh(float x) { return cl::sycl::sinh(x); } +EIGEN_ALWAYS_INLINE double sinh(double x) { return cl::sycl::sinh(x); } +#endif // defined(__SYCL_DEVICE_ONLY__) + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float sinh(const float &x) { return ::sinhf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double sinh(const double &x) { return ::sinh(x); } +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T tanh(const T &x) { + EIGEN_USING_STD_MATH(tanh); + return tanh(x); +} + +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float tanh(float x) { return cl::sycl::tanh(x); } +EIGEN_ALWAYS_INLINE double tanh(double x) { return cl::sycl::tanh(x); } +#elif (!defined(__CUDACC__)) && EIGEN_FAST_MATH +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float tanh(float x) { return internal::generic_fast_tanh_float(x); } +#endif + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float tanh(const float &x) { return ::tanhf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double tanh(const double &x) { return ::tanh(x); } +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T fmod(const T& a, const T& b) { + EIGEN_USING_STD_MATH(fmod); + return fmod(a, b); +} + +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float fmod(float x, float y) { return cl::sycl::fmod(x, y); } +EIGEN_ALWAYS_INLINE double fmod(double x, double y) { return cl::sycl::fmod(x, y); } +#endif // defined(__SYCL_DEVICE_ONLY__) + +#ifdef __CUDACC__ +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float fmod(const float& a, const float& b) { + return ::fmodf(a, b); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double fmod(const double& a, const double& b) { + return ::fmod(a, b); +} +#endif + } // end namespace numext namespace internal { +template +EIGEN_DEVICE_FUNC bool isfinite_impl(const std::complex& x) +{ + return (numext::isfinite)(numext::real(x)) && (numext::isfinite)(numext::imag(x)); +} + +template +EIGEN_DEVICE_FUNC bool isnan_impl(const std::complex& x) +{ + return (numext::isnan)(numext::real(x)) || (numext::isnan)(numext::imag(x)); +} + +template +EIGEN_DEVICE_FUNC bool isinf_impl(const std::complex& x) +{ + return ((numext::isinf)(numext::real(x)) || (numext::isinf)(numext::imag(x))) && (!(numext::isnan)(x)); +} + /**************************************************************************** * Implementation of fuzzy comparisons * ****************************************************************************/ @@ -649,18 +1545,17 @@ template struct scalar_fuzzy_default_impl { typedef typename NumTraits::Real RealScalar; - template + template EIGEN_DEVICE_FUNC static inline bool isMuchSmallerThan(const Scalar& x, const OtherScalar& y, const RealScalar& prec) { - using std::abs; - return abs(x) <= abs(y) * prec; + return numext::abs(x) <= numext::abs(y) * prec; } + EIGEN_DEVICE_FUNC static inline bool isApprox(const Scalar& x, const Scalar& y, const RealScalar& prec) { - using std::min; - using std::abs; - return abs(x - y) <= (min)(abs(x), abs(y)) * prec; + return numext::abs(x - y) <= numext::mini(numext::abs(x), numext::abs(y)) * prec; } + EIGEN_DEVICE_FUNC static inline bool isApproxOrLessThan(const Scalar& x, const Scalar& y, const RealScalar& prec) { return x <= y || isApprox(x, y, prec); @@ -671,15 +1566,17 @@ template struct scalar_fuzzy_default_impl { typedef typename NumTraits::Real RealScalar; - template + template EIGEN_DEVICE_FUNC static inline bool isMuchSmallerThan(const Scalar& x, const Scalar&, const RealScalar&) { return x == Scalar(0); } + EIGEN_DEVICE_FUNC static inline bool isApprox(const Scalar& x, const Scalar& y, const RealScalar&) { return x == y; } + EIGEN_DEVICE_FUNC static inline bool isApproxOrLessThan(const Scalar& x, const Scalar& y, const RealScalar&) { return x <= y; @@ -690,38 +1587,38 @@ template struct scalar_fuzzy_default_impl { typedef typename NumTraits::Real RealScalar; - template + template EIGEN_DEVICE_FUNC static inline bool isMuchSmallerThan(const Scalar& x, const OtherScalar& y, const RealScalar& prec) { return numext::abs2(x) <= numext::abs2(y) * prec * prec; } + EIGEN_DEVICE_FUNC static inline bool isApprox(const Scalar& x, const Scalar& y, const RealScalar& prec) { - using std::min; - return numext::abs2(x - y) <= (min)(numext::abs2(x), numext::abs2(y)) * prec * prec; + return numext::abs2(x - y) <= numext::mini(numext::abs2(x), numext::abs2(y)) * prec * prec; } }; template struct scalar_fuzzy_impl : scalar_fuzzy_default_impl::IsComplex, NumTraits::IsInteger> {}; -template +template EIGEN_DEVICE_FUNC inline bool isMuchSmallerThan(const Scalar& x, const OtherScalar& y, - typename NumTraits::Real precision = NumTraits::dummy_precision()) + const typename NumTraits::Real &precision = NumTraits::dummy_precision()) { return scalar_fuzzy_impl::template isMuchSmallerThan(x, y, precision); } -template +template EIGEN_DEVICE_FUNC inline bool isApprox(const Scalar& x, const Scalar& y, - typename NumTraits::Real precision = NumTraits::dummy_precision()) + const typename NumTraits::Real &precision = NumTraits::dummy_precision()) { return scalar_fuzzy_impl::isApprox(x, y, precision); } -template +template EIGEN_DEVICE_FUNC inline bool isApproxOrLessThan(const Scalar& x, const Scalar& y, - typename NumTraits::Real precision = NumTraits::dummy_precision()) + const typename NumTraits::Real &precision = NumTraits::dummy_precision()) { return scalar_fuzzy_impl::isApproxOrLessThan(x, y, precision); } @@ -741,26 +1638,28 @@ template<> struct random_impl template<> struct scalar_fuzzy_impl { typedef bool RealScalar; - - template + + template EIGEN_DEVICE_FUNC static inline bool isMuchSmallerThan(const bool& x, const bool&, const bool&) { return !x; } - + + EIGEN_DEVICE_FUNC static inline bool isApprox(bool x, bool y, bool) { return x == y; } + EIGEN_DEVICE_FUNC static inline bool isApproxOrLessThan(const bool& x, const bool& y, const bool&) { return (!x) || y; } - + }; - + } // end namespace internal } // end namespace Eigen diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/MathFunctionsImpl.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/MathFunctionsImpl.h new file mode 100644 index 00000000..ae1386b4 --- /dev/null +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/MathFunctionsImpl.h @@ -0,0 +1,73 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Pedro Gonnet (pedro.gonnet@gmail.com) +// Copyright (C) 2016 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_MATHFUNCTIONSIMPL_H +#define EIGEN_MATHFUNCTIONSIMPL_H + +namespace Eigen { + +namespace internal { + +/** \internal \returns the hyperbolic tan of \a a (coeff-wise) + Doesn't do anything fancy, just a 13/6-degree rational interpolant which + is accurate up to a couple of ulp in the range [-9, 9], outside of which + the tanh(x) = +/-1. + + This implementation works on both scalars and packets. +*/ +template +T generic_fast_tanh_float(const T& a_x) +{ + // Clamp the inputs to the range [-9, 9] since anything outside + // this range is +/-1.0f in single-precision. + const T plus_9 = pset1(9.f); + const T minus_9 = pset1(-9.f); + const T x = pmax(pmin(a_x, plus_9), minus_9); + // The monomial coefficients of the numerator polynomial (odd). + const T alpha_1 = pset1(4.89352455891786e-03f); + const T alpha_3 = pset1(6.37261928875436e-04f); + const T alpha_5 = pset1(1.48572235717979e-05f); + const T alpha_7 = pset1(5.12229709037114e-08f); + const T alpha_9 = pset1(-8.60467152213735e-11f); + const T alpha_11 = pset1(2.00018790482477e-13f); + const T alpha_13 = pset1(-2.76076847742355e-16f); + + // The monomial coefficients of the denominator polynomial (even). + const T beta_0 = pset1(4.89352518554385e-03f); + const T beta_2 = pset1(2.26843463243900e-03f); + const T beta_4 = pset1(1.18534705686654e-04f); + const T beta_6 = pset1(1.19825839466702e-06f); + + // Since the polynomials are odd/even, we need x^2. + const T x2 = pmul(x, x); + + // Evaluate the numerator polynomial p. + T p = pmadd(x2, alpha_13, alpha_11); + p = pmadd(x2, p, alpha_9); + p = pmadd(x2, p, alpha_7); + p = pmadd(x2, p, alpha_5); + p = pmadd(x2, p, alpha_3); + p = pmadd(x2, p, alpha_1); + p = pmul(x, p); + + // Evaluate the denominator polynomial p. + T q = pmadd(x2, beta_6, beta_4); + q = pmadd(x2, q, beta_2); + q = pmadd(x2, q, beta_0); + + // Divide the numerator by the denominator. + return pdiv(p, q); +} + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_MATHFUNCTIONSIMPL_H diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/Matrix.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/Matrix.h index d7d0b5b9..90c336d8 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/Matrix.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/Matrix.h @@ -13,6 +13,45 @@ namespace Eigen { +namespace internal { +template +struct traits > +{ +private: + enum { size = internal::size_at_compile_time<_Rows,_Cols>::ret }; + typedef typename find_best_packet<_Scalar,size>::type PacketScalar; + enum { + row_major_bit = _Options&RowMajor ? RowMajorBit : 0, + is_dynamic_size_storage = _MaxRows==Dynamic || _MaxCols==Dynamic, + max_size = is_dynamic_size_storage ? Dynamic : _MaxRows*_MaxCols, + default_alignment = compute_default_alignment<_Scalar,max_size>::value, + actual_alignment = ((_Options&DontAlign)==0) ? default_alignment : 0, + required_alignment = unpacket_traits::alignment, + packet_access_bit = (packet_traits<_Scalar>::Vectorizable && (EIGEN_UNALIGNED_VECTORIZE || (actual_alignment>=required_alignment))) ? PacketAccessBit : 0 + }; + +public: + typedef _Scalar Scalar; + typedef Dense StorageKind; + typedef Eigen::Index StorageIndex; + typedef MatrixXpr XprKind; + enum { + RowsAtCompileTime = _Rows, + ColsAtCompileTime = _Cols, + MaxRowsAtCompileTime = _MaxRows, + MaxColsAtCompileTime = _MaxCols, + Flags = compute_matrix_flags<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>::ret, + Options = _Options, + InnerStrideAtCompileTime = 1, + OuterStrideAtCompileTime = (Options&RowMajor) ? ColsAtCompileTime : RowsAtCompileTime, + + // FIXME, the following flag in only used to define NeedsToAlign in PlainObjectBase + EvaluatorFlags = LinearAccessBit | DirectAccessBit | packet_access_bit | row_major_bit, + Alignment = actual_alignment + }; +}; +} + /** \class Matrix * \ingroup Core_Module * @@ -24,13 +63,13 @@ namespace Eigen { * The %Matrix class encompasses \em both fixed-size and dynamic-size objects (\ref fixedsize "note"). * * The first three template parameters are required: - * \tparam _Scalar \anchor matrix_tparam_scalar Numeric type, e.g. float, double, int or std::complex. - * User defined sclar types are supported as well (see \ref user_defined_scalars "here"). + * \tparam _Scalar Numeric type, e.g. float, double, int or std::complex. + * User defined scalar types are supported as well (see \ref user_defined_scalars "here"). * \tparam _Rows Number of rows, or \b Dynamic * \tparam _Cols Number of columns, or \b Dynamic * * The remaining template parameters are optional -- in most cases you don't have to worry about them. - * \tparam _Options \anchor matrix_tparam_options A combination of either \b #RowMajor or \b #ColMajor, and of either + * \tparam _Options A combination of either \b #RowMajor or \b #ColMajor, and of either * \b #AutoAlign or \b #DontAlign. * The former controls \ref TopicStorageOrders "storage order", and defaults to column-major. The latter controls alignment, which is required * for vectorization. It defaults to aligning matrices except for fixed sizes that aren't a multiple of the packet size. @@ -67,7 +106,7 @@ namespace Eigen { * \endcode * * This class can be extended with the help of the plugin mechanism described on the page - * \ref TopicCustomizingEigen by defining the preprocessor symbol \c EIGEN_MATRIX_PLUGIN. + * \ref TopicCustomizing_Plugins by defining the preprocessor symbol \c EIGEN_MATRIX_PLUGIN. * * Some notes: * @@ -97,32 +136,44 @@ namespace Eigen { * are the dimensions of the original matrix, while _Rows and _Cols are Dynamic. * * - * \see MatrixBase for the majority of the API methods for matrices, \ref TopicClassHierarchy, - * \ref TopicStorageOrders + * ABI and storage layout + * + * The table below summarizes the ABI of some possible Matrix instances which is fixed thorough the lifetime of Eigen 3. + * + * + * + * + * + * + *
Matrix typeEquivalent C structure
\code Matrix \endcode\code + * struct { + * T *data; // with (size_t(data)%EIGEN_MAX_ALIGN_BYTES)==0 + * Eigen::Index rows, cols; + * }; + * \endcode
\code + * Matrix + * Matrix \endcode\code + * struct { + * T *data; // with (size_t(data)%EIGEN_MAX_ALIGN_BYTES)==0 + * Eigen::Index size; + * }; + * \endcode
\code Matrix \endcode\code + * struct { + * T data[Rows*Cols]; // with (size_t(data)%A(Rows*Cols*sizeof(T)))==0 + * }; + * \endcode
\code Matrix \endcode\code + * struct { + * T data[MaxRows*MaxCols]; // with (size_t(data)%A(MaxRows*MaxCols*sizeof(T)))==0 + * Eigen::Index rows, cols; + * }; + * \endcode
+ * Note that in this table Rows, Cols, MaxRows and MaxCols are all positive integers. A(S) is defined to the largest possible power-of-two + * smaller to EIGEN_MAX_STATIC_ALIGN_BYTES. + * + * \see MatrixBase for the majority of the API methods for matrices, \ref TopicClassHierarchy, + * \ref TopicStorageOrders */ -namespace internal { -template -struct traits > -{ - typedef _Scalar Scalar; - typedef Dense StorageKind; - typedef DenseIndex Index; - typedef MatrixXpr XprKind; - enum { - RowsAtCompileTime = _Rows, - ColsAtCompileTime = _Cols, - MaxRowsAtCompileTime = _MaxRows, - MaxColsAtCompileTime = _MaxCols, - Flags = compute_matrix_flags<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>::ret, - CoeffReadCost = NumTraits::ReadCost, - Options = _Options, - InnerStrideAtCompileTime = 1, - OuterStrideAtCompileTime = (Options&RowMajor) ? ColsAtCompileTime : RowsAtCompileTime - }; -}; -} - template class Matrix : public PlainObjectBase > @@ -151,6 +202,7 @@ class Matrix * * \callgraph */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix& operator=(const Matrix& other) { return Base::_set(other); @@ -167,7 +219,8 @@ class Matrix * remain row-vectors and vectors remain vectors. */ template - EIGEN_STRONG_INLINE Matrix& operator=(const MatrixBase& other) + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Matrix& operator=(const DenseBase& other) { return Base::_set(other); } @@ -179,12 +232,14 @@ class Matrix * \copydetails DenseBase::operator=(const EigenBase &other) */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix& operator=(const EigenBase &other) { return Base::operator=(other); } template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix& operator=(const ReturnByValue& func) { return Base::operator=(func); @@ -200,6 +255,7 @@ class Matrix * * \sa resize(Index,Index) */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix() : Base() { Base::_check_template_params(); @@ -207,45 +263,87 @@ class Matrix } // FIXME is it still needed - Matrix(internal::constructor_without_unaligned_array_assert) + EIGEN_DEVICE_FUNC + explicit Matrix(internal::constructor_without_unaligned_array_assert) : Base(internal::constructor_without_unaligned_array_assert()) { Base::_check_template_params(); EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED } - /** \brief Constructs a vector or row-vector with given dimension. \only_for_vectors - * - * Note that this is only useful for dynamic-size vectors. For fixed-size vectors, - * it is redundant to pass the dimension here, so it makes more sense to use the default - * constructor Matrix() instead. - */ - EIGEN_STRONG_INLINE explicit Matrix(Index dim) - : Base(dim, RowsAtCompileTime == 1 ? 1 : dim, ColsAtCompileTime == 1 ? 1 : dim) +#if EIGEN_HAS_RVALUE_REFERENCES + EIGEN_DEVICE_FUNC + Matrix(Matrix&& other) EIGEN_NOEXCEPT_IF(std::is_nothrow_move_constructible::value) + : Base(std::move(other)) { Base::_check_template_params(); - EIGEN_STATIC_ASSERT_VECTOR_ONLY(Matrix) - eigen_assert(dim >= 0); - eigen_assert(SizeAtCompileTime == Dynamic || SizeAtCompileTime == dim); - EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED + if (RowsAtCompileTime!=Dynamic && ColsAtCompileTime!=Dynamic) + Base::_set_noalias(other); } + EIGEN_DEVICE_FUNC + Matrix& operator=(Matrix&& other) EIGEN_NOEXCEPT_IF(std::is_nothrow_move_assignable::value) + { + other.swap(*this); + return *this; + } +#endif #ifndef EIGEN_PARSED_BY_DOXYGEN + + // This constructor is for both 1x1 matrices and dynamic vectors + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE explicit Matrix(const T& x) + { + Base::_check_template_params(); + Base::template _init1(x); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix(const T0& x, const T1& y) { Base::_check_template_params(); Base::template _init2(x, y); } #else + /** \brief Constructs a fixed-sized matrix initialized with coefficients starting at \a data */ + EIGEN_DEVICE_FUNC + explicit Matrix(const Scalar *data); + + /** \brief Constructs a vector or row-vector with given dimension. \only_for_vectors + * + * This is useful for dynamic-size vectors. For fixed-size vectors, + * it is redundant to pass these parameters, so one should use the default constructor + * Matrix() instead. + * + * \warning This constructor is disabled for fixed-size \c 1x1 matrices. For instance, + * calling Matrix(1) will call the initialization constructor: Matrix(const Scalar&). + * For fixed-size \c 1x1 matrices it is therefore recommended to use the default + * constructor Matrix() instead, especially when using one of the non standard + * \c EIGEN_INITIALIZE_MATRICES_BY_{ZERO,\c NAN} macros (see \ref TopicPreprocessorDirectives). + */ + EIGEN_STRONG_INLINE explicit Matrix(Index dim); + /** \brief Constructs an initialized 1x1 matrix with the given coefficient */ + Matrix(const Scalar& x); /** \brief Constructs an uninitialized matrix with \a rows rows and \a cols columns. * * This is useful for dynamic-size matrices. For fixed-size matrices, * it is redundant to pass these parameters, so one should use the default constructor - * Matrix() instead. */ + * Matrix() instead. + * + * \warning This constructor is disabled for fixed-size \c 1x2 and \c 2x1 vectors. For instance, + * calling Matrix2f(2,1) will call the initialization constructor: Matrix(const Scalar& x, const Scalar& y). + * For fixed-size \c 1x2 or \c 2x1 vectors it is therefore recommended to use the default + * constructor Matrix() instead, especially when using one of the non standard + * \c EIGEN_INITIALIZE_MATRICES_BY_{ZERO,\c NAN} macros (see \ref TopicPreprocessorDirectives). + */ + EIGEN_DEVICE_FUNC Matrix(Index rows, Index cols); + /** \brief Constructs an initialized 2D vector with given coefficients */ Matrix(const Scalar& x, const Scalar& y); #endif /** \brief Constructs an initialized 3D vector with given coefficients */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix(const Scalar& x, const Scalar& y, const Scalar& z) { Base::_check_template_params(); @@ -255,6 +353,7 @@ class Matrix m_storage.data()[2] = z; } /** \brief Constructs an initialized 4D vector with given coefficients */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix(const Scalar& x, const Scalar& y, const Scalar& z, const Scalar& w) { Base::_check_template_params(); @@ -265,76 +364,33 @@ class Matrix m_storage.data()[3] = w; } - explicit Matrix(const Scalar *data); - /** \brief Constructor copying the value of the expression \a other */ - template - EIGEN_STRONG_INLINE Matrix(const MatrixBase& other) - : Base(other.rows() * other.cols(), other.rows(), other.cols()) - { - // This test resides here, to bring the error messages closer to the user. Normally, these checks - // are performed deeply within the library, thus causing long and scary error traces. - EIGEN_STATIC_ASSERT((internal::is_same::value), - YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) - - Base::_check_template_params(); - Base::_set_noalias(other); - } /** \brief Copy constructor */ - EIGEN_STRONG_INLINE Matrix(const Matrix& other) - : Base(other.rows() * other.cols(), other.rows(), other.cols()) - { - Base::_check_template_params(); - Base::_set_noalias(other); - } - /** \brief Copy constructor with in-place evaluation */ - template - EIGEN_STRONG_INLINE Matrix(const ReturnByValue& other) - { - Base::_check_template_params(); - Base::resize(other.rows(), other.cols()); - other.evalTo(*this); - } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Matrix(const Matrix& other) : Base(other) + { } /** \brief Copy constructor for generic expressions. * \sa MatrixBase::operator=(const EigenBase&) */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix(const EigenBase &other) - : Base(other.derived().rows() * other.derived().cols(), other.derived().rows(), other.derived().cols()) - { - Base::_check_template_params(); - Base::_resize_to_match(other); - // FIXME/CHECK: isn't *this = other.derived() more efficient. it allows to - // go for pure _set() implementations, right? - *this = other; - } + : Base(other.derived()) + { } - /** \internal - * \brief Override MatrixBase::swap() since for dynamic-sized matrices - * of same type it is enough to swap the data pointers. - */ - template - void swap(MatrixBase const & other) - { this->_swap(other.derived()); } - - inline Index innerStride() const { return 1; } - inline Index outerStride() const { return this->innerSize(); } + EIGEN_DEVICE_FUNC inline Index innerStride() const { return 1; } + EIGEN_DEVICE_FUNC inline Index outerStride() const { return this->innerSize(); } /////////// Geometry module /////////// template + EIGEN_DEVICE_FUNC explicit Matrix(const RotationBase& r); template + EIGEN_DEVICE_FUNC Matrix& operator=(const RotationBase& r); - #ifdef EIGEN2_SUPPORT - template - explicit Matrix(const eigen2_RotationBase& r); - template - Matrix& operator=(const eigen2_RotationBase& r); - #endif - // allow to extend Matrix outside Eigen #ifdef EIGEN_MATRIX_PLUGIN #include EIGEN_MATRIX_PLUGIN diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/MatrixBase.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/MatrixBase.h index cc327974..200e5774 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/MatrixBase.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/MatrixBase.h @@ -41,9 +41,9 @@ namespace Eigen { * \endcode * * This class can be extended with the help of the plugin mechanism described on the page - * \ref TopicCustomizingEigen by defining the preprocessor symbol \c EIGEN_MATRIXBASE_PLUGIN. + * \ref TopicCustomizing_Plugins by defining the preprocessor symbol \c EIGEN_MATRIXBASE_PLUGIN. * - * \sa \ref TopicClassHierarchy + * \sa \blank \ref TopicClassHierarchy */ template class MatrixBase : public DenseBase @@ -52,7 +52,7 @@ template class MatrixBase #ifndef EIGEN_PARSED_BY_DOXYGEN typedef MatrixBase StorageBaseType; typedef typename internal::traits::StorageKind StorageKind; - typedef typename internal::traits::Index Index; + typedef typename internal::traits::StorageIndex StorageIndex; typedef typename internal::traits::Scalar Scalar; typedef typename internal::packet_traits::type PacketScalar; typedef typename NumTraits::Real RealScalar; @@ -66,7 +66,6 @@ template class MatrixBase using Base::MaxSizeAtCompileTime; using Base::IsVectorAtCompileTime; using Base::Flags; - using Base::CoeffReadCost; using Base::derived; using Base::const_cast_derived; @@ -77,6 +76,7 @@ template class MatrixBase using Base::coeffRef; using Base::lazyAssign; using Base::eval; + using Base::operator-; using Base::operator+=; using Base::operator-=; using Base::operator*=; @@ -98,25 +98,14 @@ template class MatrixBase /** \returns the size of the main diagonal, which is min(rows(),cols()). * \sa rows(), cols(), SizeAtCompileTime. */ - inline Index diagonalSize() const { return (std::min)(rows(),cols()); } + EIGEN_DEVICE_FUNC + inline Index diagonalSize() const { return (numext::mini)(rows(),cols()); } - /** \brief The plain matrix type corresponding to this expression. - * - * This is not necessarily exactly the return type of eval(). In the case of plain matrices, - * the return type of eval() is a const reference to a matrix, not a matrix! It is however guaranteed - * that the return type of eval() is either PlainObject or const PlainObject&. - */ - typedef Matrix::Scalar, - internal::traits::RowsAtCompileTime, - internal::traits::ColsAtCompileTime, - AutoAlign | (internal::traits::Flags&RowMajorBit ? RowMajor : ColMajor), - internal::traits::MaxRowsAtCompileTime, - internal::traits::MaxColsAtCompileTime - > PlainObject; + typedef typename Base::PlainObject PlainObject; #ifndef EIGEN_PARSED_BY_DOXYGEN /** \internal Represents a matrix with all coefficients equal to one another*/ - typedef CwiseNullaryOp,Derived> ConstantReturnType; + typedef CwiseNullaryOp,PlainObject> ConstantReturnType; /** \internal the return type of MatrixBase::adjoint() */ typedef typename internal::conditional::IsComplex, CwiseUnaryOp, ConstTransposeReturnType>, @@ -125,7 +114,7 @@ template class MatrixBase /** \internal Return type of eigenvalues() */ typedef Matrix, internal::traits::ColsAtCompileTime, 1, ColMajor> EigenvaluesReturnType; /** \internal the return type of identity */ - typedef CwiseNullaryOp,Derived> IdentityReturnType; + typedef CwiseNullaryOp,PlainObject> IdentityReturnType; /** \internal the return type of unit vectors */ typedef Block, SquareMatrixType>, internal::traits::RowsAtCompileTime, @@ -133,7 +122,7 @@ template class MatrixBase #endif // not EIGEN_PARSED_BY_DOXYGEN #define EIGEN_CURRENT_STORAGE_BASE_CLASS Eigen::MatrixBase -# include "../plugins/CommonCwiseUnaryOps.h" +#define EIGEN_DOC_UNARY_ADDONS(X,Y) # include "../plugins/CommonCwiseBinaryOps.h" # include "../plugins/MatrixCwiseUnaryOps.h" # include "../plugins/MatrixCwiseBinaryOps.h" @@ -141,43 +130,53 @@ template class MatrixBase # include EIGEN_MATRIXBASE_PLUGIN # endif #undef EIGEN_CURRENT_STORAGE_BASE_CLASS +#undef EIGEN_DOC_UNARY_ADDONS /** Special case of the template operator=, in order to prevent the compiler * from generating a default operator= (issue hit with g++ 4.1) */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const MatrixBase& other); // We cannot inherit here via Base::operator= since it is causing // trouble with MSVC. template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const DenseBase& other); template + EIGEN_DEVICE_FUNC Derived& operator=(const EigenBase& other); template + EIGEN_DEVICE_FUNC Derived& operator=(const ReturnByValue& other); -#ifndef EIGEN_PARSED_BY_DOXYGEN - template - Derived& lazyAssign(const ProductBase& other); - - template - Derived& lazyAssign(const MatrixPowerProduct& other); -#endif // not EIGEN_PARSED_BY_DOXYGEN - template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator+=(const MatrixBase& other); template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator-=(const MatrixBase& other); +#ifdef __CUDACC__ template - const typename ProductReturnType::Type - operator*(const MatrixBase &other) const; + EIGEN_DEVICE_FUNC + const Product + operator*(const MatrixBase &other) const + { return this->lazyProduct(other); } +#else template - const typename LazyProductReturnType::Type + const Product + operator*(const MatrixBase &other) const; + +#endif + + template + EIGEN_DEVICE_FUNC + const Product lazyProduct(const MatrixBase &other) const; template @@ -190,84 +189,93 @@ template class MatrixBase void applyOnTheRight(const EigenBase& other); template - const DiagonalProduct + EIGEN_DEVICE_FUNC + const Product operator*(const DiagonalBase &diagonal) const; template - typename internal::scalar_product_traits::Scalar,typename internal::traits::Scalar>::ReturnType + EIGEN_DEVICE_FUNC + typename ScalarBinaryOpTraits::Scalar,typename internal::traits::Scalar>::ReturnType dot(const MatrixBase& other) const; - #ifdef EIGEN2_SUPPORT - template - Scalar eigen2_dot(const MatrixBase& other) const; - #endif - - RealScalar squaredNorm() const; - RealScalar norm() const; + EIGEN_DEVICE_FUNC RealScalar squaredNorm() const; + EIGEN_DEVICE_FUNC RealScalar norm() const; RealScalar stableNorm() const; RealScalar blueNorm() const; RealScalar hypotNorm() const; - const PlainObject normalized() const; - void normalize(); + EIGEN_DEVICE_FUNC const PlainObject normalized() const; + EIGEN_DEVICE_FUNC const PlainObject stableNormalized() const; + EIGEN_DEVICE_FUNC void normalize(); + EIGEN_DEVICE_FUNC void stableNormalize(); - const AdjointReturnType adjoint() const; - void adjointInPlace(); + EIGEN_DEVICE_FUNC const AdjointReturnType adjoint() const; + EIGEN_DEVICE_FUNC void adjointInPlace(); typedef Diagonal DiagonalReturnType; + EIGEN_DEVICE_FUNC DiagonalReturnType diagonal(); + typedef typename internal::add_const >::type ConstDiagonalReturnType; + EIGEN_DEVICE_FUNC ConstDiagonalReturnType diagonal() const; template struct DiagonalIndexReturnType { typedef Diagonal Type; }; template struct ConstDiagonalIndexReturnType { typedef const Diagonal Type; }; - template typename DiagonalIndexReturnType::Type diagonal(); - template typename ConstDiagonalIndexReturnType::Type diagonal() const; - + template + EIGEN_DEVICE_FUNC + typename DiagonalIndexReturnType::Type diagonal(); + + template + EIGEN_DEVICE_FUNC + typename ConstDiagonalIndexReturnType::Type diagonal() const; + typedef Diagonal DiagonalDynamicIndexReturnType; typedef typename internal::add_const >::type ConstDiagonalDynamicIndexReturnType; + EIGEN_DEVICE_FUNC DiagonalDynamicIndexReturnType diagonal(Index index); + EIGEN_DEVICE_FUNC ConstDiagonalDynamicIndexReturnType diagonal(Index index) const; - #ifdef EIGEN2_SUPPORT - template typename internal::eigen2_part_return_type::type part(); - template const typename internal::eigen2_part_return_type::type part() const; - - // huuuge hack. make Eigen2's matrix.part() work in eigen3. Problem: Diagonal is now a class template instead - // of an integer constant. Solution: overload the part() method template wrt template parameters list. - template class U> - const DiagonalWrapper part() const - { return diagonal().asDiagonal(); } - #endif // EIGEN2_SUPPORT - template struct TriangularViewReturnType { typedef TriangularView Type; }; template struct ConstTriangularViewReturnType { typedef const TriangularView Type; }; - template typename TriangularViewReturnType::Type triangularView(); - template typename ConstTriangularViewReturnType::Type triangularView() const; + template + EIGEN_DEVICE_FUNC + typename TriangularViewReturnType::Type triangularView(); + template + EIGEN_DEVICE_FUNC + typename ConstTriangularViewReturnType::Type triangularView() const; template struct SelfAdjointViewReturnType { typedef SelfAdjointView Type; }; template struct ConstSelfAdjointViewReturnType { typedef const SelfAdjointView Type; }; - template typename SelfAdjointViewReturnType::Type selfadjointView(); - template typename ConstSelfAdjointViewReturnType::Type selfadjointView() const; + template + EIGEN_DEVICE_FUNC + typename SelfAdjointViewReturnType::Type selfadjointView(); + template + EIGEN_DEVICE_FUNC + typename ConstSelfAdjointViewReturnType::Type selfadjointView() const; const SparseView sparseView(const Scalar& m_reference = Scalar(0), const typename NumTraits::Real& m_epsilon = NumTraits::dummy_precision()) const; - static const IdentityReturnType Identity(); - static const IdentityReturnType Identity(Index rows, Index cols); - static const BasisReturnType Unit(Index size, Index i); - static const BasisReturnType Unit(Index i); - static const BasisReturnType UnitX(); - static const BasisReturnType UnitY(); - static const BasisReturnType UnitZ(); - static const BasisReturnType UnitW(); + EIGEN_DEVICE_FUNC static const IdentityReturnType Identity(); + EIGEN_DEVICE_FUNC static const IdentityReturnType Identity(Index rows, Index cols); + EIGEN_DEVICE_FUNC static const BasisReturnType Unit(Index size, Index i); + EIGEN_DEVICE_FUNC static const BasisReturnType Unit(Index i); + EIGEN_DEVICE_FUNC static const BasisReturnType UnitX(); + EIGEN_DEVICE_FUNC static const BasisReturnType UnitY(); + EIGEN_DEVICE_FUNC static const BasisReturnType UnitZ(); + EIGEN_DEVICE_FUNC static const BasisReturnType UnitW(); + EIGEN_DEVICE_FUNC const DiagonalWrapper asDiagonal() const; const PermutationWrapper asPermutation() const; + EIGEN_DEVICE_FUNC Derived& setIdentity(); + EIGEN_DEVICE_FUNC Derived& setIdentity(Index rows, Index cols); bool isIdentity(const RealScalar& prec = NumTraits::dummy_precision()) const; @@ -286,7 +294,7 @@ template class MatrixBase * fuzzy comparison such as isApprox() * \sa isApprox(), operator!= */ template - inline bool operator==(const MatrixBase& other) const + EIGEN_DEVICE_FUNC inline bool operator==(const MatrixBase& other) const { return cwiseEqual(other).all(); } /** \returns true if at least one pair of coefficients of \c *this and \a other are not exactly equal to each other. @@ -294,64 +302,50 @@ template class MatrixBase * fuzzy comparison such as isApprox() * \sa isApprox(), operator== */ template - inline bool operator!=(const MatrixBase& other) const + EIGEN_DEVICE_FUNC inline bool operator!=(const MatrixBase& other) const { return cwiseNotEqual(other).any(); } NoAlias noalias(); - inline const ForceAlignedAccess forceAlignedAccess() const; - inline ForceAlignedAccess forceAlignedAccess(); - template inline typename internal::add_const_on_value_type,Derived&>::type>::type forceAlignedAccessIf() const; - template inline typename internal::conditional,Derived&>::type forceAlignedAccessIf(); + // TODO forceAlignedAccess is temporarily disabled + // Need to find a nicer workaround. + inline const Derived& forceAlignedAccess() const { return derived(); } + inline Derived& forceAlignedAccess() { return derived(); } + template inline const Derived& forceAlignedAccessIf() const { return derived(); } + template inline Derived& forceAlignedAccessIf() { return derived(); } - Scalar trace() const; + EIGEN_DEVICE_FUNC Scalar trace() const; -/////////// Array module /////////// + template EIGEN_DEVICE_FUNC RealScalar lpNorm() const; - template RealScalar lpNorm() const; - - MatrixBase& matrix() { return *this; } - const MatrixBase& matrix() const { return *this; } + EIGEN_DEVICE_FUNC MatrixBase& matrix() { return *this; } + EIGEN_DEVICE_FUNC const MatrixBase& matrix() const { return *this; } /** \returns an \link Eigen::ArrayBase Array \endlink expression of this matrix * \sa ArrayBase::matrix() */ - ArrayWrapper array() { return derived(); } - const ArrayWrapper array() const { return derived(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ArrayWrapper array() { return ArrayWrapper(derived()); } + /** \returns a const \link Eigen::ArrayBase Array \endlink expression of this matrix + * \sa ArrayBase::matrix() */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const ArrayWrapper array() const { return ArrayWrapper(derived()); } /////////// LU module /////////// - const FullPivLU fullPivLu() const; - const PartialPivLU partialPivLu() const; + inline const FullPivLU fullPivLu() const; + inline const PartialPivLU partialPivLu() const; - #if EIGEN2_SUPPORT_STAGE < STAGE20_RESOLVE_API_CONFLICTS - const LU lu() const; - #endif + inline const PartialPivLU lu() const; - #ifdef EIGEN2_SUPPORT - const LU eigen2_lu() const; - #endif + inline const Inverse inverse() const; - #if EIGEN2_SUPPORT_STAGE > STAGE20_RESOLVE_API_CONFLICTS - const PartialPivLU lu() const; - #endif - - #ifdef EIGEN2_SUPPORT template - void computeInverse(MatrixBase *result) const { - *result = this->inverse(); - } - #endif - - const internal::inverse_impl inverse() const; - template - void computeInverseAndDetWithCheck( + inline void computeInverseAndDetWithCheck( ResultType& inverse, typename ResultType::Scalar& determinant, bool& invertible, const RealScalar& absDeterminantThreshold = NumTraits::dummy_precision() ) const; template - void computeInverseWithCheck( + inline void computeInverseWithCheck( ResultType& inverse, bool& invertible, const RealScalar& absDeterminantThreshold = NumTraits::dummy_precision() @@ -360,65 +354,70 @@ template class MatrixBase /////////// Cholesky module /////////// - const LLT llt() const; - const LDLT ldlt() const; + inline const LLT llt() const; + inline const LDLT ldlt() const; /////////// QR module /////////// - const HouseholderQR householderQr() const; - const ColPivHouseholderQR colPivHouseholderQr() const; - const FullPivHouseholderQR fullPivHouseholderQr() const; - - #ifdef EIGEN2_SUPPORT - const QR qr() const; - #endif + inline const HouseholderQR householderQr() const; + inline const ColPivHouseholderQR colPivHouseholderQr() const; + inline const FullPivHouseholderQR fullPivHouseholderQr() const; + inline const CompleteOrthogonalDecomposition completeOrthogonalDecomposition() const; - EigenvaluesReturnType eigenvalues() const; - RealScalar operatorNorm() const; +/////////// Eigenvalues module /////////// + + inline EigenvaluesReturnType eigenvalues() const; + inline RealScalar operatorNorm() const; /////////// SVD module /////////// - JacobiSVD jacobiSvd(unsigned int computationOptions = 0) const; - - #ifdef EIGEN2_SUPPORT - SVD svd() const; - #endif + inline JacobiSVD jacobiSvd(unsigned int computationOptions = 0) const; + inline BDCSVD bdcSvd(unsigned int computationOptions = 0) const; /////////// Geometry module /////////// #ifndef EIGEN_PARSED_BY_DOXYGEN /// \internal helper struct to form the return type of the cross product template struct cross_product_return_type { - typedef typename internal::scalar_product_traits::Scalar,typename internal::traits::Scalar>::ReturnType Scalar; + typedef typename ScalarBinaryOpTraits::Scalar,typename internal::traits::Scalar>::ReturnType Scalar; typedef Matrix type; }; #endif // EIGEN_PARSED_BY_DOXYGEN template - typename cross_product_return_type::type + EIGEN_DEVICE_FUNC +#ifndef EIGEN_PARSED_BY_DOXYGEN + inline typename cross_product_return_type::type +#else + inline PlainObject +#endif cross(const MatrixBase& other) const; + template - PlainObject cross3(const MatrixBase& other) const; - PlainObject unitOrthogonal(void) const; - Matrix eulerAngles(Index a0, Index a1, Index a2) const; - - #if EIGEN2_SUPPORT_STAGE > STAGE20_RESOLVE_API_CONFLICTS - ScalarMultipleReturnType operator*(const UniformScaling& s) const; + EIGEN_DEVICE_FUNC + inline PlainObject cross3(const MatrixBase& other) const; + + EIGEN_DEVICE_FUNC + inline PlainObject unitOrthogonal(void) const; + + EIGEN_DEVICE_FUNC + inline Matrix eulerAngles(Index a0, Index a1, Index a2) const; + // put this as separate enum value to work around possible GCC 4.3 bug (?) - enum { HomogeneousReturnTypeDirection = ColsAtCompileTime==1?Vertical:Horizontal }; + enum { HomogeneousReturnTypeDirection = ColsAtCompileTime==1&&RowsAtCompileTime==1 ? ((internal::traits::Flags&RowMajorBit)==RowMajorBit ? Horizontal : Vertical) + : ColsAtCompileTime==1 ? Vertical : Horizontal }; typedef Homogeneous HomogeneousReturnType; - HomogeneousReturnType homogeneous() const; - #endif - + EIGEN_DEVICE_FUNC + inline HomogeneousReturnType homogeneous() const; + enum { SizeMinusOne = SizeAtCompileTime==Dynamic ? Dynamic : SizeAtCompileTime-1 }; typedef Block::ColsAtCompileTime==1 ? SizeMinusOne : 1, internal::traits::ColsAtCompileTime==1 ? 1 : SizeMinusOne> ConstStartMinusOne; - typedef CwiseUnaryOp::Scalar>, - const ConstStartMinusOne > HNormalizedReturnType; - - const HNormalizedReturnType hnormalized() const; + typedef EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(ConstStartMinusOne,Scalar,quotient) HNormalizedReturnType; + EIGEN_DEVICE_FUNC + inline const HNormalizedReturnType hnormalized() const; ////////// Householder module /////////// @@ -442,6 +441,15 @@ template class MatrixBase template void applyOnTheRight(Index p, Index q, const JacobiRotation& j); +///////// SparseCore module ///////// + + template + EIGEN_STRONG_INLINE const typename SparseMatrixBase::template CwiseProductDenseReturnType::Type + cwiseProduct(const SparseMatrixBase &other) const + { + return other.cwiseProduct(derived()); + } + ///////// MatrixFunctions module ///////// typedef typename internal::stem_function::type StemFunction; @@ -454,49 +462,15 @@ template class MatrixBase const MatrixSquareRootReturnValue sqrt() const; const MatrixLogarithmReturnValue log() const; const MatrixPowerReturnValue pow(const RealScalar& p) const; - -#ifdef EIGEN2_SUPPORT - template - Derived& operator+=(const Flagged, 0, - EvalBeforeAssigningBit>& other); - - template - Derived& operator-=(const Flagged, 0, - EvalBeforeAssigningBit>& other); - - /** \deprecated because .lazy() is deprecated - * Overloaded for cache friendly product evaluation */ - template - Derived& lazyAssign(const Flagged& other) - { return lazyAssign(other._expression()); } - - template - const Flagged marked() const; - const Flagged lazy() const; - - inline const Cwise cwise() const; - inline Cwise cwise(); - - VectorBlock start(Index size); - const VectorBlock start(Index size) const; - VectorBlock end(Index size); - const VectorBlock end(Index size) const; - template VectorBlock start(); - template const VectorBlock start() const; - template VectorBlock end(); - template const VectorBlock end() const; - - Minor minor(Index row, Index col); - const Minor minor(Index row, Index col) const; -#endif + const MatrixComplexPowerReturnValue pow(const std::complex& p) const; protected: - MatrixBase() : Base() {} + EIGEN_DEVICE_FUNC MatrixBase() : Base() {} private: - explicit MatrixBase(int); - MatrixBase(int,int); - template explicit MatrixBase(const MatrixBase&); + EIGEN_DEVICE_FUNC explicit MatrixBase(int); + EIGEN_DEVICE_FUNC MatrixBase(int,int); + template EIGEN_DEVICE_FUNC explicit MatrixBase(const MatrixBase&); protected: // mixing arrays and matrices is not legal template Derived& operator+=(const ArrayBase& ) diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/NestByValue.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/NestByValue.h index a893b176..01cf192e 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/NestByValue.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/NestByValue.h @@ -13,25 +13,24 @@ namespace Eigen { -/** \class NestByValue - * \ingroup Core_Module - * - * \brief Expression which must be nested by value - * - * \param ExpressionType the type of the object of which we are requiring nesting-by-value - * - * This class is the return type of MatrixBase::nestByValue() - * and most of the time this is the only way it is used. - * - * \sa MatrixBase::nestByValue() - */ - namespace internal { template struct traits > : public traits {}; } +/** \class NestByValue + * \ingroup Core_Module + * + * \brief Expression which must be nested by value + * + * \tparam ExpressionType the type of the object of which we are requiring nesting-by-value + * + * This class is the return type of MatrixBase::nestByValue() + * and most of the time this is the only way it is used. + * + * \sa MatrixBase::nestByValue() + */ template class NestByValue : public internal::dense_xpr_base< NestByValue >::type { @@ -40,58 +39,58 @@ template class NestByValue typedef typename internal::dense_xpr_base::type Base; EIGEN_DENSE_PUBLIC_INTERFACE(NestByValue) - inline NestByValue(const ExpressionType& matrix) : m_expression(matrix) {} + EIGEN_DEVICE_FUNC explicit inline NestByValue(const ExpressionType& matrix) : m_expression(matrix) {} - inline Index rows() const { return m_expression.rows(); } - inline Index cols() const { return m_expression.cols(); } - inline Index outerStride() const { return m_expression.outerStride(); } - inline Index innerStride() const { return m_expression.innerStride(); } + EIGEN_DEVICE_FUNC inline Index rows() const { return m_expression.rows(); } + EIGEN_DEVICE_FUNC inline Index cols() const { return m_expression.cols(); } + EIGEN_DEVICE_FUNC inline Index outerStride() const { return m_expression.outerStride(); } + EIGEN_DEVICE_FUNC inline Index innerStride() const { return m_expression.innerStride(); } - inline const CoeffReturnType coeff(Index row, Index col) const + EIGEN_DEVICE_FUNC inline const CoeffReturnType coeff(Index row, Index col) const { return m_expression.coeff(row, col); } - inline Scalar& coeffRef(Index row, Index col) + EIGEN_DEVICE_FUNC inline Scalar& coeffRef(Index row, Index col) { return m_expression.const_cast_derived().coeffRef(row, col); } - inline const CoeffReturnType coeff(Index index) const + EIGEN_DEVICE_FUNC inline const CoeffReturnType coeff(Index index) const { return m_expression.coeff(index); } - inline Scalar& coeffRef(Index index) + EIGEN_DEVICE_FUNC inline Scalar& coeffRef(Index index) { return m_expression.const_cast_derived().coeffRef(index); } template - inline const PacketScalar packet(Index row, Index col) const + EIGEN_DEVICE_FUNC inline const PacketScalar packet(Index row, Index col) const { return m_expression.template packet(row, col); } template - inline void writePacket(Index row, Index col, const PacketScalar& x) + EIGEN_DEVICE_FUNC inline void writePacket(Index row, Index col, const PacketScalar& x) { m_expression.const_cast_derived().template writePacket(row, col, x); } template - inline const PacketScalar packet(Index index) const + EIGEN_DEVICE_FUNC inline const PacketScalar packet(Index index) const { return m_expression.template packet(index); } template - inline void writePacket(Index index, const PacketScalar& x) + EIGEN_DEVICE_FUNC inline void writePacket(Index index, const PacketScalar& x) { m_expression.const_cast_derived().template writePacket(index, x); } - operator const ExpressionType&() const { return m_expression; } + EIGEN_DEVICE_FUNC operator const ExpressionType&() const { return m_expression; } protected: const ExpressionType m_expression; @@ -100,7 +99,7 @@ template class NestByValue /** \returns an expression of the temporary version of *this. */ template -inline const NestByValue +EIGEN_DEVICE_FUNC inline const NestByValue DenseBase::nestByValue() const { return NestByValue(derived()); diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/NoAlias.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/NoAlias.h index 768bfb18..33908010 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/NoAlias.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/NoAlias.h @@ -17,7 +17,7 @@ namespace Eigen { * * \brief Pseudo expression providing an operator = assuming no aliasing * - * \param ExpressionType the type of the object on which to do the lazy assignment + * \tparam ExpressionType the type of the object on which to do the lazy assignment * * This class represents an expression with special assignment operators * assuming no aliasing between the target expression and the source expression. @@ -30,62 +30,36 @@ namespace Eigen { template class StorageBase> class NoAlias { - typedef typename ExpressionType::Scalar Scalar; public: - NoAlias(ExpressionType& expression) : m_expression(expression) {} - - /** Behaves like MatrixBase::lazyAssign(other) - * \sa MatrixBase::lazyAssign() */ - template - EIGEN_STRONG_INLINE ExpressionType& operator=(const StorageBase& other) - { return internal::assign_selector::run(m_expression,other.derived()); } - - /** \sa MatrixBase::operator+= */ - template - EIGEN_STRONG_INLINE ExpressionType& operator+=(const StorageBase& other) - { - typedef SelfCwiseBinaryOp, ExpressionType, OtherDerived> SelfAdder; - SelfAdder tmp(m_expression); - typedef typename internal::nested::type OtherDerivedNested; - typedef typename internal::remove_all::type _OtherDerivedNested; - internal::assign_selector::run(tmp,OtherDerivedNested(other.derived())); - return m_expression; - } - - /** \sa MatrixBase::operator-= */ - template - EIGEN_STRONG_INLINE ExpressionType& operator-=(const StorageBase& other) - { - typedef SelfCwiseBinaryOp, ExpressionType, OtherDerived> SelfAdder; - SelfAdder tmp(m_expression); - typedef typename internal::nested::type OtherDerivedNested; - typedef typename internal::remove_all::type _OtherDerivedNested; - internal::assign_selector::run(tmp,OtherDerivedNested(other.derived())); - return m_expression; - } - -#ifndef EIGEN_PARSED_BY_DOXYGEN - template - EIGEN_STRONG_INLINE ExpressionType& operator+=(const ProductBase& other) - { other.derived().addTo(m_expression); return m_expression; } - - template - EIGEN_STRONG_INLINE ExpressionType& operator-=(const ProductBase& other) - { other.derived().subTo(m_expression); return m_expression; } - - template - EIGEN_STRONG_INLINE ExpressionType& operator+=(const CoeffBasedProduct& other) - { return m_expression.derived() += CoeffBasedProduct(other.lhs(), other.rhs()); } - - template - EIGEN_STRONG_INLINE ExpressionType& operator-=(const CoeffBasedProduct& other) - { return m_expression.derived() -= CoeffBasedProduct(other.lhs(), other.rhs()); } + typedef typename ExpressionType::Scalar Scalar; + + explicit NoAlias(ExpressionType& expression) : m_expression(expression) {} template - ExpressionType& operator=(const ReturnByValue& func) - { return m_expression = func; } -#endif + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE ExpressionType& operator=(const StorageBase& other) + { + call_assignment_no_alias(m_expression, other.derived(), internal::assign_op()); + return m_expression; + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE ExpressionType& operator+=(const StorageBase& other) + { + call_assignment_no_alias(m_expression, other.derived(), internal::add_assign_op()); + return m_expression; + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE ExpressionType& operator-=(const StorageBase& other) + { + call_assignment_no_alias(m_expression, other.derived(), internal::sub_assign_op()); + return m_expression; + } + EIGEN_DEVICE_FUNC ExpressionType& expression() const { return m_expression; @@ -126,7 +100,7 @@ class NoAlias template NoAlias MatrixBase::noalias() { - return derived(); + return NoAlias(derived()); } } // end namespace Eigen diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/NumTraits.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/NumTraits.h index bac9e50b..aebc0c25 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/NumTraits.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/NumTraits.h @@ -12,24 +12,57 @@ namespace Eigen { +namespace internal { + +// default implementation of digits10(), based on numeric_limits if specialized, +// 0 for integer types, and log10(epsilon()) otherwise. +template< typename T, + bool use_numeric_limits = std::numeric_limits::is_specialized, + bool is_integer = NumTraits::IsInteger> +struct default_digits10_impl +{ + static int run() { return std::numeric_limits::digits10; } +}; + +template +struct default_digits10_impl // Floating point +{ + static int run() { + using std::log10; + using std::ceil; + typedef typename NumTraits::Real Real; + return int(ceil(-log10(NumTraits::epsilon()))); + } +}; + +template +struct default_digits10_impl // Integer +{ + static int run() { return 0; } +}; + +} // end namespace internal + /** \class NumTraits * \ingroup Core_Module * * \brief Holds information about the various numeric (i.e. scalar) types allowed by Eigen. * - * \param T the numeric type at hand + * \tparam T the numeric type at hand * * This class stores enums, typedefs and static methods giving information about a numeric type. * * The provided data consists of: - * \li A typedef \a Real, giving the "real part" type of \a T. If \a T is already real, - * then \a Real is just a typedef to \a T. If \a T is \c std::complex then \a Real + * \li A typedef \c Real, giving the "real part" type of \a T. If \a T is already real, + * then \c Real is just a typedef to \a T. If \a T is \c std::complex then \c Real * is a typedef to \a U. - * \li A typedef \a NonInteger, giving the type that should be used for operations producing non-integral values, + * \li A typedef \c NonInteger, giving the type that should be used for operations producing non-integral values, * such as quotients, square roots, etc. If \a T is a floating-point type, then this typedef just gives * \a T again. Note however that many Eigen functions such as internal::sqrt simply refuse to * take integers. Outside of a few cases, Eigen doesn't do automatic type promotion. Thus, this typedef is * only intended as a helper for code that needs to explicitly promote types. + * \li A typedef \c Literal giving the type to use for numeric literals such as "2" or "0.5". For instance, for \c std::complex, Literal is defined as \c U. + * Of course, this type must be fully compatible with \a T. In doubt, just use \a T here. * \li A typedef \a Nested giving the type to use to nest a value inside of the expression tree. If you don't know what * this means, just use \a T here. * \li An enum value \a IsComplex. It is equal to 1 if \a T is a \c std::complex @@ -38,14 +71,18 @@ namespace Eigen { * and to \c 0 otherwise. * \li Enum values ReadCost, AddCost and MulCost representing a rough estimate of the number of CPU cycles needed * to by move / add / mul instructions respectively, assuming the data is already stored in CPU registers. - * Stay vague here. No need to do architecture-specific stuff. + * Stay vague here. No need to do architecture-specific stuff. If you don't know what this means, just use \c Eigen::HugeCost. * \li An enum value \a IsSigned. It is equal to \c 1 if \a T is a signed type and to 0 if \a T is unsigned. * \li An enum value \a RequireInitialization. It is equal to \c 1 if the constructor of the numeric type \a T must * be called, and to 0 if it is safe not to call it. Default is 0 if \a T is an arithmetic type, and 1 otherwise. - * \li An epsilon() function which, unlike std::numeric_limits::epsilon(), returns a \a Real instead of a \a T. + * \li An epsilon() function which, unlike std::numeric_limits::epsilon(), + * it returns a \a Real instead of a \a T. * \li A dummy_precision() function returning a weak epsilon value. It is mainly used as a default * value by the fuzzy comparison operators. * \li highest() and lowest() functions returning the highest and lowest possible values respectively. + * \li digits10() function returning the number of decimal digits that can be represented without change. This is + * the analogue of std::numeric_limits::digits10 + * which is used as the default implementation if specialized. */ template struct GenericNumTraits @@ -67,22 +104,47 @@ template struct GenericNumTraits T >::type NonInteger; typedef T Nested; + typedef T Literal; - static inline Real epsilon() { return std::numeric_limits::epsilon(); } + EIGEN_DEVICE_FUNC + static inline Real epsilon() + { + return numext::numeric_limits::epsilon(); + } + + EIGEN_DEVICE_FUNC + static inline int digits10() + { + return internal::default_digits10_impl::run(); + } + + EIGEN_DEVICE_FUNC static inline Real dummy_precision() { // make sure to override this for floating-point types return Real(0); } - static inline T highest() { return (std::numeric_limits::max)(); } - static inline T lowest() { return IsInteger ? (std::numeric_limits::min)() : (-(std::numeric_limits::max)()); } - -#ifdef EIGEN2_SUPPORT - enum { - HasFloatingPoint = !IsInteger - }; - typedef NonInteger FloatingPoint; -#endif + + + EIGEN_DEVICE_FUNC + static inline T highest() { + return (numext::numeric_limits::max)(); + } + + EIGEN_DEVICE_FUNC + static inline T lowest() { + return IsInteger ? (numext::numeric_limits::min)() : (-(numext::numeric_limits::max)()); + } + + EIGEN_DEVICE_FUNC + static inline T infinity() { + return numext::numeric_limits::infinity(); + } + + EIGEN_DEVICE_FUNC + static inline T quiet_NaN() { + return numext::numeric_limits::quiet_NaN(); + } }; template struct NumTraits : GenericNumTraits @@ -91,11 +153,13 @@ template struct NumTraits : GenericNumTraits template<> struct NumTraits : GenericNumTraits { + EIGEN_DEVICE_FUNC static inline float dummy_precision() { return 1e-5f; } }; template<> struct NumTraits : GenericNumTraits { + EIGEN_DEVICE_FUNC static inline double dummy_precision() { return 1e-12; } }; @@ -109,6 +173,7 @@ template struct NumTraits > : GenericNumTraits > { typedef _Real Real; + typedef typename NumTraits<_Real>::Literal Literal; enum { IsComplex = 1, RequireInitialization = NumTraits<_Real>::RequireInitialization, @@ -117,8 +182,12 @@ template struct NumTraits > MulCost = 4 * NumTraits::MulCost + 2 * NumTraits::AddCost }; + EIGEN_DEVICE_FUNC static inline Real epsilon() { return NumTraits::epsilon(); } + EIGEN_DEVICE_FUNC static inline Real dummy_precision() { return NumTraits::dummy_precision(); } + EIGEN_DEVICE_FUNC + static inline int digits10() { return NumTraits::digits10(); } }; template @@ -130,21 +199,48 @@ struct NumTraits > typedef typename NumTraits::NonInteger NonIntegerScalar; typedef Array NonInteger; typedef ArrayType & Nested; - + typedef typename NumTraits::Literal Literal; + enum { IsComplex = NumTraits::IsComplex, IsInteger = NumTraits::IsInteger, IsSigned = NumTraits::IsSigned, RequireInitialization = 1, - ReadCost = ArrayType::SizeAtCompileTime==Dynamic ? Dynamic : ArrayType::SizeAtCompileTime * NumTraits::ReadCost, - AddCost = ArrayType::SizeAtCompileTime==Dynamic ? Dynamic : ArrayType::SizeAtCompileTime * NumTraits::AddCost, - MulCost = ArrayType::SizeAtCompileTime==Dynamic ? Dynamic : ArrayType::SizeAtCompileTime * NumTraits::MulCost + ReadCost = ArrayType::SizeAtCompileTime==Dynamic ? HugeCost : ArrayType::SizeAtCompileTime * NumTraits::ReadCost, + AddCost = ArrayType::SizeAtCompileTime==Dynamic ? HugeCost : ArrayType::SizeAtCompileTime * NumTraits::AddCost, + MulCost = ArrayType::SizeAtCompileTime==Dynamic ? HugeCost : ArrayType::SizeAtCompileTime * NumTraits::MulCost }; - + + EIGEN_DEVICE_FUNC static inline RealScalar epsilon() { return NumTraits::epsilon(); } + EIGEN_DEVICE_FUNC static inline RealScalar dummy_precision() { return NumTraits::dummy_precision(); } }; +template<> struct NumTraits + : GenericNumTraits +{ + enum { + RequireInitialization = 1, + ReadCost = HugeCost, + AddCost = HugeCost, + MulCost = HugeCost + }; + + static inline int digits10() { return 0; } + +private: + static inline std::string epsilon(); + static inline std::string dummy_precision(); + static inline std::string lowest(); + static inline std::string highest(); + static inline std::string infinity(); + static inline std::string quiet_NaN(); +}; + +// Empty specialization for void to allow template specialization based on NumTraits::Real with T==void and SFINAE. +template<> struct NumTraits {}; + } // end namespace Eigen #endif // EIGEN_NUMTRAITS_H diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/PermutationMatrix.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/PermutationMatrix.h index f26f3e5c..b1fb455b 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/PermutationMatrix.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/PermutationMatrix.h @@ -2,7 +2,7 @@ // for linear algebra. // // Copyright (C) 2009 Benoit Jacob -// Copyright (C) 2009-2011 Gael Guennebaud +// Copyright (C) 2009-2015 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -13,14 +13,18 @@ namespace Eigen { -template class PermutedImpl; +namespace internal { + +enum PermPermProduct_t {PermPermProduct}; + +} // end namespace internal /** \class PermutationBase * \ingroup Core_Module * * \brief Base class for permutations * - * \param Derived the derived class + * \tparam Derived the derived class * * This class is the base class for all expressions representing a permutation matrix, * internally stored as a vector of integers. @@ -38,17 +42,6 @@ template -struct permut_matrix_product_retval; -template -struct permut_sparsematrix_product_retval; -enum PermPermProduct_t {PermPermProduct}; - -} // end namespace internal - template class PermutationBase : public EigenBase { @@ -60,19 +53,20 @@ class PermutationBase : public EigenBase typedef typename Traits::IndicesType IndicesType; enum { Flags = Traits::Flags, - CoeffReadCost = Traits::CoeffReadCost, RowsAtCompileTime = Traits::RowsAtCompileTime, ColsAtCompileTime = Traits::ColsAtCompileTime, MaxRowsAtCompileTime = Traits::MaxRowsAtCompileTime, MaxColsAtCompileTime = Traits::MaxColsAtCompileTime }; - typedef typename Traits::Scalar Scalar; - typedef typename Traits::Index Index; - typedef Matrix + typedef typename Traits::StorageIndex StorageIndex; + typedef Matrix DenseMatrixType; - typedef PermutationMatrix + typedef PermutationMatrix PlainPermutationType; + typedef PlainPermutationType PlainObject; using Base::derived; + typedef Inverse InverseReturnType; + typedef void Scalar; #endif /** Copies the other permutation into *this */ @@ -118,7 +112,7 @@ class PermutationBase : public EigenBase void evalTo(MatrixBase& other) const { other.setZero(); - for (int i=0; i /** Sets *this to be the identity permutation matrix */ void setIdentity() { - for(Index i = 0; i < size(); ++i) + StorageIndex n = StorageIndex(size()); + for(StorageIndex i = 0; i < n; ++i) indices().coeffRef(i) = i; } @@ -163,18 +158,18 @@ class PermutationBase : public EigenBase * * \returns a reference to *this. * - * \warning This is much slower than applyTranspositionOnTheRight(int,int): + * \warning This is much slower than applyTranspositionOnTheRight(Index,Index): * this has linear complexity and requires a lot of branching. * - * \sa applyTranspositionOnTheRight(int,int) + * \sa applyTranspositionOnTheRight(Index,Index) */ Derived& applyTranspositionOnTheLeft(Index i, Index j) { eigen_assert(i>=0 && j>=0 && i * * This is a fast operation, it only consists in swapping two indices. * - * \sa applyTranspositionOnTheLeft(int,int) + * \sa applyTranspositionOnTheLeft(Index,Index) */ Derived& applyTranspositionOnTheRight(Index i, Index j) { @@ -196,16 +191,16 @@ class PermutationBase : public EigenBase /** \returns the inverse permutation matrix. * - * \note \note_try_to_help_rvo + * \note \blank \note_try_to_help_rvo */ - inline Transpose inverse() const - { return derived(); } + inline InverseReturnType inverse() const + { return InverseReturnType(derived()); } /** \returns the tranpose permutation matrix. * - * \note \note_try_to_help_rvo + * \note \blank \note_try_to_help_rvo */ - inline Transpose transpose() const - { return derived(); } + inline InverseReturnType transpose() const + { return InverseReturnType(derived()); } /**** multiplication helpers to hopefully get RVO ****/ @@ -215,13 +210,13 @@ class PermutationBase : public EigenBase template void assignTranspose(const PermutationBase& other) { - for (int i=0; i void assignProduct(const Lhs& lhs, const Rhs& rhs) { eigen_assert(lhs.cols() == rhs.rows()); - for (int i=0; i /** \returns the product permutation matrix. * - * \note \note_try_to_help_rvo + * \note \blank \note_try_to_help_rvo */ template inline PlainPermutationType operator*(const PermutationBase& other) const @@ -237,57 +232,90 @@ class PermutationBase : public EigenBase /** \returns the product of a permutation with another inverse permutation. * - * \note \note_try_to_help_rvo + * \note \blank \note_try_to_help_rvo */ template - inline PlainPermutationType operator*(const Transpose >& other) const + inline PlainPermutationType operator*(const InverseImpl& other) const { return PlainPermutationType(internal::PermPermProduct, *this, other.eval()); } /** \returns the product of an inverse permutation with another permutation. * - * \note \note_try_to_help_rvo + * \note \blank \note_try_to_help_rvo */ template friend - inline PlainPermutationType operator*(const Transpose >& other, const PermutationBase& perm) + inline PlainPermutationType operator*(const InverseImpl& other, const PermutationBase& perm) { return PlainPermutationType(internal::PermPermProduct, other.eval(), perm); } + + /** \returns the determinant of the permutation matrix, which is either 1 or -1 depending on the parity of the permutation. + * + * This function is O(\c n) procedure allocating a buffer of \c n booleans. + */ + Index determinant() const + { + Index res = 1; + Index n = size(); + Matrix mask(n); + mask.fill(false); + Index r = 0; + while(r < n) + { + // search for the next seed + while(r=n) + break; + // we got one, let's follow it until we are back to the seed + Index k0 = r++; + mask.coeffRef(k0) = true; + for(Index k=indices().coeff(k0); k!=k0; k=indices().coeff(k)) + { + mask.coeffRef(k) = true; + res = -res; + } + } + return res; + } protected: }; +namespace internal { +template +struct traits > + : traits > +{ + typedef PermutationStorage StorageKind; + typedef Matrix<_StorageIndex, SizeAtCompileTime, 1, 0, MaxSizeAtCompileTime, 1> IndicesType; + typedef _StorageIndex StorageIndex; + typedef void Scalar; +}; +} + /** \class PermutationMatrix * \ingroup Core_Module * * \brief Permutation matrix * - * \param SizeAtCompileTime the number of rows/cols, or Dynamic - * \param MaxSizeAtCompileTime the maximum number of rows/cols, or Dynamic. This optional parameter defaults to SizeAtCompileTime. Most of the time, you should not have to specify it. - * \param IndexType the interger type of the indices + * \tparam SizeAtCompileTime the number of rows/cols, or Dynamic + * \tparam MaxSizeAtCompileTime the maximum number of rows/cols, or Dynamic. This optional parameter defaults to SizeAtCompileTime. Most of the time, you should not have to specify it. + * \tparam _StorageIndex the integer type of the indices * * This class represents a permutation matrix, internally stored as a vector of integers. * * \sa class PermutationBase, class PermutationWrapper, class DiagonalMatrix */ - -namespace internal { -template -struct traits > - : traits > -{ - typedef IndexType Index; - typedef Matrix IndicesType; -}; -} - -template -class PermutationMatrix : public PermutationBase > +template +class PermutationMatrix : public PermutationBase > { typedef PermutationBase Base; typedef internal::traits Traits; public: + typedef const PermutationMatrix& Nested; + #ifndef EIGEN_PARSED_BY_DOXYGEN typedef typename Traits::IndicesType IndicesType; + typedef typename Traits::StorageIndex StorageIndex; #endif inline PermutationMatrix() @@ -295,8 +323,10 @@ class PermutationMatrix : public PermutationBase::highest()); + } /** Copy constructor. */ template @@ -317,7 +347,7 @@ class PermutationMatrix : public PermutationBase - explicit inline PermutationMatrix(const MatrixBase& a_indices) : m_indices(a_indices) + explicit inline PermutationMatrix(const MatrixBase& indices) : m_indices(indices) {} /** Convert the Transpositions \a tr to a permutation matrix */ @@ -364,10 +394,13 @@ class PermutationMatrix : public PermutationBase - PermutationMatrix(const Transpose >& other) - : m_indices(other.nestedPermutation().size()) + PermutationMatrix(const InverseImpl& other) + : m_indices(other.derived().nestedExpression().size()) { - for (int i=0; i::highest()); + StorageIndex end = StorageIndex(m_indices.size()); + for (StorageIndex i=0; i PermutationMatrix(internal::PermPermProduct_t, const Lhs& lhs, const Rhs& rhs) @@ -384,18 +417,20 @@ class PermutationMatrix : public PermutationBase -struct traits,_PacketAccess> > - : traits > +template +struct traits,_PacketAccess> > + : traits > { - typedef IndexType Index; - typedef Map, _PacketAccess> IndicesType; + typedef PermutationStorage StorageKind; + typedef Map, _PacketAccess> IndicesType; + typedef _StorageIndex StorageIndex; + typedef void Scalar; }; } -template -class Map,_PacketAccess> - : public PermutationBase,_PacketAccess> > +template +class Map,_PacketAccess> + : public PermutationBase,_PacketAccess> > { typedef PermutationBase Base; typedef internal::traits Traits; @@ -403,14 +438,14 @@ class Map, #ifndef EIGEN_PARSED_BY_DOXYGEN typedef typename Traits::IndicesType IndicesType; - typedef typename IndicesType::Scalar Index; + typedef typename IndicesType::Scalar StorageIndex; #endif - inline Map(const Index* indicesPtr) + inline Map(const StorageIndex* indicesPtr) : m_indices(indicesPtr) {} - inline Map(const Index* indicesPtr, Index size) + inline Map(const StorageIndex* indicesPtr, Index size) : m_indices(indicesPtr,size) {} @@ -445,40 +480,36 @@ class Map, IndicesType m_indices; }; -/** \class PermutationWrapper - * \ingroup Core_Module - * - * \brief Class to view a vector of integers as a permutation matrix - * - * \param _IndicesType the type of the vector of integer (can be any compatible expression) - * - * This class allows to view any vector expression of integers as a permutation matrix. - * - * \sa class PermutationBase, class PermutationMatrix - */ - -struct PermutationStorage {}; - template class TranspositionsWrapper; namespace internal { template struct traits > { typedef PermutationStorage StorageKind; - typedef typename _IndicesType::Scalar Scalar; - typedef typename _IndicesType::Scalar Index; + typedef void Scalar; + typedef typename _IndicesType::Scalar StorageIndex; typedef _IndicesType IndicesType; enum { RowsAtCompileTime = _IndicesType::SizeAtCompileTime, ColsAtCompileTime = _IndicesType::SizeAtCompileTime, - MaxRowsAtCompileTime = IndicesType::MaxRowsAtCompileTime, - MaxColsAtCompileTime = IndicesType::MaxColsAtCompileTime, - Flags = 0, - CoeffReadCost = _IndicesType::CoeffReadCost + MaxRowsAtCompileTime = IndicesType::MaxSizeAtCompileTime, + MaxColsAtCompileTime = IndicesType::MaxSizeAtCompileTime, + Flags = 0 }; }; } +/** \class PermutationWrapper + * \ingroup Core_Module + * + * \brief Class to view a vector of integers as a permutation matrix + * + * \tparam _IndicesType the type of the vector of integer (can be any compatible expression) + * + * This class allows to view any vector expression of integers as a permutation matrix. + * + * \sa class PermutationBase, class PermutationMatrix + */ template class PermutationWrapper : public PermutationBase > { @@ -490,8 +521,8 @@ class PermutationWrapper : public PermutationBase -inline const internal::permut_matrix_product_retval -operator*(const MatrixBase& matrix, - const PermutationBase &permutation) +template +EIGEN_DEVICE_FUNC +const Product +operator*(const MatrixBase &matrix, + const PermutationBase& permutation) { - return internal::permut_matrix_product_retval - - (permutation.derived(), matrix.derived()); + return Product + (matrix.derived(), permutation.derived()); } /** \returns the matrix with the permutation applied to the rows. */ -template -inline const internal::permut_matrix_product_retval - +template +EIGEN_DEVICE_FUNC +const Product operator*(const PermutationBase &permutation, - const MatrixBase& matrix) + const MatrixBase& matrix) { - return internal::permut_matrix_product_retval - - (permutation.derived(), matrix.derived()); + return Product + (permutation.derived(), matrix.derived()); } -namespace internal { -template -struct traits > +template +class InverseImpl + : public EigenBase > { - typedef typename MatrixType::PlainObject ReturnType; -}; - -template -struct permut_matrix_product_retval - : public ReturnByValue > -{ - typedef typename remove_all::type MatrixTypeNestedCleaned; - typedef typename MatrixType::Index Index; - - permut_matrix_product_retval(const PermutationType& perm, const MatrixType& matrix) - : m_permutation(perm), m_matrix(matrix) - {} - - inline Index rows() const { return m_matrix.rows(); } - inline Index cols() const { return m_matrix.cols(); } - - template inline void evalTo(Dest& dst) const - { - const Index n = Side==OnTheLeft ? rows() : cols(); - // FIXME we need an is_same for expression that is not sensitive to constness. For instance - // is_same_xpr, Block >::value should be true. - if( is_same::value - && blas_traits::HasUsableDirectAccess - && blas_traits::HasUsableDirectAccess - && extract_data(dst) == extract_data(m_matrix)) - { - // apply the permutation inplace - Matrix mask(m_permutation.size()); - mask.fill(false); - Index r = 0; - while(r < m_permutation.size()) - { - // search for the next seed - while(r=m_permutation.size()) - break; - // we got one, let's follow it until we are back to the seed - Index k0 = r++; - Index kPrev = k0; - mask.coeffRef(k0) = true; - for(Index k=m_permutation.indices().coeff(k0); k!=k0; k=m_permutation.indices().coeff(k)) - { - Block(dst, k) - .swap(Block - (dst,((Side==OnTheLeft) ^ Transposed) ? k0 : kPrev)); - - mask.coeffRef(k) = true; - kPrev = k; - } - } - } - else - { - for(int i = 0; i < n; ++i) - { - Block - (dst, ((Side==OnTheLeft) ^ Transposed) ? m_permutation.indices().coeff(i) : i) - - = - - Block - (m_matrix, ((Side==OnTheRight) ^ Transposed) ? m_permutation.indices().coeff(i) : i); - } - } - } - - protected: - const PermutationType& m_permutation; - typename MatrixType::Nested m_matrix; -}; - -/* Template partial specialization for transposed/inverse permutations */ - -template -struct traits > > - : traits -{}; - -} // end namespace internal - -template -class Transpose > - : public EigenBase > > -{ - typedef Derived PermutationType; - typedef typename PermutationType::IndicesType IndicesType; typedef typename PermutationType::PlainPermutationType PlainPermutationType; + typedef internal::traits PermTraits; + protected: + InverseImpl() {} public: + typedef Inverse InverseType; + using EigenBase >::derived; #ifndef EIGEN_PARSED_BY_DOXYGEN - typedef internal::traits Traits; - typedef typename Derived::DenseMatrixType DenseMatrixType; + typedef typename PermutationType::DenseMatrixType DenseMatrixType; enum { - Flags = Traits::Flags, - CoeffReadCost = Traits::CoeffReadCost, - RowsAtCompileTime = Traits::RowsAtCompileTime, - ColsAtCompileTime = Traits::ColsAtCompileTime, - MaxRowsAtCompileTime = Traits::MaxRowsAtCompileTime, - MaxColsAtCompileTime = Traits::MaxColsAtCompileTime + RowsAtCompileTime = PermTraits::RowsAtCompileTime, + ColsAtCompileTime = PermTraits::ColsAtCompileTime, + MaxRowsAtCompileTime = PermTraits::MaxRowsAtCompileTime, + MaxColsAtCompileTime = PermTraits::MaxColsAtCompileTime }; - typedef typename Traits::Scalar Scalar; #endif - Transpose(const PermutationType& p) : m_permutation(p) {} - - inline int rows() const { return m_permutation.rows(); } - inline int cols() const { return m_permutation.cols(); } - #ifndef EIGEN_PARSED_BY_DOXYGEN template void evalTo(MatrixBase& other) const { other.setZero(); - for (int i=0; i friend - inline const internal::permut_matrix_product_retval - operator*(const MatrixBase& matrix, const Transpose& trPerm) + const Product + operator*(const MatrixBase& matrix, const InverseType& trPerm) { - return internal::permut_matrix_product_retval(trPerm.m_permutation, matrix.derived()); + return Product(matrix.derived(), trPerm.derived()); } /** \returns the matrix with the inverse permutation applied to the rows. */ template - inline const internal::permut_matrix_product_retval + const Product operator*(const MatrixBase& matrix) const { - return internal::permut_matrix_product_retval(m_permutation, matrix.derived()); + return Product(derived(), matrix.derived()); } - - const PermutationType& nestedPermutation() const { return m_permutation; } - - protected: - const PermutationType& m_permutation; }; template @@ -687,6 +622,12 @@ const PermutationWrapper MatrixBase::asPermutation() con return derived(); } +namespace internal { + +template<> struct AssignmentKind { typedef EigenBase2EigenBase Kind; }; + +} // end namespace internal + } // end namespace Eigen #endif // EIGEN_PERMUTATIONMATRIX_H diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/PlainObjectBase.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/PlainObjectBase.h index dd34b59e..77f4f606 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/PlainObjectBase.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/PlainObjectBase.h @@ -28,6 +28,7 @@ namespace internal { template struct check_rows_cols_for_overflow { template + EIGEN_DEVICE_FUNC static EIGEN_ALWAYS_INLINE void run(Index, Index) { } @@ -35,11 +36,12 @@ template struct check_rows_cols_for_overflow { template<> struct check_rows_cols_for_overflow { template + EIGEN_DEVICE_FUNC static EIGEN_ALWAYS_INLINE void run(Index rows, Index cols) { // http://hg.mozilla.org/mozilla-central/file/6c8a909977d3/xpcom/ds/CheckedInt.h#l242 // we assume Index is signed - Index max_index = (size_t(1) << (8 * sizeof(Index) - 1)) - 1; // assume Index is signed + Index max_index = (std::size_t(1) << (8 * sizeof(Index) - 1)) - 1; // assume Index is signed bool error = (rows == 0 || cols == 0) ? false : (rows > max_index / cols); if (error) @@ -56,33 +58,41 @@ template struct m } // end namespace internal +#ifdef EIGEN_PARSED_BY_DOXYGEN +namespace doxygen { + +// This is a workaround to doxygen not being able to understand the inheritance logic +// when it is hidden by the dense_xpr_base helper struct. +// Moreover, doxygen fails to include members that are not documented in the declaration body of +// MatrixBase if we inherits MatrixBase >, +// this is why we simply inherits MatrixBase, though this does not make sense. + +/** This class is just a workaround for Doxygen and it does not not actually exist. */ +template struct dense_xpr_base_dispatcher; +/** This class is just a workaround for Doxygen and it does not not actually exist. */ +template +struct dense_xpr_base_dispatcher > + : public MatrixBase {}; +/** This class is just a workaround for Doxygen and it does not not actually exist. */ +template +struct dense_xpr_base_dispatcher > + : public ArrayBase {}; + +} // namespace doxygen + /** \class PlainObjectBase + * \ingroup Core_Module * \brief %Dense storage base class for matrices and arrays. * * This class can be extended with the help of the plugin mechanism described on the page - * \ref TopicCustomizingEigen by defining the preprocessor symbol \c EIGEN_PLAINOBJECTBASE_PLUGIN. + * \ref TopicCustomizing_Plugins by defining the preprocessor symbol \c EIGEN_PLAINOBJECTBASE_PLUGIN. + * + * \tparam Derived is the derived type, e.g., a Matrix or Array * * \sa \ref TopicClassHierarchy */ -#ifdef EIGEN_PARSED_BY_DOXYGEN -namespace internal { - -// this is a warkaround to doxygen not being able to understand the inheritence logic -// when it is hidden by the dense_xpr_base helper struct. -template struct dense_xpr_base_dispatcher_for_doxygen;// : public MatrixBase {}; -/** This class is just a workaround for Doxygen and it does not not actually exist. */ -template -struct dense_xpr_base_dispatcher_for_doxygen > - : public MatrixBase > {}; -/** This class is just a workaround for Doxygen and it does not not actually exist. */ -template -struct dense_xpr_base_dispatcher_for_doxygen > - : public ArrayBase > {}; - -} // namespace internal - template -class PlainObjectBase : public internal::dense_xpr_base_dispatcher_for_doxygen +class PlainObjectBase : public doxygen::dense_xpr_base_dispatcher #else template class PlainObjectBase : public internal::dense_xpr_base::type @@ -93,8 +103,8 @@ class PlainObjectBase : public internal::dense_xpr_base::type typedef typename internal::dense_xpr_base::type Base; typedef typename internal::traits::StorageKind StorageKind; - typedef typename internal::traits::Index Index; typedef typename internal::traits::Scalar Scalar; + typedef typename internal::packet_traits::type PacketScalar; typedef typename NumTraits::Real RealScalar; typedef Derived DenseType; @@ -113,28 +123,40 @@ class PlainObjectBase : public internal::dense_xpr_base::type typedef Eigen::Map MapType; friend class Eigen::Map; typedef const Eigen::Map ConstMapType; - friend class Eigen::Map; - typedef Eigen::Map AlignedMapType; - friend class Eigen::Map; - typedef const Eigen::Map ConstAlignedMapType; +#if EIGEN_MAX_ALIGN_BYTES>0 + // for EIGEN_MAX_ALIGN_BYTES==0, AlignedMax==Unaligned, and many compilers generate warnings for friend-ing a class twice. + friend class Eigen::Map; + friend class Eigen::Map; +#endif + typedef Eigen::Map AlignedMapType; + typedef const Eigen::Map ConstAlignedMapType; template struct StridedMapType { typedef Eigen::Map type; }; template struct StridedConstMapType { typedef Eigen::Map type; }; - template struct StridedAlignedMapType { typedef Eigen::Map type; }; - template struct StridedConstAlignedMapType { typedef Eigen::Map type; }; + template struct StridedAlignedMapType { typedef Eigen::Map type; }; + template struct StridedConstAlignedMapType { typedef Eigen::Map type; }; protected: DenseStorage m_storage; public: - enum { NeedsToAlign = SizeAtCompileTime != Dynamic && (internal::traits::Flags & AlignedBit) != 0 }; + enum { NeedsToAlign = (SizeAtCompileTime != Dynamic) && (internal::traits::Alignment>0) }; EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + EIGEN_DEVICE_FUNC Base& base() { return *static_cast(this); } + EIGEN_DEVICE_FUNC const Base& base() const { return *static_cast(this); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rows() const { return m_storage.rows(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index cols() const { return m_storage.cols(); } + /** This is an overloaded version of DenseCoeffsBase::coeff(Index,Index) const + * provided to by-pass the creation of an evaluator of the expression, thus saving compilation efforts. + * + * See DenseCoeffsBase::coeff(Index) const for details. */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(Index rowId, Index colId) const { if(Flags & RowMajorBit) @@ -143,11 +165,21 @@ class PlainObjectBase : public internal::dense_xpr_base::type return m_storage.data()[rowId + colId * m_storage.rows()]; } + /** This is an overloaded version of DenseCoeffsBase::coeff(Index) const + * provided to by-pass the creation of an evaluator of the expression, thus saving compilation efforts. + * + * See DenseCoeffsBase::coeff(Index) const for details. */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(Index index) const { return m_storage.data()[index]; } + /** This is an overloaded version of DenseCoeffsBase::coeffRef(Index,Index) const + * provided to by-pass the creation of an evaluator of the expression, thus saving compilation efforts. + * + * See DenseCoeffsBase::coeffRef(Index,Index) const for details. */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index rowId, Index colId) { if(Flags & RowMajorBit) @@ -156,11 +188,19 @@ class PlainObjectBase : public internal::dense_xpr_base::type return m_storage.data()[rowId + colId * m_storage.rows()]; } + /** This is an overloaded version of DenseCoeffsBase::coeffRef(Index) const + * provided to by-pass the creation of an evaluator of the expression, thus saving compilation efforts. + * + * See DenseCoeffsBase::coeffRef(Index) const for details. */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index index) { return m_storage.data()[index]; } + /** This is the const version of coeffRef(Index,Index) which is thus synonym of coeff(Index,Index). + * It is provided for convenience. */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeffRef(Index rowId, Index colId) const { if(Flags & RowMajorBit) @@ -169,6 +209,9 @@ class PlainObjectBase : public internal::dense_xpr_base::type return m_storage.data()[rowId + colId * m_storage.rows()]; } + /** This is the const version of coeffRef(Index) which is thus synonym of coeff(Index). + * It is provided for convenience. */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeffRef(Index index) const { return m_storage.data()[index]; @@ -209,11 +252,11 @@ class PlainObjectBase : public internal::dense_xpr_base::type } /** \returns a const pointer to the data array of this matrix */ - EIGEN_STRONG_INLINE const Scalar *data() const + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar *data() const { return m_storage.data(); } /** \returns a pointer to the data array of this matrix */ - EIGEN_STRONG_INLINE Scalar *data() + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar *data() { return m_storage.data(); } /** Resizes \c *this to a \a rows x \a cols matrix. @@ -232,22 +275,22 @@ class PlainObjectBase : public internal::dense_xpr_base::type * * \sa resize(Index) for vectors, resize(NoChange_t, Index), resize(Index, NoChange_t) */ - EIGEN_STRONG_INLINE void resize(Index nbRows, Index nbCols) + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void resize(Index rows, Index cols) { - eigen_assert( EIGEN_IMPLIES(RowsAtCompileTime!=Dynamic,nbRows==RowsAtCompileTime) - && EIGEN_IMPLIES(ColsAtCompileTime!=Dynamic,nbCols==ColsAtCompileTime) - && EIGEN_IMPLIES(RowsAtCompileTime==Dynamic && MaxRowsAtCompileTime!=Dynamic,nbRows<=MaxRowsAtCompileTime) - && EIGEN_IMPLIES(ColsAtCompileTime==Dynamic && MaxColsAtCompileTime!=Dynamic,nbCols<=MaxColsAtCompileTime) - && nbRows>=0 && nbCols>=0 && "Invalid sizes when resizing a matrix or array."); - internal::check_rows_cols_for_overflow::run(nbRows, nbCols); + eigen_assert( EIGEN_IMPLIES(RowsAtCompileTime!=Dynamic,rows==RowsAtCompileTime) + && EIGEN_IMPLIES(ColsAtCompileTime!=Dynamic,cols==ColsAtCompileTime) + && EIGEN_IMPLIES(RowsAtCompileTime==Dynamic && MaxRowsAtCompileTime!=Dynamic,rows<=MaxRowsAtCompileTime) + && EIGEN_IMPLIES(ColsAtCompileTime==Dynamic && MaxColsAtCompileTime!=Dynamic,cols<=MaxColsAtCompileTime) + && rows>=0 && cols>=0 && "Invalid sizes when resizing a matrix or array."); + internal::check_rows_cols_for_overflow::run(rows, cols); #ifdef EIGEN_INITIALIZE_COEFFS - Index size = nbRows*nbCols; + Index size = rows*cols; bool size_changed = size != this->size(); - m_storage.resize(size, nbRows, nbCols); + m_storage.resize(size, rows, cols); if(size_changed) EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED #else - internal::check_rows_cols_for_overflow::run(nbRows, nbCols); - m_storage.resize(nbRows*nbCols, nbRows, nbCols); + m_storage.resize(rows*cols, rows, cols); #endif } @@ -262,6 +305,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type * * \sa resize(Index,Index), resize(NoChange_t, Index), resize(Index, NoChange_t) */ + EIGEN_DEVICE_FUNC inline void resize(Index size) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(PlainObjectBase) @@ -286,9 +330,10 @@ class PlainObjectBase : public internal::dense_xpr_base::type * * \sa resize(Index,Index) */ - inline void resize(NoChange_t, Index nbCols) + EIGEN_DEVICE_FUNC + inline void resize(NoChange_t, Index cols) { - resize(rows(), nbCols); + resize(rows(), cols); } /** Resizes the matrix, changing only the number of rows. For the parameter of type NoChange_t, just pass the special value \c NoChange @@ -299,9 +344,10 @@ class PlainObjectBase : public internal::dense_xpr_base::type * * \sa resize(Index,Index) */ - inline void resize(Index nbRows, NoChange_t) + EIGEN_DEVICE_FUNC + inline void resize(Index rows, NoChange_t) { - resize(nbRows, cols()); + resize(rows, cols()); } /** Resizes \c *this to have the same dimensions as \a other. @@ -312,6 +358,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type * remain row-vectors and vectors remain vectors. */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resizeLike(const EigenBase& _other) { const OtherDerived& other = _other.derived(); @@ -339,9 +386,10 @@ class PlainObjectBase : public internal::dense_xpr_base::type * Matrices are resized relative to the top-left element. In case values need to be * appended to the matrix they will be uninitialized. */ - EIGEN_STRONG_INLINE void conservativeResize(Index nbRows, Index nbCols) + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void conservativeResize(Index rows, Index cols) { - internal::conservative_resize_like_impl::run(*this, nbRows, nbCols); + internal::conservative_resize_like_impl::run(*this, rows, cols); } /** Resizes the matrix to \a rows x \a cols while leaving old values untouched. @@ -351,10 +399,11 @@ class PlainObjectBase : public internal::dense_xpr_base::type * * In case the matrix is growing, new rows will be uninitialized. */ - EIGEN_STRONG_INLINE void conservativeResize(Index nbRows, NoChange_t) + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void conservativeResize(Index rows, NoChange_t) { // Note: see the comment in conservativeResize(Index,Index) - conservativeResize(nbRows, cols()); + conservativeResize(rows, cols()); } /** Resizes the matrix to \a rows x \a cols while leaving old values untouched. @@ -364,10 +413,11 @@ class PlainObjectBase : public internal::dense_xpr_base::type * * In case the matrix is growing, new columns will be uninitialized. */ - EIGEN_STRONG_INLINE void conservativeResize(NoChange_t, Index nbCols) + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void conservativeResize(NoChange_t, Index cols) { // Note: see the comment in conservativeResize(Index,Index) - conservativeResize(rows(), nbCols); + conservativeResize(rows(), cols); } /** Resizes the vector to \a size while retaining old values. @@ -378,6 +428,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type * * When values are appended, they will be uninitialized. */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void conservativeResize(Index size) { internal::conservative_resize_like_impl::run(*this, size); @@ -393,6 +444,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type * appended to the matrix they will copied from \c other. */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void conservativeResizeLike(const DenseBase& other) { internal::conservative_resize_like_impl::run(*this, other); @@ -401,6 +453,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type /** This is a special case of the templated operator=. Its purpose is to * prevent a default operator= from hiding the templated operator=. */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const PlainObjectBase& other) { return _set(other); @@ -408,6 +461,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type /** \sa MatrixBase::lazyAssign() */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& lazyAssign(const DenseBase& other) { _resize_to_match(other); @@ -415,12 +469,18 @@ class PlainObjectBase : public internal::dense_xpr_base::type } template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const ReturnByValue& func) { resize(func.rows(), func.cols()); return Base::operator=(func); } + // Prevent user from trying to instantiate PlainObjectBase objects + // by making all its constructor protected. See bug 1074. + protected: + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PlainObjectBase() : m_storage() { // _check_template_params(); @@ -430,23 +490,81 @@ class PlainObjectBase : public internal::dense_xpr_base::type #ifndef EIGEN_PARSED_BY_DOXYGEN // FIXME is it still needed ? /** \internal */ - PlainObjectBase(internal::constructor_without_unaligned_array_assert) + EIGEN_DEVICE_FUNC + explicit PlainObjectBase(internal::constructor_without_unaligned_array_assert) : m_storage(internal::constructor_without_unaligned_array_assert()) { // _check_template_params(); EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED } #endif - EIGEN_STRONG_INLINE PlainObjectBase(Index a_size, Index nbRows, Index nbCols) - : m_storage(a_size, nbRows, nbCols) +#if EIGEN_HAS_RVALUE_REFERENCES + EIGEN_DEVICE_FUNC + PlainObjectBase(PlainObjectBase&& other) EIGEN_NOEXCEPT + : m_storage( std::move(other.m_storage) ) + { + } + + EIGEN_DEVICE_FUNC + PlainObjectBase& operator=(PlainObjectBase&& other) EIGEN_NOEXCEPT + { + using std::swap; + swap(m_storage, other.m_storage); + return *this; + } +#endif + + /** Copy constructor */ + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE PlainObjectBase(const PlainObjectBase& other) + : Base(), m_storage(other.m_storage) { } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE PlainObjectBase(Index size, Index rows, Index cols) + : m_storage(size, rows, cols) { // _check_template_params(); // EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED } - /** \copydoc MatrixBase::operator=(const EigenBase&) + /** \sa PlainObjectBase::operator=(const EigenBase&) */ + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE PlainObjectBase(const DenseBase &other) + : m_storage() + { + _check_template_params(); + resizeLike(other); + _set_noalias(other); + } + + /** \sa PlainObjectBase::operator=(const EigenBase&) */ + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE PlainObjectBase(const EigenBase &other) + : m_storage() + { + _check_template_params(); + resizeLike(other); + *this = other.derived(); + } + /** \brief Copy constructor with in-place evaluation */ + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE PlainObjectBase(const ReturnByValue& other) + { + _check_template_params(); + // FIXME this does not automatically transpose vectors if necessary + resize(other.rows(), other.cols()); + other.evalTo(this->derived()); + } + + public: + + /** \brief Copies the generic expression \a other into *this. + * \copydetails DenseBase::operator=(const EigenBase &other) */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const EigenBase &other) { _resize_to_match(other); @@ -454,16 +572,6 @@ class PlainObjectBase : public internal::dense_xpr_base::type return this->derived(); } - /** \sa MatrixBase::operator=(const EigenBase&) */ - template - EIGEN_STRONG_INLINE PlainObjectBase(const EigenBase &other) - : m_storage(other.derived().rows() * other.derived().cols(), other.derived().rows(), other.derived().cols()) - { - _check_template_params(); - internal::check_rows_cols_for_overflow::run(other.derived().rows(), other.derived().cols()); - Base::operator=(other.derived()); - } - /** \name Map * These are convenience functions returning Map objects. The Map() static functions return unaligned Map objects, * while the AlignedMap() functions return aligned Map objects and thus should be called only with 16-byte-aligned @@ -538,16 +646,16 @@ class PlainObjectBase : public internal::dense_xpr_base::type //@} using Base::setConstant; - Derived& setConstant(Index size, const Scalar& value); - Derived& setConstant(Index rows, Index cols, const Scalar& value); + EIGEN_DEVICE_FUNC Derived& setConstant(Index size, const Scalar& val); + EIGEN_DEVICE_FUNC Derived& setConstant(Index rows, Index cols, const Scalar& val); using Base::setZero; - Derived& setZero(Index size); - Derived& setZero(Index rows, Index cols); + EIGEN_DEVICE_FUNC Derived& setZero(Index size); + EIGEN_DEVICE_FUNC Derived& setZero(Index rows, Index cols); using Base::setOnes; - Derived& setOnes(Index size); - Derived& setOnes(Index rows, Index cols); + EIGEN_DEVICE_FUNC Derived& setOnes(Index size); + EIGEN_DEVICE_FUNC Derived& setOnes(Index rows, Index cols); using Base::setRandom; Derived& setRandom(Index size); @@ -566,6 +674,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type * remain row-vectors and vectors remain vectors. */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _resize_to_match(const EigenBase& other) { #ifdef EIGEN_NO_AUTOMATIC_RESIZING @@ -592,25 +701,23 @@ class PlainObjectBase : public internal::dense_xpr_base::type * * \internal */ + // aliasing is dealt once in internall::call_assignment + // so at this stage we have to assume aliasing... and resising has to be done later. template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& _set(const DenseBase& other) { - _set_selector(other.derived(), typename internal::conditional(int(OtherDerived::Flags) & EvalBeforeAssigningBit), internal::true_type, internal::false_type>::type()); + internal::call_assignment(this->derived(), other.derived()); return this->derived(); } - template - EIGEN_STRONG_INLINE void _set_selector(const OtherDerived& other, const internal::true_type&) { _set_noalias(other.eval()); } - - template - EIGEN_STRONG_INLINE void _set_selector(const OtherDerived& other, const internal::false_type&) { _set_noalias(other); } - /** \internal Like _set() but additionally makes the assumption that no aliasing effect can happen (which * is the case when creating a new matrix) so one can enforce lazy evaluation. * * \sa operator=(const MatrixBase&), _set() */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& _set_noalias(const DenseBase& other) { // I don't think we need this resize call since the lazyAssign will anyways resize @@ -618,40 +725,175 @@ class PlainObjectBase : public internal::dense_xpr_base::type //_resize_to_match(other); // the 'false' below means to enforce lazy evaluation. We don't use lazyAssign() because // it wouldn't allow to copy a row-vector into a column-vector. - return internal::assign_selector::run(this->derived(), other.derived()); + internal::call_assignment_no_alias(this->derived(), other.derived(), internal::assign_op()); + return this->derived(); } template - EIGEN_STRONG_INLINE void _init2(Index nbRows, Index nbCols, typename internal::enable_if::type* = 0) + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init2(Index rows, Index cols, typename internal::enable_if::type* = 0) { EIGEN_STATIC_ASSERT(bool(NumTraits::IsInteger) && bool(NumTraits::IsInteger), FLOATING_POINT_ARGUMENT_PASSED__INTEGER_WAS_EXPECTED) - resize(nbRows,nbCols); + resize(rows,cols); } + template - EIGEN_STRONG_INLINE void _init2(const Scalar& val0, const Scalar& val1, typename internal::enable_if::type* = 0) + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init2(const T0& val0, const T1& val1, typename internal::enable_if::type* = 0) { EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(PlainObjectBase, 2) - m_storage.data()[0] = val0; - m_storage.data()[1] = val1; + m_storage.data()[0] = Scalar(val0); + m_storage.data()[1] = Scalar(val1); + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init2(const Index& val0, const Index& val1, + typename internal::enable_if< (!internal::is_same::value) + && (internal::is_same::value) + && (internal::is_same::value) + && Base::SizeAtCompileTime==2,T1>::type* = 0) + { + EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(PlainObjectBase, 2) + m_storage.data()[0] = Scalar(val0); + m_storage.data()[1] = Scalar(val1); } + // The argument is convertible to the Index type and we either have a non 1x1 Matrix, or a dynamic-sized Array, + // then the argument is meant to be the size of the object. + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(Index size, typename internal::enable_if< (Base::SizeAtCompileTime!=1 || !internal::is_convertible::value) + && ((!internal::is_same::XprKind,ArrayXpr>::value || Base::SizeAtCompileTime==Dynamic)),T>::type* = 0) + { + // NOTE MSVC 2008 complains if we directly put bool(NumTraits::IsInteger) as the EIGEN_STATIC_ASSERT argument. + const bool is_integer = NumTraits::IsInteger; + EIGEN_UNUSED_VARIABLE(is_integer); + EIGEN_STATIC_ASSERT(is_integer, + FLOATING_POINT_ARGUMENT_PASSED__INTEGER_WAS_EXPECTED) + resize(size); + } + + // We have a 1x1 matrix/array => the argument is interpreted as the value of the unique coefficient (case where scalar type can be implicitely converted) + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(const Scalar& val0, typename internal::enable_if::value,T>::type* = 0) + { + EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(PlainObjectBase, 1) + m_storage.data()[0] = val0; + } + + // We have a 1x1 matrix/array => the argument is interpreted as the value of the unique coefficient (case where scalar type match the index type) + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(const Index& val0, + typename internal::enable_if< (!internal::is_same::value) + && (internal::is_same::value) + && Base::SizeAtCompileTime==1 + && internal::is_convertible::value,T*>::type* = 0) + { + EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(PlainObjectBase, 1) + m_storage.data()[0] = Scalar(val0); + } + + // Initialize a fixed size matrix from a pointer to raw data + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(const Scalar* data){ + this->_set_noalias(ConstMapType(data)); + } + + // Initialize an arbitrary matrix from a dense expression + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(const DenseBase& other){ + this->_set_noalias(other); + } + + // Initialize an arbitrary matrix from an object convertible to the Derived type. + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(const Derived& other){ + this->_set_noalias(other); + } + + // Initialize an arbitrary matrix from a generic Eigen expression + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(const EigenBase& other){ + this->derived() = other; + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(const ReturnByValue& other) + { + resize(other.rows(), other.cols()); + other.evalTo(this->derived()); + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(const RotationBase& r) + { + this->derived() = r; + } + + // For fixed-size Array + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(const Scalar& val0, + typename internal::enable_if< Base::SizeAtCompileTime!=Dynamic + && Base::SizeAtCompileTime!=1 + && internal::is_convertible::value + && internal::is_same::XprKind,ArrayXpr>::value,T>::type* = 0) + { + Base::setConstant(val0); + } + + // For fixed-size Array + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(const Index& val0, + typename internal::enable_if< (!internal::is_same::value) + && (internal::is_same::value) + && Base::SizeAtCompileTime!=Dynamic + && Base::SizeAtCompileTime!=1 + && internal::is_convertible::value + && internal::is_same::XprKind,ArrayXpr>::value,T*>::type* = 0) + { + Base::setConstant(val0); + } + template friend struct internal::matrix_swap_impl; - /** \internal generic implementation of swap for dense storage since for dynamic-sized matrices of same type it is enough to swap the - * data pointers. + public: + +#ifndef EIGEN_PARSED_BY_DOXYGEN + /** \internal + * \brief Override DenseBase::swap() since for dynamic-sized matrices + * of same type it is enough to swap the data pointers. */ template - void _swap(DenseBase const & other) + EIGEN_DEVICE_FUNC + void swap(DenseBase & other) { enum { SwapPointers = internal::is_same::value && Base::SizeAtCompileTime==Dynamic }; - internal::matrix_swap_impl::run(this->derived(), other.const_cast_derived()); + internal::matrix_swap_impl::run(this->derived(), other.derived()); } - - public: -#ifndef EIGEN_PARSED_BY_DOXYGEN + + /** \internal + * \brief const version forwarded to DenseBase::swap + */ + template + EIGEN_DEVICE_FUNC + void swap(DenseBase const & other) + { Base::swap(other.derived()); } + + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void _check_template_params() { EIGEN_STATIC_ASSERT((EIGEN_IMPLIES(MaxRowsAtCompileTime==1 && MaxColsAtCompileTime!=1, (Options&RowMajor)==RowMajor) @@ -665,10 +907,9 @@ class PlainObjectBase : public internal::dense_xpr_base::type && (Options & (DontAlign|RowMajor)) == Options), INVALID_MATRIX_TEMPLATE_PARAMETERS) } -#endif -private: - enum { ThisConstantIsPrivateInPlainObjectBase }; + enum { IsPlainObjectBase = 1 }; +#endif }; namespace internal { @@ -676,7 +917,6 @@ namespace internal { template struct conservative_resize_like_impl { - typedef typename Derived::Index Index; static void run(DenseBase& _this, Index rows, Index cols) { if (_this.rows() == rows && _this.cols() == cols) return; @@ -692,8 +932,8 @@ struct conservative_resize_like_impl { // The storage order does not allow us to use reallocation. typename Derived::PlainObject tmp(rows,cols); - const Index common_rows = (std::min)(rows, _this.rows()); - const Index common_cols = (std::min)(cols, _this.cols()); + const Index common_rows = numext::mini(rows, _this.rows()); + const Index common_cols = numext::mini(cols, _this.cols()); tmp.block(0,0,common_rows,common_cols) = _this.block(0,0,common_rows,common_cols); _this.derived().swap(tmp); } @@ -726,8 +966,8 @@ struct conservative_resize_like_impl { // The storage order does not allow us to use reallocation. typename Derived::PlainObject tmp(other); - const Index common_rows = (std::min)(tmp.rows(), _this.rows()); - const Index common_cols = (std::min)(tmp.cols(), _this.cols()); + const Index common_rows = numext::mini(tmp.rows(), _this.rows()); + const Index common_cols = numext::mini(tmp.cols(), _this.cols()); tmp.block(0,0,common_rows,common_cols) = _this.block(0,0,common_rows,common_cols); _this.derived().swap(tmp); } @@ -742,7 +982,6 @@ struct conservative_resize_like_impl { using conservative_resize_like_impl::run; - typedef typename Derived::Index Index; static void run(DenseBase& _this, Index size) { const Index new_rows = Derived::RowsAtCompileTime==1 ? 1 : size; @@ -768,6 +1007,7 @@ struct conservative_resize_like_impl template struct matrix_swap_impl { + EIGEN_DEVICE_FUNC static inline void run(MatrixTypeA& a, MatrixTypeB& b) { a.base().swap(b); @@ -777,6 +1017,7 @@ struct matrix_swap_impl template struct matrix_swap_impl { + EIGEN_DEVICE_FUNC static inline void run(MatrixTypeA& a, MatrixTypeB& b) { static_cast(a).m_storage.swap(static_cast(b).m_storage); diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/Product.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/Product.h new file mode 100644 index 00000000..ae0c94b3 --- /dev/null +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/Product.h @@ -0,0 +1,186 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2008-2011 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_PRODUCT_H +#define EIGEN_PRODUCT_H + +namespace Eigen { + +template class ProductImpl; + +namespace internal { + +template +struct traits > +{ + typedef typename remove_all::type LhsCleaned; + typedef typename remove_all::type RhsCleaned; + typedef traits LhsTraits; + typedef traits RhsTraits; + + typedef MatrixXpr XprKind; + + typedef typename ScalarBinaryOpTraits::Scalar, typename traits::Scalar>::ReturnType Scalar; + typedef typename product_promote_storage_type::ret>::ret StorageKind; + typedef typename promote_index_type::type StorageIndex; + + enum { + RowsAtCompileTime = LhsTraits::RowsAtCompileTime, + ColsAtCompileTime = RhsTraits::ColsAtCompileTime, + MaxRowsAtCompileTime = LhsTraits::MaxRowsAtCompileTime, + MaxColsAtCompileTime = RhsTraits::MaxColsAtCompileTime, + + // FIXME: only needed by GeneralMatrixMatrixTriangular + InnerSize = EIGEN_SIZE_MIN_PREFER_FIXED(LhsTraits::ColsAtCompileTime, RhsTraits::RowsAtCompileTime), + + // The storage order is somewhat arbitrary here. The correct one will be determined through the evaluator. + Flags = (MaxRowsAtCompileTime==1 && MaxColsAtCompileTime!=1) ? RowMajorBit + : (MaxColsAtCompileTime==1 && MaxRowsAtCompileTime!=1) ? 0 + : ( ((LhsTraits::Flags&NoPreferredStorageOrderBit) && (RhsTraits::Flags&RowMajorBit)) + || ((RhsTraits::Flags&NoPreferredStorageOrderBit) && (LhsTraits::Flags&RowMajorBit)) ) ? RowMajorBit + : NoPreferredStorageOrderBit + }; +}; + +} // end namespace internal + +/** \class Product + * \ingroup Core_Module + * + * \brief Expression of the product of two arbitrary matrices or vectors + * + * \tparam _Lhs the type of the left-hand side expression + * \tparam _Rhs the type of the right-hand side expression + * + * This class represents an expression of the product of two arbitrary matrices. + * + * The other template parameters are: + * \tparam Option can be DefaultProduct, AliasFreeProduct, or LazyProduct + * + */ +template +class Product : public ProductImpl<_Lhs,_Rhs,Option, + typename internal::product_promote_storage_type::StorageKind, + typename internal::traits<_Rhs>::StorageKind, + internal::product_type<_Lhs,_Rhs>::ret>::ret> +{ + public: + + typedef _Lhs Lhs; + typedef _Rhs Rhs; + + typedef typename ProductImpl< + Lhs, Rhs, Option, + typename internal::product_promote_storage_type::StorageKind, + typename internal::traits::StorageKind, + internal::product_type::ret>::ret>::Base Base; + EIGEN_GENERIC_PUBLIC_INTERFACE(Product) + + typedef typename internal::ref_selector::type LhsNested; + typedef typename internal::ref_selector::type RhsNested; + typedef typename internal::remove_all::type LhsNestedCleaned; + typedef typename internal::remove_all::type RhsNestedCleaned; + + EIGEN_DEVICE_FUNC Product(const Lhs& lhs, const Rhs& rhs) : m_lhs(lhs), m_rhs(rhs) + { + eigen_assert(lhs.cols() == rhs.rows() + && "invalid matrix product" + && "if you wanted a coeff-wise or a dot product use the respective explicit functions"); + } + + EIGEN_DEVICE_FUNC inline Index rows() const { return m_lhs.rows(); } + EIGEN_DEVICE_FUNC inline Index cols() const { return m_rhs.cols(); } + + EIGEN_DEVICE_FUNC const LhsNestedCleaned& lhs() const { return m_lhs; } + EIGEN_DEVICE_FUNC const RhsNestedCleaned& rhs() const { return m_rhs; } + + protected: + + LhsNested m_lhs; + RhsNested m_rhs; +}; + +namespace internal { + +template::ret> +class dense_product_base + : public internal::dense_xpr_base >::type +{}; + +/** Convertion to scalar for inner-products */ +template +class dense_product_base + : public internal::dense_xpr_base >::type +{ + typedef Product ProductXpr; + typedef typename internal::dense_xpr_base::type Base; +public: + using Base::derived; + typedef typename Base::Scalar Scalar; + + operator const Scalar() const + { + return internal::evaluator(derived()).coeff(0,0); + } +}; + +} // namespace internal + +// Generic API dispatcher +template +class ProductImpl : public internal::generic_xpr_base, MatrixXpr, StorageKind>::type +{ + public: + typedef typename internal::generic_xpr_base, MatrixXpr, StorageKind>::type Base; +}; + +template +class ProductImpl + : public internal::dense_product_base +{ + typedef Product Derived; + + public: + + typedef typename internal::dense_product_base Base; + EIGEN_DENSE_PUBLIC_INTERFACE(Derived) + protected: + enum { + IsOneByOne = (RowsAtCompileTime == 1 || RowsAtCompileTime == Dynamic) && + (ColsAtCompileTime == 1 || ColsAtCompileTime == Dynamic), + EnableCoeff = IsOneByOne || Option==LazyProduct + }; + + public: + + EIGEN_DEVICE_FUNC Scalar coeff(Index row, Index col) const + { + EIGEN_STATIC_ASSERT(EnableCoeff, THIS_METHOD_IS_ONLY_FOR_INNER_OR_LAZY_PRODUCTS); + eigen_assert( (Option==LazyProduct) || (this->rows() == 1 && this->cols() == 1) ); + + return internal::evaluator(derived()).coeff(row,col); + } + + EIGEN_DEVICE_FUNC Scalar coeff(Index i) const + { + EIGEN_STATIC_ASSERT(EnableCoeff, THIS_METHOD_IS_ONLY_FOR_INNER_OR_LAZY_PRODUCTS); + eigen_assert( (Option==LazyProduct) || (this->rows() == 1 && this->cols() == 1) ); + + return internal::evaluator(derived()).coeff(i); + } + + +}; + +} // end namespace Eigen + +#endif // EIGEN_PRODUCT_H diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/ProductBase.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/ProductBase.h deleted file mode 100644 index cf74470a..00000000 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/ProductBase.h +++ /dev/null @@ -1,290 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2009-2010 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#ifndef EIGEN_PRODUCTBASE_H -#define EIGEN_PRODUCTBASE_H - -namespace Eigen { - -/** \class ProductBase - * \ingroup Core_Module - * - */ - -namespace internal { -template -struct traits > -{ - typedef MatrixXpr XprKind; - typedef typename remove_all<_Lhs>::type Lhs; - typedef typename remove_all<_Rhs>::type Rhs; - typedef typename scalar_product_traits::ReturnType Scalar; - typedef typename promote_storage_type::StorageKind, - typename traits::StorageKind>::ret StorageKind; - typedef typename promote_index_type::Index, - typename traits::Index>::type Index; - enum { - RowsAtCompileTime = traits::RowsAtCompileTime, - ColsAtCompileTime = traits::ColsAtCompileTime, - MaxRowsAtCompileTime = traits::MaxRowsAtCompileTime, - MaxColsAtCompileTime = traits::MaxColsAtCompileTime, - Flags = (MaxRowsAtCompileTime==1 ? RowMajorBit : 0) - | EvalBeforeNestingBit | EvalBeforeAssigningBit | NestByRefBit, - // Note that EvalBeforeNestingBit and NestByRefBit - // are not used in practice because nested is overloaded for products - CoeffReadCost = 0 // FIXME why is it needed ? - }; -}; -} - -#define EIGEN_PRODUCT_PUBLIC_INTERFACE(Derived) \ - typedef ProductBase Base; \ - EIGEN_DENSE_PUBLIC_INTERFACE(Derived) \ - typedef typename Base::LhsNested LhsNested; \ - typedef typename Base::_LhsNested _LhsNested; \ - typedef typename Base::LhsBlasTraits LhsBlasTraits; \ - typedef typename Base::ActualLhsType ActualLhsType; \ - typedef typename Base::_ActualLhsType _ActualLhsType; \ - typedef typename Base::RhsNested RhsNested; \ - typedef typename Base::_RhsNested _RhsNested; \ - typedef typename Base::RhsBlasTraits RhsBlasTraits; \ - typedef typename Base::ActualRhsType ActualRhsType; \ - typedef typename Base::_ActualRhsType _ActualRhsType; \ - using Base::m_lhs; \ - using Base::m_rhs; - -template -class ProductBase : public MatrixBase -{ - public: - typedef MatrixBase Base; - EIGEN_DENSE_PUBLIC_INTERFACE(ProductBase) - - typedef typename Lhs::Nested LhsNested; - typedef typename internal::remove_all::type _LhsNested; - typedef internal::blas_traits<_LhsNested> LhsBlasTraits; - typedef typename LhsBlasTraits::DirectLinearAccessType ActualLhsType; - typedef typename internal::remove_all::type _ActualLhsType; - typedef typename internal::traits::Scalar LhsScalar; - - typedef typename Rhs::Nested RhsNested; - typedef typename internal::remove_all::type _RhsNested; - typedef internal::blas_traits<_RhsNested> RhsBlasTraits; - typedef typename RhsBlasTraits::DirectLinearAccessType ActualRhsType; - typedef typename internal::remove_all::type _ActualRhsType; - typedef typename internal::traits::Scalar RhsScalar; - - // Diagonal of a product: no need to evaluate the arguments because they are going to be evaluated only once - typedef CoeffBasedProduct FullyLazyCoeffBaseProductType; - - public: - -#ifndef EIGEN_NO_MALLOC - typedef typename Base::PlainObject BasePlainObject; - typedef Matrix DynPlainObject; - typedef typename internal::conditional<(BasePlainObject::SizeAtCompileTime==Dynamic) || (BasePlainObject::SizeAtCompileTime*int(sizeof(Scalar)) < int(EIGEN_STACK_ALLOCATION_LIMIT)), - BasePlainObject, DynPlainObject>::type PlainObject; -#else - typedef typename Base::PlainObject PlainObject; -#endif - - ProductBase(const Lhs& a_lhs, const Rhs& a_rhs) - : m_lhs(a_lhs), m_rhs(a_rhs) - { - eigen_assert(a_lhs.cols() == a_rhs.rows() - && "invalid matrix product" - && "if you wanted a coeff-wise or a dot product use the respective explicit functions"); - } - - inline Index rows() const { return m_lhs.rows(); } - inline Index cols() const { return m_rhs.cols(); } - - template - inline void evalTo(Dest& dst) const { dst.setZero(); scaleAndAddTo(dst,Scalar(1)); } - - template - inline void addTo(Dest& dst) const { scaleAndAddTo(dst,Scalar(1)); } - - template - inline void subTo(Dest& dst) const { scaleAndAddTo(dst,Scalar(-1)); } - - template - inline void scaleAndAddTo(Dest& dst, const Scalar& alpha) const { derived().scaleAndAddTo(dst,alpha); } - - const _LhsNested& lhs() const { return m_lhs; } - const _RhsNested& rhs() const { return m_rhs; } - - // Implicit conversion to the nested type (trigger the evaluation of the product) - operator const PlainObject& () const - { - m_result.resize(m_lhs.rows(), m_rhs.cols()); - derived().evalTo(m_result); - return m_result; - } - - const Diagonal diagonal() const - { return FullyLazyCoeffBaseProductType(m_lhs, m_rhs); } - - template - const Diagonal diagonal() const - { return FullyLazyCoeffBaseProductType(m_lhs, m_rhs); } - - const Diagonal diagonal(Index index) const - { return FullyLazyCoeffBaseProductType(m_lhs, m_rhs).diagonal(index); } - - // restrict coeff accessors to 1x1 expressions. No need to care about mutators here since this isnt a Lvalue expression - typename Base::CoeffReturnType coeff(Index row, Index col) const - { -#ifdef EIGEN2_SUPPORT - return lhs().row(row).cwiseProduct(rhs().col(col).transpose()).sum(); -#else - EIGEN_STATIC_ASSERT_SIZE_1x1(Derived) - eigen_assert(this->rows() == 1 && this->cols() == 1); - Matrix result = *this; - return result.coeff(row,col); -#endif - } - - typename Base::CoeffReturnType coeff(Index i) const - { - EIGEN_STATIC_ASSERT_SIZE_1x1(Derived) - eigen_assert(this->rows() == 1 && this->cols() == 1); - Matrix result = *this; - return result.coeff(i); - } - - const Scalar& coeffRef(Index row, Index col) const - { - EIGEN_STATIC_ASSERT_SIZE_1x1(Derived) - eigen_assert(this->rows() == 1 && this->cols() == 1); - return derived().coeffRef(row,col); - } - - const Scalar& coeffRef(Index i) const - { - EIGEN_STATIC_ASSERT_SIZE_1x1(Derived) - eigen_assert(this->rows() == 1 && this->cols() == 1); - return derived().coeffRef(i); - } - - protected: - - LhsNested m_lhs; - RhsNested m_rhs; - - mutable PlainObject m_result; -}; - -// here we need to overload the nested rule for products -// such that the nested type is a const reference to a plain matrix -namespace internal { -template -struct nested, N, PlainObject> -{ - typedef typename GeneralProduct::PlainObject const& type; -}; -template -struct nested, N, PlainObject> -{ - typedef typename GeneralProduct::PlainObject const& type; -}; -} - -template -class ScaledProduct; - -// Note that these two operator* functions are not defined as member -// functions of ProductBase, because, otherwise we would have to -// define all overloads defined in MatrixBase. Furthermore, Using -// "using Base::operator*" would not work with MSVC. -// -// Also note that here we accept any compatible scalar types -template -const ScaledProduct -operator*(const ProductBase& prod, const typename Derived::Scalar& x) -{ return ScaledProduct(prod.derived(), x); } - -template -typename internal::enable_if::value, - const ScaledProduct >::type -operator*(const ProductBase& prod, const typename Derived::RealScalar& x) -{ return ScaledProduct(prod.derived(), x); } - - -template -const ScaledProduct -operator*(const typename Derived::Scalar& x,const ProductBase& prod) -{ return ScaledProduct(prod.derived(), x); } - -template -typename internal::enable_if::value, - const ScaledProduct >::type -operator*(const typename Derived::RealScalar& x,const ProductBase& prod) -{ return ScaledProduct(prod.derived(), x); } - -namespace internal { -template -struct traits > - : traits, - typename NestedProduct::_LhsNested, - typename NestedProduct::_RhsNested> > -{ - typedef typename traits::StorageKind StorageKind; -}; -} - -template -class ScaledProduct - : public ProductBase, - typename NestedProduct::_LhsNested, - typename NestedProduct::_RhsNested> -{ - public: - typedef ProductBase, - typename NestedProduct::_LhsNested, - typename NestedProduct::_RhsNested> Base; - typedef typename Base::Scalar Scalar; - typedef typename Base::PlainObject PlainObject; -// EIGEN_PRODUCT_PUBLIC_INTERFACE(ScaledProduct) - - ScaledProduct(const NestedProduct& prod, const Scalar& x) - : Base(prod.lhs(),prod.rhs()), m_prod(prod), m_alpha(x) {} - - template - inline void evalTo(Dest& dst) const { dst.setZero(); scaleAndAddTo(dst, Scalar(1)); } - - template - inline void addTo(Dest& dst) const { scaleAndAddTo(dst, Scalar(1)); } - - template - inline void subTo(Dest& dst) const { scaleAndAddTo(dst, Scalar(-1)); } - - template - inline void scaleAndAddTo(Dest& dst, const Scalar& a_alpha) const { m_prod.derived().scaleAndAddTo(dst,a_alpha * m_alpha); } - - const Scalar& alpha() const { return m_alpha; } - - protected: - const NestedProduct& m_prod; - Scalar m_alpha; -}; - -/** \internal - * Overloaded to perform an efficient C = (A*B).lazy() */ -template -template -Derived& MatrixBase::lazyAssign(const ProductBase& other) -{ - other.derived().evalTo(derived()); - return derived(); -} - -} // end namespace Eigen - -#endif // EIGEN_PRODUCTBASE_H diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/ProductEvaluators.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/ProductEvaluators.h new file mode 100644 index 00000000..583b7f59 --- /dev/null +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/ProductEvaluators.h @@ -0,0 +1,1099 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2006-2008 Benoit Jacob +// Copyright (C) 2008-2010 Gael Guennebaud +// Copyright (C) 2011 Jitse Niesen +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + + +#ifndef EIGEN_PRODUCTEVALUATORS_H +#define EIGEN_PRODUCTEVALUATORS_H + +namespace Eigen { + +namespace internal { + +/** \internal + * Evaluator of a product expression. + * Since products require special treatments to handle all possible cases, + * we simply deffer the evaluation logic to a product_evaluator class + * which offers more partial specialization possibilities. + * + * \sa class product_evaluator + */ +template +struct evaluator > + : public product_evaluator > +{ + typedef Product XprType; + typedef product_evaluator Base; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) : Base(xpr) {} +}; + +// Catch "scalar * ( A * B )" and transform it to "(A*scalar) * B" +// TODO we should apply that rule only if that's really helpful +template +struct evaluator_assume_aliasing, + const CwiseNullaryOp, Plain1>, + const Product > > +{ + static const bool value = true; +}; +template +struct evaluator, + const CwiseNullaryOp, Plain1>, + const Product > > + : public evaluator > +{ + typedef CwiseBinaryOp, + const CwiseNullaryOp, Plain1>, + const Product > XprType; + typedef evaluator > Base; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) + : Base(xpr.lhs().functor().m_other * xpr.rhs().lhs() * xpr.rhs().rhs()) + {} +}; + + +template +struct evaluator, DiagIndex> > + : public evaluator, DiagIndex> > +{ + typedef Diagonal, DiagIndex> XprType; + typedef evaluator, DiagIndex> > Base; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) + : Base(Diagonal, DiagIndex>( + Product(xpr.nestedExpression().lhs(), xpr.nestedExpression().rhs()), + xpr.index() )) + {} +}; + + +// Helper class to perform a matrix product with the destination at hand. +// Depending on the sizes of the factors, there are different evaluation strategies +// as controlled by internal::product_type. +template< typename Lhs, typename Rhs, + typename LhsShape = typename evaluator_traits::Shape, + typename RhsShape = typename evaluator_traits::Shape, + int ProductType = internal::product_type::value> +struct generic_product_impl; + +template +struct evaluator_assume_aliasing > { + static const bool value = true; +}; + +// This is the default evaluator implementation for products: +// It creates a temporary and call generic_product_impl +template +struct product_evaluator, ProductTag, LhsShape, RhsShape> + : public evaluator::PlainObject> +{ + typedef Product XprType; + typedef typename XprType::PlainObject PlainObject; + typedef evaluator Base; + enum { + Flags = Base::Flags | EvalBeforeNestingBit + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit product_evaluator(const XprType& xpr) + : m_result(xpr.rows(), xpr.cols()) + { + ::new (static_cast(this)) Base(m_result); + +// FIXME shall we handle nested_eval here?, +// if so, then we must take care at removing the call to nested_eval in the specializations (e.g., in permutation_matrix_product, transposition_matrix_product, etc.) +// typedef typename internal::nested_eval::type LhsNested; +// typedef typename internal::nested_eval::type RhsNested; +// typedef typename internal::remove_all::type LhsNestedCleaned; +// typedef typename internal::remove_all::type RhsNestedCleaned; +// +// const LhsNested lhs(xpr.lhs()); +// const RhsNested rhs(xpr.rhs()); +// +// generic_product_impl::evalTo(m_result, lhs, rhs); + + generic_product_impl::evalTo(m_result, xpr.lhs(), xpr.rhs()); + } + +protected: + PlainObject m_result; +}; + +// The following three shortcuts are enabled only if the scalar types match excatly. +// TODO: we could enable them for different scalar types when the product is not vectorized. + +// Dense = Product +template< typename DstXprType, typename Lhs, typename Rhs, int Options, typename Scalar> +struct Assignment, internal::assign_op, Dense2Dense, + typename enable_if<(Options==DefaultProduct || Options==AliasFreeProduct)>::type> +{ + typedef Product SrcXprType; + static EIGEN_STRONG_INLINE + void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op &) + { + Index dstRows = src.rows(); + Index dstCols = src.cols(); + if((dst.rows()!=dstRows) || (dst.cols()!=dstCols)) + dst.resize(dstRows, dstCols); + // FIXME shall we handle nested_eval here? + generic_product_impl::evalTo(dst, src.lhs(), src.rhs()); + } +}; + +// Dense += Product +template< typename DstXprType, typename Lhs, typename Rhs, int Options, typename Scalar> +struct Assignment, internal::add_assign_op, Dense2Dense, + typename enable_if<(Options==DefaultProduct || Options==AliasFreeProduct)>::type> +{ + typedef Product SrcXprType; + static EIGEN_STRONG_INLINE + void run(DstXprType &dst, const SrcXprType &src, const internal::add_assign_op &) + { + eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); + // FIXME shall we handle nested_eval here? + generic_product_impl::addTo(dst, src.lhs(), src.rhs()); + } +}; + +// Dense -= Product +template< typename DstXprType, typename Lhs, typename Rhs, int Options, typename Scalar> +struct Assignment, internal::sub_assign_op, Dense2Dense, + typename enable_if<(Options==DefaultProduct || Options==AliasFreeProduct)>::type> +{ + typedef Product SrcXprType; + static EIGEN_STRONG_INLINE + void run(DstXprType &dst, const SrcXprType &src, const internal::sub_assign_op &) + { + eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); + // FIXME shall we handle nested_eval here? + generic_product_impl::subTo(dst, src.lhs(), src.rhs()); + } +}; + + +// Dense ?= scalar * Product +// TODO we should apply that rule if that's really helpful +// for instance, this is not good for inner products +template< typename DstXprType, typename Lhs, typename Rhs, typename AssignFunc, typename Scalar, typename ScalarBis, typename Plain> +struct Assignment, const CwiseNullaryOp,Plain>, + const Product >, AssignFunc, Dense2Dense> +{ + typedef CwiseBinaryOp, + const CwiseNullaryOp,Plain>, + const Product > SrcXprType; + static EIGEN_STRONG_INLINE + void run(DstXprType &dst, const SrcXprType &src, const AssignFunc& func) + { + call_assignment_no_alias(dst, (src.lhs().functor().m_other * src.rhs().lhs())*src.rhs().rhs(), func); + } +}; + +//---------------------------------------- +// Catch "Dense ?= xpr + Product<>" expression to save one temporary +// FIXME we could probably enable these rules for any product, i.e., not only Dense and DefaultProduct + +template +struct evaluator_assume_aliasing::Scalar>, const OtherXpr, + const Product >, DenseShape > { + static const bool value = true; +}; + +template +struct assignment_from_xpr_op_product +{ + template + static EIGEN_STRONG_INLINE + void run(DstXprType &dst, const SrcXprType &src, const InitialFunc& /*func*/) + { + call_assignment_no_alias(dst, src.lhs(), Func1()); + call_assignment_no_alias(dst, src.rhs(), Func2()); + } +}; + +#define EIGEN_CATCH_ASSIGN_XPR_OP_PRODUCT(ASSIGN_OP,BINOP,ASSIGN_OP2) \ + template< typename DstXprType, typename OtherXpr, typename Lhs, typename Rhs, typename DstScalar, typename SrcScalar, typename OtherScalar,typename ProdScalar> \ + struct Assignment, const OtherXpr, \ + const Product >, internal::ASSIGN_OP, Dense2Dense> \ + : assignment_from_xpr_op_product, internal::ASSIGN_OP, internal::ASSIGN_OP2 > \ + {} + +EIGEN_CATCH_ASSIGN_XPR_OP_PRODUCT(assign_op, scalar_sum_op,add_assign_op); +EIGEN_CATCH_ASSIGN_XPR_OP_PRODUCT(add_assign_op,scalar_sum_op,add_assign_op); +EIGEN_CATCH_ASSIGN_XPR_OP_PRODUCT(sub_assign_op,scalar_sum_op,sub_assign_op); + +EIGEN_CATCH_ASSIGN_XPR_OP_PRODUCT(assign_op, scalar_difference_op,sub_assign_op); +EIGEN_CATCH_ASSIGN_XPR_OP_PRODUCT(add_assign_op,scalar_difference_op,sub_assign_op); +EIGEN_CATCH_ASSIGN_XPR_OP_PRODUCT(sub_assign_op,scalar_difference_op,add_assign_op); + +//---------------------------------------- + +template +struct generic_product_impl +{ + template + static inline void evalTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { + dst.coeffRef(0,0) = (lhs.transpose().cwiseProduct(rhs)).sum(); + } + + template + static inline void addTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { + dst.coeffRef(0,0) += (lhs.transpose().cwiseProduct(rhs)).sum(); + } + + template + static void subTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { dst.coeffRef(0,0) -= (lhs.transpose().cwiseProduct(rhs)).sum(); } +}; + + +/*********************************************************************** +* Implementation of outer dense * dense vector product +***********************************************************************/ + +// Column major result +template +void outer_product_selector_run(Dst& dst, const Lhs &lhs, const Rhs &rhs, const Func& func, const false_type&) +{ + evaluator rhsEval(rhs); + typename nested_eval::type actual_lhs(lhs); + // FIXME if cols is large enough, then it might be useful to make sure that lhs is sequentially stored + // FIXME not very good if rhs is real and lhs complex while alpha is real too + const Index cols = dst.cols(); + for (Index j=0; j +void outer_product_selector_run(Dst& dst, const Lhs &lhs, const Rhs &rhs, const Func& func, const true_type&) +{ + evaluator lhsEval(lhs); + typename nested_eval::type actual_rhs(rhs); + // FIXME if rows is large enough, then it might be useful to make sure that rhs is sequentially stored + // FIXME not very good if lhs is real and rhs complex while alpha is real too + const Index rows = dst.rows(); + for (Index i=0; i +struct generic_product_impl +{ + template struct is_row_major : internal::conditional<(int(T::Flags)&RowMajorBit), internal::true_type, internal::false_type>::type {}; + typedef typename Product::Scalar Scalar; + + // TODO it would be nice to be able to exploit our *_assign_op functors for that purpose + struct set { template void operator()(const Dst& dst, const Src& src) const { dst.const_cast_derived() = src; } }; + struct add { template void operator()(const Dst& dst, const Src& src) const { dst.const_cast_derived() += src; } }; + struct sub { template void operator()(const Dst& dst, const Src& src) const { dst.const_cast_derived() -= src; } }; + struct adds { + Scalar m_scale; + explicit adds(const Scalar& s) : m_scale(s) {} + template void operator()(const Dst& dst, const Src& src) const { + dst.const_cast_derived() += m_scale * src; + } + }; + + template + static inline void evalTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { + internal::outer_product_selector_run(dst, lhs, rhs, set(), is_row_major()); + } + + template + static inline void addTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { + internal::outer_product_selector_run(dst, lhs, rhs, add(), is_row_major()); + } + + template + static inline void subTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { + internal::outer_product_selector_run(dst, lhs, rhs, sub(), is_row_major()); + } + + template + static inline void scaleAndAddTo(Dst& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) + { + internal::outer_product_selector_run(dst, lhs, rhs, adds(alpha), is_row_major()); + } + +}; + + +// This base class provides default implementations for evalTo, addTo, subTo, in terms of scaleAndAddTo +template +struct generic_product_impl_base +{ + typedef typename Product::Scalar Scalar; + + template + static EIGEN_STRONG_INLINE void evalTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { dst.setZero(); scaleAndAddTo(dst, lhs, rhs, Scalar(1)); } + + template + static EIGEN_STRONG_INLINE void addTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { scaleAndAddTo(dst,lhs, rhs, Scalar(1)); } + + template + static EIGEN_STRONG_INLINE void subTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { scaleAndAddTo(dst, lhs, rhs, Scalar(-1)); } + + template + static EIGEN_STRONG_INLINE void scaleAndAddTo(Dst& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) + { Derived::scaleAndAddTo(dst,lhs,rhs,alpha); } + +}; + +template +struct generic_product_impl + : generic_product_impl_base > +{ + typedef typename nested_eval::type LhsNested; + typedef typename nested_eval::type RhsNested; + typedef typename Product::Scalar Scalar; + enum { Side = Lhs::IsVectorAtCompileTime ? OnTheLeft : OnTheRight }; + typedef typename internal::remove_all::type>::type MatrixType; + + template + static EIGEN_STRONG_INLINE void scaleAndAddTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) + { + LhsNested actual_lhs(lhs); + RhsNested actual_rhs(rhs); + internal::gemv_dense_selector::HasUsableDirectAccess) + >::run(actual_lhs, actual_rhs, dst, alpha); + } +}; + +template +struct generic_product_impl +{ + typedef typename Product::Scalar Scalar; + + template + static EIGEN_STRONG_INLINE void evalTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { + // Same as: dst.noalias() = lhs.lazyProduct(rhs); + // but easier on the compiler side + call_assignment_no_alias(dst, lhs.lazyProduct(rhs), internal::assign_op()); + } + + template + static EIGEN_STRONG_INLINE void addTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { + // dst.noalias() += lhs.lazyProduct(rhs); + call_assignment_no_alias(dst, lhs.lazyProduct(rhs), internal::add_assign_op()); + } + + template + static EIGEN_STRONG_INLINE void subTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { + // dst.noalias() -= lhs.lazyProduct(rhs); + call_assignment_no_alias(dst, lhs.lazyProduct(rhs), internal::sub_assign_op()); + } + +// template +// static inline void scaleAndAddTo(Dst& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) +// { dst.noalias() += alpha * lhs.lazyProduct(rhs); } +}; + +// This specialization enforces the use of a coefficient-based evaluation strategy +template +struct generic_product_impl + : generic_product_impl {}; + +// Case 2: Evaluate coeff by coeff +// +// This is mostly taken from CoeffBasedProduct.h +// The main difference is that we add an extra argument to the etor_product_*_impl::run() function +// for the inner dimension of the product, because evaluator object do not know their size. + +template +struct etor_product_coeff_impl; + +template +struct etor_product_packet_impl; + +template +struct product_evaluator, ProductTag, DenseShape, DenseShape> + : evaluator_base > +{ + typedef Product XprType; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit product_evaluator(const XprType& xpr) + : m_lhs(xpr.lhs()), + m_rhs(xpr.rhs()), + m_lhsImpl(m_lhs), // FIXME the creation of the evaluator objects should result in a no-op, but check that! + m_rhsImpl(m_rhs), // Moreover, they are only useful for the packet path, so we could completely disable them when not needed, + // or perhaps declare them on the fly on the packet method... We have experiment to check what's best. + m_innerDim(xpr.lhs().cols()) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(NumTraits::MulCost); + EIGEN_INTERNAL_CHECK_COST_VALUE(NumTraits::AddCost); + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); +#if 0 + std::cerr << "LhsOuterStrideBytes= " << LhsOuterStrideBytes << "\n"; + std::cerr << "RhsOuterStrideBytes= " << RhsOuterStrideBytes << "\n"; + std::cerr << "LhsAlignment= " << LhsAlignment << "\n"; + std::cerr << "RhsAlignment= " << RhsAlignment << "\n"; + std::cerr << "CanVectorizeLhs= " << CanVectorizeLhs << "\n"; + std::cerr << "CanVectorizeRhs= " << CanVectorizeRhs << "\n"; + std::cerr << "CanVectorizeInner= " << CanVectorizeInner << "\n"; + std::cerr << "EvalToRowMajor= " << EvalToRowMajor << "\n"; + std::cerr << "Alignment= " << Alignment << "\n"; + std::cerr << "Flags= " << Flags << "\n"; +#endif + } + + // Everything below here is taken from CoeffBasedProduct.h + + typedef typename internal::nested_eval::type LhsNested; + typedef typename internal::nested_eval::type RhsNested; + + typedef typename internal::remove_all::type LhsNestedCleaned; + typedef typename internal::remove_all::type RhsNestedCleaned; + + typedef evaluator LhsEtorType; + typedef evaluator RhsEtorType; + + enum { + RowsAtCompileTime = LhsNestedCleaned::RowsAtCompileTime, + ColsAtCompileTime = RhsNestedCleaned::ColsAtCompileTime, + InnerSize = EIGEN_SIZE_MIN_PREFER_FIXED(LhsNestedCleaned::ColsAtCompileTime, RhsNestedCleaned::RowsAtCompileTime), + MaxRowsAtCompileTime = LhsNestedCleaned::MaxRowsAtCompileTime, + MaxColsAtCompileTime = RhsNestedCleaned::MaxColsAtCompileTime + }; + + typedef typename find_best_packet::type LhsVecPacketType; + typedef typename find_best_packet::type RhsVecPacketType; + + enum { + + LhsCoeffReadCost = LhsEtorType::CoeffReadCost, + RhsCoeffReadCost = RhsEtorType::CoeffReadCost, + CoeffReadCost = InnerSize==0 ? NumTraits::ReadCost + : InnerSize == Dynamic ? HugeCost + : InnerSize * (NumTraits::MulCost + LhsCoeffReadCost + RhsCoeffReadCost) + + (InnerSize - 1) * NumTraits::AddCost, + + Unroll = CoeffReadCost <= EIGEN_UNROLLING_LIMIT, + + LhsFlags = LhsEtorType::Flags, + RhsFlags = RhsEtorType::Flags, + + LhsRowMajor = LhsFlags & RowMajorBit, + RhsRowMajor = RhsFlags & RowMajorBit, + + LhsVecPacketSize = unpacket_traits::size, + RhsVecPacketSize = unpacket_traits::size, + + // Here, we don't care about alignment larger than the usable packet size. + LhsAlignment = EIGEN_PLAIN_ENUM_MIN(LhsEtorType::Alignment,LhsVecPacketSize*int(sizeof(typename LhsNestedCleaned::Scalar))), + RhsAlignment = EIGEN_PLAIN_ENUM_MIN(RhsEtorType::Alignment,RhsVecPacketSize*int(sizeof(typename RhsNestedCleaned::Scalar))), + + SameType = is_same::value, + + CanVectorizeRhs = bool(RhsRowMajor) && (RhsFlags & PacketAccessBit) && (ColsAtCompileTime!=1), + CanVectorizeLhs = (!LhsRowMajor) && (LhsFlags & PacketAccessBit) && (RowsAtCompileTime!=1), + + EvalToRowMajor = (MaxRowsAtCompileTime==1&&MaxColsAtCompileTime!=1) ? 1 + : (MaxColsAtCompileTime==1&&MaxRowsAtCompileTime!=1) ? 0 + : (bool(RhsRowMajor) && !CanVectorizeLhs), + + Flags = ((unsigned int)(LhsFlags | RhsFlags) & HereditaryBits & ~RowMajorBit) + | (EvalToRowMajor ? RowMajorBit : 0) + // TODO enable vectorization for mixed types + | (SameType && (CanVectorizeLhs || CanVectorizeRhs) ? PacketAccessBit : 0) + | (XprType::IsVectorAtCompileTime ? LinearAccessBit : 0), + + LhsOuterStrideBytes = int(LhsNestedCleaned::OuterStrideAtCompileTime) * int(sizeof(typename LhsNestedCleaned::Scalar)), + RhsOuterStrideBytes = int(RhsNestedCleaned::OuterStrideAtCompileTime) * int(sizeof(typename RhsNestedCleaned::Scalar)), + + Alignment = bool(CanVectorizeLhs) ? (LhsOuterStrideBytes<=0 || (int(LhsOuterStrideBytes) % EIGEN_PLAIN_ENUM_MAX(1,LhsAlignment))!=0 ? 0 : LhsAlignment) + : bool(CanVectorizeRhs) ? (RhsOuterStrideBytes<=0 || (int(RhsOuterStrideBytes) % EIGEN_PLAIN_ENUM_MAX(1,RhsAlignment))!=0 ? 0 : RhsAlignment) + : 0, + + /* CanVectorizeInner deserves special explanation. It does not affect the product flags. It is not used outside + * of Product. If the Product itself is not a packet-access expression, there is still a chance that the inner + * loop of the product might be vectorized. This is the meaning of CanVectorizeInner. Since it doesn't affect + * the Flags, it is safe to make this value depend on ActualPacketAccessBit, that doesn't affect the ABI. + */ + CanVectorizeInner = SameType + && LhsRowMajor + && (!RhsRowMajor) + && (LhsFlags & RhsFlags & ActualPacketAccessBit) + && (InnerSize % packet_traits::size == 0) + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const CoeffReturnType coeff(Index row, Index col) const + { + return (m_lhs.row(row).transpose().cwiseProduct( m_rhs.col(col) )).sum(); + } + + /* Allow index-based non-packet access. It is impossible though to allow index-based packed access, + * which is why we don't set the LinearAccessBit. + * TODO: this seems possible when the result is a vector + */ + EIGEN_DEVICE_FUNC const CoeffReturnType coeff(Index index) const + { + const Index row = (RowsAtCompileTime == 1 || MaxRowsAtCompileTime==1) ? 0 : index; + const Index col = (RowsAtCompileTime == 1 || MaxRowsAtCompileTime==1) ? index : 0; + return (m_lhs.row(row).transpose().cwiseProduct( m_rhs.col(col) )).sum(); + } + + template + const PacketType packet(Index row, Index col) const + { + PacketType res; + typedef etor_product_packet_impl PacketImpl; + PacketImpl::run(row, col, m_lhsImpl, m_rhsImpl, m_innerDim, res); + return res; + } + + template + const PacketType packet(Index index) const + { + const Index row = (RowsAtCompileTime == 1 || MaxRowsAtCompileTime==1) ? 0 : index; + const Index col = (RowsAtCompileTime == 1 || MaxRowsAtCompileTime==1) ? index : 0; + return packet(row,col); + } + +protected: + typename internal::add_const_on_value_type::type m_lhs; + typename internal::add_const_on_value_type::type m_rhs; + + LhsEtorType m_lhsImpl; + RhsEtorType m_rhsImpl; + + // TODO: Get rid of m_innerDim if known at compile time + Index m_innerDim; +}; + +template +struct product_evaluator, LazyCoeffBasedProductMode, DenseShape, DenseShape> + : product_evaluator, CoeffBasedProductMode, DenseShape, DenseShape> +{ + typedef Product XprType; + typedef Product BaseProduct; + typedef product_evaluator Base; + enum { + Flags = Base::Flags | EvalBeforeNestingBit + }; + EIGEN_DEVICE_FUNC explicit product_evaluator(const XprType& xpr) + : Base(BaseProduct(xpr.lhs(),xpr.rhs())) + {} +}; + +/**************************************** +*** Coeff based product, Packet path *** +****************************************/ + +template +struct etor_product_packet_impl +{ + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index innerDim, Packet &res) + { + etor_product_packet_impl::run(row, col, lhs, rhs, innerDim, res); + res = pmadd(pset1(lhs.coeff(row, Index(UnrollingIndex-1))), rhs.template packet(Index(UnrollingIndex-1), col), res); + } +}; + +template +struct etor_product_packet_impl +{ + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index innerDim, Packet &res) + { + etor_product_packet_impl::run(row, col, lhs, rhs, innerDim, res); + res = pmadd(lhs.template packet(row, Index(UnrollingIndex-1)), pset1(rhs.coeff(Index(UnrollingIndex-1), col)), res); + } +}; + +template +struct etor_product_packet_impl +{ + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index /*innerDim*/, Packet &res) + { + res = pmul(pset1(lhs.coeff(row, Index(0))),rhs.template packet(Index(0), col)); + } +}; + +template +struct etor_product_packet_impl +{ + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index /*innerDim*/, Packet &res) + { + res = pmul(lhs.template packet(row, Index(0)), pset1(rhs.coeff(Index(0), col))); + } +}; + +template +struct etor_product_packet_impl +{ + static EIGEN_STRONG_INLINE void run(Index /*row*/, Index /*col*/, const Lhs& /*lhs*/, const Rhs& /*rhs*/, Index /*innerDim*/, Packet &res) + { + res = pset1(typename unpacket_traits::type(0)); + } +}; + +template +struct etor_product_packet_impl +{ + static EIGEN_STRONG_INLINE void run(Index /*row*/, Index /*col*/, const Lhs& /*lhs*/, const Rhs& /*rhs*/, Index /*innerDim*/, Packet &res) + { + res = pset1(typename unpacket_traits::type(0)); + } +}; + +template +struct etor_product_packet_impl +{ + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index innerDim, Packet& res) + { + res = pset1(typename unpacket_traits::type(0)); + for(Index i = 0; i < innerDim; ++i) + res = pmadd(pset1(lhs.coeff(row, i)), rhs.template packet(i, col), res); + } +}; + +template +struct etor_product_packet_impl +{ + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index innerDim, Packet& res) + { + res = pset1(typename unpacket_traits::type(0)); + for(Index i = 0; i < innerDim; ++i) + res = pmadd(lhs.template packet(row, i), pset1(rhs.coeff(i, col)), res); + } +}; + + +/*************************************************************************** +* Triangular products +***************************************************************************/ +template +struct triangular_product_impl; + +template +struct generic_product_impl + : generic_product_impl_base > +{ + typedef typename Product::Scalar Scalar; + + template + static void scaleAndAddTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) + { + triangular_product_impl + ::run(dst, lhs.nestedExpression(), rhs, alpha); + } +}; + +template +struct generic_product_impl +: generic_product_impl_base > +{ + typedef typename Product::Scalar Scalar; + + template + static void scaleAndAddTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) + { + triangular_product_impl::run(dst, lhs, rhs.nestedExpression(), alpha); + } +}; + + +/*************************************************************************** +* SelfAdjoint products +***************************************************************************/ +template +struct selfadjoint_product_impl; + +template +struct generic_product_impl + : generic_product_impl_base > +{ + typedef typename Product::Scalar Scalar; + + template + static void scaleAndAddTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) + { + selfadjoint_product_impl::run(dst, lhs.nestedExpression(), rhs, alpha); + } +}; + +template +struct generic_product_impl +: generic_product_impl_base > +{ + typedef typename Product::Scalar Scalar; + + template + static void scaleAndAddTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) + { + selfadjoint_product_impl::run(dst, lhs, rhs.nestedExpression(), alpha); + } +}; + + +/*************************************************************************** +* Diagonal products +***************************************************************************/ + +template +struct diagonal_product_evaluator_base + : evaluator_base +{ + typedef typename ScalarBinaryOpTraits::ReturnType Scalar; +public: + enum { + CoeffReadCost = NumTraits::MulCost + evaluator::CoeffReadCost + evaluator::CoeffReadCost, + + MatrixFlags = evaluator::Flags, + DiagFlags = evaluator::Flags, + _StorageOrder = MatrixFlags & RowMajorBit ? RowMajor : ColMajor, + _ScalarAccessOnDiag = !((int(_StorageOrder) == ColMajor && int(ProductOrder) == OnTheLeft) + ||(int(_StorageOrder) == RowMajor && int(ProductOrder) == OnTheRight)), + _SameTypes = is_same::value, + // FIXME currently we need same types, but in the future the next rule should be the one + //_Vectorizable = bool(int(MatrixFlags)&PacketAccessBit) && ((!_PacketOnDiag) || (_SameTypes && bool(int(DiagFlags)&PacketAccessBit))), + _Vectorizable = bool(int(MatrixFlags)&PacketAccessBit) && _SameTypes && (_ScalarAccessOnDiag || (bool(int(DiagFlags)&PacketAccessBit))), + _LinearAccessMask = (MatrixType::RowsAtCompileTime==1 || MatrixType::ColsAtCompileTime==1) ? LinearAccessBit : 0, + Flags = ((HereditaryBits|_LinearAccessMask) & (unsigned int)(MatrixFlags)) | (_Vectorizable ? PacketAccessBit : 0), + Alignment = evaluator::Alignment + }; + + diagonal_product_evaluator_base(const MatrixType &mat, const DiagonalType &diag) + : m_diagImpl(diag), m_matImpl(mat) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(NumTraits::MulCost); + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar coeff(Index idx) const + { + return m_diagImpl.coeff(idx) * m_matImpl.coeff(idx); + } + +protected: + template + EIGEN_STRONG_INLINE PacketType packet_impl(Index row, Index col, Index id, internal::true_type) const + { + return internal::pmul(m_matImpl.template packet(row, col), + internal::pset1(m_diagImpl.coeff(id))); + } + + template + EIGEN_STRONG_INLINE PacketType packet_impl(Index row, Index col, Index id, internal::false_type) const + { + enum { + InnerSize = (MatrixType::Flags & RowMajorBit) ? MatrixType::ColsAtCompileTime : MatrixType::RowsAtCompileTime, + DiagonalPacketLoadMode = EIGEN_PLAIN_ENUM_MIN(LoadMode,((InnerSize%16) == 0) ? int(Aligned16) : int(evaluator::Alignment)) // FIXME hardcoded 16!! + }; + return internal::pmul(m_matImpl.template packet(row, col), + m_diagImpl.template packet(id)); + } + + evaluator m_diagImpl; + evaluator m_matImpl; +}; + +// diagonal * dense +template +struct product_evaluator, ProductTag, DiagonalShape, DenseShape> + : diagonal_product_evaluator_base, OnTheLeft> +{ + typedef diagonal_product_evaluator_base, OnTheLeft> Base; + using Base::m_diagImpl; + using Base::m_matImpl; + using Base::coeff; + typedef typename Base::Scalar Scalar; + + typedef Product XprType; + typedef typename XprType::PlainObject PlainObject; + + enum { + StorageOrder = int(Rhs::Flags) & RowMajorBit ? RowMajor : ColMajor + }; + + EIGEN_DEVICE_FUNC explicit product_evaluator(const XprType& xpr) + : Base(xpr.rhs(), xpr.lhs().diagonal()) + { + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar coeff(Index row, Index col) const + { + return m_diagImpl.coeff(row) * m_matImpl.coeff(row, col); + } + +#ifndef __CUDACC__ + template + EIGEN_STRONG_INLINE PacketType packet(Index row, Index col) const + { + // FIXME: NVCC used to complain about the template keyword, but we have to check whether this is still the case. + // See also similar calls below. + return this->template packet_impl(row,col, row, + typename internal::conditional::type()); + } + + template + EIGEN_STRONG_INLINE PacketType packet(Index idx) const + { + return packet(int(StorageOrder)==ColMajor?idx:0,int(StorageOrder)==ColMajor?0:idx); + } +#endif +}; + +// dense * diagonal +template +struct product_evaluator, ProductTag, DenseShape, DiagonalShape> + : diagonal_product_evaluator_base, OnTheRight> +{ + typedef diagonal_product_evaluator_base, OnTheRight> Base; + using Base::m_diagImpl; + using Base::m_matImpl; + using Base::coeff; + typedef typename Base::Scalar Scalar; + + typedef Product XprType; + typedef typename XprType::PlainObject PlainObject; + + enum { StorageOrder = int(Lhs::Flags) & RowMajorBit ? RowMajor : ColMajor }; + + EIGEN_DEVICE_FUNC explicit product_evaluator(const XprType& xpr) + : Base(xpr.lhs(), xpr.rhs().diagonal()) + { + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar coeff(Index row, Index col) const + { + return m_matImpl.coeff(row, col) * m_diagImpl.coeff(col); + } + +#ifndef __CUDACC__ + template + EIGEN_STRONG_INLINE PacketType packet(Index row, Index col) const + { + return this->template packet_impl(row,col, col, + typename internal::conditional::type()); + } + + template + EIGEN_STRONG_INLINE PacketType packet(Index idx) const + { + return packet(int(StorageOrder)==ColMajor?idx:0,int(StorageOrder)==ColMajor?0:idx); + } +#endif +}; + +/*************************************************************************** +* Products with permutation matrices +***************************************************************************/ + +/** \internal + * \class permutation_matrix_product + * Internal helper class implementing the product between a permutation matrix and a matrix. + * This class is specialized for DenseShape below and for SparseShape in SparseCore/SparsePermutation.h + */ +template +struct permutation_matrix_product; + +template +struct permutation_matrix_product +{ + typedef typename nested_eval::type MatrixType; + typedef typename remove_all::type MatrixTypeCleaned; + + template + static inline void run(Dest& dst, const PermutationType& perm, const ExpressionType& xpr) + { + MatrixType mat(xpr); + const Index n = Side==OnTheLeft ? mat.rows() : mat.cols(); + // FIXME we need an is_same for expression that is not sensitive to constness. For instance + // is_same_xpr, Block >::value should be true. + //if(is_same::value && extract_data(dst) == extract_data(mat)) + if(is_same_dense(dst, mat)) + { + // apply the permutation inplace + Matrix mask(perm.size()); + mask.fill(false); + Index r = 0; + while(r < perm.size()) + { + // search for the next seed + while(r=perm.size()) + break; + // we got one, let's follow it until we are back to the seed + Index k0 = r++; + Index kPrev = k0; + mask.coeffRef(k0) = true; + for(Index k=perm.indices().coeff(k0); k!=k0; k=perm.indices().coeff(k)) + { + Block(dst, k) + .swap(Block + (dst,((Side==OnTheLeft) ^ Transposed) ? k0 : kPrev)); + + mask.coeffRef(k) = true; + kPrev = k; + } + } + } + else + { + for(Index i = 0; i < n; ++i) + { + Block + (dst, ((Side==OnTheLeft) ^ Transposed) ? perm.indices().coeff(i) : i) + + = + + Block + (mat, ((Side==OnTheRight) ^ Transposed) ? perm.indices().coeff(i) : i); + } + } + } +}; + +template +struct generic_product_impl +{ + template + static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs) + { + permutation_matrix_product::run(dst, lhs, rhs); + } +}; + +template +struct generic_product_impl +{ + template + static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs) + { + permutation_matrix_product::run(dst, rhs, lhs); + } +}; + +template +struct generic_product_impl, Rhs, PermutationShape, MatrixShape, ProductTag> +{ + template + static void evalTo(Dest& dst, const Inverse& lhs, const Rhs& rhs) + { + permutation_matrix_product::run(dst, lhs.nestedExpression(), rhs); + } +}; + +template +struct generic_product_impl, MatrixShape, PermutationShape, ProductTag> +{ + template + static void evalTo(Dest& dst, const Lhs& lhs, const Inverse& rhs) + { + permutation_matrix_product::run(dst, rhs.nestedExpression(), lhs); + } +}; + + +/*************************************************************************** +* Products with transpositions matrices +***************************************************************************/ + +// FIXME could we unify Transpositions and Permutation into a single "shape"?? + +/** \internal + * \class transposition_matrix_product + * Internal helper class implementing the product between a permutation matrix and a matrix. + */ +template +struct transposition_matrix_product +{ + typedef typename nested_eval::type MatrixType; + typedef typename remove_all::type MatrixTypeCleaned; + + template + static inline void run(Dest& dst, const TranspositionType& tr, const ExpressionType& xpr) + { + MatrixType mat(xpr); + typedef typename TranspositionType::StorageIndex StorageIndex; + const Index size = tr.size(); + StorageIndex j = 0; + + if(!is_same_dense(dst,mat)) + dst = mat; + + for(Index k=(Transposed?size-1:0) ; Transposed?k>=0:k +struct generic_product_impl +{ + template + static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs) + { + transposition_matrix_product::run(dst, lhs, rhs); + } +}; + +template +struct generic_product_impl +{ + template + static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs) + { + transposition_matrix_product::run(dst, rhs, lhs); + } +}; + + +template +struct generic_product_impl, Rhs, TranspositionsShape, MatrixShape, ProductTag> +{ + template + static void evalTo(Dest& dst, const Transpose& lhs, const Rhs& rhs) + { + transposition_matrix_product::run(dst, lhs.nestedExpression(), rhs); + } +}; + +template +struct generic_product_impl, MatrixShape, TranspositionsShape, ProductTag> +{ + template + static void evalTo(Dest& dst, const Lhs& lhs, const Transpose& rhs) + { + transposition_matrix_product::run(dst, rhs.nestedExpression(), lhs); + } +}; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_PRODUCT_EVALUATORS_H diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/Random.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/Random.h index 480fea40..486e9ed5 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/Random.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/Random.h @@ -16,8 +16,7 @@ namespace internal { template struct scalar_random_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_random_op) - template - inline const Scalar operator() (Index, Index = 0) const { return random(); } + inline const Scalar operator() () const { return random(); } }; template @@ -28,12 +27,18 @@ struct functor_traits > /** \returns a random matrix expression * + * Numbers are uniformly spread through their whole definition range for integer types, + * and in the [-1:1] range for floating point scalar types. + * * The parameters \a rows and \a cols are the number of rows and of columns of * the returned matrix. Must be compatible with this MatrixBase type. * + * \not_reentrant + * * This variant is meant to be used for dynamic-size matrix types. For fixed-size types, * it is redundant to pass \a rows and \a cols as arguments, so Random() should be used * instead. + * * * Example: \include MatrixBase_random_int_int.cpp * Output: \verbinclude MatrixBase_random_int_int.out @@ -41,22 +46,28 @@ struct functor_traits > * This expression has the "evaluate before nesting" flag so that it will be evaluated into * a temporary matrix whenever it is nested in a larger expression. This prevents unexpected * behavior with expressions involving random matrices. + * + * See DenseBase::NullaryExpr(Index, const CustomNullaryOp&) for an example using C++11 random generators. * - * \sa MatrixBase::setRandom(), MatrixBase::Random(Index), MatrixBase::Random() + * \sa DenseBase::setRandom(), DenseBase::Random(Index), DenseBase::Random() */ template -inline const CwiseNullaryOp::Scalar>, Derived> +inline const typename DenseBase::RandomReturnType DenseBase::Random(Index rows, Index cols) { return NullaryExpr(rows, cols, internal::scalar_random_op()); } /** \returns a random vector expression + * + * Numbers are uniformly spread through their whole definition range for integer types, + * and in the [-1:1] range for floating point scalar types. * * The parameter \a size is the size of the returned vector. * Must be compatible with this MatrixBase type. * * \only_for_vectors + * \not_reentrant * * This variant is meant to be used for dynamic-size vector types. For fixed-size types, * it is redundant to pass \a size as argument, so Random() should be used @@ -69,10 +80,10 @@ DenseBase::Random(Index rows, Index cols) * a temporary vector whenever it is nested in a larger expression. This prevents unexpected * behavior with expressions involving random matrices. * - * \sa MatrixBase::setRandom(), MatrixBase::Random(Index,Index), MatrixBase::Random() + * \sa DenseBase::setRandom(), DenseBase::Random(Index,Index), DenseBase::Random() */ template -inline const CwiseNullaryOp::Scalar>, Derived> +inline const typename DenseBase::RandomReturnType DenseBase::Random(Index size) { return NullaryExpr(size, internal::scalar_random_op()); @@ -80,6 +91,9 @@ DenseBase::Random(Index size) /** \returns a fixed-size random matrix or vector expression * + * Numbers are uniformly spread through their whole definition range for integer types, + * and in the [-1:1] range for floating point scalar types. + * * This variant is only for fixed-size MatrixBase types. For dynamic-size types, you * need to use the variants taking size arguments. * @@ -89,11 +103,13 @@ DenseBase::Random(Index size) * This expression has the "evaluate before nesting" flag so that it will be evaluated into * a temporary matrix whenever it is nested in a larger expression. This prevents unexpected * behavior with expressions involving random matrices. + * + * \not_reentrant * - * \sa MatrixBase::setRandom(), MatrixBase::Random(Index,Index), MatrixBase::Random(Index) + * \sa DenseBase::setRandom(), DenseBase::Random(Index,Index), DenseBase::Random(Index) */ template -inline const CwiseNullaryOp::Scalar>, Derived> +inline const typename DenseBase::RandomReturnType DenseBase::Random() { return NullaryExpr(RowsAtCompileTime, ColsAtCompileTime, internal::scalar_random_op()); @@ -101,25 +117,34 @@ DenseBase::Random() /** Sets all coefficients in this expression to random values. * + * Numbers are uniformly spread through their whole definition range for integer types, + * and in the [-1:1] range for floating point scalar types. + * + * \not_reentrant + * * Example: \include MatrixBase_setRandom.cpp * Output: \verbinclude MatrixBase_setRandom.out * * \sa class CwiseNullaryOp, setRandom(Index), setRandom(Index,Index) */ template -inline Derived& DenseBase::setRandom() +EIGEN_DEVICE_FUNC inline Derived& DenseBase::setRandom() { return *this = Random(rows(), cols()); } /** Resizes to the given \a newSize, and sets all coefficients in this expression to random values. * + * Numbers are uniformly spread through their whole definition range for integer types, + * and in the [-1:1] range for floating point scalar types. + * * \only_for_vectors + * \not_reentrant * * Example: \include Matrix_setRandom_int.cpp * Output: \verbinclude Matrix_setRandom_int.out * - * \sa MatrixBase::setRandom(), setRandom(Index,Index), class CwiseNullaryOp, MatrixBase::Random() + * \sa DenseBase::setRandom(), setRandom(Index,Index), class CwiseNullaryOp, DenseBase::Random() */ template EIGEN_STRONG_INLINE Derived& @@ -131,19 +156,24 @@ PlainObjectBase::setRandom(Index newSize) /** Resizes to the given size, and sets all coefficients in this expression to random values. * - * \param nbRows the new number of rows - * \param nbCols the new number of columns + * Numbers are uniformly spread through their whole definition range for integer types, + * and in the [-1:1] range for floating point scalar types. + * + * \not_reentrant + * + * \param rows the new number of rows + * \param cols the new number of columns * * Example: \include Matrix_setRandom_int_int.cpp * Output: \verbinclude Matrix_setRandom_int_int.out * - * \sa MatrixBase::setRandom(), setRandom(Index), class CwiseNullaryOp, MatrixBase::Random() + * \sa DenseBase::setRandom(), setRandom(Index), class CwiseNullaryOp, DenseBase::Random() */ template EIGEN_STRONG_INLINE Derived& -PlainObjectBase::setRandom(Index nbRows, Index nbCols) +PlainObjectBase::setRandom(Index rows, Index cols) { - resize(nbRows, nbCols); + resize(rows, cols); return setRandom(); } diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/Redux.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/Redux.h index 50548fa9..2b5b73bf 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/Redux.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/Redux.h @@ -27,8 +27,9 @@ template struct redux_traits { public: + typedef typename find_best_packet::type PacketType; enum { - PacketSize = packet_traits::size, + PacketSize = unpacket_traits::size, InnerMaxSize = int(Derived::IsRowMajor) ? Derived::MaxColsAtCompileTime : Derived::MaxRowsAtCompileTime @@ -37,8 +38,8 @@ public: enum { MightVectorize = (int(Derived::Flags)&ActualPacketAccessBit) && (functor_traits::PacketAccess), - MayLinearVectorize = MightVectorize && (int(Derived::Flags)&LinearAccessBit), - MaySliceVectorize = MightVectorize && int(InnerMaxSize)>=3*PacketSize + MayLinearVectorize = bool(MightVectorize) && (int(Derived::Flags)&LinearAccessBit), + MaySliceVectorize = bool(MightVectorize) && int(InnerMaxSize)>=3*PacketSize }; public: @@ -50,21 +51,34 @@ public: public: enum { - Cost = ( Derived::SizeAtCompileTime == Dynamic - || Derived::CoeffReadCost == Dynamic - || (Derived::SizeAtCompileTime!=1 && functor_traits::Cost == Dynamic) - ) ? Dynamic - : Derived::SizeAtCompileTime * Derived::CoeffReadCost - + (Derived::SizeAtCompileTime-1) * functor_traits::Cost, + Cost = Derived::SizeAtCompileTime == Dynamic ? HugeCost + : Derived::SizeAtCompileTime * Derived::CoeffReadCost + (Derived::SizeAtCompileTime-1) * functor_traits::Cost, UnrollingLimit = EIGEN_UNROLLING_LIMIT * (int(Traversal) == int(DefaultTraversal) ? 1 : int(PacketSize)) }; public: enum { - Unrolling = Cost != Dynamic && Cost <= UnrollingLimit - ? CompleteUnrolling - : NoUnrolling + Unrolling = Cost <= UnrollingLimit ? CompleteUnrolling : NoUnrolling }; + +#ifdef EIGEN_DEBUG_ASSIGN + static void debug() + { + std::cerr << "Xpr: " << typeid(typename Derived::XprType).name() << std::endl; + std::cerr.setf(std::ios::hex, std::ios::basefield); + EIGEN_DEBUG_VAR(Derived::Flags) + std::cerr.unsetf(std::ios::hex); + EIGEN_DEBUG_VAR(InnerMaxSize) + EIGEN_DEBUG_VAR(PacketSize) + EIGEN_DEBUG_VAR(MightVectorize) + EIGEN_DEBUG_VAR(MayLinearVectorize) + EIGEN_DEBUG_VAR(MaySliceVectorize) + EIGEN_DEBUG_VAR(Traversal) + EIGEN_DEBUG_VAR(UnrollingLimit) + EIGEN_DEBUG_VAR(Unrolling) + std::cerr << std::endl; + } +#endif }; /*************************************************************************** @@ -82,6 +96,7 @@ struct redux_novec_unroller typedef typename Derived::Scalar Scalar; + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Scalar run(const Derived &mat, const Func& func) { return func(redux_novec_unroller::run(mat,func), @@ -99,6 +114,7 @@ struct redux_novec_unroller typedef typename Derived::Scalar Scalar; + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Scalar run(const Derived &mat, const Func&) { return mat.coeffByOuterInner(outer, inner); @@ -112,6 +128,7 @@ template struct redux_novec_unroller { typedef typename Derived::Scalar Scalar; + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Scalar run(const Derived&, const Func&) { return Scalar(); } }; @@ -121,12 +138,12 @@ template struct redux_vec_unroller { enum { - PacketSize = packet_traits::size, + PacketSize = redux_traits::PacketSize, HalfLength = Length/2 }; typedef typename Derived::Scalar Scalar; - typedef typename packet_traits::type PacketScalar; + typedef typename redux_traits::PacketType PacketScalar; static EIGEN_STRONG_INLINE PacketScalar run(const Derived &mat, const Func& func) { @@ -140,18 +157,18 @@ template struct redux_vec_unroller { enum { - index = Start * packet_traits::size, + index = Start * redux_traits::PacketSize, outer = index / int(Derived::InnerSizeAtCompileTime), inner = index % int(Derived::InnerSizeAtCompileTime), - alignment = (Derived::Flags & AlignedBit) ? Aligned : Unaligned + alignment = Derived::Alignment }; typedef typename Derived::Scalar Scalar; - typedef typename packet_traits::type PacketScalar; + typedef typename redux_traits::PacketType PacketScalar; static EIGEN_STRONG_INLINE PacketScalar run(const Derived &mat, const Func&) { - return mat.template packetByOuterInner(outer, inner); + return mat.template packetByOuterInner(outer, inner); } }; @@ -169,8 +186,8 @@ template struct redux_impl { typedef typename Derived::Scalar Scalar; - typedef typename Derived::Index Index; - static EIGEN_STRONG_INLINE Scalar run(const Derived& mat, const Func& func) + EIGEN_DEVICE_FUNC + static EIGEN_STRONG_INLINE Scalar run(const Derived &mat, const Func& func) { eigen_assert(mat.rows()>0 && mat.cols()>0 && "you are using an empty matrix"); Scalar res; @@ -193,19 +210,19 @@ template struct redux_impl { typedef typename Derived::Scalar Scalar; - typedef typename packet_traits::type PacketScalar; - typedef typename Derived::Index Index; + typedef typename redux_traits::PacketType PacketScalar; - static Scalar run(const Derived& mat, const Func& func) + static Scalar run(const Derived &mat, const Func& func) { const Index size = mat.size(); - eigen_assert(size && "you are using an empty matrix"); - const Index packetSize = packet_traits::size; - const Index alignedStart = internal::first_aligned(mat); + + const Index packetSize = redux_traits::PacketSize; + const int packetAlignment = unpacket_traits::alignment; enum { - alignment = bool(Derived::Flags & DirectAccessBit) || bool(Derived::Flags & AlignedBit) - ? Aligned : Unaligned + alignment0 = (bool(Derived::Flags & DirectAccessBit) && bool(packet_traits::AlignedOnScalar)) ? int(packetAlignment) : int(Unaligned), + alignment = EIGEN_PLAIN_ENUM_MAX(alignment0, Derived::Alignment) }; + const Index alignedStart = internal::first_default_aligned(mat.nestedExpression()); const Index alignedSize2 = ((size-alignedStart)/(2*packetSize))*(2*packetSize); const Index alignedSize = ((size-alignedStart)/(packetSize))*(packetSize); const Index alignedEnd2 = alignedStart + alignedSize2; @@ -213,19 +230,19 @@ struct redux_impl Scalar res; if(alignedSize) { - PacketScalar packet_res0 = mat.template packet(alignedStart); + PacketScalar packet_res0 = mat.template packet(alignedStart); if(alignedSize>packetSize) // we have at least two packets to partly unroll the loop { - PacketScalar packet_res1 = mat.template packet(alignedStart+packetSize); + PacketScalar packet_res1 = mat.template packet(alignedStart+packetSize); for(Index index = alignedStart + 2*packetSize; index < alignedEnd2; index += 2*packetSize) { - packet_res0 = func.packetOp(packet_res0, mat.template packet(index)); - packet_res1 = func.packetOp(packet_res1, mat.template packet(index+packetSize)); + packet_res0 = func.packetOp(packet_res0, mat.template packet(index)); + packet_res1 = func.packetOp(packet_res1, mat.template packet(index+packetSize)); } packet_res0 = func.packetOp(packet_res0,packet_res1); if(alignedEnd>alignedEnd2) - packet_res0 = func.packetOp(packet_res0, mat.template packet(alignedEnd2)); + packet_res0 = func.packetOp(packet_res0, mat.template packet(alignedEnd2)); } res = func.predux(packet_res0); @@ -247,29 +264,29 @@ struct redux_impl } }; -template -struct redux_impl +// NOTE: for SliceVectorizedTraversal we simply bypass unrolling +template +struct redux_impl { typedef typename Derived::Scalar Scalar; - typedef typename packet_traits::type PacketScalar; - typedef typename Derived::Index Index; + typedef typename redux_traits::PacketType PacketType; - static Scalar run(const Derived& mat, const Func& func) + EIGEN_DEVICE_FUNC static Scalar run(const Derived &mat, const Func& func) { eigen_assert(mat.rows()>0 && mat.cols()>0 && "you are using an empty matrix"); const Index innerSize = mat.innerSize(); const Index outerSize = mat.outerSize(); enum { - packetSize = packet_traits::size + packetSize = redux_traits::PacketSize }; const Index packetedInnerSize = ((innerSize)/packetSize)*packetSize; Scalar res; if(packetedInnerSize) { - PacketScalar packet_res = mat.template packet(0,0); + PacketType packet_res = mat.template packet(0,0); for(Index j=0; j(j,i)); + packet_res = func.packetOp(packet_res, mat.template packetByOuterInner(j,i)); res = func.predux(packet_res); for(Index j=0; j struct redux_impl { typedef typename Derived::Scalar Scalar; - typedef typename packet_traits::type PacketScalar; + + typedef typename redux_traits::PacketType PacketScalar; enum { - PacketSize = packet_traits::size, + PacketSize = redux_traits::PacketSize, Size = Derived::SizeAtCompileTime, VectorizedSize = (Size / PacketSize) * PacketSize }; - static EIGEN_STRONG_INLINE Scalar run(const Derived& mat, const Func& func) + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Scalar run(const Derived &mat, const Func& func) { eigen_assert(mat.rows()>0 && mat.cols()>0 && "you are using an empty matrix"); - Scalar res = func.predux(redux_vec_unroller::run(mat,func)); - if (VectorizedSize != Size) - res = func(res,redux_novec_unroller::run(mat,func)); - return res; + if (VectorizedSize > 0) { + Scalar res = func.predux(redux_vec_unroller::run(mat,func)); + if (VectorizedSize != Size) + res = func(res,redux_novec_unroller::run(mat,func)); + return res; + } + else { + return redux_novec_unroller::run(mat,func); + } } }; +// evaluator adaptor +template +class redux_evaluator +{ +public: + typedef _XprType XprType; + EIGEN_DEVICE_FUNC explicit redux_evaluator(const XprType &xpr) : m_evaluator(xpr), m_xpr(xpr) {} + + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename XprType::PacketScalar PacketScalar; + typedef typename XprType::PacketReturnType PacketReturnType; + + enum { + MaxRowsAtCompileTime = XprType::MaxRowsAtCompileTime, + MaxColsAtCompileTime = XprType::MaxColsAtCompileTime, + // TODO we should not remove DirectAccessBit and rather find an elegant way to query the alignment offset at runtime from the evaluator + Flags = evaluator::Flags & ~DirectAccessBit, + IsRowMajor = XprType::IsRowMajor, + SizeAtCompileTime = XprType::SizeAtCompileTime, + InnerSizeAtCompileTime = XprType::InnerSizeAtCompileTime, + CoeffReadCost = evaluator::CoeffReadCost, + Alignment = evaluator::Alignment + }; + + EIGEN_DEVICE_FUNC Index rows() const { return m_xpr.rows(); } + EIGEN_DEVICE_FUNC Index cols() const { return m_xpr.cols(); } + EIGEN_DEVICE_FUNC Index size() const { return m_xpr.size(); } + EIGEN_DEVICE_FUNC Index innerSize() const { return m_xpr.innerSize(); } + EIGEN_DEVICE_FUNC Index outerSize() const { return m_xpr.outerSize(); } + + EIGEN_DEVICE_FUNC + CoeffReturnType coeff(Index row, Index col) const + { return m_evaluator.coeff(row, col); } + + EIGEN_DEVICE_FUNC + CoeffReturnType coeff(Index index) const + { return m_evaluator.coeff(index); } + + template + PacketType packet(Index row, Index col) const + { return m_evaluator.template packet(row, col); } + + template + PacketType packet(Index index) const + { return m_evaluator.template packet(index); } + + EIGEN_DEVICE_FUNC + CoeffReturnType coeffByOuterInner(Index outer, Index inner) const + { return m_evaluator.coeff(IsRowMajor ? outer : inner, IsRowMajor ? inner : outer); } + + template + PacketType packetByOuterInner(Index outer, Index inner) const + { return m_evaluator.template packet(IsRowMajor ? outer : inner, IsRowMajor ? inner : outer); } + + const XprType & nestedExpression() const { return m_xpr; } + +protected: + internal::evaluator m_evaluator; + const XprType &m_xpr; +}; + } // end namespace internal /*************************************************************************** @@ -316,51 +401,56 @@ struct redux_impl /** \returns the result of a full redux operation on the whole matrix or vector using \a func * * The template parameter \a BinaryOp is the type of the functor \a func which must be - * an associative operator. Both current STL and TR1 functor styles are handled. + * an associative operator. Both current C++98 and C++11 functor styles are handled. * * \sa DenseBase::sum(), DenseBase::minCoeff(), DenseBase::maxCoeff(), MatrixBase::colwise(), MatrixBase::rowwise() */ template template -EIGEN_STRONG_INLINE typename internal::result_of::Scalar)>::type +EIGEN_DEVICE_FUNC typename internal::traits::Scalar DenseBase::redux(const Func& func) const { - typedef typename internal::remove_all::type ThisNested; - return internal::redux_impl - ::run(derived(), func); + eigen_assert(this->rows()>0 && this->cols()>0 && "you are using an empty matrix"); + + typedef typename internal::redux_evaluator ThisEvaluator; + ThisEvaluator thisEval(derived()); + + return internal::redux_impl::run(thisEval, func); } /** \returns the minimum of all coefficients of \c *this. * \warning the result is undefined if \c *this contains NaN. */ template -EIGEN_STRONG_INLINE typename internal::traits::Scalar +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename internal::traits::Scalar DenseBase::minCoeff() const { - return this->redux(Eigen::internal::scalar_min_op()); + return derived().redux(Eigen::internal::scalar_min_op()); } /** \returns the maximum of all coefficients of \c *this. * \warning the result is undefined if \c *this contains NaN. */ template -EIGEN_STRONG_INLINE typename internal::traits::Scalar +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename internal::traits::Scalar DenseBase::maxCoeff() const { - return this->redux(Eigen::internal::scalar_max_op()); + return derived().redux(Eigen::internal::scalar_max_op()); } -/** \returns the sum of all coefficients of *this +/** \returns the sum of all coefficients of \c *this + * + * If \c *this is empty, then the value 0 is returned. * * \sa trace(), prod(), mean() */ template -EIGEN_STRONG_INLINE typename internal::traits::Scalar +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename internal::traits::Scalar DenseBase::sum() const { if(SizeAtCompileTime==0 || (SizeAtCompileTime==Dynamic && size()==0)) return Scalar(0); - return this->redux(Eigen::internal::scalar_sum_op()); + return derived().redux(Eigen::internal::scalar_sum_op()); } /** \returns the mean of all coefficients of *this @@ -368,10 +458,17 @@ DenseBase::sum() const * \sa trace(), prod(), sum() */ template -EIGEN_STRONG_INLINE typename internal::traits::Scalar +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename internal::traits::Scalar DenseBase::mean() const { - return Scalar(this->redux(Eigen::internal::scalar_sum_op())) / Scalar(this->size()); +#ifdef __INTEL_COMPILER + #pragma warning push + #pragma warning ( disable : 2259 ) +#endif + return Scalar(derived().redux(Eigen::internal::scalar_sum_op())) / Scalar(this->size()); +#ifdef __INTEL_COMPILER + #pragma warning pop +#endif } /** \returns the product of all coefficients of *this @@ -382,12 +479,12 @@ DenseBase::mean() const * \sa sum(), mean(), trace() */ template -EIGEN_STRONG_INLINE typename internal::traits::Scalar +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename internal::traits::Scalar DenseBase::prod() const { if(SizeAtCompileTime==0 || (SizeAtCompileTime==Dynamic && size()==0)) return Scalar(1); - return this->redux(Eigen::internal::scalar_product_op()); + return derived().redux(Eigen::internal::scalar_product_op()); } /** \returns the trace of \c *this, i.e. the sum of the coefficients on the main diagonal. @@ -397,7 +494,7 @@ DenseBase::prod() const * \sa diagonal(), sum() */ template -EIGEN_STRONG_INLINE typename internal::traits::Scalar +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename internal::traits::Scalar MatrixBase::trace() const { return derived().diagonal().sum(); diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/Ref.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/Ref.h index df87b1af..abb1e512 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/Ref.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/Ref.h @@ -12,79 +12,6 @@ namespace Eigen { -template class RefBase; -template,OuterStride<> >::type > class Ref; - -/** \class Ref - * \ingroup Core_Module - * - * \brief A matrix or vector expression mapping an existing expressions - * - * \tparam PlainObjectType the equivalent matrix type of the mapped data - * \tparam Options specifies whether the pointer is \c #Aligned, or \c #Unaligned. - * The default is \c #Unaligned. - * \tparam StrideType optionally specifies strides. By default, Ref implies a contiguous storage along the inner dimension (inner stride==1), - * but accept a variable outer stride (leading dimension). - * This can be overridden by specifying strides. - * The type passed here must be a specialization of the Stride template, see examples below. - * - * This class permits to write non template functions taking Eigen's object as parameters while limiting the number of copies. - * A Ref<> object can represent either a const expression or a l-value: - * \code - * // in-out argument: - * void foo1(Ref x); - * - * // read-only const argument: - * void foo2(const Ref& x); - * \endcode - * - * In the in-out case, the input argument must satisfies the constraints of the actual Ref<> type, otherwise a compilation issue will be triggered. - * By default, a Ref can reference any dense vector expression of float having a contiguous memory layout. - * Likewise, a Ref can reference any column major dense matrix expression of float whose column's elements are contiguously stored with - * the possibility to have a constant space inbetween each column, i.e.: the inner stride mmust be equal to 1, but the outer-stride (or leading dimension), - * can be greater than the number of rows. - * - * In the const case, if the input expression does not match the above requirement, then it is evaluated into a temporary before being passed to the function. - * Here are some examples: - * \code - * MatrixXf A; - * VectorXf a; - * foo1(a.head()); // OK - * foo1(A.col()); // OK - * foo1(A.row()); // compilation error because here innerstride!=1 - * foo2(A.row()); // The row is copied into a contiguous temporary - * foo2(2*a); // The expression is evaluated into a temporary - * foo2(A.col().segment(2,4)); // No temporary - * \endcode - * - * The range of inputs that can be referenced without temporary can be enlarged using the last two template parameter. - * Here is an example accepting an innerstride!=1: - * \code - * // in-out argument: - * void foo3(Ref > x); - * foo3(A.row()); // OK - * \endcode - * The downside here is that the function foo3 might be significantly slower than foo1 because it won't be able to exploit vectorization, and will involved more - * expensive address computations even if the input is contiguously stored in memory. To overcome this issue, one might propose to overloads internally calling a - * template function, e.g.: - * \code - * // in the .h: - * void foo(const Ref& A); - * void foo(const Ref >& A); - * - * // in the .cpp: - * template void foo_impl(const TypeOfA& A) { - * ... // crazy code goes here - * } - * void foo(const Ref& A) { foo_impl(A); } - * void foo(const Ref >& A) { foo_impl(A); } - * \endcode - * - * - * \sa PlainObjectBase::Map(), \ref TopicStorageOrders - */ - namespace internal { template @@ -95,7 +22,8 @@ struct traits > typedef _StrideType StrideType; enum { Options = _Options, - Flags = traits >::Flags | NestByRefBit + Flags = traits >::Flags | NestByRefBit, + Alignment = traits >::Alignment }; template struct match { @@ -107,8 +35,15 @@ struct traits > || (int(StrideType::InnerStrideAtCompileTime)==0 && int(Derived::InnerStrideAtCompileTime)==1), OuterStrideMatch = Derived::IsVectorAtCompileTime || int(StrideType::OuterStrideAtCompileTime)==int(Dynamic) || int(StrideType::OuterStrideAtCompileTime)==int(Derived::OuterStrideAtCompileTime), - AlignmentMatch = (_Options!=Aligned) || ((PlainObjectType::Flags&AlignedBit)==0) || ((traits::Flags&AlignedBit)==AlignedBit), - MatchAtCompileTime = HasDirectAccess && StorageOrderMatch && InnerStrideMatch && OuterStrideMatch && AlignmentMatch + // NOTE, this indirection of evaluator::Alignment is needed + // to workaround a very strange bug in MSVC related to the instantiation + // of has_*ary_operator in evaluator. + // This line is surprisingly very sensitive. For instance, simply adding parenthesis + // as "DerivedAlignment = (int(evaluator::Alignment))," will make MSVC fail... + DerivedAlignment = int(evaluator::Alignment), + AlignmentMatch = (int(traits::Alignment)==int(Unaligned)) || (DerivedAlignment >= int(Alignment)), // FIXME the first condition is not very clear, it should be replaced by the required alignment + ScalarTypeMatch = internal::is_same::value, + MatchAtCompileTime = HasDirectAccess && StorageOrderMatch && InnerStrideMatch && OuterStrideMatch && AlignmentMatch && ScalarTypeMatch }; typedef typename internal::conditional::type type; }; @@ -131,12 +66,12 @@ public: typedef MapBase Base; EIGEN_DENSE_PUBLIC_INTERFACE(RefBase) - inline Index innerStride() const + EIGEN_DEVICE_FUNC inline Index innerStride() const { return StrideType::InnerStrideAtCompileTime != 0 ? m_stride.inner() : 1; } - inline Index outerStride() const + EIGEN_DEVICE_FUNC inline Index outerStride() const { return StrideType::OuterStrideAtCompileTime != 0 ? m_stride.outer() : IsVectorAtCompileTime ? this->size() @@ -144,7 +79,7 @@ public: : this->rows(); } - RefBase() + EIGEN_DEVICE_FUNC RefBase() : Base(0,RowsAtCompileTime==Dynamic?0:RowsAtCompileTime,ColsAtCompileTime==Dynamic?0:ColsAtCompileTime), // Stride<> does not allow default ctor for Dynamic strides, so let' initialize it with dummy values: m_stride(StrideType::OuterStrideAtCompileTime==Dynamic?0:StrideType::OuterStrideAtCompileTime, @@ -158,7 +93,7 @@ protected: typedef Stride StrideBase; template - void construct(Expression& expr) + EIGEN_DEVICE_FUNC void construct(Expression& expr) { if(PlainObjectType::RowsAtCompileTime==1) { @@ -183,13 +118,85 @@ protected: StrideBase m_stride; }; - +/** \class Ref + * \ingroup Core_Module + * + * \brief A matrix or vector expression mapping an existing expression + * + * \tparam PlainObjectType the equivalent matrix type of the mapped data + * \tparam Options specifies the pointer alignment in bytes. It can be: \c #Aligned128, , \c #Aligned64, \c #Aligned32, \c #Aligned16, \c #Aligned8 or \c #Unaligned. + * The default is \c #Unaligned. + * \tparam StrideType optionally specifies strides. By default, Ref implies a contiguous storage along the inner dimension (inner stride==1), + * but accepts a variable outer stride (leading dimension). + * This can be overridden by specifying strides. + * The type passed here must be a specialization of the Stride template, see examples below. + * + * This class provides a way to write non-template functions taking Eigen objects as parameters while limiting the number of copies. + * A Ref<> object can represent either a const expression or a l-value: + * \code + * // in-out argument: + * void foo1(Ref x); + * + * // read-only const argument: + * void foo2(const Ref& x); + * \endcode + * + * In the in-out case, the input argument must satisfy the constraints of the actual Ref<> type, otherwise a compilation issue will be triggered. + * By default, a Ref can reference any dense vector expression of float having a contiguous memory layout. + * Likewise, a Ref can reference any column-major dense matrix expression of float whose column's elements are contiguously stored with + * the possibility to have a constant space in-between each column, i.e. the inner stride must be equal to 1, but the outer stride (or leading dimension) + * can be greater than the number of rows. + * + * In the const case, if the input expression does not match the above requirement, then it is evaluated into a temporary before being passed to the function. + * Here are some examples: + * \code + * MatrixXf A; + * VectorXf a; + * foo1(a.head()); // OK + * foo1(A.col()); // OK + * foo1(A.row()); // Compilation error because here innerstride!=1 + * foo2(A.row()); // Compilation error because A.row() is a 1xN object while foo2 is expecting a Nx1 object + * foo2(A.row().transpose()); // The row is copied into a contiguous temporary + * foo2(2*a); // The expression is evaluated into a temporary + * foo2(A.col().segment(2,4)); // No temporary + * \endcode + * + * The range of inputs that can be referenced without temporary can be enlarged using the last two template parameters. + * Here is an example accepting an innerstride!=1: + * \code + * // in-out argument: + * void foo3(Ref > x); + * foo3(A.row()); // OK + * \endcode + * The downside here is that the function foo3 might be significantly slower than foo1 because it won't be able to exploit vectorization, and will involve more + * expensive address computations even if the input is contiguously stored in memory. To overcome this issue, one might propose to overload internally calling a + * template function, e.g.: + * \code + * // in the .h: + * void foo(const Ref& A); + * void foo(const Ref >& A); + * + * // in the .cpp: + * template void foo_impl(const TypeOfA& A) { + * ... // crazy code goes here + * } + * void foo(const Ref& A) { foo_impl(A); } + * void foo(const Ref >& A) { foo_impl(A); } + * \endcode + * + * See also the following stackoverflow questions for further references: + * - Correct usage of the Eigen::Ref<> class + * + * \sa PlainObjectBase::Map(), \ref TopicStorageOrders + */ template class Ref : public RefBase > { + private: typedef internal::traits Traits; template - inline Ref(const PlainObjectBase& expr); + EIGEN_DEVICE_FUNC inline Ref(const PlainObjectBase& expr, + typename internal::enable_if::MatchAtCompileTime),Derived>::type* = 0); public: typedef RefBase Base; @@ -198,21 +205,24 @@ template class Ref #ifndef EIGEN_PARSED_BY_DOXYGEN template - inline Ref(PlainObjectBase& expr) + EIGEN_DEVICE_FUNC inline Ref(PlainObjectBase& expr, + typename internal::enable_if::MatchAtCompileTime),Derived>::type* = 0) { - EIGEN_STATIC_ASSERT(static_cast(Traits::template match::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH); + EIGEN_STATIC_ASSERT(bool(Traits::template match::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH); Base::construct(expr.derived()); } template - inline Ref(const DenseBase& expr) + EIGEN_DEVICE_FUNC inline Ref(const DenseBase& expr, + typename internal::enable_if::MatchAtCompileTime),Derived>::type* = 0) #else + /** Implicit constructor from any dense expression */ template inline Ref(DenseBase& expr) #endif { - EIGEN_STATIC_ASSERT(static_cast(internal::is_lvalue::value), THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY); - EIGEN_STATIC_ASSERT(static_cast(Traits::template match::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH); - enum { THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY = Derived::ThisConstantIsPrivateInPlainObjectBase}; + EIGEN_STATIC_ASSERT(bool(internal::is_lvalue::value), THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY); + EIGEN_STATIC_ASSERT(bool(Traits::template match::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH); + EIGEN_STATIC_ASSERT(!Derived::IsPlainObjectBase,THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY); Base::construct(expr.const_cast_derived()); } @@ -231,7 +241,8 @@ template class Ref< EIGEN_DENSE_PUBLIC_INTERFACE(Ref) template - inline Ref(const DenseBase& expr) + EIGEN_DEVICE_FUNC inline Ref(const DenseBase& expr, + typename internal::enable_if::ScalarTypeMatch),Derived>::type* = 0) { // std::cout << match_helper::HasDirectAccess << "," << match_helper::OuterStrideMatch << "," << match_helper::InnerStrideMatch << "\n"; // std::cout << int(StrideType::OuterStrideAtCompileTime) << " - " << int(Derived::OuterStrideAtCompileTime) << "\n"; @@ -239,18 +250,27 @@ template class Ref< construct(expr.derived(), typename Traits::template match::type()); } + EIGEN_DEVICE_FUNC inline Ref(const Ref& other) : Base(other) { + // copy constructor shall not copy the m_object, to avoid unnecessary malloc and copy + } + + template + EIGEN_DEVICE_FUNC inline Ref(const RefBase& other) { + construct(other.derived(), typename Traits::template match::type()); + } + protected: template - void construct(const Expression& expr,internal::true_type) + EIGEN_DEVICE_FUNC void construct(const Expression& expr,internal::true_type) { Base::construct(expr); } template - void construct(const Expression& expr, internal::false_type) + EIGEN_DEVICE_FUNC void construct(const Expression& expr, internal::false_type) { - m_object.lazyAssign(expr); + internal::call_assignment_no_alias(m_object,expr,internal::assign_op()); Base::construct(m_object); } diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/Replicate.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/Replicate.h index ac4537c1..0b2d6d74 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/Replicate.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/Replicate.h @@ -12,21 +12,6 @@ namespace Eigen { -/** - * \class Replicate - * \ingroup Core_Module - * - * \brief Expression of the multiple replication of a matrix or vector - * - * \param MatrixType the type of the object we are replicating - * - * This class represents an expression of the multiple replication of a matrix or vector. - * It is the return type of DenseBase::replicate() and most of the time - * this is the only way it is used. - * - * \sa DenseBase::replicate() - */ - namespace internal { template struct traits > @@ -35,10 +20,7 @@ struct traits > typedef typename MatrixType::Scalar Scalar; typedef typename traits::StorageKind StorageKind; typedef typename traits::XprKind XprKind; - enum { - Factor = (RowFactor==Dynamic || ColFactor==Dynamic) ? Dynamic : RowFactor*ColFactor - }; - typedef typename nested::type MatrixTypeNested; + typedef typename ref_selector::type MatrixTypeNested; typedef typename remove_reference::type _MatrixTypeNested; enum { RowsAtCompileTime = RowFactor==Dynamic || int(MatrixType::RowsAtCompileTime)==Dynamic @@ -53,12 +35,29 @@ struct traits > IsRowMajor = MaxRowsAtCompileTime==1 && MaxColsAtCompileTime!=1 ? 1 : MaxColsAtCompileTime==1 && MaxRowsAtCompileTime!=1 ? 0 : (MatrixType::Flags & RowMajorBit) ? 1 : 0, - Flags = (_MatrixTypeNested::Flags & HereditaryBits & ~RowMajorBit) | (IsRowMajor ? RowMajorBit : 0), - CoeffReadCost = _MatrixTypeNested::CoeffReadCost + + // FIXME enable DirectAccess with negative strides? + Flags = IsRowMajor ? RowMajorBit : 0 }; }; } +/** + * \class Replicate + * \ingroup Core_Module + * + * \brief Expression of the multiple replication of a matrix or vector + * + * \tparam MatrixType the type of the object we are replicating + * \tparam RowFactor number of repetitions at compile time along the vertical direction, can be Dynamic. + * \tparam ColFactor number of repetitions at compile time along the horizontal direction, can be Dynamic. + * + * This class represents an expression of the multiple replication of a matrix or vector. + * It is the return type of DenseBase::replicate() and most of the time + * this is the only way it is used. + * + * \sa DenseBase::replicate() + */ template class Replicate : public internal::dense_xpr_base< Replicate >::type { @@ -68,10 +67,12 @@ template class Replicate typedef typename internal::dense_xpr_base::type Base; EIGEN_DENSE_PUBLIC_INTERFACE(Replicate) + typedef typename internal::remove_all::type NestedExpression; template - inline explicit Replicate(const OriginalMatrixType& a_matrix) - : m_matrix(a_matrix), m_rowFactor(RowFactor), m_colFactor(ColFactor) + EIGEN_DEVICE_FUNC + inline explicit Replicate(const OriginalMatrixType& matrix) + : m_matrix(matrix), m_rowFactor(RowFactor), m_colFactor(ColFactor) { EIGEN_STATIC_ASSERT((internal::is_same::type,OriginalMatrixType>::value), THE_MATRIX_OR_EXPRESSION_THAT_YOU_PASSED_DOES_NOT_HAVE_THE_EXPECTED_TYPE) @@ -79,41 +80,20 @@ template class Replicate } template - inline Replicate(const OriginalMatrixType& a_matrix, Index rowFactor, Index colFactor) - : m_matrix(a_matrix), m_rowFactor(rowFactor), m_colFactor(colFactor) + EIGEN_DEVICE_FUNC + inline Replicate(const OriginalMatrixType& matrix, Index rowFactor, Index colFactor) + : m_matrix(matrix), m_rowFactor(rowFactor), m_colFactor(colFactor) { EIGEN_STATIC_ASSERT((internal::is_same::type,OriginalMatrixType>::value), THE_MATRIX_OR_EXPRESSION_THAT_YOU_PASSED_DOES_NOT_HAVE_THE_EXPECTED_TYPE) } + EIGEN_DEVICE_FUNC inline Index rows() const { return m_matrix.rows() * m_rowFactor.value(); } + EIGEN_DEVICE_FUNC inline Index cols() const { return m_matrix.cols() * m_colFactor.value(); } - inline Scalar coeff(Index rowId, Index colId) const - { - // try to avoid using modulo; this is a pure optimization strategy - const Index actual_row = internal::traits::RowsAtCompileTime==1 ? 0 - : RowFactor==1 ? rowId - : rowId%m_matrix.rows(); - const Index actual_col = internal::traits::ColsAtCompileTime==1 ? 0 - : ColFactor==1 ? colId - : colId%m_matrix.cols(); - - return m_matrix.coeff(actual_row, actual_col); - } - template - inline PacketScalar packet(Index rowId, Index colId) const - { - const Index actual_row = internal::traits::RowsAtCompileTime==1 ? 0 - : RowFactor==1 ? rowId - : rowId%m_matrix.rows(); - const Index actual_col = internal::traits::ColsAtCompileTime==1 ? 0 - : ColFactor==1 ? colId - : colId%m_matrix.cols(); - - return m_matrix.template packet(actual_row, actual_col); - } - + EIGEN_DEVICE_FUNC const _MatrixTypeNested& nestedExpression() const { return m_matrix; @@ -135,27 +115,12 @@ template class Replicate */ template template -const Replicate +EIGEN_DEVICE_FUNC const Replicate DenseBase::replicate() const { return Replicate(derived()); } -/** - * \return an expression of the replication of \c *this - * - * Example: \include MatrixBase_replicate_int_int.cpp - * Output: \verbinclude MatrixBase_replicate_int_int.out - * - * \sa VectorwiseOp::replicate(), DenseBase::replicate(), class Replicate - */ -template -const typename DenseBase::ReplicateReturnType -DenseBase::replicate(Index rowFactor,Index colFactor) const -{ - return Replicate(derived(),rowFactor,colFactor); -} - /** * \return an expression of the replication of each column (or row) of \c *this * @@ -165,7 +130,7 @@ DenseBase::replicate(Index rowFactor,Index colFactor) const * \sa VectorwiseOp::replicate(), DenseBase::replicate(), class Replicate */ template -const typename VectorwiseOp::ReplicateReturnType +EIGEN_DEVICE_FUNC const typename VectorwiseOp::ReplicateReturnType VectorwiseOp::replicate(Index factor) const { return typename VectorwiseOp::ReplicateReturnType diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/ReturnByValue.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/ReturnByValue.h index d66c24ba..11dc86d0 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/ReturnByValue.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/ReturnByValue.h @@ -13,11 +13,6 @@ namespace Eigen { -/** \class ReturnByValue - * \ingroup Core_Module - * - */ - namespace internal { template @@ -38,17 +33,22 @@ struct traits > * So internal::nested always gives the plain return matrix type. * * FIXME: I don't understand why we need this specialization: isn't this taken care of by the EvalBeforeNestingBit ?? + * Answer: EvalBeforeNestingBit should be deprecated since we have the evaluators */ template -struct nested, n, PlainObject> +struct nested_eval, n, PlainObject> { typedef typename traits::ReturnType type; }; } // end namespace internal +/** \class ReturnByValue + * \ingroup Core_Module + * + */ template class ReturnByValue - : internal::no_assignment_operator, public internal::dense_xpr_base< ReturnByValue >::type + : public internal::dense_xpr_base< ReturnByValue >::type, internal::no_assignment_operator { public: typedef typename internal::traits::ReturnType ReturnType; @@ -57,10 +57,11 @@ template class ReturnByValue EIGEN_DENSE_PUBLIC_INTERFACE(ReturnByValue) template + EIGEN_DEVICE_FUNC inline void evalTo(Dest& dst) const { static_cast(this)->evalTo(dst); } - inline Index rows() const { return static_cast(this)->rows(); } - inline Index cols() const { return static_cast(this)->cols(); } + EIGEN_DEVICE_FUNC inline Index rows() const { return static_cast(this)->rows(); } + EIGEN_DEVICE_FUNC inline Index cols() const { return static_cast(this)->cols(); } #ifndef EIGEN_PARSED_BY_DOXYGEN #define Unusable YOU_ARE_TRYING_TO_ACCESS_A_SINGLE_COEFFICIENT_IN_A_SPECIAL_EXPRESSION_WHERE_THAT_IS_NOT_ALLOWED_BECAUSE_THAT_WOULD_BE_INEFFICIENT @@ -72,17 +73,45 @@ template class ReturnByValue const Unusable& coeff(Index,Index) const { return *reinterpret_cast(this); } Unusable& coeffRef(Index) { return *reinterpret_cast(this); } Unusable& coeffRef(Index,Index) { return *reinterpret_cast(this); } +#undef Unusable #endif }; template template -Derived& DenseBase::operator=(const ReturnByValue& other) +EIGEN_DEVICE_FUNC Derived& DenseBase::operator=(const ReturnByValue& other) { other.evalTo(derived()); return derived(); } +namespace internal { + +// Expression is evaluated in a temporary; default implementation of Assignment is bypassed so that +// when a ReturnByValue expression is assigned, the evaluator is not constructed. +// TODO: Finalize port to new regime; ReturnByValue should not exist in the expression world + +template +struct evaluator > + : public evaluator::ReturnType> +{ + typedef ReturnByValue XprType; + typedef typename internal::traits::ReturnType PlainObject; + typedef evaluator Base; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) + : m_result(xpr.rows(), xpr.cols()) + { + ::new (static_cast(this)) Base(m_result); + xpr.evalTo(m_result); + } + +protected: + PlainObject m_result; +}; + +} // end namespace internal + } // end namespace Eigen #endif // EIGEN_RETURNBYVALUE_H diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/Reverse.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/Reverse.h index e30ae3d2..8b6b3ab0 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/Reverse.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/Reverse.h @@ -14,20 +14,6 @@ namespace Eigen { -/** \class Reverse - * \ingroup Core_Module - * - * \brief Expression of the reverse of a vector or matrix - * - * \param MatrixType the type of the object of which we are taking the reverse - * - * This class represents an expression of the reverse of a vector. - * It is the return type of MatrixBase::reverse() and VectorwiseOp::reverse() - * and most of the time this is the only way it is used. - * - * \sa MatrixBase::reverse(), VectorwiseOp::reverse() - */ - namespace internal { template @@ -37,36 +23,43 @@ struct traits > typedef typename MatrixType::Scalar Scalar; typedef typename traits::StorageKind StorageKind; typedef typename traits::XprKind XprKind; - typedef typename nested::type MatrixTypeNested; + typedef typename ref_selector::type MatrixTypeNested; typedef typename remove_reference::type _MatrixTypeNested; enum { RowsAtCompileTime = MatrixType::RowsAtCompileTime, ColsAtCompileTime = MatrixType::ColsAtCompileTime, MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime, MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime, - - // let's enable LinearAccess only with vectorization because of the product overhead - LinearAccess = ( (Direction==BothDirections) && (int(_MatrixTypeNested::Flags)&PacketAccessBit) ) - ? LinearAccessBit : 0, - - Flags = int(_MatrixTypeNested::Flags) & (HereditaryBits | LvalueBit | PacketAccessBit | LinearAccess), - - CoeffReadCost = _MatrixTypeNested::CoeffReadCost + Flags = _MatrixTypeNested::Flags & (RowMajorBit | LvalueBit) }; }; -template struct reverse_packet_cond +template struct reverse_packet_cond { - static inline PacketScalar run(const PacketScalar& x) { return preverse(x); } + static inline PacketType run(const PacketType& x) { return preverse(x); } }; -template struct reverse_packet_cond +template struct reverse_packet_cond { - static inline PacketScalar run(const PacketScalar& x) { return x; } + static inline PacketType run(const PacketType& x) { return x; } }; } // end namespace internal +/** \class Reverse + * \ingroup Core_Module + * + * \brief Expression of the reverse of a vector or matrix + * + * \tparam MatrixType the type of the object of which we are taking the reverse + * \tparam Direction defines the direction of the reverse operation, can be Vertical, Horizontal, or BothDirections + * + * This class represents an expression of the reverse of a vector. + * It is the return type of MatrixBase::reverse() and VectorwiseOp::reverse() + * and most of the time this is the only way it is used. + * + * \sa MatrixBase::reverse(), VectorwiseOp::reverse() + */ template class Reverse : public internal::dense_xpr_base< Reverse >::type { @@ -74,12 +67,9 @@ template class Reverse typedef typename internal::dense_xpr_base::type Base; EIGEN_DENSE_PUBLIC_INTERFACE(Reverse) + typedef typename internal::remove_all::type NestedExpression; using Base::IsRowMajor; - // next line is necessary because otherwise const version of operator() - // is hidden by non-const version defined in this file - using Base::operator(); - protected: enum { PacketSize = internal::packet_traits::size, @@ -95,82 +85,19 @@ template class Reverse typedef internal::reverse_packet_cond reverse_packet; public: - inline Reverse(const MatrixType& matrix) : m_matrix(matrix) { } + EIGEN_DEVICE_FUNC explicit inline Reverse(const MatrixType& matrix) : m_matrix(matrix) { } EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Reverse) - inline Index rows() const { return m_matrix.rows(); } - inline Index cols() const { return m_matrix.cols(); } + EIGEN_DEVICE_FUNC inline Index rows() const { return m_matrix.rows(); } + EIGEN_DEVICE_FUNC inline Index cols() const { return m_matrix.cols(); } - inline Index innerStride() const + EIGEN_DEVICE_FUNC inline Index innerStride() const { return -m_matrix.innerStride(); } - inline Scalar& operator()(Index row, Index col) - { - eigen_assert(row >= 0 && row < rows() && col >= 0 && col < cols()); - return coeffRef(row, col); - } - - inline Scalar& coeffRef(Index row, Index col) - { - return m_matrix.const_cast_derived().coeffRef(ReverseRow ? m_matrix.rows() - row - 1 : row, - ReverseCol ? m_matrix.cols() - col - 1 : col); - } - - inline CoeffReturnType coeff(Index row, Index col) const - { - return m_matrix.coeff(ReverseRow ? m_matrix.rows() - row - 1 : row, - ReverseCol ? m_matrix.cols() - col - 1 : col); - } - - inline CoeffReturnType coeff(Index index) const - { - return m_matrix.coeff(m_matrix.size() - index - 1); - } - - inline Scalar& coeffRef(Index index) - { - return m_matrix.const_cast_derived().coeffRef(m_matrix.size() - index - 1); - } - - inline Scalar& operator()(Index index) - { - eigen_assert(index >= 0 && index < m_matrix.size()); - return coeffRef(index); - } - - template - inline const PacketScalar packet(Index row, Index col) const - { - return reverse_packet::run(m_matrix.template packet( - ReverseRow ? m_matrix.rows() - row - OffsetRow : row, - ReverseCol ? m_matrix.cols() - col - OffsetCol : col)); - } - - template - inline void writePacket(Index row, Index col, const PacketScalar& x) - { - m_matrix.const_cast_derived().template writePacket( - ReverseRow ? m_matrix.rows() - row - OffsetRow : row, - ReverseCol ? m_matrix.cols() - col - OffsetCol : col, - reverse_packet::run(x)); - } - - template - inline const PacketScalar packet(Index index) const - { - return internal::preverse(m_matrix.template packet( m_matrix.size() - index - PacketSize )); - } - - template - inline void writePacket(Index index, const PacketScalar& x) - { - m_matrix.const_cast_derived().template writePacket(m_matrix.size() - index - PacketSize, internal::preverse(x)); - } - - const typename internal::remove_all::type& + EIGEN_DEVICE_FUNC const typename internal::remove_all::type& nestedExpression() const { return m_matrix; @@ -187,36 +114,96 @@ template class Reverse * */ template -inline typename DenseBase::ReverseReturnType +EIGEN_DEVICE_FUNC inline typename DenseBase::ReverseReturnType DenseBase::reverse() { - return derived(); + return ReverseReturnType(derived()); } -/** This is the const version of reverse(). */ -template -inline const typename DenseBase::ConstReverseReturnType -DenseBase::reverse() const -{ - return derived(); -} + +//reverse const overload moved DenseBase.h due to a CUDA compiler bug /** This is the "in place" version of reverse: it reverses \c *this. * * In most cases it is probably better to simply use the reversed expression * of a matrix. However, when reversing the matrix data itself is really needed, * then this "in-place" version is probably the right choice because it provides - * the following additional features: + * the following additional benefits: * - less error prone: doing the same operation with .reverse() requires special care: * \code m = m.reverse().eval(); \endcode - * - this API allows to avoid creating a temporary (the current implementation creates a temporary, but that could be avoided using swap) + * - this API enables reverse operations without the need for a temporary * - it allows future optimizations (cache friendliness, etc.) * - * \sa reverse() */ + * \sa VectorwiseOp::reverseInPlace(), reverse() */ template -inline void DenseBase::reverseInPlace() +EIGEN_DEVICE_FUNC inline void DenseBase::reverseInPlace() { - derived() = derived().reverse().eval(); + if(cols()>rows()) + { + Index half = cols()/2; + leftCols(half).swap(rightCols(half).reverse()); + if((cols()%2)==1) + { + Index half2 = rows()/2; + col(half).head(half2).swap(col(half).tail(half2).reverse()); + } + } + else + { + Index half = rows()/2; + topRows(half).swap(bottomRows(half).reverse()); + if((rows()%2)==1) + { + Index half2 = cols()/2; + row(half).head(half2).swap(row(half).tail(half2).reverse()); + } + } +} + +namespace internal { + +template +struct vectorwise_reverse_inplace_impl; + +template<> +struct vectorwise_reverse_inplace_impl +{ + template + static void run(ExpressionType &xpr) + { + Index half = xpr.rows()/2; + xpr.topRows(half).swap(xpr.bottomRows(half).colwise().reverse()); + } +}; + +template<> +struct vectorwise_reverse_inplace_impl +{ + template + static void run(ExpressionType &xpr) + { + Index half = xpr.cols()/2; + xpr.leftCols(half).swap(xpr.rightCols(half).rowwise().reverse()); + } +}; + +} // end namespace internal + +/** This is the "in place" version of VectorwiseOp::reverse: it reverses each column or row of \c *this. + * + * In most cases it is probably better to simply use the reversed expression + * of a matrix. However, when reversing the matrix data itself is really needed, + * then this "in-place" version is probably the right choice because it provides + * the following additional benefits: + * - less error prone: doing the same operation with .reverse() requires special care: + * \code m = m.reverse().eval(); \endcode + * - this API enables reverse operations without the need for a temporary + * + * \sa DenseBase::reverseInPlace(), reverse() */ +template +EIGEN_DEVICE_FUNC void VectorwiseOp::reverseInPlace() +{ + internal::vectorwise_reverse_inplace_impl::run(_expression().const_cast_derived()); } } // end namespace Eigen diff --git a/testbed/nanogui/ext/eigen/Eigen/src/Core/Select.h b/testbed/nanogui/ext/eigen/Eigen/src/Core/Select.h index 87993bbb..79eec1b5 100644 --- a/testbed/nanogui/ext/eigen/Eigen/src/Core/Select.h +++ b/testbed/nanogui/ext/eigen/Eigen/src/Core/Select.h @@ -43,23 +43,21 @@ struct traits > ColsAtCompileTime = ConditionMatrixType::ColsAtCompileTime, MaxRowsAtCompileTime = ConditionMatrixType::MaxRowsAtCompileTime, MaxColsAtCompileTime = ConditionMatrixType::MaxColsAtCompileTime, - Flags = (unsigned int)ThenMatrixType::Flags & ElseMatrixType::Flags & HereditaryBits, - CoeffReadCost = traits::type>::CoeffReadCost - + EIGEN_SIZE_MAX(traits::type>::CoeffReadCost, - traits::type>::CoeffReadCost) + Flags = (unsigned int)ThenMatrixType::Flags & ElseMatrixType::Flags & RowMajorBit }; }; } template -class Select : internal::no_assignment_operator, - public internal::dense_xpr_base< Select >::type +class Select : public internal::dense_xpr_base< Select >::type, + internal::no_assignment_operator { public: typedef typename internal::dense_xpr_base" << endl; + cerr << "available actions:" << endl; + for (auto it = available_actions.begin(); it != available_actions.end(); ++it) { + cerr << " " << (*it)->invokation_name() << endl; + } + cerr << "the input files should each contain an output of benchmark-blocking-sizes" << endl; + exit(1); +} + +int main(int argc, char* argv[]) +{ + cout.precision(default_precision); + cerr.precision(default_precision); + + vector> available_actions; + available_actions.emplace_back(new partition_action_t); + available_actions.emplace_back(new evaluate_defaults_action_t); + + vector input_filenames; + + action_t* action = nullptr; + + if (argc < 2) { + show_usage_and_exit(argc, argv, available_actions); + } + for (int i = 1; i < argc; i++) { + bool arg_handled = false; + // Step 1. Try to match action invokation names. + for (auto it = available_actions.begin(); it != available_actions.end(); ++it) { + if (!strcmp(argv[i], (*it)->invokation_name())) { + if (!action) { + action = it->get(); + arg_handled = true; + break; + } else { + cerr << "can't specify more than one action!" << endl; + show_usage_and_exit(argc, argv, available_actions); + } + } + } + if (arg_handled) { + continue; + } + // Step 2. Try to match option names. + if (argv[i][0] == '-') { + if (!strcmp(argv[i], "--only-cubic-sizes")) { + only_cubic_sizes = true; + arg_handled = true; + } + if (!strcmp(argv[i], "--dump-tables")) { + dump_tables = true; + arg_handled = true; + } + if (!arg_handled) { + cerr << "Unrecognized option: " << argv[i] << endl; + show_usage_and_exit(argc, argv, available_actions); + } + } + if (arg_handled) { + continue; + } + // Step 3. Default to interpreting args as input filenames. + input_filenames.emplace_back(argv[i]); + } + + if (dump_tables && only_cubic_sizes) { + cerr << "Incompatible options: --only-cubic-sizes and --dump-tables." << endl; + show_usage_and_exit(argc, argv, available_actions); + } + + if (!action) { + show_usage_and_exit(argc, argv, available_actions); + } + + action->run(input_filenames); +} diff --git a/testbed/nanogui/ext/eigen/bench/benchCholesky.cpp b/testbed/nanogui/ext/eigen/bench/benchCholesky.cpp index 42b3e128..9a8e7cf6 100644 --- a/testbed/nanogui/ext/eigen/bench/benchCholesky.cpp +++ b/testbed/nanogui/ext/eigen/bench/benchCholesky.cpp @@ -31,7 +31,7 @@ __attribute__ ((noinline)) void benchLLT(const MatrixType& m) int rows = m.rows(); int cols = m.cols(); - int cost = 0; + double cost = 0; for (int j=0; j0; ++i) + for (int i=0; dynsizes[i]>0; ++i) benchLLT(Matrix(dynsizes[i],dynsizes[i])); benchLLT(Matrix()); diff --git a/testbed/nanogui/ext/eigen/bench/bench_gemm.cpp b/testbed/nanogui/ext/eigen/bench/bench_gemm.cpp index 41ca8b3b..8528c558 100644 --- a/testbed/nanogui/ext/eigen/bench/bench_gemm.cpp +++ b/testbed/nanogui/ext/eigen/bench/bench_gemm.cpp @@ -2,6 +2,14 @@ // g++-4.4 bench_gemm.cpp -I .. -O2 -DNDEBUG -lrt -fopenmp && OMP_NUM_THREADS=2 ./a.out // icpc bench_gemm.cpp -I .. -O3 -DNDEBUG -lrt -openmp && OMP_NUM_THREADS=2 ./a.out +// Compilation options: +// +// -DSCALAR=std::complex +// -DSCALARA=double or -DSCALARB=double +// -DHAVE_BLAS +// -DDECOUPLED +// + #include #include #include @@ -14,10 +22,18 @@ using namespace Eigen; #define SCALAR float #endif +#ifndef SCALARA +#define SCALARA SCALAR +#endif + +#ifndef SCALARB +#define SCALARB SCALAR +#endif + typedef SCALAR Scalar; typedef NumTraits::Real RealScalar; -typedef Matrix A; -typedef Matrix B; +typedef Matrix A; +typedef Matrix B; typedef Matrix C; typedef Matrix M; @@ -129,35 +145,69 @@ int main(int argc, char ** argv) int tries = 2; // number of tries, we keep the best int s = 2048; - int cache_size = -1; + int m = s; + int n = s; + int p = s; + int cache_size1=-1, cache_size2=l2, cache_size3 = 0; bool need_help = false; - for (int i=1; i c t p\n"; + std::cout << argv[0] << " -s -c -t -p \n"; + std::cout << " : size\n"; + std::cout << " : rows columns depth\n"; return 1; } - if(cache_size>0) - setCpuCacheSizes(cache_size,96*cache_size); - - int m = s; - int n = s; - int p = s; +#if EIGEN_VERSION_AT_LEAST(3,2,90) + if(cache_size1>0) + setCpuCacheSizes(cache_size1,cache_size2,cache_size3); +#endif + A a(m,p); a.setRandom(); B b(p,n); b.setRandom(); C c(m,n); c.setOnes(); @@ -172,6 +222,7 @@ int main(int argc, char ** argv) // check the parallel product is correct #if defined EIGEN_HAS_OPENMP + Eigen::initParallel(); int procs = omp_get_max_threads(); if(procs>1) { @@ -188,11 +239,20 @@ int main(int argc, char ** argv) #elif defined HAVE_BLAS blas_gemm(a,b,r); c.noalias() += a * b; - if(!r.isApprox(c)) std::cerr << "Warning, your product is crap!\n\n"; + if(!r.isApprox(c)) { + std::cout << r - c << "\n"; + std::cerr << "Warning, your product is crap!\n\n"; + } #else - gemm(a,b,c); - r.noalias() += a.cast() * b.cast(); - if(!r.isApprox(c)) std::cerr << "Warning, your product is crap!\n\n"; + if(1.*m*n*p<2000.*2000*2000) + { + gemm(a,b,c); + r.noalias() += a.cast() .lazyProduct( b.cast() ); + if(!r.isApprox(c)) { + std::cout << r - c << "\n"; + std::cerr << "Warning, your product is crap!\n\n"; + } + } #endif #ifdef HAVE_BLAS @@ -214,7 +274,7 @@ int main(int argc, char ** argv) { BenchTimer tmono; omp_set_num_threads(1); - Eigen::internal::setNbThreads(1); + Eigen::setNbThreads(1); c = rc; BENCH(tmono, tries, rep, gemm(a,b,c)); std::cout << "eigen mono cpu " << tmono.best(CPU_TIMER)/rep << "s \t" << (double(m)*n*p*rep*2/tmono.best(CPU_TIMER))*1e-9 << " GFLOPS \t(" << tmono.total(CPU_TIMER) << "s)\n"; @@ -223,6 +283,15 @@ int main(int argc, char ** argv) } #endif + if(1.*m*n*p<30*30*30) + { + BenchTimer tmt; + c = rc; + BENCH(tmt, tries, rep, c.noalias()+=a.lazyProduct(b)); + std::cout << "lazy cpu " << tmt.best(CPU_TIMER)/rep << "s \t" << (double(m)*n*p*rep*2/tmt.best(CPU_TIMER))*1e-9 << " GFLOPS \t(" << tmt.total(CPU_TIMER) << "s)\n"; + std::cout << "lazy real " << tmt.best(REAL_TIMER)/rep << "s \t" << (double(m)*n*p*rep*2/tmt.best(REAL_TIMER))*1e-9 << " GFLOPS \t(" << tmt.total(REAL_TIMER) << "s)\n"; + } + #ifdef DECOUPLED if((NumTraits::IsComplex) && (NumTraits::IsComplex)) { diff --git a/testbed/nanogui/ext/eigen/bench/bench_norm.cpp b/testbed/nanogui/ext/eigen/bench/bench_norm.cpp index 806db292..129afcfb 100644 --- a/testbed/nanogui/ext/eigen/bench/bench_norm.cpp +++ b/testbed/nanogui/ext/eigen/bench/bench_norm.cpp @@ -6,19 +6,25 @@ using namespace Eigen; using namespace std; template -EIGEN_DONT_INLINE typename T::Scalar sqsumNorm(const T& v) +EIGEN_DONT_INLINE typename T::Scalar sqsumNorm(T& v) { return v.norm(); } template -EIGEN_DONT_INLINE typename T::Scalar hypotNorm(const T& v) +EIGEN_DONT_INLINE typename T::Scalar stableNorm(T& v) +{ + return v.stableNorm(); +} + +template +EIGEN_DONT_INLINE typename T::Scalar hypotNorm(T& v) { return v.hypotNorm(); } template -EIGEN_DONT_INLINE typename T::Scalar blueNorm(const T& v) +EIGEN_DONT_INLINE typename T::Scalar blueNorm(T& v) { return v.blueNorm(); } @@ -32,25 +38,25 @@ EIGEN_DONT_INLINE typename T::Scalar lapackNorm(T& v) Scalar ssq = 1; for (int i=0;i= ax) { - ssq += internal::abs2(ax/scale); + ssq += numext::abs2(ax/scale); } else { - ssq = Scalar(1) + ssq * internal::abs2(scale/ax); + ssq = Scalar(1) + ssq * numext::abs2(scale/ax); scale = ax; } } - return scale * internal::sqrt(ssq); + return scale * std::sqrt(ssq); } template EIGEN_DONT_INLINE typename T::Scalar twopassNorm(T& v) { typedef typename T::Scalar Scalar; - Scalar s = v.cwise().abs().maxCoeff(); + Scalar s = v.array().abs().maxCoeff(); return s*(v/s).norm(); } @@ -73,16 +79,20 @@ EIGEN_DONT_INLINE typename T::Scalar divacNorm(T& v) v(i) = v(2*i) + v(2*i+1); n = n/2; } - return internal::sqrt(v(0)); + return std::sqrt(v(0)); } +namespace Eigen { +namespace internal { #ifdef EIGEN_VECTORIZE -Packet4f internal::plt(const Packet4f& a, Packet4f& b) { return _mm_cmplt_ps(a,b); } -Packet2d internal::plt(const Packet2d& a, Packet2d& b) { return _mm_cmplt_pd(a,b); } +Packet4f plt(const Packet4f& a, Packet4f& b) { return _mm_cmplt_ps(a,b); } +Packet2d plt(const Packet2d& a, Packet2d& b) { return _mm_cmplt_pd(a,b); } -Packet4f internal::pandnot(const Packet4f& a, Packet4f& b) { return _mm_andnot_ps(a,b); } -Packet2d internal::pandnot(const Packet2d& a, Packet2d& b) { return _mm_andnot_pd(a,b); } +Packet4f pandnot(const Packet4f& a, Packet4f& b) { return _mm_andnot_ps(a,b); } +Packet2d pandnot(const Packet2d& a, Packet2d& b) { return _mm_andnot_pd(a,b); } #endif +} +} template EIGEN_DONT_INLINE typename T::Scalar pblueNorm(const T& v) @@ -126,7 +136,7 @@ EIGEN_DONT_INLINE typename T::Scalar pblueNorm(const T& v) overfl = rbig*s2m; // overfow boundary for abig eps = std::pow(ibeta, 1-it); - relerr = internal::sqrt(eps); // tolerance for neglecting asml + relerr = std::sqrt(eps); // tolerance for neglecting asml abig = 1.0/eps - 1.0; if (Scalar(nbig)>abig) nmax = abig; // largest safe n else nmax = nbig; @@ -134,13 +144,13 @@ EIGEN_DONT_INLINE typename T::Scalar pblueNorm(const T& v) typedef typename internal::packet_traits::type Packet; const int ps = internal::packet_traits::size; - Packet pasml = internal::pset1(Scalar(0)); - Packet pamed = internal::pset1(Scalar(0)); - Packet pabig = internal::pset1(Scalar(0)); - Packet ps2m = internal::pset1(s2m); - Packet ps1m = internal::pset1(s1m); - Packet pb2 = internal::pset1(b2); - Packet pb1 = internal::pset1(b1); + Packet pasml = internal::pset1(Scalar(0)); + Packet pamed = internal::pset1(Scalar(0)); + Packet pabig = internal::pset1(Scalar(0)); + Packet ps2m = internal::pset1(s2m); + Packet ps1m = internal::pset1(s1m); + Packet pb2 = internal::pset1(b2); + Packet pb1 = internal::pset1(b1); for(int j=0; j(j)); @@ -170,7 +180,7 @@ EIGEN_DONT_INLINE typename T::Scalar pblueNorm(const T& v) Scalar amed = internal::predux(pamed); if(abig > Scalar(0)) { - abig = internal::sqrt(abig); + abig = std::sqrt(abig); if(abig > overfl) { eigen_assert(false && "overflow"); @@ -179,7 +189,7 @@ EIGEN_DONT_INLINE typename T::Scalar pblueNorm(const T& v) if(amed > Scalar(0)) { abig = abig/s2m; - amed = internal::sqrt(amed); + amed = std::sqrt(amed); } else { @@ -191,55 +201,56 @@ EIGEN_DONT_INLINE typename T::Scalar pblueNorm(const T& v) { if (amed > Scalar(0)) { - abig = internal::sqrt(amed); - amed = internal::sqrt(asml) / s1m; + abig = std::sqrt(amed); + amed = std::sqrt(asml) / s1m; } else { - return internal::sqrt(asml)/s1m; + return std::sqrt(asml)/s1m; } } else { - return internal::sqrt(amed); + return std::sqrt(amed); } asml = std::min(abig, amed); abig = std::max(abig, amed); if(asml <= abig*relerr) return abig; else - return abig * internal::sqrt(Scalar(1) + internal::abs2(asml/abig)); + return abig * std::sqrt(Scalar(1) + numext::abs2(asml/abig)); #endif } #define BENCH_PERF(NRM) { \ + float af = 0; double ad = 0; std::complex ac = 0; \ Eigen::BenchTimer tf, td, tcf; tf.reset(); td.reset(); tcf.reset();\ for (int k=0; k()); - double yd = based * internal::abs(internal::random()); + double yf = basef * std::abs(internal::random()); + double yd = based * std::abs(internal::random()); VectorXf vf = VectorXf::Ones(s) * yf; VectorXd vd = VectorXd::Ones(s) * yd; - std::cout << "reference\t" << internal::sqrt(double(s))*yf << "\t" << internal::sqrt(double(s))*yd << "\n"; + std::cout << "reference\t" << std::sqrt(double(s))*yf << "\t" << std::sqrt(double(s))*yd << "\n"; std::cout << "sqsumNorm\t" << sqsumNorm(vf) << "\t" << sqsumNorm(vd) << "\n"; std::cout << "hypotNorm\t" << hypotNorm(vf) << "\t" << hypotNorm(vd) << "\n"; std::cout << "blueNorm\t" << blueNorm(vf) << "\t" << blueNorm(vd) << "\n"; @@ -255,8 +266,8 @@ void check_accuracy_var(int ef0, int ef1, int ed0, int ed1, int s) VectorXd vd(s); for (int i=0; i()) * std::pow(double(10), internal::random(ef0,ef1)); - vd[i] = internal::abs(internal::random()) * std::pow(double(10), internal::random(ed0,ed1)); + vf[i] = std::abs(internal::random()) * std::pow(double(10), internal::random(ef0,ef1)); + vd[i] = std::abs(internal::random()) * std::pow(double(10), internal::random(ed0,ed1)); } //std::cout << "reference\t" << internal::sqrt(double(s))*yf << "\t" << internal::sqrt(double(s))*yd << "\n"; @@ -312,34 +323,38 @@ int main(int argc, char** argv) std::cout << "\n"; } + y = 1; std::cout.precision(4); - std::cerr << "Performance (out of cache):\n"; + int s1 = 1024*1024*32; + std::cerr << "Performance (out of cache, " << s1 << "):\n"; { int iters = 1; - VectorXf vf = VectorXf::Random(1024*1024*32) * y; - VectorXd vd = VectorXd::Random(1024*1024*32) * y; - VectorXcf vcf = VectorXcf::Random(1024*1024*32) * y; + VectorXf vf = VectorXf::Random(s1) * y; + VectorXd vd = VectorXd::Random(s1) * y; + VectorXcf vcf = VectorXcf::Random(s1) * y; BENCH_PERF(sqsumNorm); + BENCH_PERF(stableNorm); BENCH_PERF(blueNorm); -// BENCH_PERF(pblueNorm); -// BENCH_PERF(lapackNorm); -// BENCH_PERF(hypotNorm); -// BENCH_PERF(twopassNorm); + BENCH_PERF(pblueNorm); + BENCH_PERF(lapackNorm); + BENCH_PERF(hypotNorm); + BENCH_PERF(twopassNorm); BENCH_PERF(bl2passNorm); } - std::cerr << "\nPerformance (in cache):\n"; + std::cerr << "\nPerformance (in cache, " << 512 << "):\n"; { int iters = 100000; VectorXf vf = VectorXf::Random(512) * y; VectorXd vd = VectorXd::Random(512) * y; VectorXcf vcf = VectorXcf::Random(512) * y; BENCH_PERF(sqsumNorm); + BENCH_PERF(stableNorm); BENCH_PERF(blueNorm); -// BENCH_PERF(pblueNorm); -// BENCH_PERF(lapackNorm); -// BENCH_PERF(hypotNorm); -// BENCH_PERF(twopassNorm); + BENCH_PERF(pblueNorm); + BENCH_PERF(lapackNorm); + BENCH_PERF(hypotNorm); + BENCH_PERF(twopassNorm); BENCH_PERF(bl2passNorm); } } diff --git a/testbed/nanogui/ext/eigen/bench/benchmark-blocking-sizes.cpp b/testbed/nanogui/ext/eigen/bench/benchmark-blocking-sizes.cpp new file mode 100644 index 00000000..827be288 --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/benchmark-blocking-sizes.cpp @@ -0,0 +1,677 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Benoit Jacob +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include +#include +#include +#include +#include +#include +#include + +bool eigen_use_specific_block_size; +int eigen_block_size_k, eigen_block_size_m, eigen_block_size_n; +#define EIGEN_TEST_SPECIFIC_BLOCKING_SIZES eigen_use_specific_block_size +#define EIGEN_TEST_SPECIFIC_BLOCKING_SIZE_K eigen_block_size_k +#define EIGEN_TEST_SPECIFIC_BLOCKING_SIZE_M eigen_block_size_m +#define EIGEN_TEST_SPECIFIC_BLOCKING_SIZE_N eigen_block_size_n +#include + +#include + +using namespace Eigen; +using namespace std; + +static BenchTimer timer; + +// how many times we repeat each measurement. +// measurements are randomly shuffled - we're not doing +// all N identical measurements in a row. +const int measurement_repetitions = 3; + +// Timings below this value are too short to be accurate, +// we'll repeat measurements with more iterations until +// we get a timing above that threshold. +const float min_accurate_time = 1e-2f; + +// See --min-working-set-size command line parameter. +size_t min_working_set_size = 0; + +float max_clock_speed = 0.0f; + +// range of sizes that we will benchmark (in all 3 K,M,N dimensions) +const size_t maxsize = 2048; +const size_t minsize = 16; + +typedef MatrixXf MatrixType; +typedef MatrixType::Scalar Scalar; +typedef internal::packet_traits::type Packet; + +static_assert((maxsize & (maxsize - 1)) == 0, "maxsize must be a power of two"); +static_assert((minsize & (minsize - 1)) == 0, "minsize must be a power of two"); +static_assert(maxsize > minsize, "maxsize must be larger than minsize"); +static_assert(maxsize < (minsize << 16), "maxsize must be less than (minsize<<16)"); + +// just a helper to store a triple of K,M,N sizes for matrix product +struct size_triple_t +{ + size_t k, m, n; + size_triple_t() : k(0), m(0), n(0) {} + size_triple_t(size_t _k, size_t _m, size_t _n) : k(_k), m(_m), n(_n) {} + size_triple_t(const size_triple_t& o) : k(o.k), m(o.m), n(o.n) {} + size_triple_t(uint16_t compact) + { + k = 1 << ((compact & 0xf00) >> 8); + m = 1 << ((compact & 0x0f0) >> 4); + n = 1 << ((compact & 0x00f) >> 0); + } +}; + +uint8_t log2_pot(size_t x) { + size_t l = 0; + while (x >>= 1) l++; + return l; +} + +// Convert between size tripes and a compact form fitting in 12 bits +// where each size, which must be a POT, is encoded as its log2, on 4 bits +// so the largest representable size is 2^15 == 32k ... big enough. +uint16_t compact_size_triple(size_t k, size_t m, size_t n) +{ + return (log2_pot(k) << 8) | (log2_pot(m) << 4) | log2_pot(n); +} + +uint16_t compact_size_triple(const size_triple_t& t) +{ + return compact_size_triple(t.k, t.m, t.n); +} + +// A single benchmark. Initially only contains benchmark params. +// Then call run(), which stores the result in the gflops field. +struct benchmark_t +{ + uint16_t compact_product_size; + uint16_t compact_block_size; + bool use_default_block_size; + float gflops; + benchmark_t() + : compact_product_size(0) + , compact_block_size(0) + , use_default_block_size(false) + , gflops(0) + { + } + benchmark_t(size_t pk, size_t pm, size_t pn, + size_t bk, size_t bm, size_t bn) + : compact_product_size(compact_size_triple(pk, pm, pn)) + , compact_block_size(compact_size_triple(bk, bm, bn)) + , use_default_block_size(false) + , gflops(0) + {} + benchmark_t(size_t pk, size_t pm, size_t pn) + : compact_product_size(compact_size_triple(pk, pm, pn)) + , compact_block_size(0) + , use_default_block_size(true) + , gflops(0) + {} + + void run(); +}; + +ostream& operator<<(ostream& s, const benchmark_t& b) +{ + s << hex << b.compact_product_size << dec; + if (b.use_default_block_size) { + size_triple_t t(b.compact_product_size); + Index k = t.k, m = t.m, n = t.n; + internal::computeProductBlockingSizes(k, m, n); + s << " default(" << k << ", " << m << ", " << n << ")"; + } else { + s << " " << hex << b.compact_block_size << dec; + } + s << " " << b.gflops; + return s; +} + +// We sort first by increasing benchmark parameters, +// then by decreasing performance. +bool operator<(const benchmark_t& b1, const benchmark_t& b2) +{ + return b1.compact_product_size < b2.compact_product_size || + (b1.compact_product_size == b2.compact_product_size && ( + (b1.compact_block_size < b2.compact_block_size || ( + b1.compact_block_size == b2.compact_block_size && + b1.gflops > b2.gflops)))); +} + +void benchmark_t::run() +{ + size_triple_t productsizes(compact_product_size); + + if (use_default_block_size) { + eigen_use_specific_block_size = false; + } else { + // feed eigen with our custom blocking params + eigen_use_specific_block_size = true; + size_triple_t blocksizes(compact_block_size); + eigen_block_size_k = blocksizes.k; + eigen_block_size_m = blocksizes.m; + eigen_block_size_n = blocksizes.n; + } + + // set up the matrix pool + + const size_t combined_three_matrices_sizes = + sizeof(Scalar) * + (productsizes.k * productsizes.m + + productsizes.k * productsizes.n + + productsizes.m * productsizes.n); + + // 64 M is large enough that nobody has a cache bigger than that, + // while still being small enough that everybody has this much RAM, + // so conveniently we don't need to special-case platforms here. + const size_t unlikely_large_cache_size = 64 << 20; + + const size_t working_set_size = + min_working_set_size ? min_working_set_size : unlikely_large_cache_size; + + const size_t matrix_pool_size = + 1 + working_set_size / combined_three_matrices_sizes; + + MatrixType *lhs = new MatrixType[matrix_pool_size]; + MatrixType *rhs = new MatrixType[matrix_pool_size]; + MatrixType *dst = new MatrixType[matrix_pool_size]; + + for (size_t i = 0; i < matrix_pool_size; i++) { + lhs[i] = MatrixType::Zero(productsizes.m, productsizes.k); + rhs[i] = MatrixType::Zero(productsizes.k, productsizes.n); + dst[i] = MatrixType::Zero(productsizes.m, productsizes.n); + } + + // main benchmark loop + + int iters_at_a_time = 1; + float time_per_iter = 0.0f; + size_t matrix_index = 0; + while (true) { + + double starttime = timer.getCpuTime(); + for (int i = 0; i < iters_at_a_time; i++) { + dst[matrix_index].noalias() = lhs[matrix_index] * rhs[matrix_index]; + matrix_index++; + if (matrix_index == matrix_pool_size) { + matrix_index = 0; + } + } + double endtime = timer.getCpuTime(); + + const float timing = float(endtime - starttime); + + if (timing >= min_accurate_time) { + time_per_iter = timing / iters_at_a_time; + break; + } + + iters_at_a_time *= 2; + } + + delete[] lhs; + delete[] rhs; + delete[] dst; + + gflops = 2e-9 * productsizes.k * productsizes.m * productsizes.n / time_per_iter; +} + +void print_cpuinfo() +{ +#ifdef __linux__ + cout << "contents of /proc/cpuinfo:" << endl; + string line; + ifstream cpuinfo("/proc/cpuinfo"); + if (cpuinfo.is_open()) { + while (getline(cpuinfo, line)) { + cout << line << endl; + } + cpuinfo.close(); + } + cout << endl; +#elif defined __APPLE__ + cout << "output of sysctl hw:" << endl; + system("sysctl hw"); + cout << endl; +#endif +} + +template +string type_name() +{ + return "unknown"; +} + +template<> +string type_name() +{ + return "float"; +} + +template<> +string type_name() +{ + return "double"; +} + +struct action_t +{ + virtual const char* invokation_name() const { abort(); return nullptr; } + virtual void run() const { abort(); } + virtual ~action_t() {} +}; + +void show_usage_and_exit(int /*argc*/, char* argv[], + const vector>& available_actions) +{ + cerr << "usage: " << argv[0] << " [options...]" << endl << endl; + cerr << "available actions:" << endl << endl; + for (auto it = available_actions.begin(); it != available_actions.end(); ++it) { + cerr << " " << (*it)->invokation_name() << endl; + } + cerr << endl; + cerr << "options:" << endl << endl; + cerr << " --min-working-set-size=N:" << endl; + cerr << " Set the minimum working set size to N bytes." << endl; + cerr << " This is rounded up as needed to a multiple of matrix size." << endl; + cerr << " A larger working set lowers the chance of a warm cache." << endl; + cerr << " The default value 0 means use a large enough working" << endl; + cerr << " set to likely outsize caches." << endl; + cerr << " A value of 1 (that is, 1 byte) would mean don't do anything to" << endl; + cerr << " avoid warm caches." << endl; + exit(1); +} + +float measure_clock_speed() +{ + cerr << "Measuring clock speed... \r" << flush; + + vector all_gflops; + for (int i = 0; i < 8; i++) { + benchmark_t b(1024, 1024, 1024); + b.run(); + all_gflops.push_back(b.gflops); + } + + sort(all_gflops.begin(), all_gflops.end()); + float stable_estimate = all_gflops[2] + all_gflops[3] + all_gflops[4] + all_gflops[5]; + + // multiply by an arbitrary constant to discourage trying doing anything with the + // returned values besides just comparing them with each other. + float result = stable_estimate * 123.456f; + + return result; +} + +struct human_duration_t +{ + int seconds; + human_duration_t(int s) : seconds(s) {} +}; + +ostream& operator<<(ostream& s, const human_duration_t& d) +{ + int remainder = d.seconds; + if (remainder > 3600) { + int hours = remainder / 3600; + s << hours << " h "; + remainder -= hours * 3600; + } + if (remainder > 60) { + int minutes = remainder / 60; + s << minutes << " min "; + remainder -= minutes * 60; + } + if (d.seconds < 600) { + s << remainder << " s"; + } + return s; +} + +const char session_filename[] = "/data/local/tmp/benchmark-blocking-sizes-session.data"; + +void serialize_benchmarks(const char* filename, const vector& benchmarks, size_t first_benchmark_to_run) +{ + FILE* file = fopen(filename, "w"); + if (!file) { + cerr << "Could not open file " << filename << " for writing." << endl; + cerr << "Do you have write permissions on the current working directory?" << endl; + exit(1); + } + size_t benchmarks_vector_size = benchmarks.size(); + fwrite(&max_clock_speed, sizeof(max_clock_speed), 1, file); + fwrite(&benchmarks_vector_size, sizeof(benchmarks_vector_size), 1, file); + fwrite(&first_benchmark_to_run, sizeof(first_benchmark_to_run), 1, file); + fwrite(benchmarks.data(), sizeof(benchmark_t), benchmarks.size(), file); + fclose(file); +} + +bool deserialize_benchmarks(const char* filename, vector& benchmarks, size_t& first_benchmark_to_run) +{ + FILE* file = fopen(filename, "r"); + if (!file) { + return false; + } + if (1 != fread(&max_clock_speed, sizeof(max_clock_speed), 1, file)) { + return false; + } + size_t benchmarks_vector_size = 0; + if (1 != fread(&benchmarks_vector_size, sizeof(benchmarks_vector_size), 1, file)) { + return false; + } + if (1 != fread(&first_benchmark_to_run, sizeof(first_benchmark_to_run), 1, file)) { + return false; + } + benchmarks.resize(benchmarks_vector_size); + if (benchmarks.size() != fread(benchmarks.data(), sizeof(benchmark_t), benchmarks.size(), file)) { + return false; + } + unlink(filename); + return true; +} + +void try_run_some_benchmarks( + vector& benchmarks, + double time_start, + size_t& first_benchmark_to_run) +{ + if (first_benchmark_to_run == benchmarks.size()) { + return; + } + + double time_last_progress_update = 0; + double time_last_clock_speed_measurement = 0; + double time_now = 0; + + size_t benchmark_index = first_benchmark_to_run; + + while (true) { + float ratio_done = float(benchmark_index) / benchmarks.size(); + time_now = timer.getRealTime(); + + // We check clock speed every minute and at the end. + if (benchmark_index == benchmarks.size() || + time_now > time_last_clock_speed_measurement + 60.0f) + { + time_last_clock_speed_measurement = time_now; + + // Ensure that clock speed is as expected + float current_clock_speed = measure_clock_speed(); + + // The tolerance needs to be smaller than the relative difference between + // clock speeds that a device could operate under. + // It seems unlikely that a device would be throttling clock speeds by + // amounts smaller than 2%. + // With a value of 1%, I was getting within noise on a Sandy Bridge. + const float clock_speed_tolerance = 0.02f; + + if (current_clock_speed > (1 + clock_speed_tolerance) * max_clock_speed) { + // Clock speed is now higher than we previously measured. + // Either our initial measurement was inaccurate, which won't happen + // too many times as we are keeping the best clock speed value and + // and allowing some tolerance; or something really weird happened, + // which invalidates all benchmark results collected so far. + // Either way, we better restart all over again now. + if (benchmark_index) { + cerr << "Restarting at " << 100.0f * ratio_done + << " % because clock speed increased. " << endl; + } + max_clock_speed = current_clock_speed; + first_benchmark_to_run = 0; + return; + } + + bool rerun_last_tests = false; + + if (current_clock_speed < (1 - clock_speed_tolerance) * max_clock_speed) { + cerr << "Measurements completed so far: " + << 100.0f * ratio_done + << " % " << endl; + cerr << "Clock speed seems to be only " + << current_clock_speed/max_clock_speed + << " times what it used to be." << endl; + + unsigned int seconds_to_sleep_if_lower_clock_speed = 1; + + while (current_clock_speed < (1 - clock_speed_tolerance) * max_clock_speed) { + if (seconds_to_sleep_if_lower_clock_speed > 32) { + cerr << "Sleeping longer probably won't make a difference." << endl; + cerr << "Serializing benchmarks to " << session_filename << endl; + serialize_benchmarks(session_filename, benchmarks, first_benchmark_to_run); + cerr << "Now restart this benchmark, and it should pick up where we left." << endl; + exit(2); + } + rerun_last_tests = true; + cerr << "Sleeping " + << seconds_to_sleep_if_lower_clock_speed + << " s... \r" << endl; + sleep(seconds_to_sleep_if_lower_clock_speed); + current_clock_speed = measure_clock_speed(); + seconds_to_sleep_if_lower_clock_speed *= 2; + } + } + + if (rerun_last_tests) { + cerr << "Redoing the last " + << 100.0f * float(benchmark_index - first_benchmark_to_run) / benchmarks.size() + << " % because clock speed had been low. " << endl; + return; + } + + // nothing wrong with the clock speed so far, so there won't be a need to rerun + // benchmarks run so far in case we later encounter a lower clock speed. + first_benchmark_to_run = benchmark_index; + } + + if (benchmark_index == benchmarks.size()) { + // We're done! + first_benchmark_to_run = benchmarks.size(); + // Erase progress info + cerr << " " << endl; + return; + } + + // Display progress info on stderr + if (time_now > time_last_progress_update + 1.0f) { + time_last_progress_update = time_now; + cerr << "Measurements... " << 100.0f * ratio_done + << " %, ETA " + << human_duration_t(float(time_now - time_start) * (1.0f - ratio_done) / ratio_done) + << " \r" << flush; + } + + // This is where we actually run a benchmark! + benchmarks[benchmark_index].run(); + benchmark_index++; + } +} + +void run_benchmarks(vector& benchmarks) +{ + size_t first_benchmark_to_run; + vector deserialized_benchmarks; + bool use_deserialized_benchmarks = false; + if (deserialize_benchmarks(session_filename, deserialized_benchmarks, first_benchmark_to_run)) { + cerr << "Found serialized session with " + << 100.0f * first_benchmark_to_run / deserialized_benchmarks.size() + << " % already done" << endl; + if (deserialized_benchmarks.size() == benchmarks.size() && + first_benchmark_to_run > 0 && + first_benchmark_to_run < benchmarks.size()) + { + use_deserialized_benchmarks = true; + } + } + + if (use_deserialized_benchmarks) { + benchmarks = deserialized_benchmarks; + } else { + // not using deserialized benchmarks, starting from scratch + first_benchmark_to_run = 0; + + // Randomly shuffling benchmarks allows us to get accurate enough progress info, + // as now the cheap/expensive benchmarks are randomly mixed so they average out. + // It also means that if data is corrupted for some time span, the odds are that + // not all repetitions of a given benchmark will be corrupted. + random_shuffle(benchmarks.begin(), benchmarks.end()); + } + + for (int i = 0; i < 4; i++) { + max_clock_speed = max(max_clock_speed, measure_clock_speed()); + } + + double time_start = 0.0; + while (first_benchmark_to_run < benchmarks.size()) { + if (first_benchmark_to_run == 0) { + time_start = timer.getRealTime(); + } + try_run_some_benchmarks(benchmarks, + time_start, + first_benchmark_to_run); + } + + // Sort timings by increasing benchmark parameters, and decreasing gflops. + // The latter is very important. It means that we can ignore all but the first + // benchmark with given parameters. + sort(benchmarks.begin(), benchmarks.end()); + + // Collect best (i.e. now first) results for each parameter values. + vector best_benchmarks; + for (auto it = benchmarks.begin(); it != benchmarks.end(); ++it) { + if (best_benchmarks.empty() || + best_benchmarks.back().compact_product_size != it->compact_product_size || + best_benchmarks.back().compact_block_size != it->compact_block_size) + { + best_benchmarks.push_back(*it); + } + } + + // keep and return only the best benchmarks + benchmarks = best_benchmarks; +} + +struct measure_all_pot_sizes_action_t : action_t +{ + virtual const char* invokation_name() const { return "all-pot-sizes"; } + virtual void run() const + { + vector benchmarks; + for (int repetition = 0; repetition < measurement_repetitions; repetition++) { + for (size_t ksize = minsize; ksize <= maxsize; ksize *= 2) { + for (size_t msize = minsize; msize <= maxsize; msize *= 2) { + for (size_t nsize = minsize; nsize <= maxsize; nsize *= 2) { + for (size_t kblock = minsize; kblock <= ksize; kblock *= 2) { + for (size_t mblock = minsize; mblock <= msize; mblock *= 2) { + for (size_t nblock = minsize; nblock <= nsize; nblock *= 2) { + benchmarks.emplace_back(ksize, msize, nsize, kblock, mblock, nblock); + } + } + } + } + } + } + } + + run_benchmarks(benchmarks); + + cout << "BEGIN MEASUREMENTS ALL POT SIZES" << endl; + for (auto it = benchmarks.begin(); it != benchmarks.end(); ++it) { + cout << *it << endl; + } + } +}; + +struct measure_default_sizes_action_t : action_t +{ + virtual const char* invokation_name() const { return "default-sizes"; } + virtual void run() const + { + vector benchmarks; + for (int repetition = 0; repetition < measurement_repetitions; repetition++) { + for (size_t ksize = minsize; ksize <= maxsize; ksize *= 2) { + for (size_t msize = minsize; msize <= maxsize; msize *= 2) { + for (size_t nsize = minsize; nsize <= maxsize; nsize *= 2) { + benchmarks.emplace_back(ksize, msize, nsize); + } + } + } + } + + run_benchmarks(benchmarks); + + cout << "BEGIN MEASUREMENTS DEFAULT SIZES" << endl; + for (auto it = benchmarks.begin(); it != benchmarks.end(); ++it) { + cout << *it << endl; + } + } +}; + +int main(int argc, char* argv[]) +{ + double time_start = timer.getRealTime(); + cout.precision(4); + cerr.precision(4); + + vector> available_actions; + available_actions.emplace_back(new measure_all_pot_sizes_action_t); + available_actions.emplace_back(new measure_default_sizes_action_t); + + auto action = available_actions.end(); + + if (argc <= 1) { + show_usage_and_exit(argc, argv, available_actions); + } + for (auto it = available_actions.begin(); it != available_actions.end(); ++it) { + if (!strcmp(argv[1], (*it)->invokation_name())) { + action = it; + break; + } + } + + if (action == available_actions.end()) { + show_usage_and_exit(argc, argv, available_actions); + } + + for (int i = 2; i < argc; i++) { + if (argv[i] == strstr(argv[i], "--min-working-set-size=")) { + const char* equals_sign = strchr(argv[i], '='); + min_working_set_size = strtoul(equals_sign+1, nullptr, 10); + } else { + cerr << "unrecognized option: " << argv[i] << endl << endl; + show_usage_and_exit(argc, argv, available_actions); + } + } + + print_cpuinfo(); + + cout << "benchmark parameters:" << endl; + cout << "pointer size: " << 8*sizeof(void*) << " bits" << endl; + cout << "scalar type: " << type_name() << endl; + cout << "packet size: " << internal::packet_traits::size << endl; + cout << "minsize = " << minsize << endl; + cout << "maxsize = " << maxsize << endl; + cout << "measurement_repetitions = " << measurement_repetitions << endl; + cout << "min_accurate_time = " << min_accurate_time << endl; + cout << "min_working_set_size = " << min_working_set_size; + if (min_working_set_size == 0) { + cout << " (try to outsize caches)"; + } + cout << endl << endl; + + (*action)->run(); + + double time_end = timer.getRealTime(); + cerr << "Finished in " << human_duration_t(time_end - time_start) << endl; +} diff --git a/testbed/nanogui/ext/eigen/bench/btl/CMakeLists.txt b/testbed/nanogui/ext/eigen/bench/btl/CMakeLists.txt index 119b470d..38ff9f48 100644 --- a/testbed/nanogui/ext/eigen/bench/btl/CMakeLists.txt +++ b/testbed/nanogui/ext/eigen/bench/btl/CMakeLists.txt @@ -11,29 +11,24 @@ SET(CMAKE_INCLUDE_CURRENT_DIR ON) string(REGEX MATCH icpc IS_ICPC ${CMAKE_CXX_COMPILER}) IF(CMAKE_COMPILER_IS_GNUCXX OR IS_ICPC) - SET(CMAKE_CXX_FLAGS "-g0 -O3 -DNDEBUG") - SET(CMAKE_Fortran_FLAGS "-g0 -O3 -DNDEBUG") - IF(NOT BTL_NOVEC) - SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -msse2") - SET(CMAKE_Fortran_FLAGS "${CMAKE_Fortran_FLAGS} -msse2") - ELSE(NOT BTL_NOVEC) + SET(CMAKE_CXX_FLAGS "-g0 -O3 -DNDEBUG ${CMAKE_CXX_FLAGS}") + SET(CMAKE_Fortran_FLAGS "-g0 -O3 -DNDEBUG ${CMAKE_Fortran_FLAGS}") + IF(BTL_NOVEC) SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DEIGEN_DONT_VECTORIZE") - ENDIF(NOT BTL_NOVEC) + ENDIF(BTL_NOVEC) ENDIF(CMAKE_COMPILER_IS_GNUCXX OR IS_ICPC) IF(MSVC) SET(CMAKE_CXX_FLAGS " /O2 /Ot /GL /fp:fast -DNDEBUG") # SET(CMAKE_Fortran_FLAGS "-g0 -O3 -DNDEBUG") - IF(NOT BTL_NOVEC) - SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /arch:SSE2") - ELSE(NOT BTL_NOVEC) + IF(BTL_NOVEC) SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DEIGEN_DONT_VECTORIZE") - ENDIF(NOT BTL_NOVEC) + ENDIF(BTL_NOVEC) ENDIF(MSVC) if(IS_ICPC) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fast") - set(CMAKE_Fortran_FLAGS "${CMAKE_Fortran_FLAGS} -fast") + set(CMAKE_CXX_FLAGS "-fast ${CMAKE_CXX_FLAGS}") + set(CMAKE_Fortran_FLAGS "-fast ${CMAKE_Fortran_FLAGS}") endif(IS_ICPC) include_directories( @@ -48,6 +43,12 @@ include_directories( # set(DEFAULT_LIBRARIES ${MKL_LIBRARIES}) # endif (MKL_FOUND) +find_library(EIGEN_BTL_RT_LIBRARY rt) +# if we cannot find it easily, then we don't need it! +if(NOT EIGEN_BTL_RT_LIBRARY) + set(EIGEN_BTL_RT_LIBRARY "") +endif() + MACRO(BTL_ADD_BENCH targetname) foreach(_current_var ${ARGN}) @@ -70,7 +71,7 @@ MACRO(BTL_ADD_BENCH targetname) IF(BUILD_${targetname}) ADD_EXECUTABLE(${targetname} ${_sources}) ADD_TEST(${targetname} "${targetname}") - target_link_libraries(${targetname} ${DEFAULT_LIBRARIES} rt) + target_link_libraries(${targetname} ${DEFAULT_LIBRARIES} ${EIGEN_BTL_RT_LIBRARY}) ENDIF(BUILD_${targetname}) ENDMACRO(BTL_ADD_BENCH) @@ -91,6 +92,7 @@ ENABLE_TESTING() add_subdirectory(libs/eigen3) add_subdirectory(libs/eigen2) +add_subdirectory(libs/tensors) add_subdirectory(libs/BLAS) add_subdirectory(libs/ublas) add_subdirectory(libs/gmm) @@ -98,6 +100,7 @@ add_subdirectory(libs/mtl4) add_subdirectory(libs/blitz) add_subdirectory(libs/tvmet) add_subdirectory(libs/STL) +add_subdirectory(libs/blaze) add_subdirectory(data) diff --git a/testbed/nanogui/ext/eigen/bench/btl/actions/action_axpby.hh b/testbed/nanogui/ext/eigen/bench/btl/actions/action_axpby.hh index 98511ab6..dadd0ccf 100644 --- a/testbed/nanogui/ext/eigen/bench/btl/actions/action_axpby.hh +++ b/testbed/nanogui/ext/eigen/bench/btl/actions/action_axpby.hh @@ -33,7 +33,7 @@ class Action_axpby { public : // Ctor - Action_axpby( int size ):_size(size),_alpha(0.5),_beta(0.95) + Action_axpby( int size ):_alpha(0.5),_beta(0.95),_size(size) { MESSAGE("Action_axpby Ctor"); diff --git a/testbed/nanogui/ext/eigen/bench/btl/actions/action_axpy.hh b/testbed/nanogui/ext/eigen/bench/btl/actions/action_axpy.hh index e4cb3a5b..261be4cb 100644 --- a/testbed/nanogui/ext/eigen/bench/btl/actions/action_axpy.hh +++ b/testbed/nanogui/ext/eigen/bench/btl/actions/action_axpy.hh @@ -35,7 +35,7 @@ public : // Ctor - Action_axpy( int size ):_size(size),_coef(1.0) + Action_axpy( int size ):_coef(1.0),_size(size) { MESSAGE("Action_axpy Ctor"); diff --git a/testbed/nanogui/ext/eigen/bench/btl/actions/basic_actions.hh b/testbed/nanogui/ext/eigen/bench/btl/actions/basic_actions.hh index a3333ea2..62442f01 100644 --- a/testbed/nanogui/ext/eigen/bench/btl/actions/basic_actions.hh +++ b/testbed/nanogui/ext/eigen/bench/btl/actions/basic_actions.hh @@ -6,7 +6,7 @@ #include "action_atv_product.hh" #include "action_matrix_matrix_product.hh" -// #include "action_ata_product.hh" +#include "action_ata_product.hh" #include "action_aat_product.hh" #include "action_trisolve.hh" diff --git a/testbed/nanogui/ext/eigen/bench/btl/cmake/FindACML.cmake b/testbed/nanogui/ext/eigen/bench/btl/cmake/FindACML.cmake index f45ae1b0..4989fa2f 100644 --- a/testbed/nanogui/ext/eigen/bench/btl/cmake/FindACML.cmake +++ b/testbed/nanogui/ext/eigen/bench/btl/cmake/FindACML.cmake @@ -17,6 +17,7 @@ find_file(ACML_LIBRARIES libacml_mp.so PATHS /usr/lib + /usr/lib64 $ENV{ACMLDIR}/lib ${LIB_INSTALL_DIR} ) @@ -35,6 +36,7 @@ if(NOT ACML_LIBRARIES) libacml.so libacml_mv.so PATHS /usr/lib + /usr/lib64 $ENV{ACMLDIR}/lib ${LIB_INSTALL_DIR} ) diff --git a/testbed/nanogui/ext/eigen/bench/btl/cmake/FindATLAS.cmake b/testbed/nanogui/ext/eigen/bench/btl/cmake/FindATLAS.cmake index 6b906520..4136a989 100644 --- a/testbed/nanogui/ext/eigen/bench/btl/cmake/FindATLAS.cmake +++ b/testbed/nanogui/ext/eigen/bench/btl/cmake/FindATLAS.cmake @@ -3,33 +3,25 @@ if (ATLAS_LIBRARIES) set(ATLAS_FIND_QUIETLY TRUE) endif (ATLAS_LIBRARIES) -find_file(ATLAS_LIB libatlas.so.3 PATHS /usr/lib $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) -find_library(ATLAS_LIB atlas PATHS $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) +find_file(ATLAS_LIB libatlas.so.3 PATHS /usr/lib /usr/lib/atlas /usr/lib64 /usr/lib64/atlas $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) +find_library(ATLAS_LIB satlas PATHS $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) -find_file(ATLAS_CBLAS libcblas.so.3 PATHS /usr/lib $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) -find_library(ATLAS_CBLAS cblas PATHS $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) +find_file(ATLAS_LAPACK NAMES liblapack_atlas.so.3 liblapack.so.3 PATHS /usr/lib /usr/lib/atlas /usr/lib64 /usr/lib64/atlas $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) +find_library(ATLAS_LAPACK NAMES lapack_atlas lapack PATHS $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) -find_file(ATLAS_LAPACK liblapack_atlas.so.3 PATHS /usr/lib $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) -find_library(ATLAS_LAPACK lapack_atlas PATHS $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) - -if(NOT ATLAS_LAPACK) - find_file(ATLAS_LAPACK liblapack.so.3 PATHS /usr/lib/atlas $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) - find_library(ATLAS_LAPACK lapack PATHS $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) -endif(NOT ATLAS_LAPACK) - -find_file(ATLAS_F77BLAS libf77blas.so.3 PATHS /usr/lib $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) +find_file(ATLAS_F77BLAS libf77blas.so.3 PATHS /usr/lib /usr/lib/atlas /usr/lib64 /usr/lib64/atlas $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) find_library(ATLAS_F77BLAS f77blas PATHS $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) if(ATLAS_LIB AND ATLAS_CBLAS AND ATLAS_LAPACK AND ATLAS_F77BLAS) - set(ATLAS_LIBRARIES ${ATLAS_LAPACK} ${ATLAS_CBLAS} ${ATLAS_F77BLAS} ${ATLAS_LIB}) + set(ATLAS_LIBRARIES ${ATLAS_LAPACK} ${ATLAS_LIB}) # search the default lapack lib link to it find_file(ATLAS_REFERENCE_LAPACK liblapack.so.3 PATHS /usr/lib /usr/lib64) find_library(ATLAS_REFERENCE_LAPACK NAMES lapack) - if(ATLAS_REFERENCE_LAPACK) - set(ATLAS_LIBRARIES ${ATLAS_LIBRARIES} ${ATLAS_REFERENCE_LAPACK}) - endif() +# if(ATLAS_REFERENCE_LAPACK) +# set(ATLAS_LIBRARIES ${ATLAS_LIBRARIES} ${ATLAS_REFERENCE_LAPACK}) +# endif() endif(ATLAS_LIB AND ATLAS_CBLAS AND ATLAS_LAPACK AND ATLAS_F77BLAS) diff --git a/testbed/nanogui/ext/eigen/bench/btl/cmake/FindBLAZE.cmake b/testbed/nanogui/ext/eigen/bench/btl/cmake/FindBLAZE.cmake new file mode 100644 index 00000000..dba4c89f --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/btl/cmake/FindBLAZE.cmake @@ -0,0 +1,31 @@ +# - Try to find eigen2 headers +# Once done this will define +# +# BLAZE_FOUND - system has blaze lib +# BLAZE_INCLUDE_DIR - the blaze include directory +# +# Copyright (C) 2008 Gael Guennebaud +# Adapted from FindEigen.cmake: +# Copyright (c) 2006, 2007 Montel Laurent, +# Redistribution and use is allowed according to the terms of the BSD license. +# For details see the accompanying COPYING-CMAKE-SCRIPTS file. + +if (BLAZE_INCLUDE_DIR) + + # in cache already + set(BLAZE_FOUND TRUE) + +else (BLAZE_INCLUDE_DIR) + +find_path(BLAZE_INCLUDE_DIR NAMES blaze/Blaze.h + PATHS + ${INCLUDE_INSTALL_DIR} + ) + +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(BLAZE DEFAULT_MSG BLAZE_INCLUDE_DIR) + +mark_as_advanced(BLAZE_INCLUDE_DIR) + +endif(BLAZE_INCLUDE_DIR) + diff --git a/testbed/nanogui/ext/eigen/bench/btl/cmake/FindCBLAS.cmake b/testbed/nanogui/ext/eigen/bench/btl/cmake/FindCBLAS.cmake index 554f0291..ce0f2f2b 100644 --- a/testbed/nanogui/ext/eigen/bench/btl/cmake/FindCBLAS.cmake +++ b/testbed/nanogui/ext/eigen/bench/btl/cmake/FindCBLAS.cmake @@ -23,6 +23,7 @@ find_file(CBLAS_LIBRARIES libcblas.so.3 PATHS /usr/lib + /usr/lib64 $ENV{CBLASDIR}/lib ${LIB_INSTALL_DIR} ) diff --git a/testbed/nanogui/ext/eigen/bench/btl/cmake/FindGOTO.cmake b/testbed/nanogui/ext/eigen/bench/btl/cmake/FindGOTO.cmake deleted file mode 100644 index 67ea0934..00000000 --- a/testbed/nanogui/ext/eigen/bench/btl/cmake/FindGOTO.cmake +++ /dev/null @@ -1,15 +0,0 @@ - -if (GOTO_LIBRARIES) - set(GOTO_FIND_QUIETLY TRUE) -endif (GOTO_LIBRARIES) - -find_library(GOTO_LIBRARIES goto PATHS $ENV{GOTODIR} ${LIB_INSTALL_DIR}) - -if(GOTO_LIBRARIES AND CMAKE_COMPILER_IS_GNUCXX) - set(GOTO_LIBRARIES ${GOTO_LIBRARIES} "-lpthread -lgfortran") -endif() - -include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(GOTO DEFAULT_MSG GOTO_LIBRARIES) - -mark_as_advanced(GOTO_LIBRARIES) diff --git a/testbed/nanogui/ext/eigen/bench/btl/cmake/FindGOTO2.cmake b/testbed/nanogui/ext/eigen/bench/btl/cmake/FindGOTO2.cmake deleted file mode 100644 index baa68d21..00000000 --- a/testbed/nanogui/ext/eigen/bench/btl/cmake/FindGOTO2.cmake +++ /dev/null @@ -1,25 +0,0 @@ - -if (GOTO2_LIBRARIES) - set(GOTO2_FIND_QUIETLY TRUE) -endif (GOTO2_LIBRARIES) -# -# find_path(GOTO_INCLUDES -# NAMES -# cblas.h -# PATHS -# $ENV{GOTODIR}/include -# ${INCLUDE_INSTALL_DIR} -# ) - -find_file(GOTO2_LIBRARIES libgoto2.so PATHS /usr/lib $ENV{GOTO2DIR} ${LIB_INSTALL_DIR}) -find_library(GOTO2_LIBRARIES goto2 PATHS $ENV{GOTO2DIR} ${LIB_INSTALL_DIR}) - -if(GOTO2_LIBRARIES AND CMAKE_COMPILER_IS_GNUCXX) - set(GOTO2_LIBRARIES ${GOTO2_LIBRARIES} "-lpthread -lgfortran") -endif() - -include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(GOTO2 DEFAULT_MSG - GOTO2_LIBRARIES) - -mark_as_advanced(GOTO2_LIBRARIES) diff --git a/testbed/nanogui/ext/eigen/bench/btl/cmake/FindOPENBLAS.cmake b/testbed/nanogui/ext/eigen/bench/btl/cmake/FindOPENBLAS.cmake new file mode 100644 index 00000000..2a091943 --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/btl/cmake/FindOPENBLAS.cmake @@ -0,0 +1,17 @@ + +if (OPENBLAS_LIBRARIES) + set(OPENBLAS_FIND_QUIETLY TRUE) +endif (OPENBLAS_LIBRARIES) + +find_file(OPENBLAS_LIBRARIES NAMES libopenblas.so libopenblas.so.0 PATHS /usr/lib /usr/lib64 $ENV{OPENBLASDIR} ${LIB_INSTALL_DIR}) +find_library(OPENBLAS_LIBRARIES openblas PATHS $ENV{OPENBLASDIR} ${LIB_INSTALL_DIR}) + +if(OPENBLAS_LIBRARIES AND CMAKE_COMPILER_IS_GNUCXX) + set(OPENBLAS_LIBRARIES ${OPENBLAS_LIBRARIES} "-lpthread -lgfortran") +endif() + +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(OPENBLAS DEFAULT_MSG + OPENBLAS_LIBRARIES) + +mark_as_advanced(OPENBLAS_LIBRARIES) diff --git a/testbed/nanogui/ext/eigen/bench/btl/data/action_settings.txt b/testbed/nanogui/ext/eigen/bench/btl/data/action_settings.txt index e32213e2..39d2b5dc 100644 --- a/testbed/nanogui/ext/eigen/bench/btl/data/action_settings.txt +++ b/testbed/nanogui/ext/eigen/bench/btl/data/action_settings.txt @@ -1,19 +1,19 @@ -aat ; "{/*1.5 A x A^T}" ; "matrix size" ; 4:3000 -ata ; "{/*1.5 A^T x A}" ; "matrix size" ; 4:3000 -atv ; "{/*1.5 matrix^T x vector}" ; "matrix size" ; 4:3000 +aat ; "{/*1.5 A x A^T}" ; "matrix size" ; 4:5000 +ata ; "{/*1.5 A^T x A}" ; "matrix size" ; 4:5000 +atv ; "{/*1.5 matrix^T x vector}" ; "matrix size" ; 4:5000 axpby ; "{/*1.5 Y = alpha X + beta Y}" ; "vector size" ; 5:1000000 axpy ; "{/*1.5 Y += alpha X}" ; "vector size" ; 5:1000000 -matrix_matrix ; "{/*1.5 matrix matrix product}" ; "matrix size" ; 4:3000 -matrix_vector ; "{/*1.5 matrix vector product}" ; "matrix size" ; 4:3000 -trmm ; "{/*1.5 triangular matrix matrix product}" ; "matrix size" ; 4:3000 -trisolve_vector ; "{/*1.5 triangular solver - vector (X = inv(L) X)}" ; "size" ; 4:3000 -trisolve_matrix ; "{/*1.5 triangular solver - matrix (M = inv(L) M)}" ; "size" ; 4:3000 -cholesky ; "{/*1.5 Cholesky decomposition}" ; "matrix size" ; 4:3000 -complete_lu_decomp ; "{/*1.5 Complete LU decomposition}" ; "matrix size" ; 4:3000 -partial_lu_decomp ; "{/*1.5 Partial LU decomposition}" ; "matrix size" ; 4:3000 -tridiagonalization ; "{/*1.5 Tridiagonalization}" ; "matrix size" ; 4:3000 -hessenberg ; "{/*1.5 Hessenberg decomposition}" ; "matrix size" ; 4:3000 -symv ; "{/*1.5 symmetric matrix vector product}" ; "matrix size" ; 4:3000 -syr2 ; "{/*1.5 symmretric rank-2 update (A += u^T v + u v^T)}" ; "matrix size" ; 4:3000 -ger ; "{/*1.5 general rank-1 update (A += u v^T)}" ; "matrix size" ; 4:3000 -rot ; "{/*1.5 apply rotation in the plane}" ; "vector size" ; 4:1000000 \ No newline at end of file +matrix_matrix ; "{/*1.5 matrix matrix product}" ; "matrix size" ; 4:5000 +matrix_vector ; "{/*1.5 matrix vector product}" ; "matrix size" ; 4:5000 +trmm ; "{/*1.5 triangular matrix matrix product}" ; "matrix size" ; 4:5000 +trisolve_vector ; "{/*1.5 triangular solver - vector (X = inv(L) X)}" ; "size" ; 4:5000 +trisolve_matrix ; "{/*1.5 triangular solver - matrix (M = inv(L) M)}" ; "size" ; 4:5000 +cholesky ; "{/*1.5 Cholesky decomposition}" ; "matrix size" ; 4:5000 +complete_lu_decomp ; "{/*1.5 Complete LU decomposition}" ; "matrix size" ; 4:5000 +partial_lu_decomp ; "{/*1.5 Partial LU decomposition}" ; "matrix size" ; 4:5000 +tridiagonalization ; "{/*1.5 Tridiagonalization}" ; "matrix size" ; 4:5000 +hessenberg ; "{/*1.5 Hessenberg decomposition}" ; "matrix size" ; 4:5000 +symv ; "{/*1.5 symmetric matrix vector product}" ; "matrix size" ; 4:5000 +syr2 ; "{/*1.5 symmretric rank-2 update (A += u^T v + u v^T)}" ; "matrix size" ; 4:5000 +ger ; "{/*1.5 general rank-1 update (A += u v^T)}" ; "matrix size" ; 4:5000 +rot ; "{/*1.5 apply rotation in the plane}" ; "vector size" ; 4:1000000 diff --git a/testbed/nanogui/ext/eigen/bench/btl/data/perlib_plot_settings.txt b/testbed/nanogui/ext/eigen/bench/btl/data/perlib_plot_settings.txt index 6844bab2..f023cfe0 100644 --- a/testbed/nanogui/ext/eigen/bench/btl/data/perlib_plot_settings.txt +++ b/testbed/nanogui/ext/eigen/bench/btl/data/perlib_plot_settings.txt @@ -10,7 +10,7 @@ ublas ; with lines lw 3 lt 1 lc rgbcolor "#00b7ff" mtl4 ; with lines lw 3 lt 1 lc rgbcolor "#d18847" blitz ; with lines lw 3 lt 1 lc rgbcolor "#ff00ff" F77 ; with lines lw 3 lt 3 lc rgbcolor "#e6e64c" -GOTO ; with lines lw 3 lt 3 lc rgbcolor "#C05600" -GOTO2 ; with lines lw 3 lt 1 lc rgbcolor "#C05600" +OPENBLAS ; with lines lw 3 lt 1 lc rgbcolor "#C05600" C ; with lines lw 3 lt 3 lc rgbcolor "#e6bd96" ACML ; with lines lw 2 lt 3 lc rgbcolor "#e6e64c" +blaze ; with lines lw 3 lt 1 lc rgbcolor "#ff00ff" diff --git a/testbed/nanogui/ext/eigen/bench/btl/generic_bench/bench.hh b/testbed/nanogui/ext/eigen/bench/btl/generic_bench/bench.hh index 005c3639..7b7b951b 100644 --- a/testbed/nanogui/ext/eigen/bench/btl/generic_bench/bench.hh +++ b/testbed/nanogui/ext/eigen/bench/btl/generic_bench/bench.hh @@ -102,8 +102,8 @@ BTL_DONT_INLINE void bench( int size_min, int size_max, int nb_point ) // merge the two data std::vector newSizes; std::vector newFlops; - int i=0; - int j=0; + unsigned int i=0; + unsigned int j=0; while (i config = BtlString(_config).split(" \t\n"); - for (int i = 0; i BTL_DONT_INLINE void init_matrix(Vector & A, int size){ A.resize(size); - for (int row=0; row(A[row],size,row); } } @@ -50,11 +50,11 @@ BTL_DONT_INLINE void init_matrix(Vector & A, int size){ template BTL_DONT_INLINE void init_matrix_symm(Matrix& A, int size){ A.resize(size); - for (int row=0; row @@ -87,6 +87,48 @@ }; // Portable_Timer +#elif defined(__APPLE__) +#include +#include + + +class Portable_Timer +{ + public: + + Portable_Timer() + { + } + + void start() + { + m_start_time = double(mach_absolute_time())*1e-9;; + + } + + void stop() + { + m_stop_time = double(mach_absolute_time())*1e-9;; + + } + + double elapsed() + { + return user_time(); + } + + double user_time() + { + return m_stop_time - m_start_time; + } + + +private: + + double m_stop_time, m_start_time; + +}; // Portable_Timer (Apple) + #else #include @@ -138,7 +180,7 @@ private: int m_clkid; double m_stop_time, m_start_time; -}; // Portable_Timer +}; // Portable_Timer (Linux) #endif diff --git a/testbed/nanogui/ext/eigen/bench/btl/generic_bench/utils/size_lin_log.hh b/testbed/nanogui/ext/eigen/bench/btl/generic_bench/utils/size_lin_log.hh index bca3932a..bbc9f543 100644 --- a/testbed/nanogui/ext/eigen/bench/btl/generic_bench/utils/size_lin_log.hh +++ b/testbed/nanogui/ext/eigen/bench/btl/generic_bench/utils/size_lin_log.hh @@ -23,7 +23,7 @@ #include "size_log.hh" template -void size_lin_log(const int nb_point, const int size_min, const int size_max, Vector & X) +void size_lin_log(const int nb_point, const int /*size_min*/, const int size_max, Vector & X) { int ten=10; int nine=9; diff --git a/testbed/nanogui/ext/eigen/bench/btl/libs/BLAS/CMakeLists.txt b/testbed/nanogui/ext/eigen/bench/btl/libs/BLAS/CMakeLists.txt index de42fe04..0272ccad 100644 --- a/testbed/nanogui/ext/eigen/bench/btl/libs/BLAS/CMakeLists.txt +++ b/testbed/nanogui/ext/eigen/bench/btl/libs/BLAS/CMakeLists.txt @@ -18,27 +18,14 @@ if (MKL_FOUND) endif (MKL_FOUND) -find_package(GOTO2) -if (GOTO2_FOUND) - btl_add_bench(btl_goto2 main.cpp) - if(BUILD_btl_goto2) - target_link_libraries(btl_goto2 ${GOTO_LIBRARIES} ) - set_target_properties(btl_goto2 PROPERTIES COMPILE_FLAGS "-DCBLASNAME=GOTO2") - endif(BUILD_btl_goto2) -endif (GOTO2_FOUND) - -find_package(GOTO) -if (GOTO_FOUND) - if(GOTO2_FOUND) - btl_add_bench(btl_goto main.cpp OFF) - else() - btl_add_bench(btl_goto main.cpp) - endif() - if(BUILD_btl_goto) - target_link_libraries(btl_goto ${GOTO_LIBRARIES} ) - set_target_properties(btl_goto PROPERTIES COMPILE_FLAGS "-DCBLASNAME=GOTO") - endif(BUILD_btl_goto) -endif (GOTO_FOUND) +find_package(OPENBLAS) +if (OPENBLAS_FOUND) + btl_add_bench(btl_openblas main.cpp) + if(BUILD_btl_openblas) + target_link_libraries(btl_openblas ${OPENBLAS_LIBRARIES} ) + set_target_properties(btl_openblas PROPERTIES COMPILE_FLAGS "-DCBLASNAME=OPENBLAS") + endif(BUILD_btl_openblas) +endif (OPENBLAS_FOUND) find_package(ACML) if (ACML_FOUND) diff --git a/testbed/nanogui/ext/eigen/bench/btl/libs/BLAS/blas_interface_impl.hh b/testbed/nanogui/ext/eigen/bench/btl/libs/BLAS/blas_interface_impl.hh index 0e84df03..9e0a6490 100644 --- a/testbed/nanogui/ext/eigen/bench/btl/libs/BLAS/blas_interface_impl.hh +++ b/testbed/nanogui/ext/eigen/bench/btl/libs/BLAS/blas_interface_impl.hh @@ -46,9 +46,9 @@ public : BLAS_FUNC(gemm)(¬rans,¬rans,&N,&N,&N,&fone,A,&N,B,&N,&fzero,X,&N); } -// static inline void ata_product(gene_matrix & A, gene_matrix & X, int N){ -// ssyrk_(&lower,&trans,&N,&N,&fone,A,&N,&fzero,X,&N); -// } + static inline void ata_product(gene_matrix & A, gene_matrix & X, int N){ + BLAS_FUNC(syrk)(&lower,&trans,&N,&N,&fone,A,&N,&fzero,X,&N); + } static inline void aat_product(gene_matrix & A, gene_matrix & X, int N){ BLAS_FUNC(syrk)(&lower,¬rans,&N,&N,&fone,A,&N,&fzero,X,&N); @@ -75,7 +75,6 @@ public : static inline void partial_lu_decomp(const gene_matrix & X, gene_matrix & C, int N){ int N2 = N*N; BLAS_FUNC(copy)(&N2, X, &intone, C, &intone); - char uplo = 'L'; int info = 0; int * ipiv = (int*)alloca(sizeof(int)*N); BLAS_FUNC(getrf)(&N, &N, C, &N, ipiv, &info); @@ -92,7 +91,7 @@ public : BLAS_FUNC(trsm)(&right, &lower, ¬rans, &nonunit, &N, &N, &fone, L, &N, X, &N); } - static inline void trmm(gene_matrix & A, gene_matrix & B, gene_matrix & X, int N){ + static inline void trmm(gene_matrix & A, gene_matrix & B, gene_matrix & /*X*/, int N){ BLAS_FUNC(trmm)(&left, &lower, ¬rans,&nonunit, &N,&N,&fone,A,&N,B,&N); } @@ -101,7 +100,6 @@ public : static inline void lu_decomp(const gene_matrix & X, gene_matrix & C, int N){ int N2 = N*N; BLAS_FUNC(copy)(&N2, X, &intone, C, &intone); - char uplo = 'L'; int info = 0; int * ipiv = (int*)alloca(sizeof(int)*N); int * jpiv = (int*)alloca(sizeof(int)*N); @@ -134,8 +132,6 @@ public : } char uplo = 'U'; int info = 0; - int ilo = 1; - int ihi = N; int bsize = 64; int worksize = N*bsize; SCALAR* d = new SCALAR[3*N+worksize]; diff --git a/testbed/nanogui/ext/eigen/bench/btl/libs/BLAS/c_interface_base.h b/testbed/nanogui/ext/eigen/bench/btl/libs/BLAS/c_interface_base.h index 515d8dcf..de613803 100644 --- a/testbed/nanogui/ext/eigen/bench/btl/libs/BLAS/c_interface_base.h +++ b/testbed/nanogui/ext/eigen/bench/btl/libs/BLAS/c_interface_base.h @@ -17,12 +17,12 @@ public: typedef real* gene_matrix; typedef real* gene_vector; - static void free_matrix(gene_matrix & A, int N){ - delete A; + static void free_matrix(gene_matrix & A, int /*N*/){ + delete[] A; } static void free_vector(gene_vector & B){ - delete B; + delete[] B; } static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){ diff --git a/testbed/nanogui/ext/eigen/bench/btl/libs/BLAS/main.cpp b/testbed/nanogui/ext/eigen/bench/btl/libs/BLAS/main.cpp index 8347c9f0..fd991490 100644 --- a/testbed/nanogui/ext/eigen/bench/btl/libs/BLAS/main.cpp +++ b/testbed/nanogui/ext/eigen/bench/btl/libs/BLAS/main.cpp @@ -48,7 +48,7 @@ int main() bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); bench > >(MIN_MM,MAX_MM,NB_POINT); -// bench > >(MIN_MM,MAX_MM,NB_POINT); + bench > >(MIN_MM,MAX_MM,NB_POINT); bench > >(MIN_MM,MAX_MM,NB_POINT); bench > >(MIN_MM,MAX_MM,NB_POINT); @@ -56,13 +56,13 @@ int main() bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); + bench > >(MIN_LU,MAX_LU,NB_POINT); + bench > >(MIN_LU,MAX_LU,NB_POINT); #ifdef HAS_LAPACK - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); +// bench > >(MIN_LU,MAX_LU,NB_POINT); + bench > >(MIN_LU,MAX_LU,NB_POINT); + bench > >(MIN_LU,MAX_LU,NB_POINT); #endif //bench > >(MIN_LU,MAX_LU,NB_POINT); diff --git a/testbed/nanogui/ext/eigen/bench/btl/libs/STL/STL_interface.hh b/testbed/nanogui/ext/eigen/bench/btl/libs/STL/STL_interface.hh index 93e76bd5..16658c4b 100644 --- a/testbed/nanogui/ext/eigen/bench/btl/libs/STL/STL_interface.hh +++ b/testbed/nanogui/ext/eigen/bench/btl/libs/STL/STL_interface.hh @@ -44,9 +44,9 @@ public : return "STL"; } - static void free_matrix(gene_matrix & A, int N){} + static void free_matrix(gene_matrix & /*A*/, int /*N*/){} - static void free_vector(gene_vector & B){} + static void free_vector(gene_vector & /*B*/){} static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){ A = A_stl; @@ -78,18 +78,18 @@ public : cible[i][j]=source[i][j]; } -// static inline void ata_product(const gene_matrix & A, gene_matrix & X, int N) -// { -// real somme; -// for (int j=0;j +//===================================================== +// +// This program is free software; you can redistribute it and/or +// modify it under the terms of the GNU General Public License +// as published by the Free Software Foundation; either version 2 +// of the License, or (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// You should have received a copy of the GNU General Public License +// along with this program; if not, write to the Free Software +// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. +// +#ifndef BLAZE_INTERFACE_HH +#define BLAZE_INTERFACE_HH + +#include +#include +#include +// using namespace blaze; + +#include + +template +class blaze_interface { + +public : + + typedef real real_type ; + + typedef std::vector stl_vector; + typedef std::vector stl_matrix; + + typedef blaze::DynamicMatrix gene_matrix; + typedef blaze::DynamicVector gene_vector; + + static inline std::string name() { return "blaze"; } + + static void free_matrix(gene_matrix & A, int N){ + return ; + } + + static void free_vector(gene_vector & B){ + return ; + } + + static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){ + A.resize(A_stl[0].size(), A_stl.size()); + + for (int j=0; j ipvt(N); +// lu_factor(R, ipvt); +// } + +// static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector & X, int N){ +// X = lower_trisolve(L, B); +// } + + static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){ + cible = source; + } + + static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){ + cible = source; + } + +}; + +#endif diff --git a/testbed/nanogui/ext/eigen/bench/btl/libs/blaze/main.cpp b/testbed/nanogui/ext/eigen/bench/btl/libs/blaze/main.cpp new file mode 100644 index 00000000..ccae0cbd --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/btl/libs/blaze/main.cpp @@ -0,0 +1,40 @@ +//===================================================== +// Copyright (C) 2008 Gael Guennebaud +//===================================================== +// +// This program is free software; you can redistribute it and/or +// modify it under the terms of the GNU General Public License +// as published by the Free Software Foundation; either version 2 +// of the License, or (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// You should have received a copy of the GNU General Public License +// along with this program; if not, write to the Free Software +// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. +// +#include "utilities.h" +#include "blaze_interface.hh" +#include "bench.hh" +#include "basic_actions.hh" + +BTL_MAIN; + +int main() +{ + + bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); + bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); + + bench > >(MIN_MV,MAX_MV,NB_POINT); + bench > >(MIN_MV,MAX_MV,NB_POINT); + bench > >(MIN_MM,MAX_MM,NB_POINT); + bench > >(MIN_MM,MAX_MM,NB_POINT); + bench > >(MIN_MM,MAX_MM,NB_POINT); + + return 0; +} + + diff --git a/testbed/nanogui/ext/eigen/bench/btl/libs/eigen2/eigen2_interface.hh b/testbed/nanogui/ext/eigen/bench/btl/libs/eigen2/eigen2_interface.hh index 47fe5813..1deabdae 100644 --- a/testbed/nanogui/ext/eigen/bench/btl/libs/eigen2/eigen2_interface.hh +++ b/testbed/nanogui/ext/eigen/bench/btl/libs/eigen2/eigen2_interface.hh @@ -47,7 +47,7 @@ public : { #if defined(EIGEN_VECTORIZE_SSE) if (SIZE==Dynamic) return "eigen2"; else return "tiny_eigen2"; - #elif defined(EIGEN_VECTORIZE_ALTIVEC) + #elif defined(EIGEN_VECTORIZE_ALTIVEC) || defined(EIGEN_VECTORIZE_VSX) if (SIZE==Dynamic) return "eigen2"; else return "tiny_eigen2"; #else if (SIZE==Dynamic) return "eigen2_novec"; else return "tiny_eigen2_novec"; diff --git a/testbed/nanogui/ext/eigen/bench/btl/libs/eigen3/eigen3_interface.hh b/testbed/nanogui/ext/eigen/bench/btl/libs/eigen3/eigen3_interface.hh index 31bcc1f9..2e302d07 100644 --- a/testbed/nanogui/ext/eigen/bench/btl/libs/eigen3/eigen3_interface.hh +++ b/testbed/nanogui/ext/eigen/bench/btl/libs/eigen3/eigen3_interface.hh @@ -45,15 +45,15 @@ public : return EIGEN_MAKESTRING(BTL_PREFIX); } - static void free_matrix(gene_matrix & A, int N) {} + static void free_matrix(gene_matrix & /*A*/, int /*N*/) {} - static void free_vector(gene_vector & B) {} + static void free_vector(gene_vector & /*B*/) {} static BTL_DONT_INLINE void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){ A.resize(A_stl[0].size(), A_stl.size()); - for (int j=0; j().setZero(); + X.template selfadjointView().rankUpdate(A.transpose()); + } - static inline void aat_product(const gene_matrix & A, gene_matrix & X, int N){ + static inline void aat_product(const gene_matrix & A, gene_matrix & X, int /*N*/){ X.template triangularView().setZero(); X.template selfadjointView().rankUpdate(A); } - static inline void matrix_vector_product(const gene_matrix & A, const gene_vector & B, gene_vector & X, int N){ + static inline void matrix_vector_product(const gene_matrix & A, const gene_vector & B, gene_vector & X, int /*N*/){ X.noalias() = A*B; } - static inline void symv(const gene_matrix & A, const gene_vector & B, gene_vector & X, int N){ + static inline void symv(const gene_matrix & A, const gene_vector & B, gene_vector & X, int /*N*/){ X.noalias() = (A.template selfadjointView() * B); // internal::product_selfadjoint_vector(N,A.data(),N, B.data(), 1, X.data(), 1); } @@ -155,54 +157,54 @@ public : } } - static EIGEN_DONT_INLINE void syr2(gene_matrix & A, gene_vector & X, gene_vector & Y, int N){ + static EIGEN_DONT_INLINE void syr2(gene_matrix & A, gene_vector & X, gene_vector & Y, int N){ // internal::product_selfadjoint_rank2_update(N,A.data(),N, X.data(), 1, Y.data(), 1, -1); for(int j=0; j(c,s)); } - static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){ + static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int /*N*/){ X.noalias() = (A.transpose()*B); } - static inline void axpy(real coef, const gene_vector & X, gene_vector & Y, int N){ + static inline void axpy(real coef, const gene_vector & X, gene_vector & Y, int /*N*/){ Y += coef * X; } - static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int N){ + static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int /*N*/){ Y = a*X + b*Y; } - static EIGEN_DONT_INLINE void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){ + static EIGEN_DONT_INLINE void copy_matrix(const gene_matrix & source, gene_matrix & cible, int /*N*/){ cible = source; } - static EIGEN_DONT_INLINE void copy_vector(const gene_vector & source, gene_vector & cible, int N){ + static EIGEN_DONT_INLINE void copy_vector(const gene_vector & source, gene_vector & cible, int /*N*/){ cible = source; } - static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector& X, int N){ + static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector& X, int /*N*/){ X = L.template triangularView().solve(B); } - static inline void trisolve_lower_matrix(const gene_matrix & L, const gene_matrix& B, gene_matrix& X, int N){ + static inline void trisolve_lower_matrix(const gene_matrix & L, const gene_matrix& B, gene_matrix& X, int /*N*/){ X = L.template triangularView().solve(B); } - static inline void trmm(const gene_matrix & L, const gene_matrix& B, gene_matrix& X, int N){ + static inline void trmm(const gene_matrix & L, const gene_matrix& B, gene_matrix& X, int /*N*/){ X.noalias() = L.template triangularView() * B; } - static inline void cholesky(const gene_matrix & X, gene_matrix & C, int N){ + static inline void cholesky(const gene_matrix & X, gene_matrix & C, int /*N*/){ C = X; internal::llt_inplace::blocked(C); //C = X.llt().matrixL(); @@ -211,11 +213,11 @@ public : // Cholesky::computeInPlaceBlock(C); } - static inline void lu_decomp(const gene_matrix & X, gene_matrix & C, int N){ + static inline void lu_decomp(const gene_matrix & X, gene_matrix & C, int /*N*/){ C = X.fullPivLu().matrixLU(); } - static inline void partial_lu_decomp(const gene_matrix & X, gene_matrix & C, int N){ + static inline void partial_lu_decomp(const gene_matrix & X, gene_matrix & C, int N){ Matrix piv(N); DenseIndex nb; C = X; @@ -223,13 +225,13 @@ public : // C = X.partialPivLu().matrixLU(); } - static inline void tridiagonalization(const gene_matrix & X, gene_matrix & C, int N){ + static inline void tridiagonalization(const gene_matrix & X, gene_matrix & C, int N){ typename Tridiagonalization::CoeffVectorType aux(N-1); C = X; internal::tridiagonalization_inplace(C, aux); } - static inline void hessenberg(const gene_matrix & X, gene_matrix & C, int N){ + static inline void hessenberg(const gene_matrix & X, gene_matrix & C, int /*N*/){ C = HessenbergDecomposition(X).packedMatrix(); } diff --git a/testbed/nanogui/ext/eigen/bench/btl/libs/eigen3/main_adv.cpp b/testbed/nanogui/ext/eigen/bench/btl/libs/eigen3/main_adv.cpp index efe5857e..95865357 100644 --- a/testbed/nanogui/ext/eigen/bench/btl/libs/eigen3/main_adv.cpp +++ b/testbed/nanogui/ext/eigen/bench/btl/libs/eigen3/main_adv.cpp @@ -29,14 +29,14 @@ BTL_MAIN; int main() { - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); + bench > >(MIN_LU,MAX_LU,NB_POINT); + bench > >(MIN_LU,MAX_LU,NB_POINT); + bench > >(MIN_LU,MAX_LU,NB_POINT); +// bench > >(MIN_LU,MAX_LU,NB_POINT); + bench > >(MIN_LU,MAX_LU,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); +// bench > >(MIN_LU,MAX_LU,NB_POINT); + bench > >(MIN_LU,MAX_LU,NB_POINT); return 0; } diff --git a/testbed/nanogui/ext/eigen/bench/btl/libs/eigen3/main_matmat.cpp b/testbed/nanogui/ext/eigen/bench/btl/libs/eigen3/main_matmat.cpp index 926fa2b0..052810a1 100644 --- a/testbed/nanogui/ext/eigen/bench/btl/libs/eigen3/main_matmat.cpp +++ b/testbed/nanogui/ext/eigen/bench/btl/libs/eigen3/main_matmat.cpp @@ -25,7 +25,7 @@ BTL_MAIN; int main() { bench > >(MIN_MM,MAX_MM,NB_POINT); -// bench > >(MIN_MM,MAX_MM,NB_POINT); + bench > >(MIN_MM,MAX_MM,NB_POINT); bench > >(MIN_MM,MAX_MM,NB_POINT); bench > >(MIN_MM,MAX_MM,NB_POINT); diff --git a/testbed/nanogui/ext/eigen/bench/btl/libs/tensors/CMakeLists.txt b/testbed/nanogui/ext/eigen/bench/btl/libs/tensors/CMakeLists.txt new file mode 100644 index 00000000..09d6d8e4 --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/btl/libs/tensors/CMakeLists.txt @@ -0,0 +1,44 @@ + + +if((NOT TENSOR_INCLUDE_DIR) AND Eigen_SOURCE_DIR) + # unless TENSOR_INCLUDE_DIR is defined, let's use current Eigen version + set(TENSOR_INCLUDE_DIR ${Eigen_SOURCE_DIR}) + set(TENSOR_FOUND TRUE) +else() + find_package(Tensor) +endif() + +if (TENSOR_FOUND) + + include_directories(${TENSOR_INCLUDE_DIR}) + btl_add_bench(btl_tensor_linear main_linear.cpp) + btl_add_bench(btl_tensor_vecmat main_vecmat.cpp) + btl_add_bench(btl_tensor_matmat main_matmat.cpp) + + btl_add_target_property(btl_tensor_linear COMPILE_FLAGS "-fno-exceptions -DBTL_PREFIX=tensor") + btl_add_target_property(btl_tensor_vecmat COMPILE_FLAGS "-fno-exceptions -DBTL_PREFIX=tensor") + btl_add_target_property(btl_tensor_matmat COMPILE_FLAGS "-fno-exceptions -DBTL_PREFIX=tensor") + + option(BTL_BENCH_NOGCCVEC "also bench Eigen explicit vec without GCC's auto vec" OFF) + if(CMAKE_COMPILER_IS_GNUCXX AND BTL_BENCH_NOGCCVEC) + btl_add_bench(btl_tensor_nogccvec_linear main_linear.cpp) + btl_add_bench(btl_tensor_nogccvec_vecmat main_vecmat.cpp) + btl_add_bench(btl_tensor_nogccvec_matmat main_matmat.cpp) + + btl_add_target_property(btl_tensor_nogccvec_linear COMPILE_FLAGS "-fno-exceptions -fno-tree-vectorize -DBTL_PREFIX=tensor_nogccvec") + btl_add_target_property(btl_tensor_nogccvec_vecmat COMPILE_FLAGS "-fno-exceptions -fno-tree-vectorize -DBTL_PREFIX=tensor_nogccvec") + btl_add_target_property(btl_tensor_nogccvec_matmat COMPILE_FLAGS "-fno-exceptions -fno-tree-vectorize -DBTL_PREFIX=tensor_nogccvec") + endif() + + + if(NOT BTL_NOVEC) + btl_add_bench(btl_tensor_novec_linear main_linear.cpp OFF) + btl_add_bench(btl_tensor_novec_vecmat main_vecmat.cpp OFF) + btl_add_bench(btl_tensor_novec_matmat main_matmat.cpp OFF) + btl_add_target_property(btl_tensor_novec_linear COMPILE_FLAGS "-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=tensor_novec") + btl_add_target_property(btl_tensor_novec_vecmat COMPILE_FLAGS "-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=tensor_novec") + btl_add_target_property(btl_tensor_novec_matmat COMPILE_FLAGS "-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=tensor_novec") + + endif(NOT BTL_NOVEC) + +endif (TENSOR_FOUND) diff --git a/testbed/nanogui/ext/eigen/bench/btl/libs/tensors/main_linear.cpp b/testbed/nanogui/ext/eigen/bench/btl/libs/tensors/main_linear.cpp new file mode 100644 index 00000000..e257f1e7 --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/btl/libs/tensors/main_linear.cpp @@ -0,0 +1,23 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "utilities.h" +#include "tensor_interface.hh" +#include "bench.hh" +#include "basic_actions.hh" + +BTL_MAIN; + +int main() +{ + bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); + bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); + + return 0; +} diff --git a/testbed/nanogui/ext/eigen/bench/btl/libs/tensors/main_matmat.cpp b/testbed/nanogui/ext/eigen/bench/btl/libs/tensors/main_matmat.cpp new file mode 100644 index 00000000..675fcfc6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/btl/libs/tensors/main_matmat.cpp @@ -0,0 +1,21 @@ +//===================================================== +// Copyright (C) 2014 Benoit Steiner +//===================================================== +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +// +#include "utilities.h" +#include "tensor_interface.hh" +#include "bench.hh" +#include "basic_actions.hh" + +BTL_MAIN; + +int main() +{ + bench > >(MIN_MM,MAX_MM,NB_POINT); + + return 0; +} diff --git a/testbed/nanogui/ext/eigen/bench/btl/libs/tensors/main_vecmat.cpp b/testbed/nanogui/ext/eigen/bench/btl/libs/tensors/main_vecmat.cpp new file mode 100644 index 00000000..1af00c81 --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/btl/libs/tensors/main_vecmat.cpp @@ -0,0 +1,21 @@ +//===================================================== +// Copyright (C) 2014 Benoit Steiner +//===================================================== +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +// +#include "utilities.h" +#include "tensor_interface.hh" +#include "bench.hh" +#include "basic_actions.hh" + +BTL_MAIN; + +int main() +{ + bench > >(MIN_MV,MAX_MV,NB_POINT); + + return 0; +} diff --git a/testbed/nanogui/ext/eigen/bench/btl/libs/tensors/tensor_interface.hh b/testbed/nanogui/ext/eigen/bench/btl/libs/tensors/tensor_interface.hh new file mode 100644 index 00000000..97b8e0f0 --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/btl/libs/tensors/tensor_interface.hh @@ -0,0 +1,105 @@ +//===================================================== +// Copyright (C) 2014 Benoit Steiner +//===================================================== +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +// +#ifndef TENSOR_INTERFACE_HH +#define TENSOR_INTERFACE_HH + +#include +#include +#include "btl.hh" + +using namespace Eigen; + +template +class tensor_interface +{ +public : + typedef real real_type; + typedef typename Eigen::Tensor::Index Index; + + typedef std::vector stl_vector; + typedef std::vector stl_matrix; + + typedef Eigen::Tensor gene_matrix; + typedef Eigen::Tensor gene_vector; + + + static inline std::string name( void ) + { + return EIGEN_MAKESTRING(BTL_PREFIX); + } + + static void free_matrix(gene_matrix & /*A*/, int /*N*/) {} + + static void free_vector(gene_vector & /*B*/) {} + + static BTL_DONT_INLINE void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){ + A.resize(Eigen::array(A_stl[0].size(), A_stl.size())); + + for (unsigned int j=0; j(i,j)) = A_stl[j][i]; + } + } + } + + static BTL_DONT_INLINE void vector_from_stl(gene_vector & B, stl_vector & B_stl){ + B.resize(B_stl.size()); + + for (unsigned int i=0; i(i,j)); + } + } + } + + static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int /*N*/){ + typedef typename Eigen::Tensor::DimensionPair DimPair; + const Eigen::array dims(DimPair(1, 0)); + X/*.noalias()*/ = A.contract(B, dims); + } + + static inline void matrix_vector_product(const gene_matrix & A, const gene_vector & B, gene_vector & X, int /*N*/){ + typedef typename Eigen::Tensor::DimensionPair DimPair; + const Eigen::array dims(DimPair(1, 0)); + X/*.noalias()*/ = A.contract(B, dims); + } + + static inline void axpy(real coef, const gene_vector & X, gene_vector & Y, int /*N*/){ + Y += X.constant(coef) * X; + } + + static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int /*N*/){ + Y = X.constant(a)*X + Y.constant(b)*Y; + } + + static EIGEN_DONT_INLINE void copy_matrix(const gene_matrix & source, gene_matrix & cible, int /*N*/){ + cible = source; + } + + static EIGEN_DONT_INLINE void copy_vector(const gene_vector & source, gene_vector & cible, int /*N*/){ + cible = source; + } +}; + +#endif diff --git a/testbed/nanogui/ext/eigen/bench/dense_solvers.cpp b/testbed/nanogui/ext/eigen/bench/dense_solvers.cpp new file mode 100644 index 00000000..24343dcd --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/dense_solvers.cpp @@ -0,0 +1,186 @@ +#include +#include "BenchTimer.h" +#include +#include +#include +#include +#include +using namespace Eigen; + +std::map > results; +std::vector labels; +std::vector sizes; + +template +EIGEN_DONT_INLINE +void compute_norm_equation(Solver &solver, const MatrixType &A) { + if(A.rows()!=A.cols()) + solver.compute(A.transpose()*A); + else + solver.compute(A); +} + +template +EIGEN_DONT_INLINE +void compute(Solver &solver, const MatrixType &A) { + solver.compute(A); +} + +template +void bench(int id, int rows, int size = Size) +{ + typedef Matrix Mat; + typedef Matrix MatDyn; + typedef Matrix MatSquare; + Mat A(rows,size); + A.setRandom(); + if(rows==size) + A = A*A.adjoint(); + BenchTimer t_llt, t_ldlt, t_lu, t_fplu, t_qr, t_cpqr, t_cod, t_fpqr, t_jsvd, t_bdcsvd; + + int svd_opt = ComputeThinU|ComputeThinV; + + int tries = 5; + int rep = 1000/size; + if(rep==0) rep = 1; +// rep = rep*rep; + + LLT llt(size); + LDLT ldlt(size); + PartialPivLU lu(size); + FullPivLU fplu(size,size); + HouseholderQR qr(A.rows(),A.cols()); + ColPivHouseholderQR cpqr(A.rows(),A.cols()); + CompleteOrthogonalDecomposition cod(A.rows(),A.cols()); + FullPivHouseholderQR fpqr(A.rows(),A.cols()); + JacobiSVD jsvd(A.rows(),A.cols()); + BDCSVD bdcsvd(A.rows(),A.cols()); + + BENCH(t_llt, tries, rep, compute_norm_equation(llt,A)); + BENCH(t_ldlt, tries, rep, compute_norm_equation(ldlt,A)); + BENCH(t_lu, tries, rep, compute_norm_equation(lu,A)); + if(size<=1000) + BENCH(t_fplu, tries, rep, compute_norm_equation(fplu,A)); + BENCH(t_qr, tries, rep, compute(qr,A)); + BENCH(t_cpqr, tries, rep, compute(cpqr,A)); + BENCH(t_cod, tries, rep, compute(cod,A)); + if(size*rows<=10000000) + BENCH(t_fpqr, tries, rep, compute(fpqr,A)); + if(size<500) // JacobiSVD is really too slow for too large matrices + BENCH(t_jsvd, tries, rep, jsvd.compute(A,svd_opt)); +// if(size*rows<=20000000) + BENCH(t_bdcsvd, tries, rep, bdcsvd.compute(A,svd_opt)); + + results["LLT"][id] = t_llt.best(); + results["LDLT"][id] = t_ldlt.best(); + results["PartialPivLU"][id] = t_lu.best(); + results["FullPivLU"][id] = t_fplu.best(); + results["HouseholderQR"][id] = t_qr.best(); + results["ColPivHouseholderQR"][id] = t_cpqr.best(); + results["CompleteOrthogonalDecomposition"][id] = t_cod.best(); + results["FullPivHouseholderQR"][id] = t_fpqr.best(); + results["JacobiSVD"][id] = t_jsvd.best(); + results["BDCSVD"][id] = t_bdcsvd.best(); +} + + +int main() +{ + labels.push_back("LLT"); + labels.push_back("LDLT"); + labels.push_back("PartialPivLU"); + labels.push_back("FullPivLU"); + labels.push_back("HouseholderQR"); + labels.push_back("ColPivHouseholderQR"); + labels.push_back("CompleteOrthogonalDecomposition"); + labels.push_back("FullPivHouseholderQR"); + labels.push_back("JacobiSVD"); + labels.push_back("BDCSVD"); + + for(int i=0; i(k,sizes[k](0),sizes[k](1)); + } + + cout.width(32); + cout << "solver/size"; + cout << " "; + for(int k=0; k=1e6) cout << "-"; + else cout << r(k); + cout << " "; + } + cout << endl; + } + + // HTML output + cout << "" << endl; + cout << "" << endl; + for(int k=0; k" << sizes[k](0) << "x" << sizes[k](1) << ""; + cout << "" << endl; + for(int i=0; i"; + ArrayXf r = (results[labels[i]]*100000.f).floor()/100.f; + for(int k=0; k=1e6) cout << ""; + else + { + cout << ""; + } + } + cout << "" << endl; + } + cout << "
solver/size
" << labels[i] << "-" << r(k); + if(i>0) + cout << " (x" << numext::round(10.f*results[labels[i]](k)/results["LLT"](k))/10.f << ")"; + if(i<4 && sizes[k](0)!=sizes[k](1)) + cout << " *"; + cout << "
" << endl; + +// cout << "LLT (ms) " << (results["LLT"]*1000.).format(fmt) << "\n"; +// cout << "LDLT (%) " << (results["LDLT"]/results["LLT"]).format(fmt) << "\n"; +// cout << "PartialPivLU (%) " << (results["PartialPivLU"]/results["LLT"]).format(fmt) << "\n"; +// cout << "FullPivLU (%) " << (results["FullPivLU"]/results["LLT"]).format(fmt) << "\n"; +// cout << "HouseholderQR (%) " << (results["HouseholderQR"]/results["LLT"]).format(fmt) << "\n"; +// cout << "ColPivHouseholderQR (%) " << (results["ColPivHouseholderQR"]/results["LLT"]).format(fmt) << "\n"; +// cout << "CompleteOrthogonalDecomposition (%) " << (results["CompleteOrthogonalDecomposition"]/results["LLT"]).format(fmt) << "\n"; +// cout << "FullPivHouseholderQR (%) " << (results["FullPivHouseholderQR"]/results["LLT"]).format(fmt) << "\n"; +// cout << "JacobiSVD (%) " << (results["JacobiSVD"]/results["LLT"]).format(fmt) << "\n"; +// cout << "BDCSVD (%) " << (results["BDCSVD"]/results["LLT"]).format(fmt) << "\n"; +} diff --git a/testbed/nanogui/ext/eigen/bench/eig33.cpp b/testbed/nanogui/ext/eigen/bench/eig33.cpp index 1608b999..47947a9b 100644 --- a/testbed/nanogui/ext/eigen/bench/eig33.cpp +++ b/testbed/nanogui/ext/eigen/bench/eig33.cpp @@ -50,7 +50,7 @@ inline void computeRoots(const Matrix& m, Roots& roots) { typedef typename Matrix::Scalar Scalar; const Scalar s_inv3 = 1.0/3.0; - const Scalar s_sqrt3 = internal::sqrt(Scalar(3.0)); + const Scalar s_sqrt3 = std::sqrt(Scalar(3.0)); // The characteristic equation is x^3 - c2*x^2 + c1*x - c0 = 0. The // eigenvalues are the roots to this equation, all guaranteed to be @@ -73,23 +73,13 @@ inline void computeRoots(const Matrix& m, Roots& roots) q = Scalar(0); // Compute the eigenvalues by solving for the roots of the polynomial. - Scalar rho = internal::sqrt(-a_over_3); - Scalar theta = std::atan2(internal::sqrt(-q),half_b)*s_inv3; - Scalar cos_theta = internal::cos(theta); - Scalar sin_theta = internal::sin(theta); - roots(0) = c2_over_3 + Scalar(2)*rho*cos_theta; - roots(1) = c2_over_3 - rho*(cos_theta + s_sqrt3*sin_theta); - roots(2) = c2_over_3 - rho*(cos_theta - s_sqrt3*sin_theta); - - // Sort in increasing order. - if (roots(0) >= roots(1)) - std::swap(roots(0),roots(1)); - if (roots(1) >= roots(2)) - { - std::swap(roots(1),roots(2)); - if (roots(0) >= roots(1)) - std::swap(roots(0),roots(1)); - } + Scalar rho = std::sqrt(-a_over_3); + Scalar theta = std::atan2(std::sqrt(-q),half_b)*s_inv3; + Scalar cos_theta = std::cos(theta); + Scalar sin_theta = std::sin(theta); + roots(2) = c2_over_3 + Scalar(2)*rho*cos_theta; + roots(0) = c2_over_3 - rho*(cos_theta + s_sqrt3*sin_theta); + roots(1) = c2_over_3 - rho*(cos_theta - s_sqrt3*sin_theta); } template @@ -99,9 +89,12 @@ void eigen33(const Matrix& mat, Matrix& evecs, Vector& evals) // Scale the matrix so its entries are in [-1,1]. The scaling is applied // only when at least one matrix entry has magnitude larger than 1. - Scalar scale = mat.cwiseAbs()/*.template triangularView()*/.maxCoeff(); + Scalar shift = mat.trace()/3; + Matrix scaledMat = mat; + scaledMat.diagonal().array() -= shift; + Scalar scale = scaledMat.cwiseAbs()/*.template triangularView()*/.maxCoeff(); scale = std::max(scale,Scalar(1)); - Matrix scaledMat = mat / scale; + scaledMat/=scale; // Compute the eigenvalues // scaledMat.setZero(); @@ -166,6 +159,7 @@ void eigen33(const Matrix& mat, Matrix& evecs, Vector& evals) // Rescale back to the original size. evals *= scale; + evals.array()+=shift; } int main() @@ -173,24 +167,29 @@ int main() BenchTimer t; int tries = 10; int rep = 400000; - typedef Matrix3f Mat; - typedef Vector3f Vec; + typedef Matrix3d Mat; + typedef Vector3d Vec; Mat A = Mat::Random(3,3); A = A.adjoint() * A; +// Mat Q = A.householderQr().householderQ(); +// A = Q * Vec(2.2424567,2.2424566,7.454353).asDiagonal() * Q.transpose(); SelfAdjointEigenSolver eig(A); BENCH(t, tries, rep, eig.compute(A)); - std::cout << "Eigen: " << t.best() << "s\n"; + std::cout << "Eigen iterative: " << t.best() << "s\n"; + + BENCH(t, tries, rep, eig.computeDirect(A)); + std::cout << "Eigen direct : " << t.best() << "s\n"; Mat evecs; Vec evals; BENCH(t, tries, rep, eigen33(A,evecs,evals)); std::cout << "Direct: " << t.best() << "s\n\n"; - std::cerr << "Eigenvalue/eigenvector diffs:\n"; - std::cerr << (evals - eig.eigenvalues()).transpose() << "\n"; - for(int k=0;k<3;++k) - if(evecs.col(k).dot(eig.eigenvectors().col(k))<0) - evecs.col(k) = -evecs.col(k); - std::cerr << evecs - eig.eigenvectors() << "\n\n"; +// std::cerr << "Eigenvalue/eigenvector diffs:\n"; +// std::cerr << (evals - eig.eigenvalues()).transpose() << "\n"; +// for(int k=0;k<3;++k) +// if(evecs.col(k).dot(eig.eigenvectors().col(k))<0) +// evecs.col(k) = -evecs.col(k); +// std::cerr << evecs - eig.eigenvectors() << "\n\n"; } diff --git a/testbed/nanogui/ext/eigen/bench/perf_monitoring/changesets.txt b/testbed/nanogui/ext/eigen/bench/perf_monitoring/changesets.txt new file mode 100644 index 00000000..960699c0 --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/perf_monitoring/changesets.txt @@ -0,0 +1,71 @@ +#3.0.1 +#3.1.1 +#3.2.0 +3.2.4 +#5745:37f59e65eb6c +5891:d8652709345d # introduce AVX +#5893:24b4dc92c6d3 # merge +5895:997c2ef9fc8b # introduce FMA +#5904:e1eafd14eaa1 # complex and AVX +5908:f8ee3c721251 # improve packing with ptranspose +#5921:ca808bb456b0 # merge +#5927:8b1001f9e3ac +5937:5a4ca1ad8c53 # New gebp kernel handling up to 3 packets x 4 register-level blocks +#5949:f3488f4e45b2 # merge +#5969:e09031dccfd9 # Disable 3pX4 kernel on Altivec +#5992:4a429f5e0483 # merge +before-evaluators +#6334:f6a45e5b8b7c # Implement evaluator for sparse outer products +#6639:c9121c60b5c7 +#6655:06f163b5221f # Properly detect FMA support on ARM +#6677:700e023044e7 # FMA has been wrongly disabled +#6681:11d31dafb0e3 +#6699:5e6e8e10aad1 # merge default to tensors +#6726:ff2d2388e7b9 # merge default to tensors +#6742:0cbd6195e829 # merge default to tensors +#6747:853d2bafeb8f # Generalized the gebp apis +6765:71584fd55762 # Made the blocking computation aware of the l3 cache; Also optimized the blocking parameters to take into account the number of threads used for a computation +6781:9cc5a931b2c6 # generalized gemv +6792:f6e1daab600a # ensured that contractions that can be reduced to a matrix vector product +#6844:039efd86b75c # merge tensor +6845:7333ed40c6ef # change prefetching in gebp +#6856:b5be5e10eb7f # merge index conversion +6893:c3a64aba7c70 # clean blocking size computation +6899:877facace746 # rotating kernel for ARM only +#6904:c250623ae9fa # result_of +6921:915f1b1fc158 # fix prefetching change for ARM +6923:9ff25f6dacc6 # prefetching +6933:52572e60b5d3 # blocking size strategy +6937:c8c042f286b2 # avoid redundant pack_rhs +6981:7e5d6f78da59 # dynamic loop swapping +6984:45f26866c091 # rm dynamic loop swapping, adjust lhs's micro panel height to fully exploit L1 cache +6986:a675d05b6f8f # blocking heuristic: block on the rhs in L1 if the lhs fit in L1. +7013:f875e75f07e5 # organize a little our default cache sizes, and use a saner default L1 outside of x86 (10% faster on Nexus 5) +7015:8aad8f35c955 # Refactor computeProductBlockingSizes to make room for the possibility of using lookup tables +7016:a58d253e8c91 # Polish lookup tables generation +7018:9b27294a8186 # actual_panel_rows computation should always be resilient to parameters not consistent with the known L1 cache size, see comment +7019:c758b1e2c073 # Provide a empirical lookup table for blocking sizes measured on a Nexus 5. Only for float, only for Android on ARM 32bit for now. +7085:627e039fba68 # Bug 986: add support for coefficient-based product with 0 depth. +7098:b6f1db9cf9ec # Bug 992: don't select a 3p GEMM path with non-vectorizable scalar types, this hits unsupported paths in symm/triangular products code +7591:09a8e2186610 # 3.3-alpha1 +7650:b0f3c8f43025 # help clang inlining +7708:dfc6ab9d9458 # Improve numerical accuracy in LLT and triangular solve by using true scalar divisions (instead of x * (1/y)) +#8744:74b789ada92a # Improved the matrix multiplication blocking in the case where mr is not a power of 2 (e.g on Haswell CPUs) +8789:efcb912e4356 # Made the index type a template parameter to evaluateProductBlockingSizes. Use numext::mini and numext::maxi instead of std::min/std::max to compute blocking sizes +8972:81d53c711775 # Don't optimize the processing of the last rows of a matrix matrix product in cases that violate the assumptions made by the optimized code path +8985:d935df21a082 # Remove the rotating kernel. +8988:6c2dc56e73b3 # Bug 256: enable vectorization with unaligned loads/stores. +9148:b8b8c421e36c # Relax mixing-type constraints for binary coefficient-wise operators +9174:d228bc282ac9 # merge +9212:c90098affa7b # Fix performance regression introduced in changeset 8aad8f35c955 +9213:9f1c14e4694b # Fix performance regression in dgemm introduced by changeset 81d53c711775 +9361:69d418c06999 # 3.3-beta2 +9583:bef509908b9d # 3.3-rc1 +9792:26667be4f70b # 3.3.0 +9942:b1d3eba60130 # Operators += and -= do not resize! +9943:79bb9887afd4 # Ease compiler job to generate clean and efficient code in mat*vec +9946:2213991340ea # Complete rewrite of column-major-matrix * vector product to deliver higher performance of modern CPU. +9955:630471c3298c # Improve performance of row-major-dense-matrix * vector products for recent CPUs. (this is the next changeset fixing a typo) +9975:2eeed9de710c # Revert vec/y to vec*(1/y) in row-major TRSM + + diff --git a/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemm.cpp b/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemm.cpp new file mode 100644 index 00000000..804139db --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemm.cpp @@ -0,0 +1,12 @@ +#include "gemm_common.h" + +EIGEN_DONT_INLINE +void gemm(const Mat &A, const Mat &B, Mat &C) +{ + C.noalias() += A * B; +} + +int main(int argc, char **argv) +{ + return main_gemm(argc, argv, gemm); +} diff --git a/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemm_common.h b/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemm_common.h new file mode 100644 index 00000000..30dbc0df --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemm_common.h @@ -0,0 +1,67 @@ +#include +#include +#include +#include +#include "eigen_src/Eigen/Core" +#include "../BenchTimer.h" +using namespace Eigen; + +#ifndef SCALAR +#error SCALAR must be defined +#endif + +typedef SCALAR Scalar; + +typedef Matrix Mat; + +template +EIGEN_DONT_INLINE +double bench(long m, long n, long k, const Func& f) +{ + Mat A(m,k); + Mat B(k,n); + Mat C(m,n); + A.setRandom(); + B.setRandom(); + C.setZero(); + + BenchTimer t; + + double up = 1e8*4/sizeof(Scalar); + double tm0 = 4, tm1 = 10; + if(NumTraits::IsComplex) + { + up /= 4; + tm0 = 2; + tm1 = 4; + } + + double flops = 2. * m * n * k; + long rep = std::max(1., std::min(100., up/flops) ); + long tries = std::max(tm0, std::min(tm1, up/flops) ); + + BENCH(t, tries, rep, f(A,B,C)); + + return 1e-9 * rep * flops / t.best(); +} + +template +int main_gemm(int argc, char **argv, const Func& f) +{ + std::vector results; + + std::string filename = std::string("gemm_settings.txt"); + if(argc>1) + filename = std::string(argv[1]); + std::ifstream settings(filename); + long m, n, k; + while(settings >> m >> n >> k) + { + //std::cerr << " Testing " << m << " " << n << " " << k << std::endl; + results.push_back( bench(m, n, k, f) ); + } + + std::cout << RowVectorXd::Map(results.data(), results.size()); + + return 0; +} diff --git a/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemm_settings.txt b/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemm_settings.txt new file mode 100644 index 00000000..5c43e1c7 --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemm_settings.txt @@ -0,0 +1,15 @@ +8 8 8 +9 9 9 +24 24 24 +239 239 239 +240 240 240 +2400 24 24 +24 2400 24 +24 24 2400 +24 2400 2400 +2400 24 2400 +2400 2400 24 +2400 2400 64 +4800 23 160 +23 4800 160 +2400 2400 2400 diff --git a/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemm_square_settings.txt b/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemm_square_settings.txt new file mode 100644 index 00000000..98474d17 --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemm_square_settings.txt @@ -0,0 +1,11 @@ +8 8 8 +9 9 9 +12 12 12 +15 15 15 +16 16 16 +24 24 24 +102 102 102 +239 239 239 +240 240 240 +2400 2400 2400 +2463 2463 2463 diff --git a/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemv.cpp b/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemv.cpp new file mode 100644 index 00000000..82e5ab96 --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemv.cpp @@ -0,0 +1,12 @@ +#include "gemv_common.h" + +EIGEN_DONT_INLINE +void gemv(const Mat &A, const Vec &B, Vec &C) +{ + C.noalias() += A * B; +} + +int main(int argc, char **argv) +{ + return main_gemv(argc, argv, gemv); +} diff --git a/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemv_common.h b/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemv_common.h new file mode 100644 index 00000000..cc325772 --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemv_common.h @@ -0,0 +1,69 @@ +#include +#include +#include +#include +#include +#include "eigen_src/Eigen/Core" +#include "../BenchTimer.h" +using namespace Eigen; + +#ifndef SCALAR +#error SCALAR must be defined +#endif + +typedef SCALAR Scalar; + +typedef Matrix Mat; +typedef Matrix Vec; + +template +EIGEN_DONT_INLINE +double bench(long m, long n, Func &f) +{ + Mat A(m,n); + Vec B(n); + Vec C(m); + A.setRandom(); + B.setRandom(); + C.setRandom(); + + BenchTimer t; + + double up = 1e8/sizeof(Scalar); + double tm0 = 4, tm1 = 10; + if(NumTraits::IsComplex) + { + up /= 4; + tm0 = 2; + tm1 = 4; + } + + double flops = 2. * m * n; + long rep = std::max(1., std::min(100., up/flops) ); + long tries = std::max(tm0, std::min(tm1, up/flops) ); + + BENCH(t, tries, rep, f(A,B,C)); + + return 1e-9 * rep * flops / t.best(); +} + +template +int main_gemv(int argc, char **argv, Func& f) +{ + std::vector results; + + std::string filename = std::string("gemv_settings.txt"); + if(argc>1) + filename = std::string(argv[1]); + std::ifstream settings(filename); + long m, n; + while(settings >> m >> n) + { + //std::cerr << " Testing " << m << " " << n << std::endl; + results.push_back( bench(m, n, f) ); + } + + std::cout << RowVectorXd::Map(results.data(), results.size()); + + return 0; +} diff --git a/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemv_settings.txt b/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemv_settings.txt new file mode 100644 index 00000000..21a5ee05 --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemv_settings.txt @@ -0,0 +1,11 @@ +8 8 +9 9 +24 24 +239 239 +240 240 +2400 24 +24 2400 +24 240 +2400 2400 +4800 23 +23 4800 diff --git a/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemv_square_settings.txt b/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemv_square_settings.txt new file mode 100644 index 00000000..5165759f --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemv_square_settings.txt @@ -0,0 +1,13 @@ +8 8 +9 9 +12 12 +15 15 +16 16 +24 24 +53 53 +74 74 +102 102 +239 239 +240 240 +2400 2400 +2463 2463 diff --git a/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemvt.cpp b/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemvt.cpp new file mode 100644 index 00000000..fe945767 --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/perf_monitoring/gemvt.cpp @@ -0,0 +1,12 @@ +#include "gemv_common.h" + +EIGEN_DONT_INLINE +void gemv(const Mat &A, Vec &B, const Vec &C) +{ + B.noalias() += A.transpose() * C; +} + +int main(int argc, char **argv) +{ + return main_gemv(argc, argv, gemv); +} diff --git a/testbed/nanogui/ext/eigen/bench/perf_monitoring/lazy_gemm.cpp b/testbed/nanogui/ext/eigen/bench/perf_monitoring/lazy_gemm.cpp new file mode 100644 index 00000000..77330604 --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/perf_monitoring/lazy_gemm.cpp @@ -0,0 +1,101 @@ +#include +#include +#include +#include +#include "../../BenchTimer.h" +using namespace Eigen; + +#ifndef SCALAR +#error SCALAR must be defined +#endif + +typedef SCALAR Scalar; + +template +EIGEN_DONT_INLINE +void lazy_gemm(const MatA &A, const MatB &B, MatC &C) +{ +// escape((void*)A.data()); +// escape((void*)B.data()); + C.noalias() += A.lazyProduct(B); +// escape((void*)C.data()); +} + +template +EIGEN_DONT_INLINE +double bench() +{ + typedef Matrix MatA; + typedef Matrix MatB; + typedef Matrix MatC; + + MatA A(m,k); + MatB B(k,n); + MatC C(m,n); + A.setRandom(); + B.setRandom(); + C.setZero(); + + BenchTimer t; + + double up = 1e7*4/sizeof(Scalar); + double tm0 = 10, tm1 = 20; + + double flops = 2. * m * n * k; + long rep = std::max(10., std::min(10000., up/flops) ); + long tries = std::max(tm0, std::min(tm1, up/flops) ); + + BENCH(t, tries, rep, lazy_gemm(A,B,C)); + + return 1e-9 * rep * flops / t.best(); +} + +template +double bench_t(int t) +{ + if(t) + return bench(); + else + return bench(); +} + +EIGEN_DONT_INLINE +double bench_mnk(int m, int n, int k, int t) +{ + int id = m*10000 + n*100 + k; + switch(id) { + case 10101 : return bench_t< 1, 1, 1>(t); break; + case 20202 : return bench_t< 2, 2, 2>(t); break; + case 30303 : return bench_t< 3, 3, 3>(t); break; + case 40404 : return bench_t< 4, 4, 4>(t); break; + case 50505 : return bench_t< 5, 5, 5>(t); break; + case 60606 : return bench_t< 6, 6, 6>(t); break; + case 70707 : return bench_t< 7, 7, 7>(t); break; + case 80808 : return bench_t< 8, 8, 8>(t); break; + case 90909 : return bench_t< 9, 9, 9>(t); break; + case 101010 : return bench_t<10,10,10>(t); break; + case 111111 : return bench_t<11,11,11>(t); break; + case 121212 : return bench_t<12,12,12>(t); break; + } + return 0; +} + +int main(int argc, char **argv) +{ + std::vector results; + + std::string filename = std::string("lazy_gemm_settings.txt"); + if(argc>1) + filename = std::string(argv[1]); + std::ifstream settings(filename); + long m, n, k, t; + while(settings >> m >> n >> k >> t) + { + //std::cerr << " Testing " << m << " " << n << " " << k << std::endl; + results.push_back( bench_mnk(m, n, k, t) ); + } + + std::cout << RowVectorXd::Map(results.data(), results.size()); + + return 0; +} diff --git a/testbed/nanogui/ext/eigen/bench/perf_monitoring/lazy_gemm_settings.txt b/testbed/nanogui/ext/eigen/bench/perf_monitoring/lazy_gemm_settings.txt new file mode 100644 index 00000000..407d5d4f --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/perf_monitoring/lazy_gemm_settings.txt @@ -0,0 +1,15 @@ +1 1 1 0 +2 2 2 0 +3 3 3 0 +4 4 4 0 +4 4 4 1 +5 5 5 0 +6 6 6 0 +7 7 7 0 +7 7 7 1 +8 8 8 0 +9 9 9 0 +10 10 10 0 +11 11 11 0 +12 12 12 0 +12 12 12 1 diff --git a/testbed/nanogui/ext/eigen/bench/perf_monitoring/llt.cpp b/testbed/nanogui/ext/eigen/bench/perf_monitoring/llt.cpp new file mode 100644 index 00000000..d55b7d80 --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/perf_monitoring/llt.cpp @@ -0,0 +1,15 @@ +#include "gemm_common.h" +#include + +EIGEN_DONT_INLINE +void llt(const Mat &A, const Mat &B, Mat &C) +{ + C = A; + C.diagonal().array() += 1000; + Eigen::internal::llt_inplace::blocked(C); +} + +int main(int argc, char **argv) +{ + return main_gemm(argc, argv, llt); +} diff --git a/testbed/nanogui/ext/eigen/bench/perf_monitoring/make_plot.sh b/testbed/nanogui/ext/eigen/bench/perf_monitoring/make_plot.sh new file mode 100644 index 00000000..ca9fa966 --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/perf_monitoring/make_plot.sh @@ -0,0 +1,98 @@ +#!/bin/bash + +# base name of the bench +# it reads $1.out +# and generates $1.pdf +WHAT=$1 +bench=$2 +settings_file=$3 + +header="rev " +while read line +do + if [ ! -z '$line' ]; then + header="$header \"$line\"" + fi +done < $settings_file + +echo $header > $WHAT.out.header +cat $WHAT.out >> $WHAT.out.header + + +echo "set title '$WHAT'" > $WHAT.gnuplot +echo "set key autotitle columnhead outside " >> $WHAT.gnuplot +echo "set xtics rotate 1" >> $WHAT.gnuplot + +echo "set term pdf color rounded enhanced fontscale 0.35 size 7in,5in" >> $WHAT.gnuplot +echo set output "'"$WHAT.pdf"'" >> $WHAT.gnuplot + +col=`cat $settings_file | wc -l` +echo "plot for [col=2:$col+1] '$WHAT.out.header' using 0:col:xticlabels(1) with lines" >> $WHAT.gnuplot +echo " " >> $WHAT.gnuplot + +gnuplot -persist < $WHAT.gnuplot + +# generate a png file (thumbnail) +convert -colors 256 -background white -density 300 -resize 300 -quality 0 $WHAT.pdf -background white -flatten $WHAT.png + +# clean +rm $WHAT.out.header $WHAT.gnuplot + + +# generate html/svg graph + +echo " " > $WHAT.html +cat resources/chart_header.html > $WHAT.html +echo 'var customSettings = {"TITLE":"","SUBTITLE":"","XLABEL":"","YLABEL":""};' >> $WHAT.html +# 'data' is an array of datasets (i.e. curves), each of which is an object of the form +# { +# key: , +# color: , +# values: [{ +# r: , +# v: +# }] +# } +echo 'var data = [' >> $WHAT.html + +col=2 +while read line +do + if [ ! -z '$line' ]; then + header="$header \"$line\"" + echo '{"key":"'$line'","values":[' >> $WHAT.html + i=0 + while read line2 + do + if [ ! -z '$line2' ]; then + echo '{"r":'$i',"v":'`echo $line2 | cut -f $col -d ' '`'},' >> $WHAT.html + fi + ((i++)) + done < $WHAT.out + echo ']},' >> $WHAT.html + fi + ((col++)) +done < $settings_file +echo '];' >> $WHAT.html + +echo 'var changesets = [' >> $WHAT.html +while read line2 +do + if [ ! -z '$line2' ]; then + echo '"'`echo $line2 | cut -f 1 -d ' '`'",' >> $WHAT.html + fi +done < $WHAT.out +echo '];' >> $WHAT.html + +echo 'var changesets_count = [' >> $WHAT.html +i=0 +while read line2 +do + if [ ! -z '$line2' ]; then + echo $i ',' >> $WHAT.html + fi + ((i++)) +done < $WHAT.out +echo '];' >> $WHAT.html + +cat resources/chart_footer.html >> $WHAT.html diff --git a/testbed/nanogui/ext/eigen/bench/perf_monitoring/resources/chart_footer.html b/testbed/nanogui/ext/eigen/bench/perf_monitoring/resources/chart_footer.html new file mode 100644 index 00000000..8acc69f1 --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/perf_monitoring/resources/chart_footer.html @@ -0,0 +1,37 @@ + /* setup the chart and its options */ + var chart = nv.models.lineChart() + .color(d3.scale.category10().range()) + .margin({left: 75, bottom: 100}) + .forceX([0]).forceY([0]); + + chart.x(function(datum){ return datum.r; }) + .xAxis.options({ + axisLabel: customSettings.XLABEL || 'Changeset', + tickFormat: d3.format('.0f') + }); + chart.xAxis + .tickValues(changesets_count) + .tickFormat(function(d){return changesets[d]}) + .rotateLabels(-90); + + chart.y(function(datum){ return datum.v; }) + .yAxis.options({ + axisLabel: customSettings.YLABEL || 'GFlops'/*, + tickFormat: function(val){ return d3.format('.0f')(val) + ' GFlops'; }*/ + }); + + //chart.useInteractiveGuideline(true); + d3.select('#chart').datum(data).call(chart); + var plot = d3.select('#chart > g'); + + /* setup the title */ + plot.append('text') + .style('font-size', '24px') + .attr('text-anchor', 'middle').attr('x', '50%').attr('y', '20px') + .text(customSettings.TITLE || ''); + + /* ensure the chart is responsive */ + nv.utils.windowResize(chart.update); + + + \ No newline at end of file diff --git a/testbed/nanogui/ext/eigen/bench/perf_monitoring/resources/chart_header.html b/testbed/nanogui/ext/eigen/bench/perf_monitoring/resources/chart_header.html new file mode 100644 index 00000000..bb9ddffd --- /dev/null +++ b/testbed/nanogui/ext/eigen/bench/perf_monitoring/resources/chart_header.html @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + diff --git a/testbed/nanogui/ext/eigen/doc/eigendoxy_header.html.in b/testbed/nanogui/ext/eigen/doc/eigendoxy_header.html.in new file mode 100644 index 00000000..0f3859f4 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/eigendoxy_header.html.in @@ -0,0 +1,61 @@ + + + + + + +$projectname: $title +$title + + + +$treeview +$search +$mathjax + + + + + + + + + +
+ + + +
+ + + + + + + + + + + + + + + + + + + + + +
+
$projectname +  $projectnumber +
+
$projectbrief
+
+
$projectbrief
+
$searchbox
+
+ + + diff --git a/testbed/nanogui/ext/eigen/doc/eigendoxy_layout.xml.in b/testbed/nanogui/ext/eigen/doc/eigendoxy_layout.xml.in new file mode 100644 index 00000000..c14b621e --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/eigendoxy_layout.xml.in @@ -0,0 +1,178 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/testbed/nanogui/ext/eigen/doc/eigendoxy_tabs.css b/testbed/nanogui/ext/eigen/doc/eigendoxy_tabs.css new file mode 100644 index 00000000..21920562 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/eigendoxy_tabs.css @@ -0,0 +1,59 @@ +.tabs, .tabs2, .tabs3 { + background-image: url('tab_b.png'); + width: 100%; + z-index: 101; + font-size: 13px; +} + +.tabs2 { + font-size: 10px; +} +.tabs3 { + font-size: 9px; +} + +.tablist { + margin: 0; + padding: 0; + display: table; +} + +.tablist li { + float: left; + display: table-cell; + background-image: url('tab_b.png'); + line-height: 36px; + list-style: none; +} + +.tablist a { + display: block; + padding: 0 20px; + font-weight: bold; + background-image:url('tab_s.png'); + background-repeat:no-repeat; + background-position:right; + color: #283A5D; + text-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9); + text-decoration: none; + outline: none; +} + +.tabs3 .tablist a { + padding: 0 10px; +} + +.tablist a:hover { + background-image: url('tab_h.png'); + background-repeat:repeat-x; + color: #fff; + text-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0); + text-decoration: none; +} + +.tablist li.current a { + background-image: url('tab_a.png'); + background-repeat:repeat-x; + color: #fff; + text-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0); +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/.krazy b/testbed/nanogui/ext/eigen/doc/examples/.krazy new file mode 100644 index 00000000..00b99405 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/.krazy @@ -0,0 +1,2 @@ +EXCLUDE copyright +EXCLUDE license diff --git a/testbed/nanogui/ext/eigen/doc/examples/CMakeLists.txt b/testbed/nanogui/ext/eigen/doc/examples/CMakeLists.txt new file mode 100644 index 00000000..f7a19055 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/CMakeLists.txt @@ -0,0 +1,21 @@ +file(GLOB examples_SRCS "*.cpp") + +foreach(example_src ${examples_SRCS}) + get_filename_component(example ${example_src} NAME_WE) + add_executable(${example} ${example_src}) + if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO) + target_link_libraries(${example} ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO}) + endif() + add_custom_command( + TARGET ${example} + POST_BUILD + COMMAND ${example} + ARGS >${CMAKE_CURRENT_BINARY_DIR}/${example}.out + ) + add_dependencies(all_examples ${example}) +endforeach(example_src) + +check_cxx_compiler_flag("-std=c++11" EIGEN_COMPILER_SUPPORT_CPP11) +if(EIGEN_COMPILER_SUPPORT_CPP11) +ei_add_target_property(nullary_indexing COMPILE_FLAGS "-std=c++11") +endif() \ No newline at end of file diff --git a/testbed/nanogui/ext/eigen/doc/examples/CustomizingEigen_Inheritance.cpp b/testbed/nanogui/ext/eigen/doc/examples/CustomizingEigen_Inheritance.cpp new file mode 100644 index 00000000..48df64ee --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/CustomizingEigen_Inheritance.cpp @@ -0,0 +1,30 @@ +#include +#include + +class MyVectorType : public Eigen::VectorXd +{ +public: + MyVectorType(void):Eigen::VectorXd() {} + + // This constructor allows you to construct MyVectorType from Eigen expressions + template + MyVectorType(const Eigen::MatrixBase& other) + : Eigen::VectorXd(other) + { } + + // This method allows you to assign Eigen expressions to MyVectorType + template + MyVectorType& operator=(const Eigen::MatrixBase & other) + { + this->Eigen::VectorXd::operator=(other); + return *this; + } +}; + +int main() +{ + MyVectorType v = MyVectorType::Ones(4); + v(2) += 10; + v = 2 * v; + std::cout << v.transpose() << std::endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Cwise_erf.cpp b/testbed/nanogui/ext/eigen/doc/examples/Cwise_erf.cpp new file mode 100644 index 00000000..e7cd2c1c --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Cwise_erf.cpp @@ -0,0 +1,9 @@ +#include +#include +#include +using namespace Eigen; +int main() +{ + Array4d v(-0.5,2,0,-7); + std::cout << v.erf() << std::endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Cwise_erfc.cpp b/testbed/nanogui/ext/eigen/doc/examples/Cwise_erfc.cpp new file mode 100644 index 00000000..d8bb04c3 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Cwise_erfc.cpp @@ -0,0 +1,9 @@ +#include +#include +#include +using namespace Eigen; +int main() +{ + Array4d v(-0.5,2,0,-7); + std::cout << v.erfc() << std::endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Cwise_lgamma.cpp b/testbed/nanogui/ext/eigen/doc/examples/Cwise_lgamma.cpp new file mode 100644 index 00000000..f1c4f503 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Cwise_lgamma.cpp @@ -0,0 +1,9 @@ +#include +#include +#include +using namespace Eigen; +int main() +{ + Array4d v(0.5,10,0,-1); + std::cout << v.lgamma() << std::endl; +} \ No newline at end of file diff --git a/testbed/nanogui/ext/eigen/doc/examples/DenseBase_middleCols_int.cpp b/testbed/nanogui/ext/eigen/doc/examples/DenseBase_middleCols_int.cpp new file mode 100644 index 00000000..0ebd955e --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/DenseBase_middleCols_int.cpp @@ -0,0 +1,15 @@ +#include +#include + +using namespace Eigen; +using namespace std; + +int main(void) +{ + int const N = 5; + MatrixXi A(N,N); + A.setRandom(); + cout << "A =\n" << A << '\n' << endl; + cout << "A(1..3,:) =\n" << A.middleCols(1,3) << endl; + return 0; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/DenseBase_middleRows_int.cpp b/testbed/nanogui/ext/eigen/doc/examples/DenseBase_middleRows_int.cpp new file mode 100644 index 00000000..a6fe9e84 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/DenseBase_middleRows_int.cpp @@ -0,0 +1,15 @@ +#include +#include + +using namespace Eigen; +using namespace std; + +int main(void) +{ + int const N = 5; + MatrixXi A(N,N); + A.setRandom(); + cout << "A =\n" << A << '\n' << endl; + cout << "A(2..3,:) =\n" << A.middleRows(2,2) << endl; + return 0; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/DenseBase_template_int_middleCols.cpp b/testbed/nanogui/ext/eigen/doc/examples/DenseBase_template_int_middleCols.cpp new file mode 100644 index 00000000..6191d79c --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/DenseBase_template_int_middleCols.cpp @@ -0,0 +1,15 @@ +#include +#include + +using namespace Eigen; +using namespace std; + +int main(void) +{ + int const N = 5; + MatrixXi A(N,N); + A.setRandom(); + cout << "A =\n" << A << '\n' << endl; + cout << "A(:,1..3) =\n" << A.middleCols<3>(1) << endl; + return 0; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/DenseBase_template_int_middleRows.cpp b/testbed/nanogui/ext/eigen/doc/examples/DenseBase_template_int_middleRows.cpp new file mode 100644 index 00000000..7e8b6573 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/DenseBase_template_int_middleRows.cpp @@ -0,0 +1,15 @@ +#include +#include + +using namespace Eigen; +using namespace std; + +int main(void) +{ + int const N = 5; + MatrixXi A(N,N); + A.setRandom(); + cout << "A =\n" << A << '\n' << endl; + cout << "A(1..3,:) =\n" << A.middleRows<3>(1) << endl; + return 0; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/QuickStart_example.cpp b/testbed/nanogui/ext/eigen/doc/examples/QuickStart_example.cpp new file mode 100644 index 00000000..7238c0c4 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/QuickStart_example.cpp @@ -0,0 +1,14 @@ +#include +#include + +using Eigen::MatrixXd; + +int main() +{ + MatrixXd m(2,2); + m(0,0) = 3; + m(1,0) = 2.5; + m(0,1) = -1; + m(1,1) = m(1,0) + m(0,1); + std::cout << m << std::endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/QuickStart_example2_dynamic.cpp b/testbed/nanogui/ext/eigen/doc/examples/QuickStart_example2_dynamic.cpp new file mode 100644 index 00000000..ff6746e2 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/QuickStart_example2_dynamic.cpp @@ -0,0 +1,15 @@ +#include +#include + +using namespace Eigen; +using namespace std; + +int main() +{ + MatrixXd m = MatrixXd::Random(3,3); + m = (m + MatrixXd::Constant(3,3,1.2)) * 50; + cout << "m =" << endl << m << endl; + VectorXd v(3); + v << 1, 2, 3; + cout << "m * v =" << endl << m * v << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/QuickStart_example2_fixed.cpp b/testbed/nanogui/ext/eigen/doc/examples/QuickStart_example2_fixed.cpp new file mode 100644 index 00000000..d9117527 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/QuickStart_example2_fixed.cpp @@ -0,0 +1,15 @@ +#include +#include + +using namespace Eigen; +using namespace std; + +int main() +{ + Matrix3d m = Matrix3d::Random(); + m = (m + Matrix3d::Constant(1.2)) * 50; + cout << "m =" << endl << m << endl; + Vector3d v(1,2,3); + + cout << "m * v =" << endl << m * v << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/TemplateKeyword_flexible.cpp b/testbed/nanogui/ext/eigen/doc/examples/TemplateKeyword_flexible.cpp new file mode 100644 index 00000000..9d85292d --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/TemplateKeyword_flexible.cpp @@ -0,0 +1,22 @@ +#include +#include + +using namespace Eigen; + +template +void copyUpperTriangularPart(MatrixBase& dst, const MatrixBase& src) +{ + /* Note the 'template' keywords in the following line! */ + dst.template triangularView() = src.template triangularView(); +} + +int main() +{ + MatrixXi m1 = MatrixXi::Ones(5,5); + MatrixXi m2 = MatrixXi::Random(4,4); + std::cout << "m2 before copy:" << std::endl; + std::cout << m2 << std::endl << std::endl; + copyUpperTriangularPart(m2, m1.topLeftCorner(4,4)); + std::cout << "m2 after copy:" << std::endl; + std::cout << m2 << std::endl << std::endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/TemplateKeyword_simple.cpp b/testbed/nanogui/ext/eigen/doc/examples/TemplateKeyword_simple.cpp new file mode 100644 index 00000000..6998c176 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/TemplateKeyword_simple.cpp @@ -0,0 +1,20 @@ +#include +#include + +using namespace Eigen; + +void copyUpperTriangularPart(MatrixXf& dst, const MatrixXf& src) +{ + dst.triangularView() = src.triangularView(); +} + +int main() +{ + MatrixXf m1 = MatrixXf::Ones(4,4); + MatrixXf m2 = MatrixXf::Random(4,4); + std::cout << "m2 before copy:" << std::endl; + std::cout << m2 << std::endl << std::endl; + copyUpperTriangularPart(m2, m1); + std::cout << "m2 after copy:" << std::endl; + std::cout << m2 << std::endl << std::endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/TutorialInplaceLU.cpp b/testbed/nanogui/ext/eigen/doc/examples/TutorialInplaceLU.cpp new file mode 100644 index 00000000..cb9c59b6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/TutorialInplaceLU.cpp @@ -0,0 +1,61 @@ +#include +struct init { + init() { std::cout << "[" << "init" << "]" << std::endl; } +}; +init init_obj; +// [init] +#include +#include + +using namespace std; +using namespace Eigen; + +int main() +{ + MatrixXd A(2,2); + A << 2, -1, 1, 3; + cout << "Here is the input matrix A before decomposition:\n" << A << endl; +cout << "[init]" << endl; + +cout << "[declaration]" << endl; + PartialPivLU > lu(A); + cout << "Here is the input matrix A after decomposition:\n" << A << endl; +cout << "[declaration]" << endl; + +cout << "[matrixLU]" << endl; + cout << "Here is the matrix storing the L and U factors:\n" << lu.matrixLU() << endl; +cout << "[matrixLU]" << endl; + +cout << "[solve]" << endl; + MatrixXd A0(2,2); A0 << 2, -1, 1, 3; + VectorXd b(2); b << 1, 2; + VectorXd x = lu.solve(b); + cout << "Residual: " << (A0 * x - b).norm() << endl; +cout << "[solve]" << endl; + +cout << "[modifyA]" << endl; + A << 3, 4, -2, 1; + x = lu.solve(b); + cout << "Residual: " << (A0 * x - b).norm() << endl; +cout << "[modifyA]" << endl; + +cout << "[recompute]" << endl; + A0 = A; // save A + lu.compute(A); + x = lu.solve(b); + cout << "Residual: " << (A0 * x - b).norm() << endl; +cout << "[recompute]" << endl; + +cout << "[recompute_bis0]" << endl; + MatrixXd A1(2,2); + A1 << 5,-2,3,4; + lu.compute(A1); + cout << "Here is the input matrix A1 after decomposition:\n" << A1 << endl; +cout << "[recompute_bis0]" << endl; + +cout << "[recompute_bis1]" << endl; + x = lu.solve(b); + cout << "Residual: " << (A1 * x - b).norm() << endl; +cout << "[recompute_bis1]" << endl; + +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgComputeTwice.cpp b/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgComputeTwice.cpp new file mode 100644 index 00000000..06ba6461 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgComputeTwice.cpp @@ -0,0 +1,23 @@ +#include +#include + +using namespace std; +using namespace Eigen; + +int main() +{ + Matrix2f A, b; + LLT llt; + A << 2, -1, -1, 3; + b << 1, 2, 3, 1; + cout << "Here is the matrix A:\n" << A << endl; + cout << "Here is the right hand side b:\n" << b << endl; + cout << "Computing LLT decomposition..." << endl; + llt.compute(A); + cout << "The solution is:\n" << llt.solve(b) << endl; + A(1,1)++; + cout << "The matrix A is now:\n" << A << endl; + cout << "Computing LLT decomposition..." << endl; + llt.compute(A); + cout << "The solution is now:\n" << llt.solve(b) << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgExComputeSolveError.cpp b/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgExComputeSolveError.cpp new file mode 100644 index 00000000..f362fb71 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgExComputeSolveError.cpp @@ -0,0 +1,14 @@ +#include +#include + +using namespace std; +using namespace Eigen; + +int main() +{ + MatrixXd A = MatrixXd::Random(100,100); + MatrixXd b = MatrixXd::Random(100,50); + MatrixXd x = A.fullPivLu().solve(b); + double relative_error = (A*x - b).norm() / b.norm(); // norm() is L2 norm + cout << "The relative error is:\n" << relative_error << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgExSolveColPivHouseholderQR.cpp b/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgExSolveColPivHouseholderQR.cpp new file mode 100644 index 00000000..3a99a94d --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgExSolveColPivHouseholderQR.cpp @@ -0,0 +1,17 @@ +#include +#include + +using namespace std; +using namespace Eigen; + +int main() +{ + Matrix3f A; + Vector3f b; + A << 1,2,3, 4,5,6, 7,8,10; + b << 3, 3, 4; + cout << "Here is the matrix A:\n" << A << endl; + cout << "Here is the vector b:\n" << b << endl; + Vector3f x = A.colPivHouseholderQr().solve(b); + cout << "The solution is:\n" << x << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgExSolveLDLT.cpp b/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgExSolveLDLT.cpp new file mode 100644 index 00000000..f8beacd2 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgExSolveLDLT.cpp @@ -0,0 +1,16 @@ +#include +#include + +using namespace std; +using namespace Eigen; + +int main() +{ + Matrix2f A, b; + A << 2, -1, -1, 3; + b << 1, 2, 3, 1; + cout << "Here is the matrix A:\n" << A << endl; + cout << "Here is the right hand side b:\n" << b << endl; + Matrix2f x = A.ldlt().solve(b); + cout << "The solution is:\n" << x << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgInverseDeterminant.cpp b/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgInverseDeterminant.cpp new file mode 100644 index 00000000..14dde5b3 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgInverseDeterminant.cpp @@ -0,0 +1,16 @@ +#include +#include + +using namespace std; +using namespace Eigen; + +int main() +{ + Matrix3f A; + A << 1, 2, 1, + 2, 1, 0, + -1, 1, 2; + cout << "Here is the matrix A:\n" << A << endl; + cout << "The determinant of A is " << A.determinant() << endl; + cout << "The inverse of A is:\n" << A.inverse() << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgRankRevealing.cpp b/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgRankRevealing.cpp new file mode 100644 index 00000000..c5165077 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgRankRevealing.cpp @@ -0,0 +1,20 @@ +#include +#include + +using namespace std; +using namespace Eigen; + +int main() +{ + Matrix3f A; + A << 1, 2, 5, + 2, 1, 4, + 3, 0, 3; + cout << "Here is the matrix A:\n" << A << endl; + FullPivLU lu_decomp(A); + cout << "The rank of A is " << lu_decomp.rank() << endl; + cout << "Here is a matrix whose columns form a basis of the null-space of A:\n" + << lu_decomp.kernel() << endl; + cout << "Here is a matrix whose columns form a basis of the column-space of A:\n" + << lu_decomp.image(A) << endl; // yes, have to pass the original A +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgSVDSolve.cpp b/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgSVDSolve.cpp new file mode 100644 index 00000000..9fbc031d --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgSVDSolve.cpp @@ -0,0 +1,15 @@ +#include +#include + +using namespace std; +using namespace Eigen; + +int main() +{ + MatrixXf A = MatrixXf::Random(3, 2); + cout << "Here is the matrix A:\n" << A << endl; + VectorXf b = VectorXf::Random(3); + cout << "Here is the right hand side b:\n" << b << endl; + cout << "The least-squares solution is:\n" + << A.jacobiSvd(ComputeThinU | ComputeThinV).solve(b) << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgSelfAdjointEigenSolver.cpp b/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgSelfAdjointEigenSolver.cpp new file mode 100644 index 00000000..8d1d1ed6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgSelfAdjointEigenSolver.cpp @@ -0,0 +1,18 @@ +#include +#include + +using namespace std; +using namespace Eigen; + +int main() +{ + Matrix2f A; + A << 1, 2, 2, 3; + cout << "Here is the matrix A:\n" << A << endl; + SelfAdjointEigenSolver eigensolver(A); + if (eigensolver.info() != Success) abort(); + cout << "The eigenvalues of A are:\n" << eigensolver.eigenvalues() << endl; + cout << "Here's a matrix whose columns are eigenvectors of A \n" + << "corresponding to these eigenvalues:\n" + << eigensolver.eigenvectors() << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgSetThreshold.cpp b/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgSetThreshold.cpp new file mode 100644 index 00000000..3956b13a --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/TutorialLinAlgSetThreshold.cpp @@ -0,0 +1,16 @@ +#include +#include + +using namespace std; +using namespace Eigen; + +int main() +{ + Matrix2d A; + A << 2, 1, + 2, 0.9999999999; + FullPivLU lu(A); + cout << "By default, the rank of A is found to be " << lu.rank() << endl; + lu.setThreshold(1e-5); + cout << "With threshold 1e-5, the rank of A is found to be " << lu.rank() << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_accessors.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_accessors.cpp new file mode 100644 index 00000000..dc720ff5 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_accessors.cpp @@ -0,0 +1,24 @@ +#include +#include + +using namespace Eigen; +using namespace std; + +int main() +{ + ArrayXXf m(2,2); + + // assign some values coefficient by coefficient + m(0,0) = 1.0; m(0,1) = 2.0; + m(1,0) = 3.0; m(1,1) = m(0,1) + m(1,0); + + // print values to standard output + cout << m << endl << endl; + + // using the comma-initializer is also allowed + m << 1.0,2.0, + 3.0,4.0; + + // print values to standard output + cout << m << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_addition.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_addition.cpp new file mode 100644 index 00000000..480ffb00 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_addition.cpp @@ -0,0 +1,23 @@ +#include +#include + +using namespace Eigen; +using namespace std; + +int main() +{ + ArrayXXf a(3,3); + ArrayXXf b(3,3); + a << 1,2,3, + 4,5,6, + 7,8,9; + b << 1,2,3, + 1,2,3, + 1,2,3; + + // Adding two arrays + cout << "a + b = " << endl << a + b << endl << endl; + + // Subtracting a scalar from an array + cout << "a - 2 = " << endl << a - 2 << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_cwise_other.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_cwise_other.cpp new file mode 100644 index 00000000..d9046c63 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_cwise_other.cpp @@ -0,0 +1,19 @@ +#include +#include + +using namespace Eigen; +using namespace std; + +int main() +{ + ArrayXf a = ArrayXf::Random(5); + a *= 2; + cout << "a =" << endl + << a << endl; + cout << "a.abs() =" << endl + << a.abs() << endl; + cout << "a.abs().sqrt() =" << endl + << a.abs().sqrt() << endl; + cout << "a.min(a.abs().sqrt()) =" << endl + << a.min(a.abs().sqrt()) << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_interop.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_interop.cpp new file mode 100644 index 00000000..371f0706 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_interop.cpp @@ -0,0 +1,22 @@ +#include +#include + +using namespace Eigen; +using namespace std; + +int main() +{ + MatrixXf m(2,2); + MatrixXf n(2,2); + MatrixXf result(2,2); + + m << 1,2, + 3,4; + n << 5,6, + 7,8; + + result = (m.array() + 4).matrix() * m; + cout << "-- Combination 1: --" << endl << result << endl << endl; + result = (m.array() * n.array()).matrix() * m; + cout << "-- Combination 2: --" << endl << result << endl << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_interop_matrix.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_interop_matrix.cpp new file mode 100644 index 00000000..10142751 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_interop_matrix.cpp @@ -0,0 +1,26 @@ +#include +#include + +using namespace Eigen; +using namespace std; + +int main() +{ + MatrixXf m(2,2); + MatrixXf n(2,2); + MatrixXf result(2,2); + + m << 1,2, + 3,4; + n << 5,6, + 7,8; + + result = m * n; + cout << "-- Matrix m*n: --" << endl << result << endl << endl; + result = m.array() * n.array(); + cout << "-- Array m*n: --" << endl << result << endl << endl; + result = m.cwiseProduct(n); + cout << "-- With cwiseProduct: --" << endl << result << endl << endl; + result = m.array() + 4; + cout << "-- Array m + 4: --" << endl << result << endl << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_mult.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_mult.cpp new file mode 100644 index 00000000..6cb439ff --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ArrayClass_mult.cpp @@ -0,0 +1,16 @@ +#include +#include + +using namespace Eigen; +using namespace std; + +int main() +{ + ArrayXXf a(2,2); + ArrayXXf b(2,2); + a << 1,2, + 3,4; + b << 5,6, + 7,8; + cout << "a * b = " << endl << a * b << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_BlockOperations_block_assignment.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_BlockOperations_block_assignment.cpp new file mode 100644 index 00000000..76f49f2f --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_BlockOperations_block_assignment.cpp @@ -0,0 +1,18 @@ +#include +#include + +using namespace std; +using namespace Eigen; + +int main() +{ + Array22f m; + m << 1,2, + 3,4; + Array44f a = Array44f::Constant(0.6); + cout << "Here is the array a:" << endl << a << endl << endl; + a.block<2,2>(1,1) = m; + cout << "Here is now a with m copied into its central 2x2 block:" << endl << a << endl << endl; + a.block(0,0,2,3) = a.block(2,1,2,3); + cout << "Here is now a with bottom-right 2x3 block copied into top-left 2x2 block:" << endl << a << endl << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_BlockOperations_colrow.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_BlockOperations_colrow.cpp new file mode 100644 index 00000000..2e7eb009 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_BlockOperations_colrow.cpp @@ -0,0 +1,17 @@ +#include +#include + +using namespace std; + +int main() +{ + Eigen::MatrixXf m(3,3); + m << 1,2,3, + 4,5,6, + 7,8,9; + cout << "Here is the matrix m:" << endl << m << endl; + cout << "2nd Row: " << m.row(1) << endl; + m.col(2) += 3 * m.col(0); + cout << "After adding 3 times the first column into the third column, the matrix m is:\n"; + cout << m << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_BlockOperations_corner.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_BlockOperations_corner.cpp new file mode 100644 index 00000000..3a31507a --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_BlockOperations_corner.cpp @@ -0,0 +1,17 @@ +#include +#include + +using namespace std; + +int main() +{ + Eigen::Matrix4f m; + m << 1, 2, 3, 4, + 5, 6, 7, 8, + 9, 10,11,12, + 13,14,15,16; + cout << "m.leftCols(2) =" << endl << m.leftCols(2) << endl << endl; + cout << "m.bottomRows<2>() =" << endl << m.bottomRows<2>() << endl << endl; + m.topLeftCorner(1,3) = m.bottomRightCorner(3,1).transpose(); + cout << "After assignment, m = " << endl << m << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_BlockOperations_print_block.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_BlockOperations_print_block.cpp new file mode 100644 index 00000000..edea4aef --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_BlockOperations_print_block.cpp @@ -0,0 +1,20 @@ +#include +#include + +using namespace std; + +int main() +{ + Eigen::MatrixXf m(4,4); + m << 1, 2, 3, 4, + 5, 6, 7, 8, + 9,10,11,12, + 13,14,15,16; + cout << "Block in the middle" << endl; + cout << m.block<2,2>(1,1) << endl << endl; + for (int i = 1; i <= 3; ++i) + { + cout << "Block of size " << i << "x" << i << endl; + cout << m.block(0,0,i,i) << endl << endl; + } +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_BlockOperations_vector.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_BlockOperations_vector.cpp new file mode 100644 index 00000000..4a0b0234 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_BlockOperations_vector.cpp @@ -0,0 +1,14 @@ +#include +#include + +using namespace std; + +int main() +{ + Eigen::ArrayXf v(6); + v << 1, 2, 3, 4, 5, 6; + cout << "v.head(3) =" << endl << v.head(3) << endl << endl; + cout << "v.tail<3>() = " << endl << v.tail<3>() << endl << endl; + v.segment(1,4) *= 2; + cout << "after 'v.segment(1,4) *= 2', v =" << endl << v << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_PartialLU_solve.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_PartialLU_solve.cpp new file mode 100644 index 00000000..a5608792 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_PartialLU_solve.cpp @@ -0,0 +1,18 @@ +#include +#include +#include + +using namespace std; +using namespace Eigen; + +int main() +{ + Matrix3f A; + Vector3f b; + A << 1,2,3, 4,5,6, 7,8,10; + b << 3, 3, 4; + cout << "Here is the matrix A:" << endl << A << endl; + cout << "Here is the vector b:" << endl << b << endl; + Vector3f x = A.lu().solve(b); + cout << "The solution is:" << endl << x << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_1nn.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_1nn.cpp new file mode 100644 index 00000000..334b4d85 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_1nn.cpp @@ -0,0 +1,24 @@ +#include +#include + +using namespace std; +using namespace Eigen; + +int main() +{ + Eigen::MatrixXf m(2,4); + Eigen::VectorXf v(2); + + m << 1, 23, 6, 9, + 3, 11, 7, 2; + + v << 2, + 3; + + MatrixXf::Index index; + // find nearest neighbour + (m.colwise() - v).colwise().squaredNorm().minCoeff(&index); + + cout << "Nearest neighbour is column " << index << ":" << endl; + cout << m.col(index) << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple.cpp new file mode 100644 index 00000000..e6c87c6a --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple.cpp @@ -0,0 +1,21 @@ +#include +#include + +using namespace std; +int main() +{ + Eigen::MatrixXf mat(2,4); + Eigen::VectorXf v(2); + + mat << 1, 2, 6, 9, + 3, 1, 7, 2; + + v << 0, + 1; + + //add v to each column of m + mat.colwise() += v; + + std::cout << "Broadcasting result: " << std::endl; + std::cout << mat << std::endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple_rowwise.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple_rowwise.cpp new file mode 100644 index 00000000..d87c96ab --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple_rowwise.cpp @@ -0,0 +1,20 @@ +#include +#include + +using namespace std; +int main() +{ + Eigen::MatrixXf mat(2,4); + Eigen::VectorXf v(4); + + mat << 1, 2, 6, 9, + 3, 1, 7, 2; + + v << 0,1,2,3; + + //add v to each row of m + mat.rowwise() += v.transpose(); + + std::cout << "Broadcasting result: " << std::endl; + std::cout << mat << std::endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_colwise.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_colwise.cpp new file mode 100644 index 00000000..df682566 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_colwise.cpp @@ -0,0 +1,13 @@ +#include +#include + +using namespace std; +int main() +{ + Eigen::MatrixXf mat(2,4); + mat << 1, 2, 6, 9, + 3, 1, 7, 2; + + std::cout << "Column's maximum: " << std::endl + << mat.colwise().maxCoeff() << std::endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_maxnorm.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_maxnorm.cpp new file mode 100644 index 00000000..049c747b --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_maxnorm.cpp @@ -0,0 +1,20 @@ +#include +#include + +using namespace std; +using namespace Eigen; +int main() +{ + MatrixXf mat(2,4); + mat << 1, 2, 6, 9, + 3, 1, 7, 2; + + MatrixXf::Index maxIndex; + float maxNorm = mat.colwise().sum().maxCoeff(&maxIndex); + + std::cout << "Maximum sum at position " << maxIndex << std::endl; + + std::cout << "The corresponding vector is: " << std::endl; + std::cout << mat.col( maxIndex ) << std::endl; + std::cout << "And its sum is is: " << maxNorm << std::endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_bool.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_bool.cpp new file mode 100644 index 00000000..0cca37f3 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_bool.cpp @@ -0,0 +1,21 @@ +#include +#include + +using namespace std; +using namespace Eigen; + +int main() +{ + ArrayXXf a(2,2); + + a << 1,2, + 3,4; + + cout << "(a > 0).all() = " << (a > 0).all() << endl; + cout << "(a > 0).any() = " << (a > 0).any() << endl; + cout << "(a > 0).count() = " << (a > 0).count() << endl; + cout << endl; + cout << "(a > 2).all() = " << (a > 2).all() << endl; + cout << "(a > 2).any() = " << (a > 2).any() << endl; + cout << "(a > 2).count() = " << (a > 2).count() << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_norm.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_norm.cpp new file mode 100644 index 00000000..740439fb --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_norm.cpp @@ -0,0 +1,28 @@ +#include +#include + +using namespace std; +using namespace Eigen; + +int main() +{ + VectorXf v(2); + MatrixXf m(2,2), n(2,2); + + v << -1, + 2; + + m << 1,-2, + -3,4; + + cout << "v.squaredNorm() = " << v.squaredNorm() << endl; + cout << "v.norm() = " << v.norm() << endl; + cout << "v.lpNorm<1>() = " << v.lpNorm<1>() << endl; + cout << "v.lpNorm() = " << v.lpNorm() << endl; + + cout << endl; + cout << "m.squaredNorm() = " << m.squaredNorm() << endl; + cout << "m.norm() = " << m.norm() << endl; + cout << "m.lpNorm<1>() = " << m.lpNorm<1>() << endl; + cout << "m.lpNorm() = " << m.lpNorm() << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_operatornorm.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_operatornorm.cpp new file mode 100644 index 00000000..62e28fc3 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_operatornorm.cpp @@ -0,0 +1,18 @@ +#include +#include + +using namespace Eigen; +using namespace std; + +int main() +{ + MatrixXf m(2,2); + m << 1,-2, + -3,4; + + cout << "1-norm(m) = " << m.cwiseAbs().colwise().sum().maxCoeff() + << " == " << m.colwise().lpNorm<1>().maxCoeff() << endl; + + cout << "infty-norm(m) = " << m.cwiseAbs().rowwise().sum().maxCoeff() + << " == " << m.rowwise().lpNorm<1>().maxCoeff() << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_rowwise.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_rowwise.cpp new file mode 100644 index 00000000..80427c9f --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_rowwise.cpp @@ -0,0 +1,13 @@ +#include +#include + +using namespace std; +int main() +{ + Eigen::MatrixXf mat(2,4); + mat << 1, 2, 6, 9, + 3, 1, 7, 2; + + std::cout << "Row's maximum: " << std::endl + << mat.rowwise().maxCoeff() << std::endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_visitors.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_visitors.cpp new file mode 100644 index 00000000..b54e9aa3 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_visitors.cpp @@ -0,0 +1,26 @@ +#include +#include + +using namespace std; +using namespace Eigen; + +int main() +{ + Eigen::MatrixXf m(2,2); + + m << 1, 2, + 3, 4; + + //get location of maximum + MatrixXf::Index maxRow, maxCol; + float max = m.maxCoeff(&maxRow, &maxCol); + + //get location of minimum + MatrixXf::Index minRow, minCol; + float min = m.minCoeff(&minRow, &minCol); + + cout << "Max: " << max << ", at: " << + maxRow << "," << maxCol << endl; + cout << "Min: " << min << ", at: " << + minRow << "," << minCol << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/Tutorial_simple_example_dynamic_size.cpp b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_simple_example_dynamic_size.cpp new file mode 100644 index 00000000..0f0280e0 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/Tutorial_simple_example_dynamic_size.cpp @@ -0,0 +1,22 @@ +#include +#include + +using namespace Eigen; + +int main() +{ + for (int size=1; size<=4; ++size) + { + MatrixXi m(size,size+1); // a (size)x(size+1)-matrix of int's + for (int j=0; j +#include + +using namespace Eigen; + +int main() +{ + Matrix3f m3; + m3 << 1, 2, 3, 4, 5, 6, 7, 8, 9; + Matrix4f m4 = Matrix4f::Identity(); + Vector4i v4(1, 2, 3, 4); + + std::cout << "m3\n" << m3 << "\nm4:\n" + << m4 << "\nv4:\n" << v4 << std::endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/class_Block.cpp b/testbed/nanogui/ext/eigen/doc/examples/class_Block.cpp new file mode 100644 index 00000000..ace719af --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/class_Block.cpp @@ -0,0 +1,27 @@ +#include +#include +using namespace Eigen; +using namespace std; + +template +Eigen::Block +topLeftCorner(MatrixBase& m, int rows, int cols) +{ + return Eigen::Block(m.derived(), 0, 0, rows, cols); +} + +template +const Eigen::Block +topLeftCorner(const MatrixBase& m, int rows, int cols) +{ + return Eigen::Block(m.derived(), 0, 0, rows, cols); +} + +int main(int, char**) +{ + Matrix4d m = Matrix4d::Identity(); + cout << topLeftCorner(4*m, 2, 3) << endl; // calls the const version + topLeftCorner(m, 2, 3) *= 5; // calls the non-const version + cout << "Now the matrix m is:" << endl << m << endl; + return 0; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/class_CwiseBinaryOp.cpp b/testbed/nanogui/ext/eigen/doc/examples/class_CwiseBinaryOp.cpp new file mode 100644 index 00000000..682af46d --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/class_CwiseBinaryOp.cpp @@ -0,0 +1,18 @@ +#include +#include +using namespace Eigen; +using namespace std; + +// define a custom template binary functor +template struct MakeComplexOp { + EIGEN_EMPTY_STRUCT_CTOR(MakeComplexOp) + typedef complex result_type; + complex operator()(const Scalar& a, const Scalar& b) const { return complex(a,b); } +}; + +int main(int, char**) +{ + Matrix4d m1 = Matrix4d::Random(), m2 = Matrix4d::Random(); + cout << m1.binaryExpr(m2, MakeComplexOp()) << endl; + return 0; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/class_CwiseUnaryOp.cpp b/testbed/nanogui/ext/eigen/doc/examples/class_CwiseUnaryOp.cpp new file mode 100644 index 00000000..a5fcc153 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/class_CwiseUnaryOp.cpp @@ -0,0 +1,19 @@ +#include +#include +using namespace Eigen; +using namespace std; + +// define a custom template unary functor +template +struct CwiseClampOp { + CwiseClampOp(const Scalar& inf, const Scalar& sup) : m_inf(inf), m_sup(sup) {} + const Scalar operator()(const Scalar& x) const { return xm_sup ? m_sup : x); } + Scalar m_inf, m_sup; +}; + +int main(int, char**) +{ + Matrix4d m1 = Matrix4d::Random(); + cout << m1 << endl << "becomes: " << endl << m1.unaryExpr(CwiseClampOp(-0.5,0.5)) << endl; + return 0; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/class_CwiseUnaryOp_ptrfun.cpp b/testbed/nanogui/ext/eigen/doc/examples/class_CwiseUnaryOp_ptrfun.cpp new file mode 100644 index 00000000..36706d8e --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/class_CwiseUnaryOp_ptrfun.cpp @@ -0,0 +1,20 @@ +#include +#include +using namespace Eigen; +using namespace std; + +// define function to be applied coefficient-wise +double ramp(double x) +{ + if (x > 0) + return x; + else + return 0; +} + +int main(int, char**) +{ + Matrix4d m1 = Matrix4d::Random(); + cout << m1 << endl << "becomes: " << endl << m1.unaryExpr(ptr_fun(ramp)) << endl; + return 0; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/class_FixedBlock.cpp b/testbed/nanogui/ext/eigen/doc/examples/class_FixedBlock.cpp new file mode 100644 index 00000000..9978b32e --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/class_FixedBlock.cpp @@ -0,0 +1,27 @@ +#include +#include +using namespace Eigen; +using namespace std; + +template +Eigen::Block +topLeft2x2Corner(MatrixBase& m) +{ + return Eigen::Block(m.derived(), 0, 0); +} + +template +const Eigen::Block +topLeft2x2Corner(const MatrixBase& m) +{ + return Eigen::Block(m.derived(), 0, 0); +} + +int main(int, char**) +{ + Matrix3d m = Matrix3d::Identity(); + cout << topLeft2x2Corner(4*m) << endl; // calls the const version + topLeft2x2Corner(m) *= 2; // calls the non-const version + cout << "Now the matrix m is:" << endl << m << endl; + return 0; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/class_FixedVectorBlock.cpp b/testbed/nanogui/ext/eigen/doc/examples/class_FixedVectorBlock.cpp new file mode 100644 index 00000000..c88c9fbf --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/class_FixedVectorBlock.cpp @@ -0,0 +1,27 @@ +#include +#include +using namespace Eigen; +using namespace std; + +template +Eigen::VectorBlock +firstTwo(MatrixBase& v) +{ + return Eigen::VectorBlock(v.derived(), 0); +} + +template +const Eigen::VectorBlock +firstTwo(const MatrixBase& v) +{ + return Eigen::VectorBlock(v.derived(), 0); +} + +int main(int, char**) +{ + Matrix v; v << 1,2,3,4,5,6; + cout << firstTwo(4*v) << endl; // calls the const version + firstTwo(v) *= 2; // calls the non-const version + cout << "Now the vector v is:" << endl << v << endl; + return 0; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/class_VectorBlock.cpp b/testbed/nanogui/ext/eigen/doc/examples/class_VectorBlock.cpp new file mode 100644 index 00000000..dc213df2 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/class_VectorBlock.cpp @@ -0,0 +1,27 @@ +#include +#include +using namespace Eigen; +using namespace std; + +template +Eigen::VectorBlock +segmentFromRange(MatrixBase& v, int start, int end) +{ + return Eigen::VectorBlock(v.derived(), start, end-start); +} + +template +const Eigen::VectorBlock +segmentFromRange(const MatrixBase& v, int start, int end) +{ + return Eigen::VectorBlock(v.derived(), start, end-start); +} + +int main(int, char**) +{ + Matrix v; v << 1,2,3,4,5,6; + cout << segmentFromRange(2*v, 2, 4) << endl; // calls the const version + segmentFromRange(v, 1, 3) *= 5; // calls the non-const version + cout << "Now the vector v is:" << endl << v << endl; + return 0; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/function_taking_eigenbase.cpp b/testbed/nanogui/ext/eigen/doc/examples/function_taking_eigenbase.cpp new file mode 100644 index 00000000..49d94b3d --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/function_taking_eigenbase.cpp @@ -0,0 +1,18 @@ +#include +#include +using namespace Eigen; + +template +void print_size(const EigenBase& b) +{ + std::cout << "size (rows, cols): " << b.size() << " (" << b.rows() + << ", " << b.cols() << ")" << std::endl; +} + +int main() +{ + Vector3f v; + print_size(v); + // v.asDiagonal() returns a 3x3 diagonal matrix pseudo-expression + print_size(v.asDiagonal()); +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/function_taking_ref.cpp b/testbed/nanogui/ext/eigen/doc/examples/function_taking_ref.cpp new file mode 100644 index 00000000..162a202e --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/function_taking_ref.cpp @@ -0,0 +1,19 @@ +#include +#include +using namespace Eigen; +using namespace std; + +float inv_cond(const Ref& a) +{ + const VectorXf sing_vals = a.jacobiSvd().singularValues(); + return sing_vals(sing_vals.size()-1) / sing_vals(0); +} + +int main() +{ + Matrix4f m = Matrix4f::Random(); + cout << "matrix m:" << endl << m << endl << endl; + cout << "inv_cond(m): " << inv_cond(m) << endl; + cout << "inv_cond(m(1:3,1:3)): " << inv_cond(m.topLeftCorner(3,3)) << endl; + cout << "inv_cond(m+I): " << inv_cond(m+Matrix4f::Identity()) << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp b/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp new file mode 100644 index 00000000..92e6aaa2 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp @@ -0,0 +1,11 @@ +/* +This program is presented in several fragments in the doc page. +Every fragment is in its own file; this file simply combines them. +*/ + +#include "make_circulant.cpp.preamble" +#include "make_circulant.cpp.traits" +#include "make_circulant.cpp.expression" +#include "make_circulant.cpp.evaluator" +#include "make_circulant.cpp.entry" +#include "make_circulant.cpp.main" diff --git a/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.entry b/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.entry new file mode 100644 index 00000000..f9d2eb8a --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.entry @@ -0,0 +1,5 @@ +template +Circulant makeCirculant(const Eigen::MatrixBase& arg) +{ + return Circulant(arg.derived()); +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.evaluator b/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.evaluator new file mode 100644 index 00000000..2ba79e78 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.evaluator @@ -0,0 +1,32 @@ +namespace Eigen { + namespace internal { + template + struct evaluator > + : evaluator_base > + { + typedef Circulant XprType; + typedef typename nested_eval::type ArgTypeNested; + typedef typename remove_all::type ArgTypeNestedCleaned; + typedef typename XprType::CoeffReturnType CoeffReturnType; + + enum { + CoeffReadCost = evaluator::CoeffReadCost, + Flags = Eigen::ColMajor + }; + + evaluator(const XprType& xpr) + : m_argImpl(xpr.m_arg), m_rows(xpr.rows()) + { } + + CoeffReturnType coeff(Index row, Index col) const + { + Index index = row - col; + if (index < 0) index += m_rows; + return m_argImpl.coeff(index); + } + + evaluator m_argImpl; + const Index m_rows; + }; + } +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.expression b/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.expression new file mode 100644 index 00000000..380cd445 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.expression @@ -0,0 +1,20 @@ +template +class Circulant : public Eigen::MatrixBase > +{ +public: + Circulant(const ArgType& arg) + : m_arg(arg) + { + EIGEN_STATIC_ASSERT(ArgType::ColsAtCompileTime == 1, + YOU_TRIED_CALLING_A_VECTOR_METHOD_ON_A_MATRIX); + } + + typedef typename Eigen::internal::ref_selector::type Nested; + + typedef Eigen::Index Index; + Index rows() const { return m_arg.rows(); } + Index cols() const { return m_arg.rows(); } + + typedef typename Eigen::internal::ref_selector::type ArgTypeNested; + ArgTypeNested m_arg; +}; diff --git a/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.main b/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.main new file mode 100644 index 00000000..877f97f6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.main @@ -0,0 +1,8 @@ +int main() +{ + Eigen::VectorXd vec(4); + vec << 1, 2, 4, 8; + Eigen::MatrixXd mat; + mat = makeCirculant(vec); + std::cout << mat << std::endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.preamble b/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.preamble new file mode 100644 index 00000000..e575cce1 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.preamble @@ -0,0 +1,4 @@ +#include +#include + +template class Circulant; diff --git a/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.traits b/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.traits new file mode 100644 index 00000000..4e04535d --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/make_circulant.cpp.traits @@ -0,0 +1,19 @@ +namespace Eigen { + namespace internal { + template + struct traits > + { + typedef Eigen::Dense StorageKind; + typedef Eigen::MatrixXpr XprKind; + typedef typename ArgType::StorageIndex StorageIndex; + typedef typename ArgType::Scalar Scalar; + enum { + Flags = Eigen::ColMajor, + RowsAtCompileTime = ArgType::RowsAtCompileTime, + ColsAtCompileTime = ArgType::RowsAtCompileTime, + MaxRowsAtCompileTime = ArgType::MaxRowsAtCompileTime, + MaxColsAtCompileTime = ArgType::MaxRowsAtCompileTime + }; + }; + } +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/make_circulant2.cpp b/testbed/nanogui/ext/eigen/doc/examples/make_circulant2.cpp new file mode 100644 index 00000000..95d3dd31 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/make_circulant2.cpp @@ -0,0 +1,52 @@ +#include +#include + +using namespace Eigen; + +// [circulant_func] +template +class circulant_functor { + const ArgType &m_vec; +public: + circulant_functor(const ArgType& arg) : m_vec(arg) {} + + const typename ArgType::Scalar& operator() (Index row, Index col) const { + Index index = row - col; + if (index < 0) index += m_vec.size(); + return m_vec(index); + } +}; +// [circulant_func] + +// [square] +template +struct circulant_helper { + typedef Matrix MatrixType; +}; +// [square] + +// [makeCirculant] +template +CwiseNullaryOp, typename circulant_helper::MatrixType> +makeCirculant(const Eigen::MatrixBase& arg) +{ + typedef typename circulant_helper::MatrixType MatrixType; + return MatrixType::NullaryExpr(arg.size(), arg.size(), circulant_functor(arg.derived())); +} +// [makeCirculant] + +// [main] +int main() +{ + Eigen::VectorXd vec(4); + vec << 1, 2, 4, 8; + Eigen::MatrixXd mat; + mat = makeCirculant(vec); + std::cout << mat << std::endl; +} +// [main] diff --git a/testbed/nanogui/ext/eigen/doc/examples/matrixfree_cg.cpp b/testbed/nanogui/ext/eigen/doc/examples/matrixfree_cg.cpp new file mode 100644 index 00000000..6a205aea --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/matrixfree_cg.cpp @@ -0,0 +1,128 @@ +#include +#include +#include +#include +#include + +class MatrixReplacement; +using Eigen::SparseMatrix; + +namespace Eigen { +namespace internal { + // MatrixReplacement looks-like a SparseMatrix, so let's inherits its traits: + template<> + struct traits : public Eigen::internal::traits > + {}; +} +} + +// Example of a matrix-free wrapper from a user type to Eigen's compatible type +// For the sake of simplicity, this example simply wrap a Eigen::SparseMatrix. +class MatrixReplacement : public Eigen::EigenBase { +public: + // Required typedefs, constants, and method: + typedef double Scalar; + typedef double RealScalar; + typedef int StorageIndex; + enum { + ColsAtCompileTime = Eigen::Dynamic, + MaxColsAtCompileTime = Eigen::Dynamic, + IsRowMajor = false + }; + + Index rows() const { return mp_mat->rows(); } + Index cols() const { return mp_mat->cols(); } + + template + Eigen::Product operator*(const Eigen::MatrixBase& x) const { + return Eigen::Product(*this, x.derived()); + } + + // Custom API: + MatrixReplacement() : mp_mat(0) {} + + void attachMyMatrix(const SparseMatrix &mat) { + mp_mat = &mat; + } + const SparseMatrix my_matrix() const { return *mp_mat; } + +private: + const SparseMatrix *mp_mat; +}; + + +// Implementation of MatrixReplacement * Eigen::DenseVector though a specialization of internal::generic_product_impl: +namespace Eigen { +namespace internal { + + template + struct generic_product_impl // GEMV stands for matrix-vector + : generic_product_impl_base > + { + typedef typename Product::Scalar Scalar; + + template + static void scaleAndAddTo(Dest& dst, const MatrixReplacement& lhs, const Rhs& rhs, const Scalar& alpha) + { + // This method should implement "dst += alpha * lhs * rhs" inplace, + // however, for iterative solvers, alpha is always equal to 1, so let's not bother about it. + assert(alpha==Scalar(1) && "scaling is not implemented"); + + // Here we could simply call dst.noalias() += lhs.my_matrix() * rhs, + // but let's do something fancier (and less efficient): + for(Index i=0; i S = Eigen::MatrixXd::Random(n,n).sparseView(0.5,1); + S = S.transpose()*S; + + MatrixReplacement A; + A.attachMyMatrix(S); + + Eigen::VectorXd b(n), x; + b.setRandom(); + + // Solve Ax = b using various iterative solver with matrix-free version: + { + Eigen::ConjugateGradient cg; + cg.compute(A); + x = cg.solve(b); + std::cout << "CG: #iterations: " << cg.iterations() << ", estimated error: " << cg.error() << std::endl; + } + + { + Eigen::BiCGSTAB bicg; + bicg.compute(A); + x = bicg.solve(b); + std::cout << "BiCGSTAB: #iterations: " << bicg.iterations() << ", estimated error: " << bicg.error() << std::endl; + } + + { + Eigen::GMRES gmres; + gmres.compute(A); + x = gmres.solve(b); + std::cout << "GMRES: #iterations: " << gmres.iterations() << ", estimated error: " << gmres.error() << std::endl; + } + + { + Eigen::DGMRES gmres; + gmres.compute(A); + x = gmres.solve(b); + std::cout << "DGMRES: #iterations: " << gmres.iterations() << ", estimated error: " << gmres.error() << std::endl; + } + + { + Eigen::MINRES minres; + minres.compute(A); + x = minres.solve(b); + std::cout << "MINRES: #iterations: " << minres.iterations() << ", estimated error: " << minres.error() << std::endl; + } +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/nullary_indexing.cpp b/testbed/nanogui/ext/eigen/doc/examples/nullary_indexing.cpp new file mode 100644 index 00000000..e27c3585 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/nullary_indexing.cpp @@ -0,0 +1,66 @@ +#include +#include + +using namespace Eigen; + +// [functor] +template +class indexing_functor { + const ArgType &m_arg; + const RowIndexType &m_rowIndices; + const ColIndexType &m_colIndices; +public: + typedef Matrix MatrixType; + + indexing_functor(const ArgType& arg, const RowIndexType& row_indices, const ColIndexType& col_indices) + : m_arg(arg), m_rowIndices(row_indices), m_colIndices(col_indices) + {} + + const typename ArgType::Scalar& operator() (Index row, Index col) const { + return m_arg(m_rowIndices[row], m_colIndices[col]); + } +}; +// [functor] + +// [function] +template +CwiseNullaryOp, typename indexing_functor::MatrixType> +indexing(const Eigen::MatrixBase& arg, const RowIndexType& row_indices, const ColIndexType& col_indices) +{ + typedef indexing_functor Func; + typedef typename Func::MatrixType MatrixType; + return MatrixType::NullaryExpr(row_indices.size(), col_indices.size(), Func(arg.derived(), row_indices, col_indices)); +} +// [function] + + +int main() +{ + std::cout << "[main1]\n"; + Eigen::MatrixXi A = Eigen::MatrixXi::Random(4,4); + Array3i ri(1,2,1); + ArrayXi ci(6); ci << 3,2,1,0,0,2; + Eigen::MatrixXi B = indexing(A, ri, ci); + std::cout << "A =" << std::endl; + std::cout << A << std::endl << std::endl; + std::cout << "A([" << ri.transpose() << "], [" << ci.transpose() << "]) =" << std::endl; + std::cout << B << std::endl; + std::cout << "[main1]\n"; + + std::cout << "[main2]\n"; + B = indexing(A, ri+1, ci); + std::cout << "A(ri+1,ci) =" << std::endl; + std::cout << B << std::endl << std::endl; +#if __cplusplus >= 201103L + B = indexing(A, ArrayXi::LinSpaced(13,0,12).unaryExpr([](int x){return x%4;}), ArrayXi::LinSpaced(4,0,3)); + std::cout << "A(ArrayXi::LinSpaced(13,0,12).unaryExpr([](int x){return x%4;}), ArrayXi::LinSpaced(4,0,3)) =" << std::endl; + std::cout << B << std::endl << std::endl; +#endif + std::cout << "[main2]\n"; +} + diff --git a/testbed/nanogui/ext/eigen/doc/examples/tut_arithmetic_add_sub.cpp b/testbed/nanogui/ext/eigen/doc/examples/tut_arithmetic_add_sub.cpp new file mode 100644 index 00000000..e97477b6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/tut_arithmetic_add_sub.cpp @@ -0,0 +1,22 @@ +#include +#include + +using namespace Eigen; + +int main() +{ + Matrix2d a; + a << 1, 2, + 3, 4; + MatrixXd b(2,2); + b << 2, 3, + 1, 4; + std::cout << "a + b =\n" << a + b << std::endl; + std::cout << "a - b =\n" << a - b << std::endl; + std::cout << "Doing a += b;" << std::endl; + a += b; + std::cout << "Now a =\n" << a << std::endl; + Vector3d v(1,2,3); + Vector3d w(1,0,0); + std::cout << "-v + w - v =\n" << -v + w - v << std::endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/tut_arithmetic_dot_cross.cpp b/testbed/nanogui/ext/eigen/doc/examples/tut_arithmetic_dot_cross.cpp new file mode 100644 index 00000000..631c9a5e --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/tut_arithmetic_dot_cross.cpp @@ -0,0 +1,15 @@ +#include +#include + +using namespace Eigen; +using namespace std; +int main() +{ + Vector3d v(1,2,3); + Vector3d w(0,1,2); + + cout << "Dot product: " << v.dot(w) << endl; + double dp = v.adjoint()*w; // automatic conversion of the inner product to a scalar + cout << "Dot product via a matrix product: " << dp << endl; + cout << "Cross product:\n" << v.cross(w) << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/tut_arithmetic_matrix_mul.cpp b/testbed/nanogui/ext/eigen/doc/examples/tut_arithmetic_matrix_mul.cpp new file mode 100644 index 00000000..f2139024 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/tut_arithmetic_matrix_mul.cpp @@ -0,0 +1,19 @@ +#include +#include + +using namespace Eigen; +int main() +{ + Matrix2d mat; + mat << 1, 2, + 3, 4; + Vector2d u(-1,1), v(2,0); + std::cout << "Here is mat*mat:\n" << mat*mat << std::endl; + std::cout << "Here is mat*u:\n" << mat*u << std::endl; + std::cout << "Here is u^T*mat:\n" << u.transpose()*mat << std::endl; + std::cout << "Here is u^T*v:\n" << u.transpose()*v << std::endl; + std::cout << "Here is u*v^T:\n" << u*v.transpose() << std::endl; + std::cout << "Let's multiply mat by itself" << std::endl; + mat = mat*mat; + std::cout << "Now mat is mat:\n" << mat << std::endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/tut_arithmetic_redux_basic.cpp b/testbed/nanogui/ext/eigen/doc/examples/tut_arithmetic_redux_basic.cpp new file mode 100644 index 00000000..5632fb52 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/tut_arithmetic_redux_basic.cpp @@ -0,0 +1,16 @@ +#include +#include + +using namespace std; +int main() +{ + Eigen::Matrix2d mat; + mat << 1, 2, + 3, 4; + cout << "Here is mat.sum(): " << mat.sum() << endl; + cout << "Here is mat.prod(): " << mat.prod() << endl; + cout << "Here is mat.mean(): " << mat.mean() << endl; + cout << "Here is mat.minCoeff(): " << mat.minCoeff() << endl; + cout << "Here is mat.maxCoeff(): " << mat.maxCoeff() << endl; + cout << "Here is mat.trace(): " << mat.trace() << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/tut_arithmetic_scalar_mul_div.cpp b/testbed/nanogui/ext/eigen/doc/examples/tut_arithmetic_scalar_mul_div.cpp new file mode 100644 index 00000000..d5f65b53 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/tut_arithmetic_scalar_mul_div.cpp @@ -0,0 +1,17 @@ +#include +#include + +using namespace Eigen; + +int main() +{ + Matrix2d a; + a << 1, 2, + 3, 4; + Vector3d v(1,2,3); + std::cout << "a * 2.5 =\n" << a * 2.5 << std::endl; + std::cout << "0.1 * v =\n" << 0.1 * v << std::endl; + std::cout << "Doing v *= 2;" << std::endl; + v *= 2; + std::cout << "Now v =\n" << v << std::endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/tut_matrix_coefficient_accessors.cpp b/testbed/nanogui/ext/eigen/doc/examples/tut_matrix_coefficient_accessors.cpp new file mode 100644 index 00000000..c2da1715 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/tut_matrix_coefficient_accessors.cpp @@ -0,0 +1,18 @@ +#include +#include + +using namespace Eigen; + +int main() +{ + MatrixXd m(2,2); + m(0,0) = 3; + m(1,0) = 2.5; + m(0,1) = -1; + m(1,1) = m(1,0) + m(0,1); + std::cout << "Here is the matrix m:\n" << m << std::endl; + VectorXd v(2); + v(0) = 4; + v(1) = v(0) - 1; + std::cout << "Here is the vector v:\n" << v << std::endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/tut_matrix_resize.cpp b/testbed/nanogui/ext/eigen/doc/examples/tut_matrix_resize.cpp new file mode 100644 index 00000000..0392c3aa --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/tut_matrix_resize.cpp @@ -0,0 +1,18 @@ +#include +#include + +using namespace Eigen; + +int main() +{ + MatrixXd m(2,5); + m.resize(4,3); + std::cout << "The matrix m is of size " + << m.rows() << "x" << m.cols() << std::endl; + std::cout << "It has " << m.size() << " coefficients" << std::endl; + VectorXd v(2); + v.resize(5); + std::cout << "The vector v is of size " << v.size() << std::endl; + std::cout << "As a matrix, v is of size " + << v.rows() << "x" << v.cols() << std::endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/examples/tut_matrix_resize_fixed_size.cpp b/testbed/nanogui/ext/eigen/doc/examples/tut_matrix_resize_fixed_size.cpp new file mode 100644 index 00000000..dcbdfa78 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/examples/tut_matrix_resize_fixed_size.cpp @@ -0,0 +1,12 @@ +#include +#include + +using namespace Eigen; + +int main() +{ + Matrix4d m; + m.resize(4,4); // no operation + std::cout << "The matrix m is of size " + << m.rows() << "x" << m.cols() << std::endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/ftv2node.png b/testbed/nanogui/ext/eigen/doc/ftv2node.png new file mode 100644 index 0000000000000000000000000000000000000000..63c605bb4c3d941c921a4b6cfa74951e946bcb48 GIT binary patch literal 86 zcmeAS@N?(olHy`uVBq!ia0vp^0zfRr!3HExu9B$%QnH>djv*C{Z|`mdau^P8_z}#X h?B8GEpdi4(BFDx$je&7RrDQEg&ePS;Wt~$(69Dh@6T1Ka literal 0 HcmV?d00001 diff --git a/testbed/nanogui/ext/eigen/doc/ftv2pnode.png b/testbed/nanogui/ext/eigen/doc/ftv2pnode.png new file mode 100644 index 0000000000000000000000000000000000000000..c6ee22f937a07d1dbfc27c669d11f8ed13e2f152 GIT binary patch literal 229 zcmV^P)R?RzRoKvklcaQ%HF6%rK2&ZgO(-ihJ_C zzrKgp4jgO( fd_(yg|3PpEQb#9`a?Pz_00000NkvXXu0mjftR`5K literal 0 HcmV?d00001 diff --git a/testbed/nanogui/ext/eigen/doc/snippets/.krazy b/testbed/nanogui/ext/eigen/doc/snippets/.krazy new file mode 100644 index 00000000..00b99405 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/.krazy @@ -0,0 +1,2 @@ +EXCLUDE copyright +EXCLUDE license diff --git a/testbed/nanogui/ext/eigen/doc/snippets/AngleAxis_mimic_euler.cpp b/testbed/nanogui/ext/eigen/doc/snippets/AngleAxis_mimic_euler.cpp new file mode 100644 index 00000000..456de7f7 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/AngleAxis_mimic_euler.cpp @@ -0,0 +1,5 @@ +Matrix3f m; +m = AngleAxisf(0.25*M_PI, Vector3f::UnitX()) + * AngleAxisf(0.5*M_PI, Vector3f::UnitY()) + * AngleAxisf(0.33*M_PI, Vector3f::UnitZ()); +cout << m << endl << "is unitary: " << m.isUnitary() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/BiCGSTAB_simple.cpp b/testbed/nanogui/ext/eigen/doc/snippets/BiCGSTAB_simple.cpp new file mode 100644 index 00000000..5520f4f1 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/BiCGSTAB_simple.cpp @@ -0,0 +1,11 @@ + int n = 10000; + VectorXd x(n), b(n); + SparseMatrix A(n,n); + /* ... fill A and b ... */ + BiCGSTAB > solver; + solver.compute(A); + x = solver.solve(b); + std::cout << "#iterations: " << solver.iterations() << std::endl; + std::cout << "estimated error: " << solver.error() << std::endl; + /* ... update b ... */ + x = solver.solve(b); // solve again \ No newline at end of file diff --git a/testbed/nanogui/ext/eigen/doc/snippets/BiCGSTAB_step_by_step.cpp b/testbed/nanogui/ext/eigen/doc/snippets/BiCGSTAB_step_by_step.cpp new file mode 100644 index 00000000..06147bb8 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/BiCGSTAB_step_by_step.cpp @@ -0,0 +1,14 @@ + int n = 10000; + VectorXd x(n), b(n); + SparseMatrix A(n,n); + /* ... fill A and b ... */ + BiCGSTAB > solver(A); + // start from a random solution + x = VectorXd::Random(n); + solver.setMaxIterations(1); + int i = 0; + do { + x = solver.solveWithGuess(b,x); + std::cout << i << " : " << solver.error() << std::endl; + ++i; + } while (solver.info()!=Success && i<100); \ No newline at end of file diff --git a/testbed/nanogui/ext/eigen/doc/snippets/CMakeLists.txt b/testbed/nanogui/ext/eigen/doc/snippets/CMakeLists.txt new file mode 100644 index 00000000..1baf32fb --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/CMakeLists.txt @@ -0,0 +1,26 @@ +file(GLOB snippets_SRCS "*.cpp") + +add_custom_target(all_snippets) + +foreach(snippet_src ${snippets_SRCS}) + get_filename_component(snippet ${snippet_src} NAME_WE) + set(compile_snippet_target compile_${snippet}) + set(compile_snippet_src ${compile_snippet_target}.cpp) + file(READ ${snippet_src} snippet_source_code) + configure_file(${CMAKE_CURRENT_SOURCE_DIR}/compile_snippet.cpp.in + ${CMAKE_CURRENT_BINARY_DIR}/${compile_snippet_src}) + add_executable(${compile_snippet_target} + ${CMAKE_CURRENT_BINARY_DIR}/${compile_snippet_src}) + if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO) + target_link_libraries(${compile_snippet_target} ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO}) + endif() + add_custom_command( + TARGET ${compile_snippet_target} + POST_BUILD + COMMAND ${compile_snippet_target} + ARGS >${CMAKE_CURRENT_BINARY_DIR}/${snippet}.out + ) + add_dependencies(all_snippets ${compile_snippet_target}) + set_source_files_properties(${CMAKE_CURRENT_BINARY_DIR}/${compile_snippet_src} + PROPERTIES OBJECT_DEPENDS ${snippet_src}) +endforeach(snippet_src) diff --git a/testbed/nanogui/ext/eigen/doc/snippets/ColPivHouseholderQR_solve.cpp b/testbed/nanogui/ext/eigen/doc/snippets/ColPivHouseholderQR_solve.cpp new file mode 100644 index 00000000..b7b204a1 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/ColPivHouseholderQR_solve.cpp @@ -0,0 +1,8 @@ +Matrix3f m = Matrix3f::Random(); +Matrix3f y = Matrix3f::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is the matrix y:" << endl << y << endl; +Matrix3f x; +x = m.colPivHouseholderQr().solve(y); +assert(y.isApprox(m*x)); +cout << "Here is a solution x to the equation mx=y:" << endl << x << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/ComplexEigenSolver_compute.cpp b/testbed/nanogui/ext/eigen/doc/snippets/ComplexEigenSolver_compute.cpp new file mode 100644 index 00000000..11d6bd39 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/ComplexEigenSolver_compute.cpp @@ -0,0 +1,16 @@ +MatrixXcf A = MatrixXcf::Random(4,4); +cout << "Here is a random 4x4 matrix, A:" << endl << A << endl << endl; + +ComplexEigenSolver ces; +ces.compute(A); +cout << "The eigenvalues of A are:" << endl << ces.eigenvalues() << endl; +cout << "The matrix of eigenvectors, V, is:" << endl << ces.eigenvectors() << endl << endl; + +complex lambda = ces.eigenvalues()[0]; +cout << "Consider the first eigenvalue, lambda = " << lambda << endl; +VectorXcf v = ces.eigenvectors().col(0); +cout << "If v is the corresponding eigenvector, then lambda * v = " << endl << lambda * v << endl; +cout << "... and A * v = " << endl << A * v << endl << endl; + +cout << "Finally, V * D * V^(-1) = " << endl + << ces.eigenvectors() * ces.eigenvalues().asDiagonal() * ces.eigenvectors().inverse() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/ComplexEigenSolver_eigenvalues.cpp b/testbed/nanogui/ext/eigen/doc/snippets/ComplexEigenSolver_eigenvalues.cpp new file mode 100644 index 00000000..5509bd89 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/ComplexEigenSolver_eigenvalues.cpp @@ -0,0 +1,4 @@ +MatrixXcf ones = MatrixXcf::Ones(3,3); +ComplexEigenSolver ces(ones, /* computeEigenvectors = */ false); +cout << "The eigenvalues of the 3x3 matrix of ones are:" + << endl << ces.eigenvalues() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/ComplexEigenSolver_eigenvectors.cpp b/testbed/nanogui/ext/eigen/doc/snippets/ComplexEigenSolver_eigenvectors.cpp new file mode 100644 index 00000000..bb1c2ccf --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/ComplexEigenSolver_eigenvectors.cpp @@ -0,0 +1,4 @@ +MatrixXcf ones = MatrixXcf::Ones(3,3); +ComplexEigenSolver ces(ones); +cout << "The first eigenvector of the 3x3 matrix of ones is:" + << endl << ces.eigenvectors().col(1) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/ComplexSchur_compute.cpp b/testbed/nanogui/ext/eigen/doc/snippets/ComplexSchur_compute.cpp new file mode 100644 index 00000000..3a517010 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/ComplexSchur_compute.cpp @@ -0,0 +1,6 @@ +MatrixXcf A = MatrixXcf::Random(4,4); +ComplexSchur schur(4); +schur.compute(A); +cout << "The matrix T in the decomposition of A is:" << endl << schur.matrixT() << endl; +schur.compute(A.inverse()); +cout << "The matrix T in the decomposition of A^(-1) is:" << endl << schur.matrixT() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/ComplexSchur_matrixT.cpp b/testbed/nanogui/ext/eigen/doc/snippets/ComplexSchur_matrixT.cpp new file mode 100644 index 00000000..8380571a --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/ComplexSchur_matrixT.cpp @@ -0,0 +1,4 @@ +MatrixXcf A = MatrixXcf::Random(4,4); +cout << "Here is a random 4x4 matrix, A:" << endl << A << endl << endl; +ComplexSchur schurOfA(A, false); // false means do not compute U +cout << "The triangular matrix T is:" << endl << schurOfA.matrixT() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/ComplexSchur_matrixU.cpp b/testbed/nanogui/ext/eigen/doc/snippets/ComplexSchur_matrixU.cpp new file mode 100644 index 00000000..ba3d9c22 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/ComplexSchur_matrixU.cpp @@ -0,0 +1,4 @@ +MatrixXcf A = MatrixXcf::Random(4,4); +cout << "Here is a random 4x4 matrix, A:" << endl << A << endl << endl; +ComplexSchur schurOfA(A); +cout << "The unitary matrix U is:" << endl << schurOfA.matrixU() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_abs.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_abs.cpp new file mode 100644 index 00000000..0aeec3a4 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_abs.cpp @@ -0,0 +1,2 @@ +Array3d v(1,-2,-3); +cout << v.abs() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_abs2.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_abs2.cpp new file mode 100644 index 00000000..2c4f9b34 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_abs2.cpp @@ -0,0 +1,2 @@ +Array3d v(1,-2,-3); +cout << v.abs2() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_acos.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_acos.cpp new file mode 100644 index 00000000..34432cba --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_acos.cpp @@ -0,0 +1,2 @@ +Array3d v(0, sqrt(2.)/2, 1); +cout << v.acos() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_arg.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_arg.cpp new file mode 100644 index 00000000..3f45133b --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_arg.cpp @@ -0,0 +1,3 @@ +ArrayXcf v = ArrayXcf::Random(3); +cout << v << endl << endl; +cout << arg(v) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_array_power_array.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_array_power_array.cpp new file mode 100644 index 00000000..432a76ee --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_array_power_array.cpp @@ -0,0 +1,4 @@ +Array x(8,25,3), + e(1./3.,0.5,2.); +cout << "[" << x << "]^[" << e << "] = " << x.pow(e) << endl; // using ArrayBase::pow +cout << "[" << x << "]^[" << e << "] = " << pow(x,e) << endl; // using Eigen::pow diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_asin.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_asin.cpp new file mode 100644 index 00000000..8dad838f --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_asin.cpp @@ -0,0 +1,2 @@ +Array3d v(0, sqrt(2.)/2, 1); +cout << v.asin() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_atan.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_atan.cpp new file mode 100644 index 00000000..44684472 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_atan.cpp @@ -0,0 +1,2 @@ +ArrayXd v = ArrayXd::LinSpaced(5,0,1); +cout << v.atan() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_boolean_and.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_boolean_and.cpp new file mode 100644 index 00000000..df6b60d9 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_boolean_and.cpp @@ -0,0 +1,2 @@ +Array3d v(-1,2,1), w(-3,2,3); +cout << ((vw) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_greater_equal.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_greater_equal.cpp new file mode 100644 index 00000000..6a08f894 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_greater_equal.cpp @@ -0,0 +1,2 @@ +Array3d v(1,2,3), w(3,2,1); +cout << (v>=w) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_inverse.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_inverse.cpp new file mode 100644 index 00000000..3967a7ec --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_inverse.cpp @@ -0,0 +1,2 @@ +Array3d v(2,3,4); +cout << v.inverse() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_isFinite.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_isFinite.cpp new file mode 100644 index 00000000..1da55fd1 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_isFinite.cpp @@ -0,0 +1,5 @@ +Array3d v(1,2,3); +v(1) *= 0.0/0.0; +v(2) /= 0.0; +cout << v << endl << endl; +cout << isfinite(v) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_isInf.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_isInf.cpp new file mode 100644 index 00000000..be793081 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_isInf.cpp @@ -0,0 +1,5 @@ +Array3d v(1,2,3); +v(1) *= 0.0/0.0; +v(2) /= 0.0; +cout << v << endl << endl; +cout << isinf(v) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_isNaN.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_isNaN.cpp new file mode 100644 index 00000000..7b2a9308 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_isNaN.cpp @@ -0,0 +1,5 @@ +Array3d v(1,2,3); +v(1) *= 0.0/0.0; +v(2) /= 0.0; +cout << v << endl << endl; +cout << isnan(v) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_less.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_less.cpp new file mode 100644 index 00000000..cafd3b6e --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_less.cpp @@ -0,0 +1,2 @@ +Array3d v(1,2,3), w(3,2,1); +cout << (v e(2,-3,1./3.); +cout << "10^[" << e << "] = " << pow(10,e) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_sign.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_sign.cpp new file mode 100644 index 00000000..49920e4f --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_sign.cpp @@ -0,0 +1,2 @@ +Array3d v(-3,5,0); +cout << v.sign() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_sin.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_sin.cpp new file mode 100644 index 00000000..46fa908c --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_sin.cpp @@ -0,0 +1,2 @@ +Array3d v(M_PI, M_PI/2, M_PI/3); +cout << v.sin() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_sinh.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_sinh.cpp new file mode 100644 index 00000000..fac9b19a --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_sinh.cpp @@ -0,0 +1,2 @@ +ArrayXd v = ArrayXd::LinSpaced(5,0,1); +cout << sinh(v) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_slash_equal.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_slash_equal.cpp new file mode 100644 index 00000000..2efd32d8 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_slash_equal.cpp @@ -0,0 +1,3 @@ +Array3d v(3,2,4), w(5,4,2); +v /= w; +cout << v << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_sqrt.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_sqrt.cpp new file mode 100644 index 00000000..97bafe8b --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_sqrt.cpp @@ -0,0 +1,2 @@ +Array3d v(1,2,4); +cout << v.sqrt() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_square.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_square.cpp new file mode 100644 index 00000000..f704c5e0 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_square.cpp @@ -0,0 +1,2 @@ +Array3d v(2,3,4); +cout << v.square() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_tan.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_tan.cpp new file mode 100644 index 00000000..b758ef04 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_tan.cpp @@ -0,0 +1,2 @@ +Array3d v(M_PI, M_PI/2, M_PI/3); +cout << v.tan() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_tanh.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_tanh.cpp new file mode 100644 index 00000000..30cd0450 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_tanh.cpp @@ -0,0 +1,2 @@ +ArrayXd v = ArrayXd::LinSpaced(5,0,1); +cout << tanh(v) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Cwise_times_equal.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_times_equal.cpp new file mode 100644 index 00000000..147556c7 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Cwise_times_equal.cpp @@ -0,0 +1,3 @@ +Array3d v(1,2,3), w(2,3,0); +v *= w; +cout << v << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/DenseBase_LinSpaced.cpp b/testbed/nanogui/ext/eigen/doc/snippets/DenseBase_LinSpaced.cpp new file mode 100644 index 00000000..8e54b17f --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/DenseBase_LinSpaced.cpp @@ -0,0 +1,2 @@ +cout << VectorXi::LinSpaced(4,7,10).transpose() << endl; +cout << VectorXd::LinSpaced(5,0.0,1.0).transpose() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/DenseBase_LinSpacedInt.cpp b/testbed/nanogui/ext/eigen/doc/snippets/DenseBase_LinSpacedInt.cpp new file mode 100644 index 00000000..0d7ae068 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/DenseBase_LinSpacedInt.cpp @@ -0,0 +1,8 @@ +cout << "Even spacing inputs:" << endl; +cout << VectorXi::LinSpaced(8,1,4).transpose() << endl; +cout << VectorXi::LinSpaced(8,1,8).transpose() << endl; +cout << VectorXi::LinSpaced(8,1,15).transpose() << endl; +cout << "Uneven spacing inputs:" << endl; +cout << VectorXi::LinSpaced(8,1,7).transpose() << endl; +cout << VectorXi::LinSpaced(8,1,9).transpose() << endl; +cout << VectorXi::LinSpaced(8,1,16).transpose() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/DenseBase_LinSpaced_seq.cpp b/testbed/nanogui/ext/eigen/doc/snippets/DenseBase_LinSpaced_seq.cpp new file mode 100644 index 00000000..f55c5085 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/DenseBase_LinSpaced_seq.cpp @@ -0,0 +1,2 @@ +cout << VectorXi::LinSpaced(Sequential,4,7,10).transpose() << endl; +cout << VectorXd::LinSpaced(Sequential,5,0.0,1.0).transpose() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/DenseBase_setLinSpaced.cpp b/testbed/nanogui/ext/eigen/doc/snippets/DenseBase_setLinSpaced.cpp new file mode 100644 index 00000000..46054f23 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/DenseBase_setLinSpaced.cpp @@ -0,0 +1,3 @@ +VectorXf v; +v.setLinSpaced(5,0.5f,1.5f); +cout << v << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/DirectionWise_hnormalized.cpp b/testbed/nanogui/ext/eigen/doc/snippets/DirectionWise_hnormalized.cpp new file mode 100644 index 00000000..3410790a --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/DirectionWise_hnormalized.cpp @@ -0,0 +1,7 @@ +typedef Matrix Matrix4Xd; +Matrix4Xd M = Matrix4Xd::Random(4,5); +Projective3d P(Matrix4d::Random()); +cout << "The matrix M is:" << endl << M << endl << endl; +cout << "M.colwise().hnormalized():" << endl << M.colwise().hnormalized() << endl << endl; +cout << "P*M:" << endl << P*M << endl << endl; +cout << "(P*M).colwise().hnormalized():" << endl << (P*M).colwise().hnormalized() << endl << endl; \ No newline at end of file diff --git a/testbed/nanogui/ext/eigen/doc/snippets/DirectionWise_replicate.cpp b/testbed/nanogui/ext/eigen/doc/snippets/DirectionWise_replicate.cpp new file mode 100644 index 00000000..d92d4a35 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/DirectionWise_replicate.cpp @@ -0,0 +1,4 @@ +MatrixXi m = MatrixXi::Random(2,3); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "m.colwise().replicate<3>() = ..." << endl; +cout << m.colwise().replicate<3>() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/DirectionWise_replicate_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/DirectionWise_replicate_int.cpp new file mode 100644 index 00000000..f9b1b535 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/DirectionWise_replicate_int.cpp @@ -0,0 +1,4 @@ +Vector3i v = Vector3i::Random(); +cout << "Here is the vector v:" << endl << v << endl; +cout << "v.rowwise().replicate(5) = ..." << endl; +cout << v.rowwise().replicate(5) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/EigenSolver_EigenSolver_MatrixType.cpp b/testbed/nanogui/ext/eigen/doc/snippets/EigenSolver_EigenSolver_MatrixType.cpp new file mode 100644 index 00000000..c1d9fa87 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/EigenSolver_EigenSolver_MatrixType.cpp @@ -0,0 +1,16 @@ +MatrixXd A = MatrixXd::Random(6,6); +cout << "Here is a random 6x6 matrix, A:" << endl << A << endl << endl; + +EigenSolver es(A); +cout << "The eigenvalues of A are:" << endl << es.eigenvalues() << endl; +cout << "The matrix of eigenvectors, V, is:" << endl << es.eigenvectors() << endl << endl; + +complex lambda = es.eigenvalues()[0]; +cout << "Consider the first eigenvalue, lambda = " << lambda << endl; +VectorXcd v = es.eigenvectors().col(0); +cout << "If v is the corresponding eigenvector, then lambda * v = " << endl << lambda * v << endl; +cout << "... and A * v = " << endl << A.cast >() * v << endl << endl; + +MatrixXcd D = es.eigenvalues().asDiagonal(); +MatrixXcd V = es.eigenvectors(); +cout << "Finally, V * D * V^(-1) = " << endl << V * D * V.inverse() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/EigenSolver_compute.cpp b/testbed/nanogui/ext/eigen/doc/snippets/EigenSolver_compute.cpp new file mode 100644 index 00000000..a5c96e9b --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/EigenSolver_compute.cpp @@ -0,0 +1,6 @@ +EigenSolver es; +MatrixXf A = MatrixXf::Random(4,4); +es.compute(A, /* computeEigenvectors = */ false); +cout << "The eigenvalues of A are: " << es.eigenvalues().transpose() << endl; +es.compute(A + MatrixXf::Identity(4,4), false); // re-use es to compute eigenvalues of A+I +cout << "The eigenvalues of A+I are: " << es.eigenvalues().transpose() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/EigenSolver_eigenvalues.cpp b/testbed/nanogui/ext/eigen/doc/snippets/EigenSolver_eigenvalues.cpp new file mode 100644 index 00000000..ed28869a --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/EigenSolver_eigenvalues.cpp @@ -0,0 +1,4 @@ +MatrixXd ones = MatrixXd::Ones(3,3); +EigenSolver es(ones, false); +cout << "The eigenvalues of the 3x3 matrix of ones are:" + << endl << es.eigenvalues() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/EigenSolver_eigenvectors.cpp b/testbed/nanogui/ext/eigen/doc/snippets/EigenSolver_eigenvectors.cpp new file mode 100644 index 00000000..8355f76c --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/EigenSolver_eigenvectors.cpp @@ -0,0 +1,4 @@ +MatrixXd ones = MatrixXd::Ones(3,3); +EigenSolver es(ones); +cout << "The first eigenvector of the 3x3 matrix of ones is:" + << endl << es.eigenvectors().col(0) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/EigenSolver_pseudoEigenvectors.cpp b/testbed/nanogui/ext/eigen/doc/snippets/EigenSolver_pseudoEigenvectors.cpp new file mode 100644 index 00000000..85e2569d --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/EigenSolver_pseudoEigenvectors.cpp @@ -0,0 +1,9 @@ +MatrixXd A = MatrixXd::Random(6,6); +cout << "Here is a random 6x6 matrix, A:" << endl << A << endl << endl; + +EigenSolver es(A); +MatrixXd D = es.pseudoEigenvalueMatrix(); +MatrixXd V = es.pseudoEigenvectors(); +cout << "The pseudo-eigenvalue matrix D is:" << endl << D << endl; +cout << "The pseudo-eigenvector matrix V is:" << endl << V << endl; +cout << "Finally, V * D * V^(-1) = " << endl << V * D * V.inverse() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/FullPivHouseholderQR_solve.cpp b/testbed/nanogui/ext/eigen/doc/snippets/FullPivHouseholderQR_solve.cpp new file mode 100644 index 00000000..23bc0749 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/FullPivHouseholderQR_solve.cpp @@ -0,0 +1,8 @@ +Matrix3f m = Matrix3f::Random(); +Matrix3f y = Matrix3f::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is the matrix y:" << endl << y << endl; +Matrix3f x; +x = m.fullPivHouseholderQr().solve(y); +assert(y.isApprox(m*x)); +cout << "Here is a solution x to the equation mx=y:" << endl << x << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/FullPivLU_image.cpp b/testbed/nanogui/ext/eigen/doc/snippets/FullPivLU_image.cpp new file mode 100644 index 00000000..817bc1e2 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/FullPivLU_image.cpp @@ -0,0 +1,9 @@ +Matrix3d m; +m << 1,1,0, + 1,3,2, + 0,1,1; +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Notice that the middle column is the sum of the two others, so the " + << "columns are linearly dependent." << endl; +cout << "Here is a matrix whose columns have the same span but are linearly independent:" + << endl << m.fullPivLu().image(m) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/FullPivLU_kernel.cpp b/testbed/nanogui/ext/eigen/doc/snippets/FullPivLU_kernel.cpp new file mode 100644 index 00000000..7086e01e --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/FullPivLU_kernel.cpp @@ -0,0 +1,7 @@ +MatrixXf m = MatrixXf::Random(3,5); +cout << "Here is the matrix m:" << endl << m << endl; +MatrixXf ker = m.fullPivLu().kernel(); +cout << "Here is a matrix whose columns form a basis of the kernel of m:" + << endl << ker << endl; +cout << "By definition of the kernel, m*ker is zero:" + << endl << m*ker << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/FullPivLU_solve.cpp b/testbed/nanogui/ext/eigen/doc/snippets/FullPivLU_solve.cpp new file mode 100644 index 00000000..c1f88235 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/FullPivLU_solve.cpp @@ -0,0 +1,11 @@ +Matrix m = Matrix::Random(); +Matrix2f y = Matrix2f::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is the matrix y:" << endl << y << endl; +Matrix x = m.fullPivLu().solve(y); +if((m*x).isApprox(y)) +{ + cout << "Here is a solution x to the equation mx=y:" << endl << x << endl; +} +else + cout << "The equation mx=y does not have any solution." << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/GeneralizedEigenSolver.cpp b/testbed/nanogui/ext/eigen/doc/snippets/GeneralizedEigenSolver.cpp new file mode 100644 index 00000000..2acda45f --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/GeneralizedEigenSolver.cpp @@ -0,0 +1,7 @@ +GeneralizedEigenSolver ges; +MatrixXf A = MatrixXf::Random(4,4); +MatrixXf B = MatrixXf::Random(4,4); +ges.compute(A, B); +cout << "The (complex) numerators of the generalzied eigenvalues are: " << ges.alphas().transpose() << endl; +cout << "The (real) denominatore of the generalzied eigenvalues are: " << ges.betas().transpose() << endl; +cout << "The (complex) generalzied eigenvalues are (alphas./beta): " << ges.eigenvalues().transpose() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/HessenbergDecomposition_compute.cpp b/testbed/nanogui/ext/eigen/doc/snippets/HessenbergDecomposition_compute.cpp new file mode 100644 index 00000000..50e37833 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/HessenbergDecomposition_compute.cpp @@ -0,0 +1,6 @@ +MatrixXcf A = MatrixXcf::Random(4,4); +HessenbergDecomposition hd(4); +hd.compute(A); +cout << "The matrix H in the decomposition of A is:" << endl << hd.matrixH() << endl; +hd.compute(2*A); // re-use hd to compute and store decomposition of 2A +cout << "The matrix H in the decomposition of 2A is:" << endl << hd.matrixH() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/HessenbergDecomposition_matrixH.cpp b/testbed/nanogui/ext/eigen/doc/snippets/HessenbergDecomposition_matrixH.cpp new file mode 100644 index 00000000..af013666 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/HessenbergDecomposition_matrixH.cpp @@ -0,0 +1,8 @@ +Matrix4f A = MatrixXf::Random(4,4); +cout << "Here is a random 4x4 matrix:" << endl << A << endl; +HessenbergDecomposition hessOfA(A); +MatrixXf H = hessOfA.matrixH(); +cout << "The Hessenberg matrix H is:" << endl << H << endl; +MatrixXf Q = hessOfA.matrixQ(); +cout << "The orthogonal matrix Q is:" << endl << Q << endl; +cout << "Q H Q^T is:" << endl << Q * H * Q.transpose() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/HessenbergDecomposition_packedMatrix.cpp b/testbed/nanogui/ext/eigen/doc/snippets/HessenbergDecomposition_packedMatrix.cpp new file mode 100644 index 00000000..4fa5957e --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/HessenbergDecomposition_packedMatrix.cpp @@ -0,0 +1,9 @@ +Matrix4d A = Matrix4d::Random(4,4); +cout << "Here is a random 4x4 matrix:" << endl << A << endl; +HessenbergDecomposition hessOfA(A); +Matrix4d pm = hessOfA.packedMatrix(); +cout << "The packed matrix M is:" << endl << pm << endl; +cout << "The upper Hessenberg part corresponds to the matrix H, which is:" + << endl << hessOfA.matrixH() << endl; +Vector3d hc = hessOfA.householderCoefficients(); +cout << "The vector of Householder coefficients is:" << endl << hc << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/HouseholderQR_householderQ.cpp b/testbed/nanogui/ext/eigen/doc/snippets/HouseholderQR_householderQ.cpp new file mode 100644 index 00000000..e859ce55 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/HouseholderQR_householderQ.cpp @@ -0,0 +1,7 @@ +MatrixXf A(MatrixXf::Random(5,3)), thinQ(MatrixXf::Identity(5,3)), Q; +A.setRandom(); +HouseholderQR qr(A); +Q = qr.householderQ(); +thinQ = qr.householderQ() * thinQ; +std::cout << "The complete unitary matrix Q is:\n" << Q << "\n\n"; +std::cout << "The thin matrix Q is:\n" << thinQ << "\n\n"; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/HouseholderQR_solve.cpp b/testbed/nanogui/ext/eigen/doc/snippets/HouseholderQR_solve.cpp new file mode 100644 index 00000000..8cce6ce6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/HouseholderQR_solve.cpp @@ -0,0 +1,9 @@ +typedef Matrix Matrix3x3; +Matrix3x3 m = Matrix3x3::Random(); +Matrix3f y = Matrix3f::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is the matrix y:" << endl << y << endl; +Matrix3f x; +x = m.householderQr().solve(y); +assert(y.isApprox(m*x)); +cout << "Here is a solution x to the equation mx=y:" << endl << x << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/HouseholderSequence_HouseholderSequence.cpp b/testbed/nanogui/ext/eigen/doc/snippets/HouseholderSequence_HouseholderSequence.cpp new file mode 100644 index 00000000..2632b83b --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/HouseholderSequence_HouseholderSequence.cpp @@ -0,0 +1,31 @@ +Matrix3d v = Matrix3d::Random(); +cout << "The matrix v is:" << endl; +cout << v << endl; + +Vector3d v0(1, v(1,0), v(2,0)); +cout << "The first Householder vector is: v_0 = " << v0.transpose() << endl; +Vector3d v1(0, 1, v(2,1)); +cout << "The second Householder vector is: v_1 = " << v1.transpose() << endl; +Vector3d v2(0, 0, 1); +cout << "The third Householder vector is: v_2 = " << v2.transpose() << endl; + +Vector3d h = Vector3d::Random(); +cout << "The Householder coefficients are: h = " << h.transpose() << endl; + +Matrix3d H0 = Matrix3d::Identity() - h(0) * v0 * v0.adjoint(); +cout << "The first Householder reflection is represented by H_0 = " << endl; +cout << H0 << endl; +Matrix3d H1 = Matrix3d::Identity() - h(1) * v1 * v1.adjoint(); +cout << "The second Householder reflection is represented by H_1 = " << endl; +cout << H1 << endl; +Matrix3d H2 = Matrix3d::Identity() - h(2) * v2 * v2.adjoint(); +cout << "The third Householder reflection is represented by H_2 = " << endl; +cout << H2 << endl; +cout << "Their product is H_0 H_1 H_2 = " << endl; +cout << H0 * H1 * H2 << endl; + +HouseholderSequence hhSeq(v, h); +Matrix3d hhSeqAsMatrix(hhSeq); +cout << "If we construct a HouseholderSequence from v and h" << endl; +cout << "and convert it to a matrix, we get:" << endl; +cout << hhSeqAsMatrix << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/IOFormat.cpp b/testbed/nanogui/ext/eigen/doc/snippets/IOFormat.cpp new file mode 100644 index 00000000..735f5dd8 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/IOFormat.cpp @@ -0,0 +1,14 @@ +std::string sep = "\n----------------------------------------\n"; +Matrix3d m1; +m1 << 1.111111, 2, 3.33333, 4, 5, 6, 7, 8.888888, 9; + +IOFormat CommaInitFmt(StreamPrecision, DontAlignCols, ", ", ", ", "", "", " << ", ";"); +IOFormat CleanFmt(4, 0, ", ", "\n", "[", "]"); +IOFormat OctaveFmt(StreamPrecision, 0, ", ", ";\n", "", "", "[", "]"); +IOFormat HeavyFmt(FullPrecision, 0, ", ", ";\n", "[", "]", "[", "]"); + +std::cout << m1 << sep; +std::cout << m1.format(CommaInitFmt) << sep; +std::cout << m1.format(CleanFmt) << sep; +std::cout << m1.format(OctaveFmt) << sep; +std::cout << m1.format(HeavyFmt) << sep; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/JacobiSVD_basic.cpp b/testbed/nanogui/ext/eigen/doc/snippets/JacobiSVD_basic.cpp new file mode 100644 index 00000000..ab24b9bc --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/JacobiSVD_basic.cpp @@ -0,0 +1,9 @@ +MatrixXf m = MatrixXf::Random(3,2); +cout << "Here is the matrix m:" << endl << m << endl; +JacobiSVD svd(m, ComputeThinU | ComputeThinV); +cout << "Its singular values are:" << endl << svd.singularValues() << endl; +cout << "Its left singular vectors are the columns of the thin U matrix:" << endl << svd.matrixU() << endl; +cout << "Its right singular vectors are the columns of the thin V matrix:" << endl << svd.matrixV() << endl; +Vector3f rhs(1, 0, 0); +cout << "Now consider this rhs vector:" << endl << rhs << endl; +cout << "A least-squares solution of m*x = rhs is:" << endl << svd.solve(rhs) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Jacobi_makeGivens.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Jacobi_makeGivens.cpp new file mode 100644 index 00000000..4b733c30 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Jacobi_makeGivens.cpp @@ -0,0 +1,6 @@ +Vector2f v = Vector2f::Random(); +JacobiRotation G; +G.makeGivens(v.x(), v.y()); +cout << "Here is the vector v:" << endl << v << endl; +v.applyOnTheLeft(0, 1, G.adjoint()); +cout << "Here is the vector J' * v:" << endl << v << endl; \ No newline at end of file diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Jacobi_makeJacobi.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Jacobi_makeJacobi.cpp new file mode 100644 index 00000000..0cc331d9 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Jacobi_makeJacobi.cpp @@ -0,0 +1,8 @@ +Matrix2f m = Matrix2f::Random(); +m = (m + m.adjoint()).eval(); +JacobiRotation J; +J.makeJacobi(m, 0, 1); +cout << "Here is the matrix m:" << endl << m << endl; +m.applyOnTheLeft(0, 1, J.adjoint()); +m.applyOnTheRight(0, 1, J); +cout << "Here is the matrix J' * m * J:" << endl << m << endl; \ No newline at end of file diff --git a/testbed/nanogui/ext/eigen/doc/snippets/LLT_example.cpp b/testbed/nanogui/ext/eigen/doc/snippets/LLT_example.cpp new file mode 100644 index 00000000..46fb4070 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/LLT_example.cpp @@ -0,0 +1,12 @@ +MatrixXd A(3,3); +A << 4,-1,2, -1,6,0, 2,0,5; +cout << "The matrix A is" << endl << A << endl; + +LLT lltOfA(A); // compute the Cholesky decomposition of A +MatrixXd L = lltOfA.matrixL(); // retrieve factor L in the decomposition +// The previous two lines can also be written as "L = A.llt().matrixL()" + +cout << "The Cholesky factor L is" << endl << L << endl; +cout << "To check this, let us compute L * L.transpose()" << endl; +cout << L * L.transpose() << endl; +cout << "This should equal the matrix A" << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/LLT_solve.cpp b/testbed/nanogui/ext/eigen/doc/snippets/LLT_solve.cpp new file mode 100644 index 00000000..7095d2cc --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/LLT_solve.cpp @@ -0,0 +1,8 @@ +typedef Matrix DataMatrix; +// let's generate some samples on the 3D plane of equation z = 2x+3y (with some noise) +DataMatrix samples = DataMatrix::Random(12,2); +VectorXf elevations = 2*samples.col(0) + 3*samples.col(1) + VectorXf::Random(12)*0.1; +// and let's solve samples * [x y]^T = elevations in least square sense: +Matrix xy + = (samples.adjoint() * samples).llt().solve((samples.adjoint()*elevations)); +cout << xy << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/LeastSquaresNormalEquations.cpp b/testbed/nanogui/ext/eigen/doc/snippets/LeastSquaresNormalEquations.cpp new file mode 100644 index 00000000..997cf171 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/LeastSquaresNormalEquations.cpp @@ -0,0 +1,4 @@ +MatrixXf A = MatrixXf::Random(3, 2); +VectorXf b = VectorXf::Random(3); +cout << "The solution using normal equations is:\n" + << (A.transpose() * A).ldlt().solve(A.transpose() * b) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/LeastSquaresQR.cpp b/testbed/nanogui/ext/eigen/doc/snippets/LeastSquaresQR.cpp new file mode 100644 index 00000000..6c970454 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/LeastSquaresQR.cpp @@ -0,0 +1,4 @@ +MatrixXf A = MatrixXf::Random(3, 2); +VectorXf b = VectorXf::Random(3); +cout << "The solution using the QR decomposition is:\n" + << A.colPivHouseholderQr().solve(b) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Map_general_stride.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Map_general_stride.cpp new file mode 100644 index 00000000..0657e7f8 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Map_general_stride.cpp @@ -0,0 +1,5 @@ +int array[24]; +for(int i = 0; i < 24; ++i) array[i] = i; +cout << Map > + (array, 3, 3, Stride(8, 2)) + << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Map_inner_stride.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Map_inner_stride.cpp new file mode 100644 index 00000000..d95ae9b3 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Map_inner_stride.cpp @@ -0,0 +1,5 @@ +int array[12]; +for(int i = 0; i < 12; ++i) array[i] = i; +cout << Map > + (array, 6) // the inner stride has already been passed as template parameter + << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Map_outer_stride.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Map_outer_stride.cpp new file mode 100644 index 00000000..2f6f052c --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Map_outer_stride.cpp @@ -0,0 +1,3 @@ +int array[12]; +for(int i = 0; i < 12; ++i) array[i] = i; +cout << Map >(array, 3, 3, OuterStride<>(4)) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Map_placement_new.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Map_placement_new.cpp new file mode 100644 index 00000000..2e40eca3 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Map_placement_new.cpp @@ -0,0 +1,5 @@ +int data[] = {1,2,3,4,5,6,7,8,9}; +Map v(data,4); +cout << "The mapped vector v is: " << v << "\n"; +new (&v) Map(data+4,5); +cout << "Now v is: " << v << "\n"; \ No newline at end of file diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Map_simple.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Map_simple.cpp new file mode 100644 index 00000000..423bb52a --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Map_simple.cpp @@ -0,0 +1,3 @@ +int array[9]; +for(int i = 0; i < 9; ++i) array[i] = i; +cout << Map(array) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_adjoint.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_adjoint.cpp new file mode 100644 index 00000000..4680d593 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_adjoint.cpp @@ -0,0 +1,3 @@ +Matrix2cf m = Matrix2cf::Random(); +cout << "Here is the 2x2 complex matrix m:" << endl << m << endl; +cout << "Here is the adjoint of m:" << endl << m.adjoint() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_all.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_all.cpp new file mode 100644 index 00000000..46f26f18 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_all.cpp @@ -0,0 +1,7 @@ +Vector3f boxMin(Vector3f::Zero()), boxMax(Vector3f::Ones()); +Vector3f p0 = Vector3f::Random(), p1 = Vector3f::Random().cwiseAbs(); +// let's check if p0 and p1 are inside the axis aligned box defined by the corners boxMin,boxMax: +cout << "Is (" << p0.transpose() << ") inside the box: " + << ((boxMin.array()p0.array()).all()) << endl; +cout << "Is (" << p1.transpose() << ") inside the box: " + << ((boxMin.array()p1.array()).all()) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_applyOnTheLeft.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_applyOnTheLeft.cpp new file mode 100644 index 00000000..6398c873 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_applyOnTheLeft.cpp @@ -0,0 +1,7 @@ +Matrix3f A = Matrix3f::Random(3,3), B; +B << 0,1,0, + 0,0,1, + 1,0,0; +cout << "At start, A = " << endl << A << endl; +A.applyOnTheLeft(B); +cout << "After applyOnTheLeft, A = " << endl << A << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_applyOnTheRight.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_applyOnTheRight.cpp new file mode 100644 index 00000000..e4b71b2d --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_applyOnTheRight.cpp @@ -0,0 +1,9 @@ +Matrix3f A = Matrix3f::Random(3,3), B; +B << 0,1,0, + 0,0,1, + 1,0,0; +cout << "At start, A = " << endl << A << endl; +A *= B; +cout << "After A *= B, A = " << endl << A << endl; +A.applyOnTheRight(B); // equivalent to A *= B +cout << "After applyOnTheRight, A = " << endl << A << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_array.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_array.cpp new file mode 100644 index 00000000..f215086d --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_array.cpp @@ -0,0 +1,4 @@ +Vector3d v(1,2,3); +v.array() += 3; +v.array() -= 2; +cout << v << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_array_const.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_array_const.cpp new file mode 100644 index 00000000..cd3b26a7 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_array_const.cpp @@ -0,0 +1,4 @@ +Vector3d v(-1,2,-3); +cout << "the absolute values:" << endl << v.array().abs() << endl; +cout << "the absolute values plus one:" << endl << v.array().abs()+1 << endl; +cout << "sum of the squares: " << v.array().square().sum() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_asDiagonal.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_asDiagonal.cpp new file mode 100644 index 00000000..b01082db --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_asDiagonal.cpp @@ -0,0 +1 @@ +cout << Matrix3i(Vector3i(2,5,6).asDiagonal()) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_block_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_block_int_int.cpp new file mode 100644 index 00000000..f99b6d4c --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_block_int_int.cpp @@ -0,0 +1,5 @@ +Matrix4i m = Matrix4i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is m.block<2,2>(1,1):" << endl << m.block<2,2>(1,1) << endl; +m.block<2,2>(1,1).setZero(); +cout << "Now the matrix m is:" << endl << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_block_int_int_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_block_int_int_int_int.cpp new file mode 100644 index 00000000..7238cbbe --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_block_int_int_int_int.cpp @@ -0,0 +1,5 @@ +Matrix4i m = Matrix4i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is m.block(1, 1, 2, 2):" << endl << m.block(1, 1, 2, 2) << endl; +m.block(1, 1, 2, 2).setZero(); +cout << "Now the matrix m is:" << endl << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_bottomLeftCorner_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_bottomLeftCorner_int_int.cpp new file mode 100644 index 00000000..ebae95e1 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_bottomLeftCorner_int_int.cpp @@ -0,0 +1,6 @@ +Matrix4i m = Matrix4i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is m.bottomLeftCorner(2, 2):" << endl; +cout << m.bottomLeftCorner(2, 2) << endl; +m.bottomLeftCorner(2, 2).setZero(); +cout << "Now the matrix m is:" << endl << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_bottomRightCorner_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_bottomRightCorner_int_int.cpp new file mode 100644 index 00000000..bf05093a --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_bottomRightCorner_int_int.cpp @@ -0,0 +1,6 @@ +Matrix4i m = Matrix4i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is m.bottomRightCorner(2, 2):" << endl; +cout << m.bottomRightCorner(2, 2) << endl; +m.bottomRightCorner(2, 2).setZero(); +cout << "Now the matrix m is:" << endl << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_bottomRows_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_bottomRows_int.cpp new file mode 100644 index 00000000..47ca92ec --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_bottomRows_int.cpp @@ -0,0 +1,6 @@ +Array44i a = Array44i::Random(); +cout << "Here is the array a:" << endl << a << endl; +cout << "Here is a.bottomRows(2):" << endl; +cout << a.bottomRows(2) << endl; +a.bottomRows(2).setZero(); +cout << "Now the array a is:" << endl << a << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cast.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cast.cpp new file mode 100644 index 00000000..016880b4 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cast.cpp @@ -0,0 +1,3 @@ +Matrix2d md = Matrix2d::Identity() * 0.45; +Matrix2f mf = Matrix2f::Identity(); +cout << md + mf.cast() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_col.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_col.cpp new file mode 100644 index 00000000..87c91b12 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_col.cpp @@ -0,0 +1,3 @@ +Matrix3d m = Matrix3d::Identity(); +m.col(1) = Vector3d(4,5,6); +cout << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_colwise.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_colwise.cpp new file mode 100644 index 00000000..a048beff --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_colwise.cpp @@ -0,0 +1,5 @@ +Matrix3d m = Matrix3d::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is the sum of each column:" << endl << m.colwise().sum() << endl; +cout << "Here is the maximum absolute value of each column:" + << endl << m.cwiseAbs().colwise().maxCoeff() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_computeInverseAndDetWithCheck.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_computeInverseAndDetWithCheck.cpp new file mode 100644 index 00000000..a7b084fd --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_computeInverseAndDetWithCheck.cpp @@ -0,0 +1,13 @@ +Matrix3d m = Matrix3d::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +Matrix3d inverse; +bool invertible; +double determinant; +m.computeInverseAndDetWithCheck(inverse,determinant,invertible); +cout << "Its determinant is " << determinant << endl; +if(invertible) { + cout << "It is invertible, and its inverse is:" << endl << inverse << endl; +} +else { + cout << "It is not invertible." << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_computeInverseWithCheck.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_computeInverseWithCheck.cpp new file mode 100644 index 00000000..873a9f87 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_computeInverseWithCheck.cpp @@ -0,0 +1,11 @@ +Matrix3d m = Matrix3d::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +Matrix3d inverse; +bool invertible; +m.computeInverseWithCheck(inverse,invertible); +if(invertible) { + cout << "It is invertible, and its inverse is:" << endl << inverse << endl; +} +else { + cout << "It is not invertible." << endl; +} diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseAbs.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseAbs.cpp new file mode 100644 index 00000000..28a31600 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseAbs.cpp @@ -0,0 +1,4 @@ +MatrixXd m(2,3); +m << 2, -4, 6, + -5, 1, 0; +cout << m.cwiseAbs() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseAbs2.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseAbs2.cpp new file mode 100644 index 00000000..889a2e2b --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseAbs2.cpp @@ -0,0 +1,4 @@ +MatrixXd m(2,3); +m << 2, -4, 6, + -5, 1, 0; +cout << m.cwiseAbs2() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseEqual.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseEqual.cpp new file mode 100644 index 00000000..eb3656f4 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseEqual.cpp @@ -0,0 +1,7 @@ +MatrixXi m(2,2); +m << 1, 0, + 1, 1; +cout << "Comparing m with identity matrix:" << endl; +cout << m.cwiseEqual(MatrixXi::Identity(2,2)) << endl; +int count = m.cwiseEqual(MatrixXi::Identity(2,2)).count(); +cout << "Number of coefficients that are equal: " << count << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseInverse.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseInverse.cpp new file mode 100644 index 00000000..23e08f7b --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseInverse.cpp @@ -0,0 +1,4 @@ +MatrixXd m(2,3); +m << 2, 0.5, 1, + 3, 0.25, 1; +cout << m.cwiseInverse() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseMax.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseMax.cpp new file mode 100644 index 00000000..3c956818 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseMax.cpp @@ -0,0 +1,2 @@ +Vector3d v(2,3,4), w(4,2,3); +cout << v.cwiseMax(w) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseMin.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseMin.cpp new file mode 100644 index 00000000..82fc761e --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseMin.cpp @@ -0,0 +1,2 @@ +Vector3d v(2,3,4), w(4,2,3); +cout << v.cwiseMin(w) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseNotEqual.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseNotEqual.cpp new file mode 100644 index 00000000..6a2e4fb6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseNotEqual.cpp @@ -0,0 +1,7 @@ +MatrixXi m(2,2); +m << 1, 0, + 1, 1; +cout << "Comparing m with identity matrix:" << endl; +cout << m.cwiseNotEqual(MatrixXi::Identity(2,2)) << endl; +int count = m.cwiseNotEqual(MatrixXi::Identity(2,2)).count(); +cout << "Number of coefficients that are not equal: " << count << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseProduct.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseProduct.cpp new file mode 100644 index 00000000..1db3a113 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseProduct.cpp @@ -0,0 +1,4 @@ +Matrix3i a = Matrix3i::Random(), b = Matrix3i::Random(); +Matrix3i c = a.cwiseProduct(b); +cout << "a:\n" << a << "\nb:\n" << b << "\nc:\n" << c << endl; + diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseQuotient.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseQuotient.cpp new file mode 100644 index 00000000..96912120 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseQuotient.cpp @@ -0,0 +1,2 @@ +Vector3d v(2,3,4), w(4,2,3); +cout << v.cwiseQuotient(w) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseSign.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseSign.cpp new file mode 100644 index 00000000..efd71795 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseSign.cpp @@ -0,0 +1,4 @@ +MatrixXd m(2,3); +m << 2, -4, 6, + -5, 1, 0; +cout << m.cwiseSign() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseSqrt.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseSqrt.cpp new file mode 100644 index 00000000..4bfd75d5 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_cwiseSqrt.cpp @@ -0,0 +1,2 @@ +Vector3d v(1,2,4); +cout << v.cwiseSqrt() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_diagonal.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_diagonal.cpp new file mode 100644 index 00000000..cd63413f --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_diagonal.cpp @@ -0,0 +1,4 @@ +Matrix3i m = Matrix3i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here are the coefficients on the main diagonal of m:" << endl + << m.diagonal() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_diagonal_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_diagonal_int.cpp new file mode 100644 index 00000000..7b66abf6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_diagonal_int.cpp @@ -0,0 +1,5 @@ +Matrix4i m = Matrix4i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here are the coefficients on the 1st super-diagonal and 2nd sub-diagonal of m:" << endl + << m.diagonal(1).transpose() << endl + << m.diagonal(-2).transpose() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_diagonal_template_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_diagonal_template_int.cpp new file mode 100644 index 00000000..0e73d1c1 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_diagonal_template_int.cpp @@ -0,0 +1,5 @@ +Matrix4i m = Matrix4i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here are the coefficients on the 1st super-diagonal and 2nd sub-diagonal of m:" << endl + << m.diagonal<1>().transpose() << endl + << m.diagonal<-2>().transpose() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_eigenvalues.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_eigenvalues.cpp new file mode 100644 index 00000000..039f8870 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_eigenvalues.cpp @@ -0,0 +1,3 @@ +MatrixXd ones = MatrixXd::Ones(3,3); +VectorXcd eivals = ones.eigenvalues(); +cout << "The eigenvalues of the 3x3 matrix of ones are:" << endl << eivals << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_end_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_end_int.cpp new file mode 100644 index 00000000..03c54a93 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_end_int.cpp @@ -0,0 +1,5 @@ +RowVector4i v = RowVector4i::Random(); +cout << "Here is the vector v:" << endl << v << endl; +cout << "Here is v.tail(2):" << endl << v.tail(2) << endl; +v.tail(2).setZero(); +cout << "Now the vector v is:" << endl << v << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_eval.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_eval.cpp new file mode 100644 index 00000000..1df3aa01 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_eval.cpp @@ -0,0 +1,12 @@ +Matrix2f M = Matrix2f::Random(); +Matrix2f m; +m = M; +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Now we want to copy a column into a row." << endl; +cout << "If we do m.col(1) = m.row(0), then m becomes:" << endl; +m.col(1) = m.row(0); +cout << m << endl << "which is wrong!" << endl; +cout << "Now let us instead do m.col(1) = m.row(0).eval(). Then m becomes" << endl; +m = M; +m.col(1) = m.row(0).eval(); +cout << m << endl << "which is right." << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_fixedBlock_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_fixedBlock_int_int.cpp new file mode 100644 index 00000000..32011274 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_fixedBlock_int_int.cpp @@ -0,0 +1,5 @@ +Matrix4d m = Vector4d(1,2,3,4).asDiagonal(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is m.fixed<2, 2>(2, 2):" << endl << m.block<2, 2>(2, 2) << endl; +m.block<2, 2>(2, 0) = m.block<2, 2>(2, 2); +cout << "Now the matrix m is:" << endl << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_hnormalized.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_hnormalized.cpp new file mode 100644 index 00000000..652cd77c --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_hnormalized.cpp @@ -0,0 +1,6 @@ +Vector4d v = Vector4d::Random(); +Projective3d P(Matrix4d::Random()); +cout << "v = " << v.transpose() << "]^T" << endl; +cout << "v.hnormalized() = " << v.hnormalized().transpose() << "]^T" << endl; +cout << "P*v = " << (P*v).transpose() << "]^T" << endl; +cout << "(P*v).hnormalized() = " << (P*v).hnormalized().transpose() << "]^T" << endl; \ No newline at end of file diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_homogeneous.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_homogeneous.cpp new file mode 100644 index 00000000..457c28f9 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_homogeneous.cpp @@ -0,0 +1,6 @@ +Vector3d v = Vector3d::Random(), w; +Projective3d P(Matrix4d::Random()); +cout << "v = [" << v.transpose() << "]^T" << endl; +cout << "h.homogeneous() = [" << v.homogeneous().transpose() << "]^T" << endl; +cout << "(P * v.homogeneous()) = [" << (P * v.homogeneous()).transpose() << "]^T" << endl; +cout << "(P * v.homogeneous()).hnormalized() = [" << (P * v.homogeneous()).eval().hnormalized().transpose() << "]^T" << endl; \ No newline at end of file diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_identity.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_identity.cpp new file mode 100644 index 00000000..b5c1e59c --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_identity.cpp @@ -0,0 +1 @@ +cout << Matrix::Identity() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_identity_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_identity_int_int.cpp new file mode 100644 index 00000000..918649d6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_identity_int_int.cpp @@ -0,0 +1 @@ +cout << MatrixXd::Identity(4, 3) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_inverse.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_inverse.cpp new file mode 100644 index 00000000..a56142ee --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_inverse.cpp @@ -0,0 +1,3 @@ +Matrix3d m = Matrix3d::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Its inverse is:" << endl << m.inverse() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isDiagonal.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isDiagonal.cpp new file mode 100644 index 00000000..5b1d5997 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isDiagonal.cpp @@ -0,0 +1,6 @@ +Matrix3d m = 10000 * Matrix3d::Identity(); +m(0,2) = 1; +cout << "Here's the matrix m:" << endl << m << endl; +cout << "m.isDiagonal() returns: " << m.isDiagonal() << endl; +cout << "m.isDiagonal(1e-3) returns: " << m.isDiagonal(1e-3) << endl; + diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isIdentity.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isIdentity.cpp new file mode 100644 index 00000000..17b756c9 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isIdentity.cpp @@ -0,0 +1,5 @@ +Matrix3d m = Matrix3d::Identity(); +m(0,2) = 1e-4; +cout << "Here's the matrix m:" << endl << m << endl; +cout << "m.isIdentity() returns: " << m.isIdentity() << endl; +cout << "m.isIdentity(1e-3) returns: " << m.isIdentity(1e-3) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isOnes.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isOnes.cpp new file mode 100644 index 00000000..f82f6280 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isOnes.cpp @@ -0,0 +1,5 @@ +Matrix3d m = Matrix3d::Ones(); +m(0,2) += 1e-4; +cout << "Here's the matrix m:" << endl << m << endl; +cout << "m.isOnes() returns: " << m.isOnes() << endl; +cout << "m.isOnes(1e-3) returns: " << m.isOnes(1e-3) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isOrthogonal.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isOrthogonal.cpp new file mode 100644 index 00000000..b22af066 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isOrthogonal.cpp @@ -0,0 +1,6 @@ +Vector3d v(1,0,0); +Vector3d w(1e-4,0,1); +cout << "Here's the vector v:" << endl << v << endl; +cout << "Here's the vector w:" << endl << w << endl; +cout << "v.isOrthogonal(w) returns: " << v.isOrthogonal(w) << endl; +cout << "v.isOrthogonal(w,1e-3) returns: " << v.isOrthogonal(w,1e-3) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isUnitary.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isUnitary.cpp new file mode 100644 index 00000000..3877da34 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isUnitary.cpp @@ -0,0 +1,5 @@ +Matrix3d m = Matrix3d::Identity(); +m(0,2) = 1e-4; +cout << "Here's the matrix m:" << endl << m << endl; +cout << "m.isUnitary() returns: " << m.isUnitary() << endl; +cout << "m.isUnitary(1e-3) returns: " << m.isUnitary(1e-3) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isZero.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isZero.cpp new file mode 100644 index 00000000..c2cfe220 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_isZero.cpp @@ -0,0 +1,5 @@ +Matrix3d m = Matrix3d::Zero(); +m(0,2) = 1e-4; +cout << "Here's the matrix m:" << endl << m << endl; +cout << "m.isZero() returns: " << m.isZero() << endl; +cout << "m.isZero(1e-3) returns: " << m.isZero(1e-3) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_leftCols_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_leftCols_int.cpp new file mode 100644 index 00000000..6ea984e4 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_leftCols_int.cpp @@ -0,0 +1,6 @@ +Array44i a = Array44i::Random(); +cout << "Here is the array a:" << endl << a << endl; +cout << "Here is a.leftCols(2):" << endl; +cout << a.leftCols(2) << endl; +a.leftCols(2).setZero(); +cout << "Now the array a is:" << endl << a << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_noalias.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_noalias.cpp new file mode 100644 index 00000000..3b54a79a --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_noalias.cpp @@ -0,0 +1,3 @@ +Matrix2d a, b, c; a << 1,2,3,4; b << 5,6,7,8; +c.noalias() = a * b; // this computes the product directly to c +cout << c << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_ones.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_ones.cpp new file mode 100644 index 00000000..02c767c9 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_ones.cpp @@ -0,0 +1,2 @@ +cout << Matrix2d::Ones() << endl; +cout << 6 * RowVector4i::Ones() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_ones_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_ones_int.cpp new file mode 100644 index 00000000..2ef188e7 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_ones_int.cpp @@ -0,0 +1,2 @@ +cout << 6 * RowVectorXi::Ones(4) << endl; +cout << VectorXf::Ones(2) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_ones_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_ones_int_int.cpp new file mode 100644 index 00000000..60f5a31e --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_ones_int_int.cpp @@ -0,0 +1 @@ +cout << MatrixXi::Ones(2,3) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_operatorNorm.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_operatorNorm.cpp new file mode 100644 index 00000000..355246f0 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_operatorNorm.cpp @@ -0,0 +1,3 @@ +MatrixXd ones = MatrixXd::Ones(3,3); +cout << "The operator norm of the 3x3 matrix of ones is " + << ones.operatorNorm() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_prod.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_prod.cpp new file mode 100644 index 00000000..d2f27bdc --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_prod.cpp @@ -0,0 +1,3 @@ +Matrix3d m = Matrix3d::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is the product of all the coefficients:" << endl << m.prod() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_random.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_random.cpp new file mode 100644 index 00000000..65fc524f --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_random.cpp @@ -0,0 +1 @@ +cout << 100 * Matrix2i::Random() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_random_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_random_int.cpp new file mode 100644 index 00000000..f161d03c --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_random_int.cpp @@ -0,0 +1 @@ +cout << VectorXi::Random(2) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_random_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_random_int_int.cpp new file mode 100644 index 00000000..3f0f7dd5 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_random_int_int.cpp @@ -0,0 +1 @@ +cout << MatrixXi::Random(2,3) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_replicate.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_replicate.cpp new file mode 100644 index 00000000..3ce52bcd --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_replicate.cpp @@ -0,0 +1,4 @@ +MatrixXi m = MatrixXi::Random(2,3); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "m.replicate<3,2>() = ..." << endl; +cout << m.replicate<3,2>() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_replicate_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_replicate_int_int.cpp new file mode 100644 index 00000000..b1dbc70b --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_replicate_int_int.cpp @@ -0,0 +1,4 @@ +Vector3i v = Vector3i::Random(); +cout << "Here is the vector v:" << endl << v << endl; +cout << "v.replicate(2,5) = ..." << endl; +cout << v.replicate(2,5) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_reverse.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_reverse.cpp new file mode 100644 index 00000000..f545a283 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_reverse.cpp @@ -0,0 +1,8 @@ +MatrixXi m = MatrixXi::Random(3,4); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is the reverse of m:" << endl << m.reverse() << endl; +cout << "Here is the coefficient (1,0) in the reverse of m:" << endl + << m.reverse()(1,0) << endl; +cout << "Let us overwrite this coefficient with the value 4." << endl; +m.reverse()(1,0) = 4; +cout << "Now the matrix m is:" << endl << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_rightCols_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_rightCols_int.cpp new file mode 100644 index 00000000..cb513401 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_rightCols_int.cpp @@ -0,0 +1,6 @@ +Array44i a = Array44i::Random(); +cout << "Here is the array a:" << endl << a << endl; +cout << "Here is a.rightCols(2):" << endl; +cout << a.rightCols(2) << endl; +a.rightCols(2).setZero(); +cout << "Now the array a is:" << endl << a << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_row.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_row.cpp new file mode 100644 index 00000000..b15e6260 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_row.cpp @@ -0,0 +1,3 @@ +Matrix3d m = Matrix3d::Identity(); +m.row(1) = Vector3d(4,5,6); +cout << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_rowwise.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_rowwise.cpp new file mode 100644 index 00000000..ae93964e --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_rowwise.cpp @@ -0,0 +1,5 @@ +Matrix3d m = Matrix3d::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is the sum of each row:" << endl << m.rowwise().sum() << endl; +cout << "Here is the maximum absolute value of each row:" + << endl << m.cwiseAbs().rowwise().maxCoeff() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_segment_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_segment_int_int.cpp new file mode 100644 index 00000000..70cd6d26 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_segment_int_int.cpp @@ -0,0 +1,5 @@ +RowVector4i v = RowVector4i::Random(); +cout << "Here is the vector v:" << endl << v << endl; +cout << "Here is v.segment(1, 2):" << endl << v.segment(1, 2) << endl; +v.segment(1, 2).setZero(); +cout << "Now the vector v is:" << endl << v << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_select.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_select.cpp new file mode 100644 index 00000000..ae5477f0 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_select.cpp @@ -0,0 +1,6 @@ +MatrixXi m(3, 3); +m << 1, 2, 3, + 4, 5, 6, + 7, 8, 9; +m = (m.array() >= 5).select(-m, m); +cout << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_selfadjointView.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_selfadjointView.cpp new file mode 100644 index 00000000..4bd3c7ee --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_selfadjointView.cpp @@ -0,0 +1,6 @@ +Matrix3i m = Matrix3i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is the symmetric matrix extracted from the upper part of m:" << endl + << Matrix3i(m.selfadjointView()) << endl; +cout << "Here is the symmetric matrix extracted from the lower part of m:" << endl + << Matrix3i(m.selfadjointView()) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_set.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_set.cpp new file mode 100644 index 00000000..50ecf5fb --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_set.cpp @@ -0,0 +1,13 @@ +Matrix3i m1; +m1 << 1, 2, 3, + 4, 5, 6, + 7, 8, 9; +cout << m1 << endl << endl; +Matrix3i m2 = Matrix3i::Identity(); +m2.block(0,0, 2,2) << 10, 11, 12, 13; +cout << m2 << endl << endl; +Vector2i v1; +v1 << 14, 15; +m2 << v1.transpose(), 16, + v1, m1.block(1,1,2,2); +cout << m2 << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_setIdentity.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_setIdentity.cpp new file mode 100644 index 00000000..4fd0aa24 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_setIdentity.cpp @@ -0,0 +1,3 @@ +Matrix4i m = Matrix4i::Zero(); +m.block<3,3>(1,0).setIdentity(); +cout << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_setOnes.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_setOnes.cpp new file mode 100644 index 00000000..4cef9c1e --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_setOnes.cpp @@ -0,0 +1,3 @@ +Matrix4i m = Matrix4i::Random(); +m.row(1).setOnes(); +cout << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_setRandom.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_setRandom.cpp new file mode 100644 index 00000000..e2c257d4 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_setRandom.cpp @@ -0,0 +1,3 @@ +Matrix4i m = Matrix4i::Zero(); +m.col(1).setRandom(); +cout << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_setZero.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_setZero.cpp new file mode 100644 index 00000000..9b5b9583 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_setZero.cpp @@ -0,0 +1,3 @@ +Matrix4i m = Matrix4i::Random(); +m.row(1).setZero(); +cout << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_start_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_start_int.cpp new file mode 100644 index 00000000..c261d2b4 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_start_int.cpp @@ -0,0 +1,5 @@ +RowVector4i v = RowVector4i::Random(); +cout << "Here is the vector v:" << endl << v << endl; +cout << "Here is v.head(2):" << endl << v.head(2) << endl; +v.head(2).setZero(); +cout << "Now the vector v is:" << endl << v << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_bottomRows.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_bottomRows.cpp new file mode 100644 index 00000000..f9ea892d --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_bottomRows.cpp @@ -0,0 +1,6 @@ +Array44i a = Array44i::Random(); +cout << "Here is the array a:" << endl << a << endl; +cout << "Here is a.bottomRows<2>():" << endl; +cout << a.bottomRows<2>() << endl; +a.bottomRows<2>().setZero(); +cout << "Now the array a is:" << endl << a << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_end.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_end.cpp new file mode 100644 index 00000000..f5ccb00f --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_end.cpp @@ -0,0 +1,5 @@ +RowVector4i v = RowVector4i::Random(); +cout << "Here is the vector v:" << endl << v << endl; +cout << "Here is v.tail(2):" << endl << v.tail<2>() << endl; +v.tail<2>().setZero(); +cout << "Now the vector v is:" << endl << v << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_block_int_int_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_block_int_int_int_int.cpp new file mode 100644 index 00000000..4dced03b --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_block_int_int_int_int.cpp @@ -0,0 +1,5 @@ +Matrix4i m = Matrix4i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is the block:" << endl << m.block<2, Dynamic>(1, 1, 2, 3) << endl; +m.block<2, Dynamic>(1, 1, 2, 3).setZero(); +cout << "Now the matrix m is:" << endl << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_bottomLeftCorner.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_bottomLeftCorner.cpp new file mode 100644 index 00000000..847892a2 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_bottomLeftCorner.cpp @@ -0,0 +1,6 @@ +Matrix4i m = Matrix4i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is m.bottomLeftCorner<2,2>():" << endl; +cout << m.bottomLeftCorner<2,2>() << endl; +m.bottomLeftCorner<2,2>().setZero(); +cout << "Now the matrix m is:" << endl << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_bottomLeftCorner_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_bottomLeftCorner_int_int.cpp new file mode 100644 index 00000000..a1edcc80 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_bottomLeftCorner_int_int.cpp @@ -0,0 +1,6 @@ +Matrix4i m = Matrix4i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is m.bottomLeftCorner<2,Dynamic>(2,2):" << endl; +cout << m.bottomLeftCorner<2,Dynamic>(2,2) << endl; +m.bottomLeftCorner<2,Dynamic>(2,2).setZero(); +cout << "Now the matrix m is:" << endl << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_bottomRightCorner.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_bottomRightCorner.cpp new file mode 100644 index 00000000..abacb014 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_bottomRightCorner.cpp @@ -0,0 +1,6 @@ +Matrix4i m = Matrix4i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is m.bottomRightCorner<2,2>():" << endl; +cout << m.bottomRightCorner<2,2>() << endl; +m.bottomRightCorner<2,2>().setZero(); +cout << "Now the matrix m is:" << endl << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_bottomRightCorner_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_bottomRightCorner_int_int.cpp new file mode 100644 index 00000000..a65508fd --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_bottomRightCorner_int_int.cpp @@ -0,0 +1,6 @@ +Matrix4i m = Matrix4i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is m.bottomRightCorner<2,Dynamic>(2,2):" << endl; +cout << m.bottomRightCorner<2,Dynamic>(2,2) << endl; +m.bottomRightCorner<2,Dynamic>(2,2).setZero(); +cout << "Now the matrix m is:" << endl << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_topLeftCorner.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_topLeftCorner.cpp new file mode 100644 index 00000000..1899d902 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_topLeftCorner.cpp @@ -0,0 +1,6 @@ +Matrix4i m = Matrix4i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is m.topLeftCorner<2,2>():" << endl; +cout << m.topLeftCorner<2,2>() << endl; +m.topLeftCorner<2,2>().setZero(); +cout << "Now the matrix m is:" << endl << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_topLeftCorner_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_topLeftCorner_int_int.cpp new file mode 100644 index 00000000..fac761f6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_topLeftCorner_int_int.cpp @@ -0,0 +1,6 @@ +Matrix4i m = Matrix4i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is m.topLeftCorner<2,Dynamic>(2,2):" << endl; +cout << m.topLeftCorner<2,Dynamic>(2,2) << endl; +m.topLeftCorner<2,Dynamic>(2,2).setZero(); +cout << "Now the matrix m is:" << endl << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_topRightCorner.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_topRightCorner.cpp new file mode 100644 index 00000000..c3a17711 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_topRightCorner.cpp @@ -0,0 +1,6 @@ +Matrix4i m = Matrix4i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is m.topRightCorner<2,2>():" << endl; +cout << m.topRightCorner<2,2>() << endl; +m.topRightCorner<2,2>().setZero(); +cout << "Now the matrix m is:" << endl << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_topRightCorner_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_topRightCorner_int_int.cpp new file mode 100644 index 00000000..a17acc00 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_int_topRightCorner_int_int.cpp @@ -0,0 +1,6 @@ +Matrix4i m = Matrix4i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is m.topRightCorner<2,Dynamic>(2,2):" << endl; +cout << m.topRightCorner<2,Dynamic>(2,2) << endl; +m.topRightCorner<2,Dynamic>(2,2).setZero(); +cout << "Now the matrix m is:" << endl << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_leftCols.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_leftCols.cpp new file mode 100644 index 00000000..1c425d91 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_leftCols.cpp @@ -0,0 +1,6 @@ +Array44i a = Array44i::Random(); +cout << "Here is the array a:" << endl << a << endl; +cout << "Here is a.leftCols<2>():" << endl; +cout << a.leftCols<2>() << endl; +a.leftCols<2>().setZero(); +cout << "Now the array a is:" << endl << a << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_rightCols.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_rightCols.cpp new file mode 100644 index 00000000..fc8c0d93 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_rightCols.cpp @@ -0,0 +1,6 @@ +Array44i a = Array44i::Random(); +cout << "Here is the array a:" << endl << a << endl; +cout << "Here is a.rightCols<2>():" << endl; +cout << a.rightCols<2>() << endl; +a.rightCols<2>().setZero(); +cout << "Now the array a is:" << endl << a << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_segment.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_segment.cpp new file mode 100644 index 00000000..e448b402 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_segment.cpp @@ -0,0 +1,5 @@ +RowVector4i v = RowVector4i::Random(); +cout << "Here is the vector v:" << endl << v << endl; +cout << "Here is v.segment<2>(1):" << endl << v.segment<2>(1) << endl; +v.segment<2>(2).setZero(); +cout << "Now the vector v is:" << endl << v << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_start.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_start.cpp new file mode 100644 index 00000000..d336b371 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_start.cpp @@ -0,0 +1,5 @@ +RowVector4i v = RowVector4i::Random(); +cout << "Here is the vector v:" << endl << v << endl; +cout << "Here is v.head(2):" << endl << v.head<2>() << endl; +v.head<2>().setZero(); +cout << "Now the vector v is:" << endl << v << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_topRows.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_topRows.cpp new file mode 100644 index 00000000..0110251a --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_template_int_topRows.cpp @@ -0,0 +1,6 @@ +Array44i a = Array44i::Random(); +cout << "Here is the array a:" << endl << a << endl; +cout << "Here is a.topRows<2>():" << endl; +cout << a.topRows<2>() << endl; +a.topRows<2>().setZero(); +cout << "Now the array a is:" << endl << a << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_topLeftCorner_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_topLeftCorner_int_int.cpp new file mode 100644 index 00000000..e52cb3bd --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_topLeftCorner_int_int.cpp @@ -0,0 +1,6 @@ +Matrix4i m = Matrix4i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is m.topLeftCorner(2, 2):" << endl; +cout << m.topLeftCorner(2, 2) << endl; +m.topLeftCorner(2, 2).setZero(); +cout << "Now the matrix m is:" << endl << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_topRightCorner_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_topRightCorner_int_int.cpp new file mode 100644 index 00000000..811fa563 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_topRightCorner_int_int.cpp @@ -0,0 +1,6 @@ +Matrix4i m = Matrix4i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is m.topRightCorner(2, 2):" << endl; +cout << m.topRightCorner(2, 2) << endl; +m.topRightCorner(2, 2).setZero(); +cout << "Now the matrix m is:" << endl << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_topRows_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_topRows_int.cpp new file mode 100644 index 00000000..f2d75f1c --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_topRows_int.cpp @@ -0,0 +1,6 @@ +Array44i a = Array44i::Random(); +cout << "Here is the array a:" << endl << a << endl; +cout << "Here is a.topRows(2):" << endl; +cout << a.topRows(2) << endl; +a.topRows(2).setZero(); +cout << "Now the array a is:" << endl << a << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_transpose.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_transpose.cpp new file mode 100644 index 00000000..88eea83c --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_transpose.cpp @@ -0,0 +1,8 @@ +Matrix2i m = Matrix2i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is the transpose of m:" << endl << m.transpose() << endl; +cout << "Here is the coefficient (1,0) in the transpose of m:" << endl + << m.transpose()(1,0) << endl; +cout << "Let us overwrite this coefficient with the value 0." << endl; +m.transpose()(1,0) = 0; +cout << "Now the matrix m is:" << endl << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_triangularView.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_triangularView.cpp new file mode 100644 index 00000000..03aa303f --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_triangularView.cpp @@ -0,0 +1,9 @@ +Matrix3i m = Matrix3i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is the upper-triangular matrix extracted from m:" << endl + << Matrix3i(m.triangularView()) << endl; +cout << "Here is the strictly-upper-triangular matrix extracted from m:" << endl + << Matrix3i(m.triangularView()) << endl; +cout << "Here is the unit-lower-triangular matrix extracted from m:" << endl + << Matrix3i(m.triangularView()) << endl; +// FIXME need to implement output for triangularViews (Bug 885) diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_zero.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_zero.cpp new file mode 100644 index 00000000..60649367 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_zero.cpp @@ -0,0 +1,2 @@ +cout << Matrix2d::Zero() << endl; +cout << RowVector4i::Zero() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_zero_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_zero_int.cpp new file mode 100644 index 00000000..370a9ba0 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_zero_int.cpp @@ -0,0 +1,2 @@ +cout << RowVectorXi::Zero(4) << endl; +cout << VectorXf::Zero(2) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_zero_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_zero_int_int.cpp new file mode 100644 index 00000000..4099c5d4 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/MatrixBase_zero_int_int.cpp @@ -0,0 +1 @@ +cout << MatrixXi::Zero(2,3) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Matrix_resize_NoChange_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_resize_NoChange_int.cpp new file mode 100644 index 00000000..acdf18c4 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_resize_NoChange_int.cpp @@ -0,0 +1,3 @@ +MatrixXd m(3,4); +m.resize(NoChange, 5); +cout << "m: " << m.rows() << " rows, " << m.cols() << " cols" << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Matrix_resize_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_resize_int.cpp new file mode 100644 index 00000000..044c7898 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_resize_int.cpp @@ -0,0 +1,6 @@ +VectorXd v(10); +v.resize(3); +RowVector3d w; +w.resize(3); // this is legal, but has no effect +cout << "v: " << v.rows() << " rows, " << v.cols() << " cols" << endl; +cout << "w: " << w.rows() << " rows, " << w.cols() << " cols" << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Matrix_resize_int_NoChange.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_resize_int_NoChange.cpp new file mode 100644 index 00000000..5c37c906 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_resize_int_NoChange.cpp @@ -0,0 +1,3 @@ +MatrixXd m(3,4); +m.resize(5, NoChange); +cout << "m: " << m.rows() << " rows, " << m.cols() << " cols" << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Matrix_resize_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_resize_int_int.cpp new file mode 100644 index 00000000..bfd47415 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_resize_int_int.cpp @@ -0,0 +1,9 @@ +MatrixXd m(2,3); +m << 1,2,3,4,5,6; +cout << "here's the 2x3 matrix m:" << endl << m << endl; +cout << "let's resize m to 3x2. This is a conservative resizing because 2*3==3*2." << endl; +m.resize(3,2); +cout << "here's the 3x2 matrix m:" << endl << m << endl; +cout << "now let's resize m to size 2x2. This is NOT a conservative resizing, so it becomes uninitialized:" << endl; +m.resize(2,2); +cout << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setConstant_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setConstant_int.cpp new file mode 100644 index 00000000..ff5a86c9 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setConstant_int.cpp @@ -0,0 +1,3 @@ +VectorXf v; +v.setConstant(3, 5); +cout << v << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setConstant_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setConstant_int_int.cpp new file mode 100644 index 00000000..32b950cf --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setConstant_int_int.cpp @@ -0,0 +1,3 @@ +MatrixXf m; +m.setConstant(3, 3, 5); +cout << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setIdentity_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setIdentity_int_int.cpp new file mode 100644 index 00000000..a6596719 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setIdentity_int_int.cpp @@ -0,0 +1,3 @@ +MatrixXf m; +m.setIdentity(3, 3); +cout << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setOnes_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setOnes_int.cpp new file mode 100644 index 00000000..752cb35b --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setOnes_int.cpp @@ -0,0 +1,3 @@ +VectorXf v; +v.setOnes(3); +cout << v << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setOnes_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setOnes_int_int.cpp new file mode 100644 index 00000000..1ffb66bb --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setOnes_int_int.cpp @@ -0,0 +1,3 @@ +MatrixXf m; +m.setOnes(3, 3); +cout << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setRandom_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setRandom_int.cpp new file mode 100644 index 00000000..e160dd7d --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setRandom_int.cpp @@ -0,0 +1,3 @@ +VectorXf v; +v.setRandom(3); +cout << v << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setRandom_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setRandom_int_int.cpp new file mode 100644 index 00000000..80cda11d --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setRandom_int_int.cpp @@ -0,0 +1,3 @@ +MatrixXf m; +m.setRandom(3, 3); +cout << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setZero_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setZero_int.cpp new file mode 100644 index 00000000..0fb16c1f --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setZero_int.cpp @@ -0,0 +1,3 @@ +VectorXf v; +v.setZero(3); +cout << v << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setZero_int_int.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setZero_int_int.cpp new file mode 100644 index 00000000..ad883b91 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Matrix_setZero_int_int.cpp @@ -0,0 +1,3 @@ +MatrixXf m; +m.setZero(3, 3); +cout << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/PartialPivLU_solve.cpp b/testbed/nanogui/ext/eigen/doc/snippets/PartialPivLU_solve.cpp new file mode 100644 index 00000000..fa3570ab --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/PartialPivLU_solve.cpp @@ -0,0 +1,7 @@ +MatrixXd A = MatrixXd::Random(3,3); +MatrixXd B = MatrixXd::Random(3,2); +cout << "Here is the invertible matrix A:" << endl << A << endl; +cout << "Here is the matrix B:" << endl << B << endl; +MatrixXd X = A.lu().solve(B); +cout << "Here is the (unique) solution X to the equation AX=B:" << endl << X << endl; +cout << "Relative error: " << (A*X-B).norm() / B.norm() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_count.cpp b/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_count.cpp new file mode 100644 index 00000000..1c3b3a28 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_count.cpp @@ -0,0 +1,5 @@ +Matrix3d m = Matrix3d::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +Matrix res = (m.array() >= 0.5).rowwise().count(); +cout << "Here is the count of elements larger or equal than 0.5 of each row:" << endl; +cout << res << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_maxCoeff.cpp b/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_maxCoeff.cpp new file mode 100644 index 00000000..e8fd3820 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_maxCoeff.cpp @@ -0,0 +1,3 @@ +Matrix3d m = Matrix3d::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is the maximum of each column:" << endl << m.colwise().maxCoeff() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_minCoeff.cpp b/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_minCoeff.cpp new file mode 100644 index 00000000..d717bc0d --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_minCoeff.cpp @@ -0,0 +1,3 @@ +Matrix3d m = Matrix3d::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is the minimum of each column:" << endl << m.colwise().minCoeff() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_norm.cpp b/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_norm.cpp new file mode 100644 index 00000000..dbcf290a --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_norm.cpp @@ -0,0 +1,3 @@ +Matrix3d m = Matrix3d::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is the norm of each column:" << endl << m.colwise().norm() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_prod.cpp b/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_prod.cpp new file mode 100644 index 00000000..aacf09cb --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_prod.cpp @@ -0,0 +1,3 @@ +Matrix3d m = Matrix3d::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is the product of each row:" << endl << m.rowwise().prod() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_squaredNorm.cpp b/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_squaredNorm.cpp new file mode 100644 index 00000000..9f3293e6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_squaredNorm.cpp @@ -0,0 +1,3 @@ +Matrix3d m = Matrix3d::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is the square norm of each row:" << endl << m.rowwise().squaredNorm() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_sum.cpp b/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_sum.cpp new file mode 100644 index 00000000..ec82d3e4 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/PartialRedux_sum.cpp @@ -0,0 +1,3 @@ +Matrix3d m = Matrix3d::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is the sum of each row:" << endl << m.rowwise().sum() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/RealQZ_compute.cpp b/testbed/nanogui/ext/eigen/doc/snippets/RealQZ_compute.cpp new file mode 100644 index 00000000..a18da42e --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/RealQZ_compute.cpp @@ -0,0 +1,17 @@ +MatrixXf A = MatrixXf::Random(4,4); +MatrixXf B = MatrixXf::Random(4,4); +RealQZ qz(4); // preallocate space for 4x4 matrices +qz.compute(A,B); // A = Q S Z, B = Q T Z + +// print original matrices and result of decomposition +cout << "A:\n" << A << "\n" << "B:\n" << B << "\n"; +cout << "S:\n" << qz.matrixS() << "\n" << "T:\n" << qz.matrixT() << "\n"; +cout << "Q:\n" << qz.matrixQ() << "\n" << "Z:\n" << qz.matrixZ() << "\n"; + +// verify precision +cout << "\nErrors:" + << "\n|A-QSZ|: " << (A-qz.matrixQ()*qz.matrixS()*qz.matrixZ()).norm() + << ", |B-QTZ|: " << (B-qz.matrixQ()*qz.matrixT()*qz.matrixZ()).norm() + << "\n|QQ* - I|: " << (qz.matrixQ()*qz.matrixQ().adjoint() - MatrixXf::Identity(4,4)).norm() + << ", |ZZ* - I|: " << (qz.matrixZ()*qz.matrixZ().adjoint() - MatrixXf::Identity(4,4)).norm() + << "\n"; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/RealSchur_RealSchur_MatrixType.cpp b/testbed/nanogui/ext/eigen/doc/snippets/RealSchur_RealSchur_MatrixType.cpp new file mode 100644 index 00000000..a5530dcc --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/RealSchur_RealSchur_MatrixType.cpp @@ -0,0 +1,10 @@ +MatrixXd A = MatrixXd::Random(6,6); +cout << "Here is a random 6x6 matrix, A:" << endl << A << endl << endl; + +RealSchur schur(A); +cout << "The orthogonal matrix U is:" << endl << schur.matrixU() << endl; +cout << "The quasi-triangular matrix T is:" << endl << schur.matrixT() << endl << endl; + +MatrixXd U = schur.matrixU(); +MatrixXd T = schur.matrixT(); +cout << "U * T * U^T = " << endl << U * T * U.transpose() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/RealSchur_compute.cpp b/testbed/nanogui/ext/eigen/doc/snippets/RealSchur_compute.cpp new file mode 100644 index 00000000..20c2611b --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/RealSchur_compute.cpp @@ -0,0 +1,6 @@ +MatrixXf A = MatrixXf::Random(4,4); +RealSchur schur(4); +schur.compute(A, /* computeU = */ false); +cout << "The matrix T in the decomposition of A is:" << endl << schur.matrixT() << endl; +schur.compute(A.inverse(), /* computeU = */ false); +cout << "The matrix T in the decomposition of A^(-1) is:" << endl << schur.matrixT() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_SelfAdjointEigenSolver.cpp b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_SelfAdjointEigenSolver.cpp new file mode 100644 index 00000000..73a7f625 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_SelfAdjointEigenSolver.cpp @@ -0,0 +1,7 @@ +SelfAdjointEigenSolver es; +Matrix4f X = Matrix4f::Random(4,4); +Matrix4f A = X + X.transpose(); +es.compute(A); +cout << "The eigenvalues of A are: " << es.eigenvalues().transpose() << endl; +es.compute(A + Matrix4f::Identity(4,4)); // re-use es to compute eigenvalues of A+I +cout << "The eigenvalues of A+I are: " << es.eigenvalues().transpose() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_SelfAdjointEigenSolver_MatrixType.cpp b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_SelfAdjointEigenSolver_MatrixType.cpp new file mode 100644 index 00000000..3599b17a --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_SelfAdjointEigenSolver_MatrixType.cpp @@ -0,0 +1,17 @@ +MatrixXd X = MatrixXd::Random(5,5); +MatrixXd A = X + X.transpose(); +cout << "Here is a random symmetric 5x5 matrix, A:" << endl << A << endl << endl; + +SelfAdjointEigenSolver es(A); +cout << "The eigenvalues of A are:" << endl << es.eigenvalues() << endl; +cout << "The matrix of eigenvectors, V, is:" << endl << es.eigenvectors() << endl << endl; + +double lambda = es.eigenvalues()[0]; +cout << "Consider the first eigenvalue, lambda = " << lambda << endl; +VectorXd v = es.eigenvectors().col(0); +cout << "If v is the corresponding eigenvector, then lambda * v = " << endl << lambda * v << endl; +cout << "... and A * v = " << endl << A * v << endl << endl; + +MatrixXd D = es.eigenvalues().asDiagonal(); +MatrixXd V = es.eigenvectors(); +cout << "Finally, V * D * V^(-1) = " << endl << V * D * V.inverse() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_SelfAdjointEigenSolver_MatrixType2.cpp b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_SelfAdjointEigenSolver_MatrixType2.cpp new file mode 100644 index 00000000..bbb821e0 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_SelfAdjointEigenSolver_MatrixType2.cpp @@ -0,0 +1,16 @@ +MatrixXd X = MatrixXd::Random(5,5); +MatrixXd A = X + X.transpose(); +cout << "Here is a random symmetric matrix, A:" << endl << A << endl; +X = MatrixXd::Random(5,5); +MatrixXd B = X * X.transpose(); +cout << "and a random postive-definite matrix, B:" << endl << B << endl << endl; + +GeneralizedSelfAdjointEigenSolver es(A,B); +cout << "The eigenvalues of the pencil (A,B) are:" << endl << es.eigenvalues() << endl; +cout << "The matrix of eigenvectors, V, is:" << endl << es.eigenvectors() << endl << endl; + +double lambda = es.eigenvalues()[0]; +cout << "Consider the first eigenvalue, lambda = " << lambda << endl; +VectorXd v = es.eigenvectors().col(0); +cout << "If v is the corresponding eigenvector, then A * v = " << endl << A * v << endl; +cout << "... and lambda * B * v = " << endl << lambda * B * v << endl << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_compute_MatrixType.cpp b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_compute_MatrixType.cpp new file mode 100644 index 00000000..2975cc3f --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_compute_MatrixType.cpp @@ -0,0 +1,7 @@ +SelfAdjointEigenSolver es(4); +MatrixXf X = MatrixXf::Random(4,4); +MatrixXf A = X + X.transpose(); +es.compute(A); +cout << "The eigenvalues of A are: " << es.eigenvalues().transpose() << endl; +es.compute(A + MatrixXf::Identity(4,4)); // re-use es to compute eigenvalues of A+I +cout << "The eigenvalues of A+I are: " << es.eigenvalues().transpose() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_compute_MatrixType2.cpp b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_compute_MatrixType2.cpp new file mode 100644 index 00000000..07c92a1e --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_compute_MatrixType2.cpp @@ -0,0 +1,9 @@ +MatrixXd X = MatrixXd::Random(5,5); +MatrixXd A = X * X.transpose(); +X = MatrixXd::Random(5,5); +MatrixXd B = X * X.transpose(); + +GeneralizedSelfAdjointEigenSolver es(A,B,EigenvaluesOnly); +cout << "The eigenvalues of the pencil (A,B) are:" << endl << es.eigenvalues() << endl; +es.compute(B,A,false); +cout << "The eigenvalues of the pencil (B,A) are:" << endl << es.eigenvalues() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_eigenvalues.cpp b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_eigenvalues.cpp new file mode 100644 index 00000000..0ff33c68 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_eigenvalues.cpp @@ -0,0 +1,4 @@ +MatrixXd ones = MatrixXd::Ones(3,3); +SelfAdjointEigenSolver es(ones); +cout << "The eigenvalues of the 3x3 matrix of ones are:" + << endl << es.eigenvalues() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_eigenvectors.cpp b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_eigenvectors.cpp new file mode 100644 index 00000000..cfc8b0d5 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_eigenvectors.cpp @@ -0,0 +1,4 @@ +MatrixXd ones = MatrixXd::Ones(3,3); +SelfAdjointEigenSolver es(ones); +cout << "The first eigenvector of the 3x3 matrix of ones is:" + << endl << es.eigenvectors().col(1) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_operatorInverseSqrt.cpp b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_operatorInverseSqrt.cpp new file mode 100644 index 00000000..114c65fb --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_operatorInverseSqrt.cpp @@ -0,0 +1,9 @@ +MatrixXd X = MatrixXd::Random(4,4); +MatrixXd A = X * X.transpose(); +cout << "Here is a random positive-definite matrix, A:" << endl << A << endl << endl; + +SelfAdjointEigenSolver es(A); +cout << "The inverse square root of A is: " << endl; +cout << es.operatorInverseSqrt() << endl; +cout << "We can also compute it with operatorSqrt() and inverse(). That yields: " << endl; +cout << es.operatorSqrt().inverse() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_operatorSqrt.cpp b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_operatorSqrt.cpp new file mode 100644 index 00000000..eeacca74 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointEigenSolver_operatorSqrt.cpp @@ -0,0 +1,8 @@ +MatrixXd X = MatrixXd::Random(4,4); +MatrixXd A = X * X.transpose(); +cout << "Here is a random positive-definite matrix, A:" << endl << A << endl << endl; + +SelfAdjointEigenSolver es(A); +MatrixXd sqrtA = es.operatorSqrt(); +cout << "The square root of A is: " << endl << sqrtA << endl; +cout << "If we square this, we get: " << endl << sqrtA*sqrtA << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointView_eigenvalues.cpp b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointView_eigenvalues.cpp new file mode 100644 index 00000000..be198677 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointView_eigenvalues.cpp @@ -0,0 +1,3 @@ +MatrixXd ones = MatrixXd::Ones(3,3); +VectorXd eivals = ones.selfadjointView().eigenvalues(); +cout << "The eigenvalues of the 3x3 matrix of ones are:" << endl << eivals << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointView_operatorNorm.cpp b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointView_operatorNorm.cpp new file mode 100644 index 00000000..f380f559 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/SelfAdjointView_operatorNorm.cpp @@ -0,0 +1,3 @@ +MatrixXd ones = MatrixXd::Ones(3,3); +cout << "The operator norm of the 3x3 matrix of ones is " + << ones.selfadjointView().operatorNorm() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/SparseMatrix_coeffs.cpp b/testbed/nanogui/ext/eigen/doc/snippets/SparseMatrix_coeffs.cpp new file mode 100644 index 00000000..f71a69b0 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/SparseMatrix_coeffs.cpp @@ -0,0 +1,9 @@ +SparseMatrix A(3,3); +A.insert(1,2) = 0; +A.insert(0,1) = 1; +A.insert(2,0) = 2; +A.makeCompressed(); +cout << "The matrix A is:" << endl << MatrixXd(A) << endl; +cout << "it has " << A.nonZeros() << " stored non zero coefficients that are: " << A.coeffs().transpose() << endl; +A.coeffs() += 10; +cout << "After adding 10 to every stored non zero coefficient, the matrix A is:" << endl << MatrixXd(A) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_block.cpp b/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_block.cpp new file mode 100644 index 00000000..03282f4f --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_block.cpp @@ -0,0 +1,7 @@ +MatrixXi mat(3,3); +mat << 1, 2, 3, 4, 5, 6, 7, 8, 9; +cout << "Here is the matrix mat:\n" << mat << endl; + +// This assignment shows the aliasing problem +mat.bottomRightCorner(2,2) = mat.topLeftCorner(2,2); +cout << "After the assignment, mat = \n" << mat << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_block_correct.cpp b/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_block_correct.cpp new file mode 100644 index 00000000..6fee5801 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_block_correct.cpp @@ -0,0 +1,7 @@ +MatrixXi mat(3,3); +mat << 1, 2, 3, 4, 5, 6, 7, 8, 9; +cout << "Here is the matrix mat:\n" << mat << endl; + +// The eval() solves the aliasing problem +mat.bottomRightCorner(2,2) = mat.topLeftCorner(2,2).eval(); +cout << "After the assignment, mat = \n" << mat << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_cwise.cpp b/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_cwise.cpp new file mode 100644 index 00000000..7049f6c5 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_cwise.cpp @@ -0,0 +1,20 @@ +MatrixXf mat(2,2); +mat << 1, 2, 4, 7; +cout << "Here is the matrix mat:\n" << mat << endl << endl; + +mat = 2 * mat; +cout << "After 'mat = 2 * mat', mat = \n" << mat << endl << endl; + + +mat = mat - MatrixXf::Identity(2,2); +cout << "After the subtraction, it becomes\n" << mat << endl << endl; + + +ArrayXXf arr = mat; +arr = arr.square(); +cout << "After squaring, it becomes\n" << arr << endl << endl; + +// Combining all operations in one statement: +mat << 1, 2, 4, 7; +mat = (2 * mat - MatrixXf::Identity(2,2)).array().square(); +cout << "Doing everything at once yields\n" << mat << endl << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_mult1.cpp b/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_mult1.cpp new file mode 100644 index 00000000..cd7e9004 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_mult1.cpp @@ -0,0 +1,4 @@ +MatrixXf matA(2,2); +matA << 2, 0, 0, 2; +matA = matA * matA; +cout << matA; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_mult2.cpp b/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_mult2.cpp new file mode 100644 index 00000000..a3ff5685 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_mult2.cpp @@ -0,0 +1,10 @@ +MatrixXf matA(2,2), matB(2,2); +matA << 2, 0, 0, 2; + +// Simple but not quite as efficient +matB = matA * matA; +cout << matB << endl << endl; + +// More complicated but also more efficient +matB.noalias() = matA * matA; +cout << matB; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_mult3.cpp b/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_mult3.cpp new file mode 100644 index 00000000..1d12a6c6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_mult3.cpp @@ -0,0 +1,4 @@ +MatrixXf matA(2,2); +matA << 2, 0, 0, 2; +matA.noalias() = matA * matA; +cout << matA; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_mult4.cpp b/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_mult4.cpp new file mode 100644 index 00000000..8a8992f6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_mult4.cpp @@ -0,0 +1,5 @@ +MatrixXf A(2,2), B(3,2); +B << 2, 0, 0, 3, 1, 1; +A << 2, 0, 0, -2; +A = (B * A).cwiseAbs(); +cout << A; \ No newline at end of file diff --git a/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_mult5.cpp b/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_mult5.cpp new file mode 100644 index 00000000..1a36defd --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/TopicAliasing_mult5.cpp @@ -0,0 +1,5 @@ +MatrixXf A(2,2), B(3,2); +B << 2, 0, 0, 3, 1, 1; +A << 2, 0, 0, -2; +A = (B * A).eval().cwiseAbs(); +cout << A; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/TopicStorageOrders_example.cpp b/testbed/nanogui/ext/eigen/doc/snippets/TopicStorageOrders_example.cpp new file mode 100644 index 00000000..0623ef0c --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/TopicStorageOrders_example.cpp @@ -0,0 +1,18 @@ +Matrix Acolmajor; +Acolmajor << 8, 2, 2, 9, + 9, 1, 4, 4, + 3, 5, 4, 5; +cout << "The matrix A:" << endl; +cout << Acolmajor << endl << endl; + +cout << "In memory (column-major):" << endl; +for (int i = 0; i < Acolmajor.size(); i++) + cout << *(Acolmajor.data() + i) << " "; +cout << endl << endl; + +Matrix Arowmajor = Acolmajor; +cout << "In memory (row-major):" << endl; +for (int i = 0; i < Arowmajor.size(); i++) + cout << *(Arowmajor.data() + i) << " "; +cout << endl; + diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Triangular_solve.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Triangular_solve.cpp new file mode 100644 index 00000000..54844246 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Triangular_solve.cpp @@ -0,0 +1,11 @@ +Matrix3d m = Matrix3d::Zero(); +m.triangularView().setOnes(); +cout << "Here is the matrix m:\n" << m << endl; +Matrix3d n = Matrix3d::Ones(); +n.triangularView() *= 2; +cout << "Here is the matrix n:\n" << n << endl; +cout << "And now here is m.inverse()*n, taking advantage of the fact that" + " m is upper-triangular:\n" + << m.triangularView().solve(n) << endl; +cout << "And this is n*m.inverse():\n" + << m.triangularView().solve(n); diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_Tridiagonalization_MatrixType.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_Tridiagonalization_MatrixType.cpp new file mode 100644 index 00000000..a2601243 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_Tridiagonalization_MatrixType.cpp @@ -0,0 +1,9 @@ +MatrixXd X = MatrixXd::Random(5,5); +MatrixXd A = X + X.transpose(); +cout << "Here is a random symmetric 5x5 matrix:" << endl << A << endl << endl; +Tridiagonalization triOfA(A); +MatrixXd Q = triOfA.matrixQ(); +cout << "The orthogonal matrix Q is:" << endl << Q << endl; +MatrixXd T = triOfA.matrixT(); +cout << "The tridiagonal matrix T is:" << endl << T << endl << endl; +cout << "Q * T * Q^T = " << endl << Q * T * Q.transpose() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_compute.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_compute.cpp new file mode 100644 index 00000000..0062a99e --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_compute.cpp @@ -0,0 +1,9 @@ +Tridiagonalization tri; +MatrixXf X = MatrixXf::Random(4,4); +MatrixXf A = X + X.transpose(); +tri.compute(A); +cout << "The matrix T in the tridiagonal decomposition of A is: " << endl; +cout << tri.matrixT() << endl; +tri.compute(2*A); // re-use tri to compute eigenvalues of 2A +cout << "The matrix T in the tridiagonal decomposition of 2A is: " << endl; +cout << tri.matrixT() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_decomposeInPlace.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_decomposeInPlace.cpp new file mode 100644 index 00000000..93dcfca1 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_decomposeInPlace.cpp @@ -0,0 +1,10 @@ +MatrixXd X = MatrixXd::Random(5,5); +MatrixXd A = X + X.transpose(); +cout << "Here is a random symmetric 5x5 matrix:" << endl << A << endl << endl; + +VectorXd diag(5); +VectorXd subdiag(4); +internal::tridiagonalization_inplace(A, diag, subdiag, true); +cout << "The orthogonal matrix Q is:" << endl << A << endl; +cout << "The diagonal of the tridiagonal matrix T is:" << endl << diag << endl; +cout << "The subdiagonal of the tridiagonal matrix T is:" << endl << subdiag << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_diagonal.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_diagonal.cpp new file mode 100644 index 00000000..6eec8216 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_diagonal.cpp @@ -0,0 +1,13 @@ +MatrixXcd X = MatrixXcd::Random(4,4); +MatrixXcd A = X + X.adjoint(); +cout << "Here is a random self-adjoint 4x4 matrix:" << endl << A << endl << endl; + +Tridiagonalization triOfA(A); +MatrixXd T = triOfA.matrixT(); +cout << "The tridiagonal matrix T is:" << endl << T << endl << endl; + +cout << "We can also extract the diagonals of T directly ..." << endl; +VectorXd diag = triOfA.diagonal(); +cout << "The diagonal is:" << endl << diag << endl; +VectorXd subdiag = triOfA.subDiagonal(); +cout << "The subdiagonal is:" << endl << subdiag << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_householderCoefficients.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_householderCoefficients.cpp new file mode 100644 index 00000000..e5d87288 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_householderCoefficients.cpp @@ -0,0 +1,6 @@ +Matrix4d X = Matrix4d::Random(4,4); +Matrix4d A = X + X.transpose(); +cout << "Here is a random symmetric 4x4 matrix:" << endl << A << endl; +Tridiagonalization triOfA(A); +Vector3d hc = triOfA.householderCoefficients(); +cout << "The vector of Householder coefficients is:" << endl << hc << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_packedMatrix.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_packedMatrix.cpp new file mode 100644 index 00000000..0f55d0c2 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tridiagonalization_packedMatrix.cpp @@ -0,0 +1,8 @@ +Matrix4d X = Matrix4d::Random(4,4); +Matrix4d A = X + X.transpose(); +cout << "Here is a random symmetric 4x4 matrix:" << endl << A << endl; +Tridiagonalization triOfA(A); +Matrix4d pm = triOfA.packedMatrix(); +cout << "The packed matrix M is:" << endl << pm << endl; +cout << "The diagonal and subdiagonal corresponds to the matrix T, which is:" + << endl << triOfA.matrixT() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_Block.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_Block.cpp new file mode 100644 index 00000000..96e40acf --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_Block.cpp @@ -0,0 +1,5 @@ +MatrixXf matA(2, 2); +matA << 1, 2, 3, 4; +MatrixXf matB(4, 4); +matB << matA, matA/10, matA/10, matA; +std::cout << matB << std::endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_CommaTemporary.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_CommaTemporary.cpp new file mode 100644 index 00000000..50cff4cb --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_CommaTemporary.cpp @@ -0,0 +1,4 @@ +MatrixXf mat = MatrixXf::Random(2, 3); +std::cout << mat << std::endl << std::endl; +mat = (MatrixXf(2,2) << 0, 1, 1, 0).finished() * mat; +std::cout << mat << std::endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_Join.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_Join.cpp new file mode 100644 index 00000000..55a21539 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_Join.cpp @@ -0,0 +1,11 @@ +RowVectorXd vec1(3); +vec1 << 1, 2, 3; +std::cout << "vec1 = " << vec1 << std::endl; + +RowVectorXd vec2(4); +vec2 << 1, 4, 9, 16; +std::cout << "vec2 = " << vec2 << std::endl; + +RowVectorXd joined(7); +joined << vec1, vec2; +std::cout << "joined = " << joined << std::endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_LinSpaced.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_LinSpaced.cpp new file mode 100644 index 00000000..c6a73ab8 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_LinSpaced.cpp @@ -0,0 +1,7 @@ +ArrayXXf table(10, 4); +table.col(0) = ArrayXf::LinSpaced(10, 0, 90); +table.col(1) = M_PI / 180 * table.col(0); +table.col(2) = table.col(1).sin(); +table.col(3) = table.col(1).cos(); +std::cout << " Degrees Radians Sine Cosine\n"; +std::cout << table << std::endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_ThreeWays.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_ThreeWays.cpp new file mode 100644 index 00000000..cb745765 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_ThreeWays.cpp @@ -0,0 +1,20 @@ +const int size = 6; +MatrixXd mat1(size, size); +mat1.topLeftCorner(size/2, size/2) = MatrixXd::Zero(size/2, size/2); +mat1.topRightCorner(size/2, size/2) = MatrixXd::Identity(size/2, size/2); +mat1.bottomLeftCorner(size/2, size/2) = MatrixXd::Identity(size/2, size/2); +mat1.bottomRightCorner(size/2, size/2) = MatrixXd::Zero(size/2, size/2); +std::cout << mat1 << std::endl << std::endl; + +MatrixXd mat2(size, size); +mat2.topLeftCorner(size/2, size/2).setZero(); +mat2.topRightCorner(size/2, size/2).setIdentity(); +mat2.bottomLeftCorner(size/2, size/2).setIdentity(); +mat2.bottomRightCorner(size/2, size/2).setZero(); +std::cout << mat2 << std::endl << std::endl; + +MatrixXd mat3(size, size); +mat3 << MatrixXd::Zero(size/2, size/2), MatrixXd::Identity(size/2, size/2), + MatrixXd::Identity(size/2, size/2), MatrixXd::Zero(size/2, size/2); +std::cout << mat3 << std::endl; + diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_Zero.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_Zero.cpp new file mode 100644 index 00000000..76a36a31 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_AdvancedInitialization_Zero.cpp @@ -0,0 +1,13 @@ +std::cout << "A fixed-size array:\n"; +Array33f a1 = Array33f::Zero(); +std::cout << a1 << "\n\n"; + + +std::cout << "A one-dimensional dynamic-size array:\n"; +ArrayXf a2 = ArrayXf::Zero(3); +std::cout << a2 << "\n\n"; + + +std::cout << "A two-dimensional dynamic-size array:\n"; +ArrayXXf a3 = ArrayXXf::Zero(3, 4); +std::cout << a3 << "\n"; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_Map_rowmajor.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_Map_rowmajor.cpp new file mode 100644 index 00000000..fd45ace0 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_Map_rowmajor.cpp @@ -0,0 +1,7 @@ +int array[8]; +for(int i = 0; i < 8; ++i) array[i] = i; +cout << "Column-major:\n" << Map >(array) << endl; +cout << "Row-major:\n" << Map >(array) << endl; +cout << "Row-major using stride:\n" << + Map, Unaligned, Stride<1,4> >(array) << endl; + diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_Map_using.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_Map_using.cpp new file mode 100644 index 00000000..e5e499f1 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_Map_using.cpp @@ -0,0 +1,21 @@ +typedef Matrix MatrixType; +typedef Map MapType; +typedef Map MapTypeConst; // a read-only map +const int n_dims = 5; + +MatrixType m1(n_dims), m2(n_dims); +m1.setRandom(); +m2.setRandom(); +float *p = &m2(0); // get the address storing the data for m2 +MapType m2map(p,m2.size()); // m2map shares data with m2 +MapTypeConst m2mapconst(p,m2.size()); // a read-only accessor for m2 + +cout << "m1: " << m1 << endl; +cout << "m2: " << m2 << endl; +cout << "Squared euclidean distance: " << (m1-m2).squaredNorm() << endl; +cout << "Squared euclidean distance, using map: " << + (m1-m2map).squaredNorm() << endl; +m2map(3) = 7; // this will change m2, since they share the same array +cout << "Updated m2: " << m2 << endl; +cout << "m2 coefficient 2, constant accessor: " << m2mapconst(2) << endl; +/* m2mapconst(2) = 5; */ // this yields a compile-time error diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_ReshapeMat2Mat.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_ReshapeMat2Mat.cpp new file mode 100644 index 00000000..f84d6e76 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_ReshapeMat2Mat.cpp @@ -0,0 +1,6 @@ +MatrixXf M1(2,6); // Column-major storage +M1 << 1, 2, 3, 4, 5, 6, + 7, 8, 9, 10, 11, 12; + +Map M2(M1.data(), 6,2); +cout << "M2:" << endl << M2 << endl; \ No newline at end of file diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_ReshapeMat2Vec.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_ReshapeMat2Vec.cpp new file mode 100644 index 00000000..95bd4e0e --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_ReshapeMat2Vec.cpp @@ -0,0 +1,11 @@ +MatrixXf M1(3,3); // Column-major storage +M1 << 1, 2, 3, + 4, 5, 6, + 7, 8, 9; + +Map v1(M1.data(), M1.size()); +cout << "v1:" << endl << v1 << endl; + +Matrix M2(M1); +Map v2(M2.data(), M2.size()); +cout << "v2:" << endl << v2 << endl; \ No newline at end of file diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_SlicingCol.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_SlicingCol.cpp new file mode 100644 index 00000000..f667ff68 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_SlicingCol.cpp @@ -0,0 +1,11 @@ +MatrixXf M1 = MatrixXf::Random(3,8); +cout << "Column major input:" << endl << M1 << "\n"; +Map > M2(M1.data(), M1.rows(), (M1.cols()+2)/3, OuterStride<>(M1.outerStride()*3)); +cout << "1 column over 3:" << endl << M2 << "\n"; + +typedef Matrix RowMajorMatrixXf; +RowMajorMatrixXf M3(M1); +cout << "Row major input:" << endl << M3 << "\n"; +Map > M4(M3.data(), M3.rows(), (M3.cols()+2)/3, + Stride(M3.outerStride(),3)); +cout << "1 column over 3:" << endl << M4 << "\n"; \ No newline at end of file diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_SlicingVec.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_SlicingVec.cpp new file mode 100644 index 00000000..07e10bf6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_SlicingVec.cpp @@ -0,0 +1,4 @@ +RowVectorXf v = RowVectorXf::LinSpaced(20,0,19); +cout << "Input:" << endl << v << endl; +Map > v2(v.data(), v.size()/2); +cout << "Even:" << v2 << endl; \ No newline at end of file diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_commainit_01.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_commainit_01.cpp new file mode 100644 index 00000000..47ba31dc --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_commainit_01.cpp @@ -0,0 +1,5 @@ +Matrix3f m; +m << 1, 2, 3, + 4, 5, 6, + 7, 8, 9; +std::cout << m; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_commainit_01b.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_commainit_01b.cpp new file mode 100644 index 00000000..2adb2e21 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_commainit_01b.cpp @@ -0,0 +1,5 @@ +Matrix3f m; +m.row(0) << 1, 2, 3; +m.block(1,0,2,2) << 4, 5, 7, 8; +m.col(2).tail(2) << 6, 9; +std::cout << m; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_commainit_02.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_commainit_02.cpp new file mode 100644 index 00000000..c960d6ab --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_commainit_02.cpp @@ -0,0 +1,7 @@ +int rows=5, cols=5; +MatrixXf m(rows,cols); +m << (Matrix3f() << 1, 2, 3, 4, 5, 6, 7, 8, 9).finished(), + MatrixXf::Zero(3,cols-3), + MatrixXf::Zero(rows-3,3), + MatrixXf::Identity(rows-3,cols-3); +cout << m; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_matrix_inverse.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_matrix_inverse.cpp new file mode 100644 index 00000000..fff32444 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_matrix_inverse.cpp @@ -0,0 +1,6 @@ +Matrix3f A; +Vector3f b; +A << 1,2,3, 4,5,6, 7,8,10; +b << 3, 3, 4; +Vector3f x = A.inverse() * b; +cout << "The solution is:" << endl << x << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_multiple_rhs.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_multiple_rhs.cpp new file mode 100644 index 00000000..5411a44a --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_multiple_rhs.cpp @@ -0,0 +1,10 @@ +Matrix3f A(3,3); +A << 1,2,3, 4,5,6, 7,8,10; +Matrix B; +B << 3,1, 3,1, 4,1; +Matrix X; +X = A.fullPivLu().solve(B); +cout << "The solution with right-hand side (3,3,4) is:" << endl; +cout << X.col(0) << endl; +cout << "The solution with right-hand side (1,1,1) is:" << endl; +cout << X.col(1) << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_reuse_decomposition.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_reuse_decomposition.cpp new file mode 100644 index 00000000..3ca06453 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_reuse_decomposition.cpp @@ -0,0 +1,13 @@ +Matrix3f A(3,3); +A << 1,2,3, 4,5,6, 7,8,10; +PartialPivLU luOfA(A); // compute LU decomposition of A +Vector3f b; +b << 3,3,4; +Vector3f x; +x = luOfA.solve(b); +cout << "The solution with right-hand side (3,3,4) is:" << endl; +cout << x << endl; +b << 1,1,1; +x = luOfA.solve(b); +cout << "The solution with right-hand side (1,1,1) is:" << endl; +cout << x << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_singular.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_singular.cpp new file mode 100644 index 00000000..abff1ef7 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_singular.cpp @@ -0,0 +1,9 @@ +Matrix3f A; +Vector3f b; +A << 1,2,3, 4,5,6, 7,8,9; +b << 3, 3, 4; +cout << "Here is the matrix A:" << endl << A << endl; +cout << "Here is the vector b:" << endl << b << endl; +Vector3f x; +x = A.lu().solve(b); +cout << "The solution is:" << endl << x << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_triangular.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_triangular.cpp new file mode 100644 index 00000000..9d13f22e --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_triangular.cpp @@ -0,0 +1,8 @@ +Matrix3f A; +Vector3f b; +A << 1,2,3, 0,5,6, 0,0,10; +b << 3, 3, 4; +cout << "Here is the matrix A:" << endl << A << endl; +cout << "Here is the vector b:" << endl << b << endl; +Vector3f x = A.triangularView().solve(b); +cout << "The solution is:" << endl << x << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_triangular_inplace.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_triangular_inplace.cpp new file mode 100644 index 00000000..16ae633a --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Tutorial_solve_triangular_inplace.cpp @@ -0,0 +1,6 @@ +Matrix3f A; +Vector3f b; +A << 1,2,3, 0,5,6, 0,0,10; +b << 3, 3, 4; +A.triangularView().solveInPlace(b); +cout << "The solution is:" << endl << b << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/VectorwiseOp_homogeneous.cpp b/testbed/nanogui/ext/eigen/doc/snippets/VectorwiseOp_homogeneous.cpp new file mode 100644 index 00000000..aba4fed0 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/VectorwiseOp_homogeneous.cpp @@ -0,0 +1,7 @@ +typedef Matrix Matrix3Xd; +Matrix3Xd M = Matrix3Xd::Random(3,5); +Projective3d P(Matrix4d::Random()); +cout << "The matrix M is:" << endl << M << endl << endl; +cout << "M.colwise().homogeneous():" << endl << M.colwise().homogeneous() << endl << endl; +cout << "P * M.colwise().homogeneous():" << endl << P * M.colwise().homogeneous() << endl << endl; +cout << "P * M.colwise().homogeneous().hnormalized(): " << endl << (P * M.colwise().homogeneous()).colwise().hnormalized() << endl << endl; \ No newline at end of file diff --git a/testbed/nanogui/ext/eigen/doc/snippets/Vectorwise_reverse.cpp b/testbed/nanogui/ext/eigen/doc/snippets/Vectorwise_reverse.cpp new file mode 100644 index 00000000..2f6a3508 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/Vectorwise_reverse.cpp @@ -0,0 +1,10 @@ +MatrixXi m = MatrixXi::Random(3,4); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is the rowwise reverse of m:" << endl << m.rowwise().reverse() << endl; +cout << "Here is the colwise reverse of m:" << endl << m.colwise().reverse() << endl; + +cout << "Here is the coefficient (1,0) in the rowise reverse of m:" << endl +<< m.rowwise().reverse()(1,0) << endl; +cout << "Let us overwrite this coefficient with the value 4." << endl; +//m.colwise().reverse()(1,0) = 4; +cout << "Now the matrix m is:" << endl << m << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/class_FullPivLU.cpp b/testbed/nanogui/ext/eigen/doc/snippets/class_FullPivLU.cpp new file mode 100644 index 00000000..fce7fac0 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/class_FullPivLU.cpp @@ -0,0 +1,16 @@ +typedef Matrix Matrix5x3; +typedef Matrix Matrix5x5; +Matrix5x3 m = Matrix5x3::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +Eigen::FullPivLU lu(m); +cout << "Here is, up to permutations, its LU decomposition matrix:" + << endl << lu.matrixLU() << endl; +cout << "Here is the L part:" << endl; +Matrix5x5 l = Matrix5x5::Identity(); +l.block<5,3>(0,0).triangularView() = lu.matrixLU(); +cout << l << endl; +cout << "Here is the U part:" << endl; +Matrix5x3 u = lu.matrixLU().triangularView(); +cout << u << endl; +cout << "Let us now reconstruct the original matrix m:" << endl; +cout << lu.permutationP().inverse() * l * u * lu.permutationQ().inverse() << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/compile_snippet.cpp.in b/testbed/nanogui/ext/eigen/doc/snippets/compile_snippet.cpp.in new file mode 100644 index 00000000..d63f371a --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/compile_snippet.cpp.in @@ -0,0 +1,20 @@ +static bool eigen_did_assert = false; +#define eigen_assert(X) if(!eigen_did_assert && !(X)){ std::cout << "### Assertion raised in " << __FILE__ << ":" << __LINE__ << ":\n" #X << "\n### The following would happen without assertions:\n"; eigen_did_assert = true;} + +#include +#include + +#ifndef M_PI +#define M_PI 3.1415926535897932384626433832795 +#endif + + +using namespace Eigen; +using namespace std; + +int main(int, char**) +{ + cout.precision(3); + ${snippet_source_code} + return 0; +} diff --git a/testbed/nanogui/ext/eigen/doc/snippets/tut_arithmetic_redux_minmax.cpp b/testbed/nanogui/ext/eigen/doc/snippets/tut_arithmetic_redux_minmax.cpp new file mode 100644 index 00000000..f4ae7f40 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/tut_arithmetic_redux_minmax.cpp @@ -0,0 +1,12 @@ + Matrix3f m = Matrix3f::Random(); + std::ptrdiff_t i, j; + float minOfM = m.minCoeff(&i,&j); + cout << "Here is the matrix m:\n" << m << endl; + cout << "Its minimum coefficient (" << minOfM + << ") is at position (" << i << "," << j << ")\n\n"; + + RowVector4i v = RowVector4i::Random(); + int maxOfV = v.maxCoeff(&i); + cout << "Here is the vector v: " << v << endl; + cout << "Its maximum coefficient (" << maxOfV + << ") is at position " << i << endl; diff --git a/testbed/nanogui/ext/eigen/doc/snippets/tut_arithmetic_transpose_aliasing.cpp b/testbed/nanogui/ext/eigen/doc/snippets/tut_arithmetic_transpose_aliasing.cpp new file mode 100644 index 00000000..c8e4746d --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/tut_arithmetic_transpose_aliasing.cpp @@ -0,0 +1,5 @@ +Matrix2i a; a << 1, 2, 3, 4; +cout << "Here is the matrix a:\n" << a << endl; + +a = a.transpose(); // !!! do NOT do this !!! +cout << "and the result of the aliasing effect:\n" << a << endl; \ No newline at end of file diff --git a/testbed/nanogui/ext/eigen/doc/snippets/tut_arithmetic_transpose_conjugate.cpp b/testbed/nanogui/ext/eigen/doc/snippets/tut_arithmetic_transpose_conjugate.cpp new file mode 100644 index 00000000..88496b22 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/tut_arithmetic_transpose_conjugate.cpp @@ -0,0 +1,12 @@ +MatrixXcf a = MatrixXcf::Random(2,2); +cout << "Here is the matrix a\n" << a << endl; + +cout << "Here is the matrix a^T\n" << a.transpose() << endl; + + +cout << "Here is the conjugate of a\n" << a.conjugate() << endl; + + +cout << "Here is the matrix a^*\n" << a.adjoint() << endl; + + diff --git a/testbed/nanogui/ext/eigen/doc/snippets/tut_arithmetic_transpose_inplace.cpp b/testbed/nanogui/ext/eigen/doc/snippets/tut_arithmetic_transpose_inplace.cpp new file mode 100644 index 00000000..7a069ff2 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/tut_arithmetic_transpose_inplace.cpp @@ -0,0 +1,6 @@ +MatrixXf a(2,3); a << 1, 2, 3, 4, 5, 6; +cout << "Here is the initial matrix a:\n" << a << endl; + + +a.transposeInPlace(); +cout << "and after being transposed:\n" << a << endl; \ No newline at end of file diff --git a/testbed/nanogui/ext/eigen/doc/snippets/tut_matrix_assignment_resizing.cpp b/testbed/nanogui/ext/eigen/doc/snippets/tut_matrix_assignment_resizing.cpp new file mode 100644 index 00000000..cf189983 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/snippets/tut_matrix_assignment_resizing.cpp @@ -0,0 +1,5 @@ +MatrixXf a(2,2); +std::cout << "a is of size " << a.rows() << "x" << a.cols() << std::endl; +MatrixXf b(3,3); +a = b; +std::cout << "a is now of size " << a.rows() << "x" << a.cols() << std::endl; diff --git a/testbed/nanogui/ext/eigen/doc/special_examples/CMakeLists.txt b/testbed/nanogui/ext/eigen/doc/special_examples/CMakeLists.txt new file mode 100644 index 00000000..101fbc5f --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/special_examples/CMakeLists.txt @@ -0,0 +1,35 @@ +if(NOT EIGEN_TEST_NOQT) + find_package(Qt4) + if(QT4_FOUND) + include(${QT_USE_FILE}) + endif() +endif(NOT EIGEN_TEST_NOQT) + +if(QT4_FOUND) + add_executable(Tutorial_sparse_example Tutorial_sparse_example.cpp Tutorial_sparse_example_details.cpp) + target_link_libraries(Tutorial_sparse_example ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO} ${QT_QTCORE_LIBRARY} ${QT_QTGUI_LIBRARY}) + + add_custom_command( + TARGET Tutorial_sparse_example + POST_BUILD + COMMAND ${CMAKE_COMMAND} -E make_directory ${CMAKE_CURRENT_BINARY_DIR}/../html/ + COMMAND Tutorial_sparse_example ARGS ${CMAKE_CURRENT_BINARY_DIR}/../html/Tutorial_sparse_example.jpeg + ) + + add_dependencies(all_examples Tutorial_sparse_example) +endif(QT4_FOUND) + +check_cxx_compiler_flag("-std=c++11" EIGEN_COMPILER_SUPPORT_CPP11) +if(EIGEN_COMPILER_SUPPORT_CPP11) + add_executable(random_cpp11 random_cpp11.cpp) + target_link_libraries(random_cpp11 ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO}) + add_dependencies(all_examples random_cpp11) + ei_add_target_property(random_cpp11 COMPILE_FLAGS "-std=c++11") + + add_custom_command( + TARGET random_cpp11 + POST_BUILD + COMMAND random_cpp11 + ARGS >${CMAKE_CURRENT_BINARY_DIR}/random_cpp11.out + ) +endif() diff --git a/testbed/nanogui/ext/eigen/doc/special_examples/Tutorial_sparse_example.cpp b/testbed/nanogui/ext/eigen/doc/special_examples/Tutorial_sparse_example.cpp new file mode 100644 index 00000000..830e196e --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/special_examples/Tutorial_sparse_example.cpp @@ -0,0 +1,34 @@ +#include +#include + +typedef Eigen::SparseMatrix SpMat; // declares a column-major sparse matrix type of double +typedef Eigen::Triplet T; + +void buildProblem(std::vector& coefficients, Eigen::VectorXd& b, int n); +void saveAsBitmap(const Eigen::VectorXd& x, int n, const char* filename); + +int main(int argc, char** argv) +{ + assert(argc==2); + + int n = 300; // size of the image + int m = n*n; // number of unknows (=number of pixels) + + // Assembly: + std::vector coefficients; // list of non-zeros coefficients + Eigen::VectorXd b(m); // the right hand side-vector resulting from the constraints + buildProblem(coefficients, b, n); + + SpMat A(m,m); + A.setFromTriplets(coefficients.begin(), coefficients.end()); + + // Solving: + Eigen::SimplicialCholesky chol(A); // performs a Cholesky factorization of A + Eigen::VectorXd x = chol.solve(b); // use the factorization to solve for the given right hand side + + // Export the result to a file: + saveAsBitmap(x, n, argv[1]); + + return 0; +} + diff --git a/testbed/nanogui/ext/eigen/doc/special_examples/Tutorial_sparse_example_details.cpp b/testbed/nanogui/ext/eigen/doc/special_examples/Tutorial_sparse_example_details.cpp new file mode 100644 index 00000000..bc18b018 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/special_examples/Tutorial_sparse_example_details.cpp @@ -0,0 +1,44 @@ +#include +#include +#include + +typedef Eigen::SparseMatrix SpMat; // declares a column-major sparse matrix type of double +typedef Eigen::Triplet T; + +void insertCoefficient(int id, int i, int j, double w, std::vector& coeffs, + Eigen::VectorXd& b, const Eigen::VectorXd& boundary) +{ + int n = int(boundary.size()); + int id1 = i+j*n; + + if(i==-1 || i==n) b(id) -= w * boundary(j); // constrained coefficient + else if(j==-1 || j==n) b(id) -= w * boundary(i); // constrained coefficient + else coeffs.push_back(T(id,id1,w)); // unknown coefficient +} + +void buildProblem(std::vector& coefficients, Eigen::VectorXd& b, int n) +{ + b.setZero(); + Eigen::ArrayXd boundary = Eigen::ArrayXd::LinSpaced(n, 0,M_PI).sin().pow(2); + for(int j=0; j bits = (x*255).cast(); + QImage img(bits.data(), n,n,QImage::Format_Indexed8); + img.setColorCount(256); + for(int i=0;i<256;i++) img.setColor(i,qRgb(i,i,i)); + img.save(filename); +} diff --git a/testbed/nanogui/ext/eigen/doc/special_examples/random_cpp11.cpp b/testbed/nanogui/ext/eigen/doc/special_examples/random_cpp11.cpp new file mode 100644 index 00000000..33744c05 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/special_examples/random_cpp11.cpp @@ -0,0 +1,14 @@ +#include +#include +#include + +using namespace Eigen; + +int main() { + std::default_random_engine generator; + std::poisson_distribution distribution(4.1); + auto poisson = [&] () {return distribution(generator);}; + + RowVectorXi v = RowVectorXi::NullaryExpr(10, poisson ); + std::cout << v << "\n"; +} diff --git a/testbed/nanogui/ext/eigen/doc/tutorial.cpp b/testbed/nanogui/ext/eigen/doc/tutorial.cpp new file mode 100644 index 00000000..62be7c27 --- /dev/null +++ b/testbed/nanogui/ext/eigen/doc/tutorial.cpp @@ -0,0 +1,62 @@ +#include + +int main(int argc, char *argv[]) +{ + std::cout.precision(2); + + // demo static functions + Eigen::Matrix3f m3 = Eigen::Matrix3f::Random(); + Eigen::Matrix4f m4 = Eigen::Matrix4f::Identity(); + + std::cout << "*** Step 1 ***\nm3:\n" << m3 << "\nm4:\n" << m4 << std::endl; + + // demo non-static set... functions + m4.setZero(); + m3.diagonal().setOnes(); + + std::cout << "*** Step 2 ***\nm3:\n" << m3 << "\nm4:\n" << m4 << std::endl; + + // demo fixed-size block() expression as lvalue and as rvalue + m4.block<3,3>(0,1) = m3; + m3.row(2) = m4.block<1,3>(2,0); + + std::cout << "*** Step 3 ***\nm3:\n" << m3 << "\nm4:\n" << m4 << std::endl; + + // demo dynamic-size block() + { + int rows = 3, cols = 3; + m4.block(0,1,3,3).setIdentity(); + std::cout << "*** Step 4 ***\nm4:\n" << m4 << std::endl; + } + + // demo vector blocks + m4.diagonal().block(1,2).setOnes(); + std::cout << "*** Step 5 ***\nm4.diagonal():\n" << m4.diagonal() << std::endl; + std::cout << "m4.diagonal().start(3)\n" << m4.diagonal().start(3) << std::endl; + + // demo coeff-wise operations + m4 = m4.cwise()*m4; + m3 = m3.cwise().cos(); + std::cout << "*** Step 6 ***\nm3:\n" << m3 << "\nm4:\n" << m4 << std::endl; + + // sums of coefficients + std::cout << "*** Step 7 ***\n m4.sum(): " << m4.sum() << std::endl; + std::cout << "m4.col(2).sum(): " << m4.col(2).sum() << std::endl; + std::cout << "m4.colwise().sum():\n" << m4.colwise().sum() << std::endl; + std::cout << "m4.rowwise().sum():\n" << m4.rowwise().sum() << std::endl; + + // demo intelligent auto-evaluation + m4 = m4 * m4; // auto-evaluates so no aliasing problem (performance penalty is low) + Eigen::Matrix4f other = (m4 * m4).lazy(); // forces lazy evaluation + m4 = m4 + m4; // here Eigen goes for lazy evaluation, as with most expressions + m4 = -m4 + m4 + 5 * m4; // same here, Eigen chooses lazy evaluation for all that. + m4 = m4 * (m4 + m4); // here Eigen chooses to first evaluate m4 + m4 into a temporary. + // indeed, here it is an optimization to cache this intermediate result. + m3 = m3 * m4.block<3,3>(1,1); // here Eigen chooses NOT to evaluate block() into a temporary + // because accessing coefficients of that block expression is not more costly than accessing + // coefficients of a plain matrix. + m4 = m4 * m4.transpose(); // same here, lazy evaluation of the transpose. + m4 = m4 * m4.transpose().eval(); // forces immediate evaluation of the transpose + + std::cout << "*** Step 8 ***\nm3:\n" << m3 << "\nm4:\n" << m4 << std::endl; +} diff --git a/testbed/nanogui/ext/eigen/eigen3.pc.in b/testbed/nanogui/ext/eigen/eigen3.pc.in index c5855de3..3368a3aa 100644 --- a/testbed/nanogui/ext/eigen/eigen3.pc.in +++ b/testbed/nanogui/ext/eigen/eigen3.pc.in @@ -1,6 +1,9 @@ +prefix=@CMAKE_INSTALL_PREFIX@ +exec_prefix=${prefix} + Name: Eigen3 Description: A C++ template library for linear algebra: vectors, matrices, and related algorithms Requires: -Version: ${EIGEN_VERSION_NUMBER} +Version: @EIGEN_VERSION_NUMBER@ Libs: -Cflags: -I${INCLUDE_INSTALL_DIR} +Cflags: -I${prefix}/@INCLUDE_INSTALL_DIR@ diff --git a/testbed/nanogui/ext/eigen/failtest/CMakeLists.txt b/testbed/nanogui/ext/eigen/failtest/CMakeLists.txt index 5c486023..1a73f05e 100644 --- a/testbed/nanogui/ext/eigen/failtest/CMakeLists.txt +++ b/testbed/nanogui/ext/eigen/failtest/CMakeLists.txt @@ -7,6 +7,9 @@ ei_add_failtest("block_nonconst_ctor_on_const_xpr_1") ei_add_failtest("block_nonconst_ctor_on_const_xpr_2") ei_add_failtest("transpose_nonconst_ctor_on_const_xpr") ei_add_failtest("diagonal_nonconst_ctor_on_const_xpr") +ei_add_failtest("cwiseunaryview_nonconst_ctor_on_const_xpr") +ei_add_failtest("triangularview_nonconst_ctor_on_const_xpr") +ei_add_failtest("selfadjointview_nonconst_ctor_on_const_xpr") ei_add_failtest("const_qualified_block_method_retval_0") ei_add_failtest("const_qualified_block_method_retval_1") @@ -25,6 +28,9 @@ ei_add_failtest("block_on_const_type_actually_const_0") ei_add_failtest("block_on_const_type_actually_const_1") ei_add_failtest("transpose_on_const_type_actually_const") ei_add_failtest("diagonal_on_const_type_actually_const") +ei_add_failtest("cwiseunaryview_on_const_type_actually_const") +ei_add_failtest("triangularview_on_const_type_actually_const") +ei_add_failtest("selfadjointview_on_const_type_actually_const") ei_add_failtest("ref_1") ei_add_failtest("ref_2") @@ -32,6 +38,32 @@ ei_add_failtest("ref_3") ei_add_failtest("ref_4") ei_add_failtest("ref_5") +ei_add_failtest("swap_1") +ei_add_failtest("swap_2") + +ei_add_failtest("ternary_1") +ei_add_failtest("ternary_2") + +ei_add_failtest("sparse_ref_1") +ei_add_failtest("sparse_ref_2") +ei_add_failtest("sparse_ref_3") +ei_add_failtest("sparse_ref_4") +ei_add_failtest("sparse_ref_5") + +ei_add_failtest("sparse_storage_mismatch") + +ei_add_failtest("partialpivlu_int") +ei_add_failtest("fullpivlu_int") +ei_add_failtest("llt_int") +ei_add_failtest("ldlt_int") +ei_add_failtest("qr_int") +ei_add_failtest("colpivqr_int") +ei_add_failtest("fullpivqr_int") +ei_add_failtest("jacobisvd_int") +ei_add_failtest("bdcsvd_int") +ei_add_failtest("eigensolver_int") +ei_add_failtest("eigensolver_cplx") + if (EIGEN_FAILTEST_FAILURE_COUNT) message(FATAL_ERROR "${EIGEN_FAILTEST_FAILURE_COUNT} out of ${EIGEN_FAILTEST_COUNT} failtests FAILED. " diff --git a/testbed/nanogui/ext/eigen/failtest/bdcsvd_int.cpp b/testbed/nanogui/ext/eigen/failtest/bdcsvd_int.cpp new file mode 100644 index 00000000..670752cf --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/bdcsvd_int.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/SVD" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR int +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + BDCSVD > qr(Matrix::Random(10,10)); +} diff --git a/testbed/nanogui/ext/eigen/failtest/colpivqr_int.cpp b/testbed/nanogui/ext/eigen/failtest/colpivqr_int.cpp new file mode 100644 index 00000000..db11910d --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/colpivqr_int.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/QR" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR int +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + ColPivHouseholderQR > qr(Matrix::Random(10,10)); +} diff --git a/testbed/nanogui/ext/eigen/failtest/cwiseunaryview_nonconst_ctor_on_const_xpr.cpp b/testbed/nanogui/ext/eigen/failtest/cwiseunaryview_nonconst_ctor_on_const_xpr.cpp new file mode 100644 index 00000000..e23cf8fd --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/cwiseunaryview_nonconst_ctor_on_const_xpr.cpp @@ -0,0 +1,15 @@ +#include "../Eigen/Core" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define CV_QUALIFIER const +#else +#define CV_QUALIFIER +#endif + +using namespace Eigen; + +void foo(CV_QUALIFIER Matrix3d &m){ + CwiseUnaryView,Matrix3d> t(m); +} + +int main() {} diff --git a/testbed/nanogui/ext/eigen/failtest/cwiseunaryview_on_const_type_actually_const.cpp b/testbed/nanogui/ext/eigen/failtest/cwiseunaryview_on_const_type_actually_const.cpp new file mode 100644 index 00000000..fcd41dfd --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/cwiseunaryview_on_const_type_actually_const.cpp @@ -0,0 +1,16 @@ +#include "../Eigen/Core" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define CV_QUALIFIER const +#else +#define CV_QUALIFIER +#endif + +using namespace Eigen; + +void foo(){ + MatrixXf m; + CwiseUnaryView,CV_QUALIFIER MatrixXf>(m).coeffRef(0, 0) = 1.0f; +} + +int main() {} diff --git a/testbed/nanogui/ext/eigen/failtest/eigensolver_cplx.cpp b/testbed/nanogui/ext/eigen/failtest/eigensolver_cplx.cpp new file mode 100644 index 00000000..c2e21e18 --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/eigensolver_cplx.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/Eigenvalues" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR std::complex +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + EigenSolver > eig(Matrix::Random(10,10)); +} diff --git a/testbed/nanogui/ext/eigen/failtest/eigensolver_int.cpp b/testbed/nanogui/ext/eigen/failtest/eigensolver_int.cpp new file mode 100644 index 00000000..eda8dc20 --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/eigensolver_int.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/Eigenvalues" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR int +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + EigenSolver > eig(Matrix::Random(10,10)); +} diff --git a/testbed/nanogui/ext/eigen/failtest/fullpivlu_int.cpp b/testbed/nanogui/ext/eigen/failtest/fullpivlu_int.cpp new file mode 100644 index 00000000..e9d2c6eb --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/fullpivlu_int.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/LU" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR int +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + FullPivLU > lu(Matrix::Random(10,10)); +} diff --git a/testbed/nanogui/ext/eigen/failtest/fullpivqr_int.cpp b/testbed/nanogui/ext/eigen/failtest/fullpivqr_int.cpp new file mode 100644 index 00000000..d182a7b6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/fullpivqr_int.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/QR" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR int +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + FullPivHouseholderQR > qr(Matrix::Random(10,10)); +} diff --git a/testbed/nanogui/ext/eigen/failtest/jacobisvd_int.cpp b/testbed/nanogui/ext/eigen/failtest/jacobisvd_int.cpp new file mode 100644 index 00000000..12790aef --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/jacobisvd_int.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/SVD" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR int +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + JacobiSVD > qr(Matrix::Random(10,10)); +} diff --git a/testbed/nanogui/ext/eigen/failtest/ldlt_int.cpp b/testbed/nanogui/ext/eigen/failtest/ldlt_int.cpp new file mode 100644 index 00000000..243e4574 --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/ldlt_int.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/Cholesky" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR int +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + LDLT > ldlt(Matrix::Random(10,10)); +} diff --git a/testbed/nanogui/ext/eigen/failtest/llt_int.cpp b/testbed/nanogui/ext/eigen/failtest/llt_int.cpp new file mode 100644 index 00000000..cb020650 --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/llt_int.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/Cholesky" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR int +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + LLT > llt(Matrix::Random(10,10)); +} diff --git a/testbed/nanogui/ext/eigen/failtest/partialpivlu_int.cpp b/testbed/nanogui/ext/eigen/failtest/partialpivlu_int.cpp new file mode 100644 index 00000000..98ef282e --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/partialpivlu_int.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/LU" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR int +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + PartialPivLU > lu(Matrix::Random(10,10)); +} diff --git a/testbed/nanogui/ext/eigen/failtest/qr_int.cpp b/testbed/nanogui/ext/eigen/failtest/qr_int.cpp new file mode 100644 index 00000000..ce200e81 --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/qr_int.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/QR" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR int +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + HouseholderQR > qr(Matrix::Random(10,10)); +} diff --git a/testbed/nanogui/ext/eigen/failtest/selfadjointview_nonconst_ctor_on_const_xpr.cpp b/testbed/nanogui/ext/eigen/failtest/selfadjointview_nonconst_ctor_on_const_xpr.cpp new file mode 100644 index 00000000..a240f818 --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/selfadjointview_nonconst_ctor_on_const_xpr.cpp @@ -0,0 +1,15 @@ +#include "../Eigen/Core" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define CV_QUALIFIER const +#else +#define CV_QUALIFIER +#endif + +using namespace Eigen; + +void foo(CV_QUALIFIER Matrix3d &m){ + SelfAdjointView t(m); +} + +int main() {} diff --git a/testbed/nanogui/ext/eigen/failtest/selfadjointview_on_const_type_actually_const.cpp b/testbed/nanogui/ext/eigen/failtest/selfadjointview_on_const_type_actually_const.cpp new file mode 100644 index 00000000..19aaad6d --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/selfadjointview_on_const_type_actually_const.cpp @@ -0,0 +1,16 @@ +#include "../Eigen/Core" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define CV_QUALIFIER const +#else +#define CV_QUALIFIER +#endif + +using namespace Eigen; + +void foo(){ + MatrixXf m; + SelfAdjointView(m).coeffRef(0, 0) = 1.0f; +} + +int main() {} diff --git a/testbed/nanogui/ext/eigen/failtest/sparse_ref_1.cpp b/testbed/nanogui/ext/eigen/failtest/sparse_ref_1.cpp new file mode 100644 index 00000000..d78d1f9b --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/sparse_ref_1.cpp @@ -0,0 +1,18 @@ +#include "../Eigen/Sparse" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define CV_QUALIFIER const +#else +#define CV_QUALIFIER +#endif + +using namespace Eigen; + +void call_ref(Ref > a) { } + +int main() +{ + SparseMatrix a(10,10); + CV_QUALIFIER SparseMatrix& ac(a); + call_ref(ac); +} diff --git a/testbed/nanogui/ext/eigen/failtest/sparse_ref_2.cpp b/testbed/nanogui/ext/eigen/failtest/sparse_ref_2.cpp new file mode 100644 index 00000000..46c9440c --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/sparse_ref_2.cpp @@ -0,0 +1,15 @@ +#include "../Eigen/Sparse" + +using namespace Eigen; + +void call_ref(Ref > a) { } + +int main() +{ + SparseMatrix A(10,10); +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD + call_ref(A.row(3)); +#else + call_ref(A.col(3)); +#endif +} diff --git a/testbed/nanogui/ext/eigen/failtest/sparse_ref_3.cpp b/testbed/nanogui/ext/eigen/failtest/sparse_ref_3.cpp new file mode 100644 index 00000000..a9949b55 --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/sparse_ref_3.cpp @@ -0,0 +1,15 @@ +#include "../Eigen/Sparse" + +using namespace Eigen; + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +void call_ref(Ref > a) { } +#else +void call_ref(const Ref > &a) { } +#endif + +int main() +{ + SparseMatrix a(10,10); + call_ref(a+a); +} diff --git a/testbed/nanogui/ext/eigen/failtest/sparse_ref_4.cpp b/testbed/nanogui/ext/eigen/failtest/sparse_ref_4.cpp new file mode 100644 index 00000000..57bb6a1f --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/sparse_ref_4.cpp @@ -0,0 +1,15 @@ +#include "../Eigen/Sparse" + +using namespace Eigen; + +void call_ref(Ref > a) {} + +int main() +{ + SparseMatrix A(10,10); +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD + call_ref(A.transpose()); +#else + call_ref(A); +#endif +} diff --git a/testbed/nanogui/ext/eigen/failtest/sparse_ref_5.cpp b/testbed/nanogui/ext/eigen/failtest/sparse_ref_5.cpp new file mode 100644 index 00000000..4478f6f2 --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/sparse_ref_5.cpp @@ -0,0 +1,16 @@ +#include "../Eigen/Sparse" + +using namespace Eigen; + +void call_ref(Ref > a) { } + +int main() +{ + SparseMatrix a(10,10); + SparseMatrixBase > &ac(a); +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD + call_ref(ac); +#else + call_ref(ac.derived()); +#endif +} diff --git a/testbed/nanogui/ext/eigen/failtest/sparse_storage_mismatch.cpp b/testbed/nanogui/ext/eigen/failtest/sparse_storage_mismatch.cpp new file mode 100644 index 00000000..51840d41 --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/sparse_storage_mismatch.cpp @@ -0,0 +1,16 @@ +#include "../Eigen/Sparse" +using namespace Eigen; + +typedef SparseMatrix Mat1; +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +typedef SparseMatrix Mat2; +#else +typedef SparseMatrix Mat2; +#endif + +int main() +{ + Mat1 a(10,10); + Mat2 b(10,10); + a += b; +} diff --git a/testbed/nanogui/ext/eigen/failtest/swap_1.cpp b/testbed/nanogui/ext/eigen/failtest/swap_1.cpp new file mode 100644 index 00000000..10637972 --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/swap_1.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/Core" + +using namespace Eigen; + +int main() +{ + VectorXf a(10), b(10); +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD + const DenseBase &ac(a); +#else + DenseBase &ac(a); +#endif + b.swap(ac); +} diff --git a/testbed/nanogui/ext/eigen/failtest/swap_2.cpp b/testbed/nanogui/ext/eigen/failtest/swap_2.cpp new file mode 100644 index 00000000..c130ba6e --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/swap_2.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/Core" + +using namespace Eigen; + +int main() +{ + VectorXf a(10), b(10); + VectorXf const &ac(a); +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD + b.swap(ac); +#else + b.swap(ac.const_cast_derived()); +#endif +} \ No newline at end of file diff --git a/testbed/nanogui/ext/eigen/failtest/ternary_1.cpp b/testbed/nanogui/ext/eigen/failtest/ternary_1.cpp new file mode 100644 index 00000000..b40bcb0c --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/ternary_1.cpp @@ -0,0 +1,13 @@ +#include "../Eigen/Core" + +using namespace Eigen; + +int main(int argc,char **) +{ + VectorXf a(10), b(10); +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD + b = argc>1 ? 2*a : -a; +#else + b = argc>1 ? 2*a : VectorXf(-a); +#endif +} diff --git a/testbed/nanogui/ext/eigen/failtest/ternary_2.cpp b/testbed/nanogui/ext/eigen/failtest/ternary_2.cpp new file mode 100644 index 00000000..a46b12b2 --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/ternary_2.cpp @@ -0,0 +1,13 @@ +#include "../Eigen/Core" + +using namespace Eigen; + +int main(int argc,char **) +{ + VectorXf a(10), b(10); +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD + b = argc>1 ? 2*a : a+a; +#else + b = argc>1 ? VectorXf(2*a) : VectorXf(a+a); +#endif +} diff --git a/testbed/nanogui/ext/eigen/failtest/triangularview_nonconst_ctor_on_const_xpr.cpp b/testbed/nanogui/ext/eigen/failtest/triangularview_nonconst_ctor_on_const_xpr.cpp new file mode 100644 index 00000000..807447e4 --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/triangularview_nonconst_ctor_on_const_xpr.cpp @@ -0,0 +1,15 @@ +#include "../Eigen/Core" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define CV_QUALIFIER const +#else +#define CV_QUALIFIER +#endif + +using namespace Eigen; + +void foo(CV_QUALIFIER Matrix3d &m){ + TriangularView t(m); +} + +int main() {} diff --git a/testbed/nanogui/ext/eigen/failtest/triangularview_on_const_type_actually_const.cpp b/testbed/nanogui/ext/eigen/failtest/triangularview_on_const_type_actually_const.cpp new file mode 100644 index 00000000..0a381a61 --- /dev/null +++ b/testbed/nanogui/ext/eigen/failtest/triangularview_on_const_type_actually_const.cpp @@ -0,0 +1,16 @@ +#include "../Eigen/Core" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define CV_QUALIFIER const +#else +#define CV_QUALIFIER +#endif + +using namespace Eigen; + +void foo(){ + MatrixXf m; + TriangularView(m).coeffRef(0, 0) = 1.0f; +} + +int main() {} diff --git a/testbed/nanogui/ext/eigen/lapack/complex_double.cpp b/testbed/nanogui/ext/eigen/lapack/complex_double.cpp index 424d2b8c..c9c57527 100644 --- a/testbed/nanogui/ext/eigen/lapack/complex_double.cpp +++ b/testbed/nanogui/ext/eigen/lapack/complex_double.cpp @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2009-2011 Gael Guennebaud +// Copyright (C) 2009-2014 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -15,3 +15,4 @@ #include "cholesky.cpp" #include "lu.cpp" +#include "svd.cpp" diff --git a/testbed/nanogui/ext/eigen/lapack/complex_single.cpp b/testbed/nanogui/ext/eigen/lapack/complex_single.cpp index c0b2d29a..6d11b26c 100644 --- a/testbed/nanogui/ext/eigen/lapack/complex_single.cpp +++ b/testbed/nanogui/ext/eigen/lapack/complex_single.cpp @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2009-2011 Gael Guennebaud +// Copyright (C) 2009-2014 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -15,3 +15,4 @@ #include "cholesky.cpp" #include "lu.cpp" +#include "svd.cpp" diff --git a/testbed/nanogui/ext/eigen/lapack/double.cpp b/testbed/nanogui/ext/eigen/lapack/double.cpp index d86549e1..ea78bb66 100644 --- a/testbed/nanogui/ext/eigen/lapack/double.cpp +++ b/testbed/nanogui/ext/eigen/lapack/double.cpp @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2009-2011 Gael Guennebaud +// Copyright (C) 2009-2014 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -15,3 +15,4 @@ #include "cholesky.cpp" #include "lu.cpp" #include "eigenvalues.cpp" +#include "svd.cpp" diff --git a/testbed/nanogui/ext/eigen/lapack/eigenvalues.cpp b/testbed/nanogui/ext/eigen/lapack/eigenvalues.cpp index a1526ebc..921c5156 100644 --- a/testbed/nanogui/ext/eigen/lapack/eigenvalues.cpp +++ b/testbed/nanogui/ext/eigen/lapack/eigenvalues.cpp @@ -7,10 +7,10 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. -#include "common.h" +#include "lapack_common.h" #include -// computes an LU factorization of a general M-by-N matrix A using partial pivoting with row interchanges +// computes eigen values and vectors of a general N-by-N matrix A EIGEN_LAPACK_FUNC(syev,(char *jobz, char *uplo, int* n, Scalar* a, int *lda, Scalar* w, Scalar* /*work*/, int* lwork, int *info)) { // TODO exploit the work buffer @@ -22,24 +22,7 @@ EIGEN_LAPACK_FUNC(syev,(char *jobz, char *uplo, int* n, Scalar* a, int *lda, Sca else if(*n<0) *info = -3; else if(*lda +// Copyright (C) 2010-2014 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -11,6 +11,7 @@ #define EIGEN_LAPACK_COMMON_H #include "../blas/common.h" +#include "../Eigen/src/misc/lapack.h" #define EIGEN_LAPACK_FUNC(FUNC,ARGLIST) \ extern "C" { int EIGEN_BLAS_FUNC(FUNC) ARGLIST; } \ @@ -18,6 +19,11 @@ typedef Eigen::Map > PivotsType; +#if ISCOMPLEX +#define EIGEN_LAPACK_ARG_IF_COMPLEX(X) X, +#else +#define EIGEN_LAPACK_ARG_IF_COMPLEX(X) +#endif #endif // EIGEN_LAPACK_COMMON_H diff --git a/testbed/nanogui/ext/eigen/lapack/single.cpp b/testbed/nanogui/ext/eigen/lapack/single.cpp index a64ed44e..c7da3eff 100644 --- a/testbed/nanogui/ext/eigen/lapack/single.cpp +++ b/testbed/nanogui/ext/eigen/lapack/single.cpp @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2009-2011 Gael Guennebaud +// Copyright (C) 2009-2014 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -15,3 +15,4 @@ #include "cholesky.cpp" #include "lu.cpp" #include "eigenvalues.cpp" +#include "svd.cpp" diff --git a/testbed/nanogui/ext/eigen/lapack/svd.cpp b/testbed/nanogui/ext/eigen/lapack/svd.cpp new file mode 100644 index 00000000..77b302b6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/lapack/svd.cpp @@ -0,0 +1,138 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "lapack_common.h" +#include + +// computes the singular values/vectors a general M-by-N matrix A using divide-and-conquer +EIGEN_LAPACK_FUNC(gesdd,(char *jobz, int *m, int* n, Scalar* a, int *lda, RealScalar *s, Scalar *u, int *ldu, Scalar *vt, int *ldvt, Scalar* /*work*/, int* lwork, + EIGEN_LAPACK_ARG_IF_COMPLEX(RealScalar */*rwork*/) int * /*iwork*/, int *info)) +{ + // TODO exploit the work buffer + bool query_size = *lwork==-1; + int diag_size = (std::min)(*m,*n); + + *info = 0; + if(*jobz!='A' && *jobz!='S' && *jobz!='O' && *jobz!='N') *info = -1; + else if(*m<0) *info = -2; + else if(*n<0) *info = -3; + else if(*lda=*n && *ldvt<*n)) *info = -10; + + if(*info!=0) + { + int e = -*info; + return xerbla_(SCALAR_SUFFIX_UP"GESDD ", &e, 6); + } + + if(query_size) + { + *lwork = 0; + return 0; + } + + if(*n==0 || *m==0) + return 0; + + PlainMatrixType mat(*m,*n); + mat = matrix(a,*m,*n,*lda); + + int option = *jobz=='A' ? ComputeFullU|ComputeFullV + : *jobz=='S' ? ComputeThinU|ComputeThinV + : *jobz=='O' ? ComputeThinU|ComputeThinV + : 0; + + BDCSVD svd(mat,option); + + make_vector(s,diag_size) = svd.singularValues().head(diag_size); + + if(*jobz=='A') + { + matrix(u,*m,*m,*ldu) = svd.matrixU(); + matrix(vt,*n,*n,*ldvt) = svd.matrixV().adjoint(); + } + else if(*jobz=='S') + { + matrix(u,*m,diag_size,*ldu) = svd.matrixU(); + matrix(vt,diag_size,*n,*ldvt) = svd.matrixV().adjoint(); + } + else if(*jobz=='O' && *m>=*n) + { + matrix(a,*m,*n,*lda) = svd.matrixU(); + matrix(vt,*n,*n,*ldvt) = svd.matrixV().adjoint(); + } + else if(*jobz=='O') + { + matrix(u,*m,*m,*ldu) = svd.matrixU(); + matrix(a,diag_size,*n,*lda) = svd.matrixV().adjoint(); + } + + return 0; +} + +// computes the singular values/vectors a general M-by-N matrix A using two sided jacobi algorithm +EIGEN_LAPACK_FUNC(gesvd,(char *jobu, char *jobv, int *m, int* n, Scalar* a, int *lda, RealScalar *s, Scalar *u, int *ldu, Scalar *vt, int *ldvt, Scalar* /*work*/, int* lwork, + EIGEN_LAPACK_ARG_IF_COMPLEX(RealScalar */*rwork*/) int *info)) +{ + // TODO exploit the work buffer + bool query_size = *lwork==-1; + int diag_size = (std::min)(*m,*n); + + *info = 0; + if( *jobu!='A' && *jobu!='S' && *jobu!='O' && *jobu!='N') *info = -1; + else if((*jobv!='A' && *jobv!='S' && *jobv!='O' && *jobv!='N') + || (*jobu=='O' && *jobv=='O')) *info = -2; + else if(*m<0) *info = -3; + else if(*n<0) *info = -4; + else if(*lda svd(mat,option); + + make_vector(s,diag_size) = svd.singularValues().head(diag_size); + { + if(*jobu=='A') matrix(u,*m,*m,*ldu) = svd.matrixU(); + else if(*jobu=='S') matrix(u,*m,diag_size,*ldu) = svd.matrixU(); + else if(*jobu=='O') matrix(a,*m,diag_size,*lda) = svd.matrixU(); + } + { + if(*jobv=='A') matrix(vt,*n,*n,*ldvt) = svd.matrixV().adjoint(); + else if(*jobv=='S') matrix(vt,diag_size,*n,*ldvt) = svd.matrixV().adjoint(); + else if(*jobv=='O') matrix(a,diag_size,*n,*lda) = svd.matrixV().adjoint(); + } + return 0; +} diff --git a/testbed/nanogui/ext/eigen/scripts/buildtests.in b/testbed/nanogui/ext/eigen/scripts/buildtests.in index 7026373c..526d5b74 100755 --- a/testbed/nanogui/ext/eigen/scripts/buildtests.in +++ b/testbed/nanogui/ext/eigen/scripts/buildtests.in @@ -2,7 +2,7 @@ if [[ $# != 1 || $1 == *help ]] then - echo "usage: ./check regexp" + echo "usage: $0 regexp" echo " Builds tests matching the regexp." echo " The EIGEN_MAKE_ARGS environment variable allows to pass args to 'make'." echo " For example, to launch 5 concurrent builds, use EIGEN_MAKE_ARGS='-j5'" @@ -14,9 +14,9 @@ targets_to_make=`echo "$TESTSLIST" | egrep "$1" | xargs echo` if [ -n "${EIGEN_MAKE_ARGS:+x}" ] then - make $targets_to_make ${EIGEN_MAKE_ARGS} + @CMAKE_MAKE_PROGRAM@ $targets_to_make ${EIGEN_MAKE_ARGS} else - make $targets_to_make + @CMAKE_MAKE_PROGRAM@ $targets_to_make @EIGEN_TEST_BUILD_FLAGS@ fi exit $? diff --git a/testbed/nanogui/ext/eigen/scripts/check.in b/testbed/nanogui/ext/eigen/scripts/check.in index a90061a5..7717e2d9 100755 --- a/testbed/nanogui/ext/eigen/scripts/check.in +++ b/testbed/nanogui/ext/eigen/scripts/check.in @@ -3,7 +3,7 @@ if [[ $# != 1 || $1 == *help ]] then - echo "usage: ./check regexp" + echo "usage: $0 regexp" echo " Builds and runs tests matching the regexp." echo " The EIGEN_MAKE_ARGS environment variable allows to pass args to 'make'." echo " For example, to launch 5 concurrent builds, use EIGEN_MAKE_ARGS='-j5'" diff --git a/testbed/nanogui/ext/eigen/scripts/eigen_gen_docs b/testbed/nanogui/ext/eigen/scripts/eigen_gen_docs index 0e6f9ada..787dcb32 100644 --- a/testbed/nanogui/ext/eigen/scripts/eigen_gen_docs +++ b/testbed/nanogui/ext/eigen/scripts/eigen_gen_docs @@ -4,7 +4,7 @@ # You should call this script with USER set as you want, else some default # will be used USER=${USER:-'orzel'} -UPLOAD_DIR=dox +UPLOAD_DIR=dox-devel #ulimit -v 1024000 diff --git a/testbed/nanogui/ext/eigen/scripts/eigen_monitor_perf.sh b/testbed/nanogui/ext/eigen/scripts/eigen_monitor_perf.sh new file mode 100644 index 00000000..39f8e7ec --- /dev/null +++ b/testbed/nanogui/ext/eigen/scripts/eigen_monitor_perf.sh @@ -0,0 +1,25 @@ +#!/bin/bash + +# This is a script example to automatically update and upload performance unit tests. +# The following five variables must be adjusted to match your settings. + +USER='ggael' +UPLOAD_DIR=perf_monitoring/ggaelmacbook26 +EIGEN_SOURCE_PATH=$HOME/Eigen/eigen +export PREFIX="haswell-fma" +export CXX_FLAGS="-mfma -w" + +#### + +BENCH_PATH=$EIGEN_SOURCE_PATH/bench/perf_monitoring/$PREFIX +PREVPATH=`pwd` +cd $EIGEN_SOURCE_PATH/bench/perf_monitoring && ./runall.sh "Haswell 2.6GHz, FMA, Apple's clang" $* +cd $PREVPATH + +ALLFILES="$BENCH_PATH/*.png $BENCH_PATH/*.html $BENCH_PATH/index.html $BENCH_PATH/s1.js $BENCH_PATH/s2.js" + +# (the '/' at the end of path is very important, see rsync documentation) +rsync -az --no-p --delete $ALLFILES $USER@ssh.tuxfamily.org:eigen/eigen.tuxfamily.org-web/htdocs/$UPLOAD_DIR/ || { echo "upload failed"; exit 1; } + +# fix the perm +ssh $USER@ssh.tuxfamily.org "chmod -R g+w /home/eigen/eigen.tuxfamily.org-web/htdocs/perf_monitoring" || { echo "perm failed"; exit 1; } diff --git a/testbed/nanogui/ext/eigen/test/CMakeLists.txt b/testbed/nanogui/ext/eigen/test/CMakeLists.txt index d32451df..d337594f 100644 --- a/testbed/nanogui/ext/eigen/test/CMakeLists.txt +++ b/testbed/nanogui/ext/eigen/test/CMakeLists.txt @@ -1,22 +1,38 @@ - -# generate split test header file -message(STATUS ${CMAKE_CURRENT_BINARY_DIR}) -file(WRITE ${CMAKE_CURRENT_BINARY_DIR}/split_test_helper.h "") -foreach(i RANGE 1 999) - file(APPEND ${CMAKE_CURRENT_BINARY_DIR}/split_test_helper.h - "#ifdef EIGEN_TEST_PART_${i}\n" - "#define CALL_SUBTEST_${i}(FUNC) CALL_SUBTEST(FUNC)\n" - "#else\n" - "#define CALL_SUBTEST_${i}(FUNC)\n" - "#endif\n\n" +# generate split test header file only if it does not yet exist +# in order to prevent a rebuild everytime cmake is configured +if(NOT EXISTS ${CMAKE_CURRENT_BINARY_DIR}/split_test_helper.h) + file(WRITE ${CMAKE_CURRENT_BINARY_DIR}/split_test_helper.h "") + foreach(i RANGE 1 999) + file(APPEND ${CMAKE_CURRENT_BINARY_DIR}/split_test_helper.h + "#ifdef EIGEN_TEST_PART_${i}\n" + "#define CALL_SUBTEST_${i}(FUNC) CALL_SUBTEST(FUNC)\n" + "#else\n" + "#define CALL_SUBTEST_${i}(FUNC)\n" + "#endif\n\n" ) -endforeach() + endforeach() +endif() + +# check if we have a Fortran compiler +include("../cmake/language_support.cmake") + +workaround_9220(Fortran EIGEN_Fortran_COMPILER_WORKS) + +if(EIGEN_Fortran_COMPILER_WORKS) + enable_language(Fortran OPTIONAL) + if(NOT CMAKE_Fortran_COMPILER) + set(EIGEN_Fortran_COMPILER_WORKS OFF) + endif() +endif() + +if(NOT EIGEN_Fortran_COMPILER_WORKS) + # search for a default Lapack library to complete Eigen's one + find_package(LAPACK) +endif() # configure blas/lapack (use Eigen's ones) -set(BLAS_FOUND TRUE) -set(LAPACK_FOUND TRUE) -set(BLAS_LIBRARIES eigen_blas) -set(LAPACK_LIBRARIES eigen_lapack) +set(EIGEN_BLAS_LIBRARIES eigen_blas) +set(EIGEN_LAPACK_LIBRARIES eigen_lapack) set(EIGEN_TEST_MATRIX_DIR "" CACHE STRING "Enable testing of realword sparse matrices contained in the specified path") if(EIGEN_TEST_MATRIX_DIR) @@ -31,33 +47,33 @@ endif(EIGEN_TEST_MATRIX_DIR) set(SPARSE_LIBS " ") find_package(Cholmod) -if(CHOLMOD_FOUND AND BLAS_FOUND AND LAPACK_FOUND) +if(CHOLMOD_FOUND) add_definitions("-DEIGEN_CHOLMOD_SUPPORT") include_directories(${CHOLMOD_INCLUDES}) - set(SPARSE_LIBS ${SPARSE_LIBS} ${CHOLMOD_LIBRARIES} ${BLAS_LIBRARIES} ${LAPACK_LIBRARIES}) - set(CHOLMOD_ALL_LIBS ${CHOLMOD_LIBRARIES} ${BLAS_LIBRARIES} ${LAPACK_LIBRARIES}) + set(SPARSE_LIBS ${SPARSE_LIBS} ${CHOLMOD_LIBRARIES} ${EIGEN_BLAS_LIBRARIES} ${EIGEN_LAPACK_LIBRARIES}) + set(CHOLMOD_ALL_LIBS ${CHOLMOD_LIBRARIES} ${EIGEN_BLAS_LIBRARIES} ${EIGEN_LAPACK_LIBRARIES}) ei_add_property(EIGEN_TESTED_BACKENDS "Cholmod, ") else() ei_add_property(EIGEN_MISSING_BACKENDS "Cholmod, ") endif() find_package(Umfpack) -if(UMFPACK_FOUND AND BLAS_FOUND) +if(UMFPACK_FOUND) add_definitions("-DEIGEN_UMFPACK_SUPPORT") include_directories(${UMFPACK_INCLUDES}) - set(SPARSE_LIBS ${SPARSE_LIBS} ${UMFPACK_LIBRARIES} ${BLAS_LIBRARIES}) - set(UMFPACK_ALL_LIBS ${UMFPACK_LIBRARIES} ${BLAS_LIBRARIES}) + set(SPARSE_LIBS ${SPARSE_LIBS} ${UMFPACK_LIBRARIES} ${EIGEN_BLAS_LIBRARIES}) + set(UMFPACK_ALL_LIBS ${UMFPACK_LIBRARIES} ${EIGEN_BLAS_LIBRARIES}) ei_add_property(EIGEN_TESTED_BACKENDS "UmfPack, ") else() ei_add_property(EIGEN_MISSING_BACKENDS "UmfPack, ") endif() -find_package(SuperLU) -if(SUPERLU_FOUND AND BLAS_FOUND) +find_package(SuperLU 4.0) +if(SUPERLU_FOUND) add_definitions("-DEIGEN_SUPERLU_SUPPORT") include_directories(${SUPERLU_INCLUDES}) - set(SPARSE_LIBS ${SPARSE_LIBS} ${SUPERLU_LIBRARIES} ${BLAS_LIBRARIES}) - set(SUPERLU_ALL_LIBS ${SUPERLU_LIBRARIES} ${BLAS_LIBRARIES}) + set(SPARSE_LIBS ${SPARSE_LIBS} ${SUPERLU_LIBRARIES} ${EIGEN_BLAS_LIBRARIES}) + set(SUPERLU_ALL_LIBS ${SUPERLU_LIBRARIES} ${EIGEN_BLAS_LIBRARIES}) ei_add_property(EIGEN_TESTED_BACKENDS "SuperLU, ") else() ei_add_property(EIGEN_MISSING_BACKENDS "SuperLU, ") @@ -67,7 +83,7 @@ endif() find_package(Pastix) find_package(Scotch) find_package(Metis 5.0 REQUIRED) -if(PASTIX_FOUND AND BLAS_FOUND) +if(PASTIX_FOUND) add_definitions("-DEIGEN_PASTIX_SUPPORT") include_directories(${PASTIX_INCLUDES}) if(SCOTCH_FOUND) @@ -79,8 +95,8 @@ if(PASTIX_FOUND AND BLAS_FOUND) else(SCOTCH_FOUND) ei_add_property(EIGEN_MISSING_BACKENDS "PaStiX, ") endif(SCOTCH_FOUND) - set(SPARSE_LIBS ${SPARSE_LIBS} ${PASTIX_LIBRARIES} ${ORDERING_LIBRARIES} ${BLAS_LIBRARIES}) - set(PASTIX_ALL_LIBS ${PASTIX_LIBRARIES} ${BLAS_LIBRARIES}) + set(SPARSE_LIBS ${SPARSE_LIBS} ${PASTIX_LIBRARIES} ${ORDERING_LIBRARIES} ${EIGEN_BLAS_LIBRARIES}) + set(PASTIX_ALL_LIBS ${PASTIX_LIBRARIES} ${EIGEN_BLAS_LIBRARIES}) ei_add_property(EIGEN_TESTED_BACKENDS "PaStiX, ") else() ei_add_property(EIGEN_MISSING_BACKENDS "PaStiX, ") @@ -95,16 +111,14 @@ else() endif() find_package(SPQR) -if(SPQR_FOUND AND BLAS_FOUND AND LAPACK_FOUND) - if(CHOLMOD_FOUND) - add_definitions("-DEIGEN_SPQR_SUPPORT") - include_directories(${SPQR_INCLUDES}) - set(SPQR_ALL_LIBS ${SPQR_LIBRARIES} ${CHOLMOD_LIBRARIES} ${LAPACK_LIBRARIES} ${BLAS_LIBRARIES}) - set(SPARSE_LIBS ${SPARSE_LIBS} ${SPQR_ALL_LIBS}) - ei_add_property(EIGEN_TESTED_BACKENDS "SPQR, ") - else(CHOLMOD_FOUND) - ei_add_property(EIGEN_MISSING_BACKENDS "SPQR, ") - endif(CHOLMOD_FOUND) +if(SPQR_FOUND AND CHOLMOD_FOUND AND (EIGEN_Fortran_COMPILER_WORKS OR LAPACK_FOUND) ) + add_definitions("-DEIGEN_SPQR_SUPPORT") + include_directories(${SPQR_INCLUDES}) + set(SPQR_ALL_LIBS ${SPQR_LIBRARIES} ${CHOLMOD_LIBRARIES} ${EIGEN_LAPACK_LIBRARIES} ${EIGEN_BLAS_LIBRARIES} ${LAPACK_LIBRARIES}) + set(SPARSE_LIBS ${SPARSE_LIBS} ${SPQR_ALL_LIBS}) + ei_add_property(EIGEN_TESTED_BACKENDS "SPQR, ") +else() + ei_add_property(EIGEN_MISSING_BACKENDS "SPQR, ") endif() option(EIGEN_TEST_NOQT "Disable Qt support in unit tests" OFF) @@ -125,25 +139,34 @@ endif(TEST_LIB) set_property(GLOBAL PROPERTY EIGEN_CURRENT_SUBPROJECT "Official") add_custom_target(BuildOfficial) +ei_add_test(rand) ei_add_test(meta) ei_add_test(sizeof) ei_add_test(dynalloc) ei_add_test(nomalloc) ei_add_test(first_aligned) +ei_add_test(nullary) ei_add_test(mixingtypes) -ei_add_test(packetmath) +ei_add_test(packetmath "-DEIGEN_FAST_MATH=1") ei_add_test(unalignedassert) ei_add_test(vectorization_logic) ei_add_test(basicstuff) +ei_add_test(constructor) ei_add_test(linearstructure) ei_add_test(integer_types) -ei_add_test(cwiseop) ei_add_test(unalignedcount) -ei_add_test(exceptions) +if(NOT EIGEN_TEST_NO_EXCEPTIONS) + ei_add_test(exceptions) +endif() ei_add_test(redux) ei_add_test(visitor) ei_add_test(block) ei_add_test(corners) +ei_add_test(symbolic_index) +ei_add_test(indexed_view) +ei_add_test(swap) +ei_add_test(resize) +ei_add_test(conservative_resize) ei_add_test(product_small) ei_add_test(product_large) ei_add_test(product_extra) @@ -161,6 +184,7 @@ ei_add_test(array_for_matrix) ei_add_test(array_replicate) ei_add_test(array_reverse) ei_add_test(ref) +ei_add_test(is_same_dense) ei_add_test(triangular) ei_add_test(selfadjoint) ei_add_test(product_selfadjoint) @@ -172,6 +196,7 @@ ei_add_test(product_trsolve) ei_add_test(product_mmtr) ei_add_test(product_notemporary) ei_add_test(stable_norm) +ei_add_test(permutationmatrices) ei_add_test(bandmatrix) ei_add_test(cholesky) ei_add_test(lu) @@ -191,52 +216,75 @@ ei_add_test(real_qz) ei_add_test(eigensolver_generalized_real) ei_add_test(jacobi) ei_add_test(jacobisvd) +ei_add_test(bdcsvd) +ei_add_test(householder) ei_add_test(geo_orthomethods) -ei_add_test(geo_homogeneous) ei_add_test(geo_quaternion) -ei_add_test(geo_transformations) ei_add_test(geo_eulerangles) -ei_add_test(geo_hyperplane) ei_add_test(geo_parametrizedline) ei_add_test(geo_alignedbox) +ei_add_test(geo_hyperplane) +ei_add_test(geo_transformations) +ei_add_test(geo_homogeneous) ei_add_test(stdvector) ei_add_test(stdvector_overload) ei_add_test(stdlist) +ei_add_test(stdlist_overload) ei_add_test(stddeque) -ei_add_test(resize) -ei_add_test(sparse_vector) +ei_add_test(stddeque_overload) ei_add_test(sparse_basic) +ei_add_test(sparse_block) +ei_add_test(sparse_vector) ei_add_test(sparse_product) +ei_add_test(sparse_ref) ei_add_test(sparse_solvers) -ei_add_test(umeyama) -ei_add_test(householder) -ei_add_test(swap) -ei_add_test(conservative_resize) -ei_add_test(permutationmatrices) ei_add_test(sparse_permutations) -ei_add_test(nullary) +ei_add_test(simplicial_cholesky) +ei_add_test(conjugate_gradient) +ei_add_test(incomplete_cholesky) +ei_add_test(bicgstab) +ei_add_test(lscg) +ei_add_test(sparselu) +ei_add_test(sparseqr) +ei_add_test(umeyama) ei_add_test(nesting_ops "${CMAKE_CXX_FLAGS_DEBUG}") ei_add_test(zerosized) ei_add_test(dontalign) -ei_add_test(sizeoverflow) +ei_add_test(evaluators) +if(NOT EIGEN_TEST_NO_EXCEPTIONS) + ei_add_test(sizeoverflow) +endif() ei_add_test(prec_inverse_4x4) ei_add_test(vectorwiseop) ei_add_test(special_numbers) +ei_add_test(rvalue_types) +ei_add_test(dense_storage) +ei_add_test(ctorleak) +ei_add_test(mpl2only) +ei_add_test(inplace_decomposition) +ei_add_test(half_float) +ei_add_test(array_of_string) -ei_add_test(simplicial_cholesky) -ei_add_test(conjugate_gradient) -ei_add_test(bicgstab) -ei_add_test(sparselu) -ei_add_test(sparseqr) +add_executable(bug1213 bug1213.cpp bug1213_main.cpp) -# ei_add_test(denseLM) +check_cxx_compiler_flag("-ffast-math" COMPILER_SUPPORT_FASTMATH) +if(COMPILER_SUPPORT_FASTMATH) + set(EIGEN_FASTMATH_FLAGS "-ffast-math") +else() + check_cxx_compiler_flag("/fp:fast" COMPILER_SUPPORT_FPFAST) + if(COMPILER_SUPPORT_FPFAST) + set(EIGEN_FASTMATH_FLAGS "/fp:fast") + endif() +endif() + +ei_add_test(fastmath " ${EIGEN_FASTMATH_FLAGS} ") + +# # ei_add_test(denseLM) if(QT4_FOUND) ei_add_test(qtvector "" "${QT_QTCORE_LIBRARY}") endif(QT4_FOUND) -ei_add_test(eigen2support) - if(UMFPACK_FOUND) ei_add_test(umfpack_support "" "${UMFPACK_ALL_LIBS}") endif() @@ -281,5 +329,56 @@ ei_add_property(EIGEN_TESTING_SUMMARY "Sparse lib flags: ${SPARSE_LIBS}\n") option(EIGEN_TEST_EIGEN2 "Run whole Eigen2 test suite against EIGEN2_SUPPORT" OFF) mark_as_advanced(EIGEN_TEST_EIGEN2) if(EIGEN_TEST_EIGEN2) - add_subdirectory(eigen2) + message(WARNING "The Eigen2 test suite has been removed") endif() + +# boost MP unit test +find_package(Boost) +if(Boost_FOUND) + include_directories(${Boost_INCLUDE_DIRS}) + ei_add_test(boostmultiprec "" "${Boost_LIBRARIES}") + ei_add_property(EIGEN_TESTED_BACKENDS "Boost.Multiprecision, ") +else() + ei_add_property(EIGEN_MISSING_BACKENDS "Boost.Multiprecision, ") +endif() + + +# CUDA unit tests +option(EIGEN_TEST_CUDA "Enable CUDA support in unit tests" OFF) +option(EIGEN_TEST_CUDA_CLANG "Use clang instead of nvcc to compile the CUDA tests" OFF) + +if(EIGEN_TEST_CUDA_CLANG AND NOT CMAKE_CXX_COMPILER MATCHES "clang") + message(WARNING "EIGEN_TEST_CUDA_CLANG is set, but CMAKE_CXX_COMPILER does not appear to be clang.") +endif() + +if(EIGEN_TEST_CUDA) + +find_package(CUDA 5.0) +if(CUDA_FOUND) + + set(CUDA_PROPAGATE_HOST_FLAGS OFF) + if("${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang") + set(CUDA_NVCC_FLAGS "-ccbin ${CMAKE_C_COMPILER}" CACHE STRING "nvcc flags" FORCE) + endif() + if(EIGEN_TEST_CUDA_CLANG) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 --cuda-gpu-arch=sm_30") + endif() + cuda_include_directories(${CMAKE_CURRENT_BINARY_DIR}) + set(EIGEN_ADD_TEST_FILENAME_EXTENSION "cu") + + ei_add_test(cuda_basic) + + unset(EIGEN_ADD_TEST_FILENAME_EXTENSION) + +endif(CUDA_FOUND) + +endif(EIGEN_TEST_CUDA) + + +file(MAKE_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/failtests) +add_test(NAME failtests WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/failtests COMMAND ${CMAKE_COMMAND} ${Eigen_SOURCE_DIR} -G "${CMAKE_GENERATOR}" -DEIGEN_FAILTEST=ON) + +option(EIGEN_TEST_BUILD_DOCUMENTATION "Test building the doxygen documentation" OFF) +IF(EIGEN_TEST_BUILD_DOCUMENTATION) + add_dependencies(buildtests doc) +ENDIF() diff --git a/testbed/nanogui/ext/eigen/test/adjoint.cpp b/testbed/nanogui/ext/eigen/test/adjoint.cpp index ea36f784..bdea51c1 100644 --- a/testbed/nanogui/ext/eigen/test/adjoint.cpp +++ b/testbed/nanogui/ext/eigen/test/adjoint.cpp @@ -42,6 +42,17 @@ template<> struct adjoint_specific { VERIFY_IS_APPROX(v1, v1.norm() * v3); VERIFY_IS_APPROX(v3, v1.normalized()); VERIFY_IS_APPROX(v3.norm(), RealScalar(1)); + + // check null inputs + VERIFY_IS_APPROX((v1*0).normalized(), (v1*0)); +#if (!EIGEN_ARCH_i386) || defined(EIGEN_VECTORIZE) + RealScalar very_small = (std::numeric_limits::min)(); + VERIFY( (v1*very_small).norm() == 0 ); + VERIFY_IS_APPROX((v1*very_small).normalized(), (v1*very_small)); + v3 = v1*very_small; + v3.normalize(); + VERIFY_IS_APPROX(v3, (v1*very_small)); +#endif // check compatibility of dot and adjoint ref = NumTraits::IsInteger ? 0 : (std::max)((std::max)(v1.norm(),v2.norm()),(std::max)((square * v2).norm(),(square.adjoint() * v1).norm())); @@ -64,6 +75,7 @@ template void adjoint(const MatrixType& m) typedef typename NumTraits::Real RealScalar; typedef Matrix VectorType; typedef Matrix SquareMatrixType; + const Index PacketSize = internal::packet_traits::size; Index rows = m.rows(); Index cols = m.cols(); @@ -108,6 +120,17 @@ template void adjoint(const MatrixType& m) VERIFY_IS_APPROX(m3,m1.transpose()); m3.transposeInPlace(); VERIFY_IS_APPROX(m3,m1); + + if(PacketSize(0,m3.rows()-PacketSize); + Index j = internal::random(0,m3.cols()-PacketSize); + m3.template block(i,j).transposeInPlace(); + VERIFY_IS_APPROX( (m3.template block(i,j)), (m1.template block(i,j).transpose()) ); + m3.template block(i,j).transposeInPlace(); + VERIFY_IS_APPROX(m3,m1); + } // check inplace adjoint m3 = m1; @@ -129,14 +152,24 @@ void test_adjoint() CALL_SUBTEST_1( adjoint(Matrix()) ); CALL_SUBTEST_2( adjoint(Matrix3d()) ); CALL_SUBTEST_3( adjoint(Matrix4f()) ); + CALL_SUBTEST_4( adjoint(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE/2), internal::random(1,EIGEN_TEST_MAX_SIZE/2))) ); CALL_SUBTEST_5( adjoint(MatrixXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); CALL_SUBTEST_6( adjoint(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + + // Complement for 128 bits vectorization: + CALL_SUBTEST_8( adjoint(Matrix2d()) ); + CALL_SUBTEST_9( adjoint(Matrix()) ); + + // 256 bits vectorization: + CALL_SUBTEST_10( adjoint(Matrix()) ); + CALL_SUBTEST_11( adjoint(Matrix()) ); + CALL_SUBTEST_12( adjoint(Matrix()) ); } // test a large static matrix only once CALL_SUBTEST_7( adjoint(Matrix()) ); -#ifdef EIGEN_TEST_PART_4 +#ifdef EIGEN_TEST_PART_13 { MatrixXcf a(10,10), b(10,10); VERIFY_RAISES_ASSERT(a = a.transpose()); @@ -154,6 +187,13 @@ void test_adjoint() a.transpose() = a.adjoint(); a.transpose() += a.adjoint(); a.transpose() += a.adjoint() + b; + + // regression tests for check_for_aliasing + MatrixXd c(10,10); + c = 1.0 * MatrixXd::Ones(10,10) + c; + c = MatrixXd::Ones(10,10) * 1.0 + c; + c = c + MatrixXd::Ones(10,10) .cwiseProduct( MatrixXd::Zero(10,10) ); + c = MatrixXd::Ones(10,10) * MatrixXd::Zero(10,10); } #endif } diff --git a/testbed/nanogui/ext/eigen/test/array.cpp b/testbed/nanogui/ext/eigen/test/array.cpp index c607da63..f7f3ba78 100644 --- a/testbed/nanogui/ext/eigen/test/array.cpp +++ b/testbed/nanogui/ext/eigen/test/array.cpp @@ -13,15 +13,18 @@ template void array(const ArrayType& m) { typedef typename ArrayType::Index Index; typedef typename ArrayType::Scalar Scalar; + typedef typename ArrayType::RealScalar RealScalar; typedef Array ColVectorType; typedef Array RowVectorType; Index rows = m.rows(); - Index cols = m.cols(); + Index cols = m.cols(); ArrayType m1 = ArrayType::Random(rows, cols), m2 = ArrayType::Random(rows, cols), m3(rows, cols); + ArrayType m4 = m1; // copy constructor + VERIFY_IS_APPROX(m1, m4); ColVectorType cv1 = ColVectorType::Random(rows); RowVectorType rv1 = RowVectorType::Random(cols); @@ -41,25 +44,25 @@ template void array(const ArrayType& m) VERIFY_IS_APPROX(m3, m1 + s2); m3 = m1; m3 -= s1; - VERIFY_IS_APPROX(m3, m1 - s1); - + VERIFY_IS_APPROX(m3, m1 - s1); + // scalar operators via Maps m3 = m1; ArrayType::Map(m1.data(), m1.rows(), m1.cols()) -= ArrayType::Map(m2.data(), m2.rows(), m2.cols()); VERIFY_IS_APPROX(m1, m3 - m2); - + m3 = m1; ArrayType::Map(m1.data(), m1.rows(), m1.cols()) += ArrayType::Map(m2.data(), m2.rows(), m2.cols()); VERIFY_IS_APPROX(m1, m3 + m2); - + m3 = m1; ArrayType::Map(m1.data(), m1.rows(), m1.cols()) *= ArrayType::Map(m2.data(), m2.rows(), m2.cols()); VERIFY_IS_APPROX(m1, m3 * m2); - + m3 = m1; m2 = ArrayType::Random(rows,cols); m2 = (m2==0).select(1,m2); - ArrayType::Map(m1.data(), m1.rows(), m1.cols()) /= ArrayType::Map(m2.data(), m2.rows(), m2.cols()); + ArrayType::Map(m1.data(), m1.rows(), m1.cols()) /= ArrayType::Map(m2.data(), m2.rows(), m2.cols()); VERIFY_IS_APPROX(m1, m3 / m2); // reductions @@ -70,7 +73,7 @@ template void array(const ArrayType& m) VERIFY_IS_MUCH_SMALLER_THAN(abs(m1.rowwise().sum().sum() - m1.sum()), m1.abs().sum()); if (!internal::isMuchSmallerThan(abs(m1.sum() - (m1+m2).sum()), m1.abs().sum(), test_precision())) VERIFY_IS_NOT_APPROX(((m1+m2).rowwise().sum()).sum(), m1.sum()); - VERIFY_IS_APPROX(m1.colwise().sum(), m1.colwise().redux(internal::scalar_sum_op())); + VERIFY_IS_APPROX(m1.colwise().sum(), m1.colwise().redux(internal::scalar_sum_op())); // vector-wise ops m3 = m1; @@ -81,6 +84,47 @@ template void array(const ArrayType& m) VERIFY_IS_APPROX(m3.rowwise() += rv1, m1.rowwise() + rv1); m3 = m1; VERIFY_IS_APPROX(m3.rowwise() -= rv1, m1.rowwise() - rv1); + + // Conversion from scalar + VERIFY_IS_APPROX((m3 = s1), ArrayType::Constant(rows,cols,s1)); + VERIFY_IS_APPROX((m3 = 1), ArrayType::Constant(rows,cols,1)); + VERIFY_IS_APPROX((m3.topLeftCorner(rows,cols) = 1), ArrayType::Constant(rows,cols,1)); + typedef Array FixedArrayType; + FixedArrayType f1(s1); + VERIFY_IS_APPROX(f1, FixedArrayType::Constant(s1)); + FixedArrayType f2(numext::real(s1)); + VERIFY_IS_APPROX(f2, FixedArrayType::Constant(numext::real(s1))); + FixedArrayType f3((int)100*numext::real(s1)); + VERIFY_IS_APPROX(f3, FixedArrayType::Constant((int)100*numext::real(s1))); + f1.setRandom(); + FixedArrayType f4(f1.data()); + VERIFY_IS_APPROX(f4, f1); + + // pow + VERIFY_IS_APPROX(m1.pow(2), m1.square()); + VERIFY_IS_APPROX(pow(m1,2), m1.square()); + VERIFY_IS_APPROX(m1.pow(3), m1.cube()); + VERIFY_IS_APPROX(pow(m1,3), m1.cube()); + VERIFY_IS_APPROX((-m1).pow(3), -m1.cube()); + VERIFY_IS_APPROX(pow(2*m1,3), 8*m1.cube()); + ArrayType exponents = ArrayType::Constant(rows, cols, RealScalar(2)); + VERIFY_IS_APPROX(Eigen::pow(m1,exponents), m1.square()); + VERIFY_IS_APPROX(m1.pow(exponents), m1.square()); + VERIFY_IS_APPROX(Eigen::pow(2*m1,exponents), 4*m1.square()); + VERIFY_IS_APPROX((2*m1).pow(exponents), 4*m1.square()); + VERIFY_IS_APPROX(Eigen::pow(m1,2*exponents), m1.square().square()); + VERIFY_IS_APPROX(m1.pow(2*exponents), m1.square().square()); + VERIFY_IS_APPROX(Eigen::pow(m1(0,0), exponents), ArrayType::Constant(rows,cols,m1(0,0)*m1(0,0))); + + // Check possible conflicts with 1D ctor + typedef Array OneDArrayType; + OneDArrayType o1(rows); + VERIFY(o1.size()==rows); + OneDArrayType o4((int)rows); + VERIFY(o4.size()==rows); } template void comparisons(const ArrayType& m) @@ -97,8 +141,11 @@ template void comparisons(const ArrayType& m) c = internal::random(0, cols-1); ArrayType m1 = ArrayType::Random(rows, cols), - m2 = ArrayType::Random(rows, cols), - m3(rows, cols); + m2 = ArrayType::Random(rows, cols), + m3(rows, cols), + m4 = m1; + + m4 = (m4.abs()==Scalar(0)).select(1,m4); VERIFY(((m1 + Scalar(1)) > m1).all()); VERIFY(((m1 - Scalar(1)) < m1).all()); @@ -109,12 +156,20 @@ template void comparisons(const ArrayType& m) VERIFY(! (m1 < m3).all() ); VERIFY(! (m1 > m3).all() ); } + VERIFY(!(m1 > m2 && m1 < m2).any()); + VERIFY((m1 <= m2 || m1 >= m2).all()); - // comparisons to scalar + // comparisons array to scalar VERIFY( (m1 != (m1(r,c)+1) ).any() ); - VERIFY( (m1 > (m1(r,c)-1) ).any() ); - VERIFY( (m1 < (m1(r,c)+1) ).any() ); - VERIFY( (m1 == m1(r,c) ).any() ); + VERIFY( (m1 > (m1(r,c)-1) ).any() ); + VERIFY( (m1 < (m1(r,c)+1) ).any() ); + VERIFY( (m1 == m1(r,c) ).any() ); + + // comparisons scalar to array + VERIFY( ( (m1(r,c)+1) != m1).any() ); + VERIFY( ( (m1(r,c)-1) < m1).any() ); + VERIFY( ( (m1(r,c)+1) > m1).any() ); + VERIFY( ( m1(r,c) == m1).any() ); // test Select VERIFY_IS_APPROX( (m1 void array_real(const ArrayType& m) ArrayType m1 = ArrayType::Random(rows, cols), m2 = ArrayType::Random(rows, cols), - m3(rows, cols); + m3(rows, cols), + m4 = m1; + + m4 = (m4.abs()==Scalar(0)).select(1,m4); Scalar s1 = internal::random(); - // these tests are mostly to check possible compilation issues. + // these tests are mostly to check possible compilation issues with free-functions. VERIFY_IS_APPROX(m1.sin(), sin(m1)); VERIFY_IS_APPROX(m1.cos(), cos(m1)); + VERIFY_IS_APPROX(m1.tan(), tan(m1)); VERIFY_IS_APPROX(m1.asin(), asin(m1)); VERIFY_IS_APPROX(m1.acos(), acos(m1)); - VERIFY_IS_APPROX(m1.tan(), tan(m1)); - - VERIFY_IS_APPROX(cos(m1+RealScalar(3)*m2), cos((m1+RealScalar(3)*m2).eval())); + VERIFY_IS_APPROX(m1.atan(), atan(m1)); + VERIFY_IS_APPROX(m1.sinh(), sinh(m1)); + VERIFY_IS_APPROX(m1.cosh(), cosh(m1)); + VERIFY_IS_APPROX(m1.tanh(), tanh(m1)); - VERIFY_IS_APPROX(m1.abs().sqrt(), sqrt(abs(m1))); - VERIFY_IS_APPROX(m1.abs(), sqrt(numext::abs2(m1))); + VERIFY_IS_APPROX(m1.arg(), arg(m1)); + VERIFY_IS_APPROX(m1.round(), round(m1)); + VERIFY_IS_APPROX(m1.floor(), floor(m1)); + VERIFY_IS_APPROX(m1.ceil(), ceil(m1)); + VERIFY((m1.isNaN() == (Eigen::isnan)(m1)).all()); + VERIFY((m1.isInf() == (Eigen::isinf)(m1)).all()); + VERIFY((m1.isFinite() == (Eigen::isfinite)(m1)).all()); + VERIFY_IS_APPROX(m1.inverse(), inverse(m1)); + VERIFY_IS_APPROX(m1.abs(), abs(m1)); + VERIFY_IS_APPROX(m1.abs2(), abs2(m1)); + VERIFY_IS_APPROX(m1.square(), square(m1)); + VERIFY_IS_APPROX(m1.cube(), cube(m1)); + VERIFY_IS_APPROX(cos(m1+RealScalar(3)*m2), cos((m1+RealScalar(3)*m2).eval())); + VERIFY_IS_APPROX(m1.sign(), sign(m1)); + + + // avoid NaNs with abs() so verification doesn't fail + m3 = m1.abs(); + VERIFY_IS_APPROX(m3.sqrt(), sqrt(abs(m1))); + VERIFY_IS_APPROX(m3.rsqrt(), Scalar(1)/sqrt(abs(m1))); + VERIFY_IS_APPROX(rsqrt(m3), Scalar(1)/sqrt(abs(m1))); + VERIFY_IS_APPROX(m3.log(), log(m3)); + VERIFY_IS_APPROX(m3.log1p(), log1p(m3)); + VERIFY_IS_APPROX(m3.log10(), log10(m3)); + + + VERIFY((!(m1>m2) == (m1<=m2)).all()); + + VERIFY_IS_APPROX(sin(m1.asin()), m1); + VERIFY_IS_APPROX(cos(m1.acos()), m1); + VERIFY_IS_APPROX(tan(m1.atan()), m1); + VERIFY_IS_APPROX(sinh(m1), 0.5*(exp(m1)-exp(-m1))); + VERIFY_IS_APPROX(cosh(m1), 0.5*(exp(m1)+exp(-m1))); + VERIFY_IS_APPROX(tanh(m1), (0.5*(exp(m1)-exp(-m1)))/(0.5*(exp(m1)+exp(-m1)))); + VERIFY_IS_APPROX(arg(m1), ((m1<0).template cast())*std::acos(-1.0)); + VERIFY((round(m1) <= ceil(m1) && round(m1) >= floor(m1)).all()); + VERIFY((Eigen::isnan)((m1*0.0)/0.0).all()); + VERIFY((Eigen::isinf)(m4/0.0).all()); + VERIFY(((Eigen::isfinite)(m1) && (!(Eigen::isfinite)(m1*0.0/0.0)) && (!(Eigen::isfinite)(m4/0.0))).all()); + VERIFY_IS_APPROX(inverse(inverse(m1)),m1); + VERIFY((abs(m1) == m1 || abs(m1) == -m1).all()); + VERIFY_IS_APPROX(m3, sqrt(abs2(m1))); + VERIFY_IS_APPROX( m1.sign(), -(-m1).sign() ); + VERIFY_IS_APPROX( m1*m1.sign(),m1.abs()); + VERIFY_IS_APPROX(m1.sign() * m1.abs(), m1); VERIFY_IS_APPROX(numext::abs2(numext::real(m1)) + numext::abs2(numext::imag(m1)), numext::abs2(m1)); VERIFY_IS_APPROX(numext::abs2(real(m1)) + numext::abs2(imag(m1)), numext::abs2(m1)); @@ -185,52 +288,141 @@ template void array_real(const ArrayType& m) // shift argument of logarithm so that it is not zero Scalar smallNumber = NumTraits::dummy_precision(); - VERIFY_IS_APPROX((m1.abs() + smallNumber).log() , log(abs(m1) + smallNumber)); + VERIFY_IS_APPROX((m3 + smallNumber).log() , log(abs(m1) + smallNumber)); + VERIFY_IS_APPROX((m3 + smallNumber + 1).log() , log1p(abs(m1) + smallNumber)); VERIFY_IS_APPROX(m1.exp() * m2.exp(), exp(m1+m2)); VERIFY_IS_APPROX(m1.exp(), exp(m1)); VERIFY_IS_APPROX(m1.exp() / m2.exp(),(m1-m2).exp()); - VERIFY_IS_APPROX(m1.pow(2), m1.square()); - VERIFY_IS_APPROX(pow(m1,2), m1.square()); + VERIFY_IS_APPROX(m1.expm1(), expm1(m1)); + VERIFY_IS_APPROX((m3 + smallNumber).exp() - 1, expm1(abs(m3) + smallNumber)); - ArrayType exponents = ArrayType::Constant(rows, cols, RealScalar(2)); - VERIFY_IS_APPROX(Eigen::pow(m1,exponents), m1.square()); - - m3 = m1.abs(); VERIFY_IS_APPROX(m3.pow(RealScalar(0.5)), m3.sqrt()); VERIFY_IS_APPROX(pow(m3,RealScalar(0.5)), m3.sqrt()); + VERIFY_IS_APPROX(m3.pow(RealScalar(-0.5)), m3.rsqrt()); + VERIFY_IS_APPROX(pow(m3,RealScalar(-0.5)), m3.rsqrt()); + + VERIFY_IS_APPROX(log10(m3), log(m3)/log(10)); + // scalar by array division const RealScalar tiny = sqrt(std::numeric_limits::epsilon()); s1 += Scalar(tiny); m1 += ArrayType::Constant(rows,cols,Scalar(tiny)); VERIFY_IS_APPROX(s1/m1, s1 * m1.inverse()); - + // check inplace transpose m3 = m1; m3.transposeInPlace(); - VERIFY_IS_APPROX(m3,m1.transpose()); + VERIFY_IS_APPROX(m3, m1.transpose()); m3.transposeInPlace(); - VERIFY_IS_APPROX(m3,m1); + VERIFY_IS_APPROX(m3, m1); } template void array_complex(const ArrayType& m) { typedef typename ArrayType::Index Index; + typedef typename ArrayType::Scalar Scalar; + typedef typename NumTraits::Real RealScalar; Index rows = m.rows(); Index cols = m.cols(); ArrayType m1 = ArrayType::Random(rows, cols), - m2(rows, cols); + m2(rows, cols), + m4 = m1; + + m4.real() = (m4.real().abs()==RealScalar(0)).select(RealScalar(1),m4.real()); + m4.imag() = (m4.imag().abs()==RealScalar(0)).select(RealScalar(1),m4.imag()); + + Array m3(rows, cols); for (Index i = 0; i < m.rows(); ++i) for (Index j = 0; j < m.cols(); ++j) m2(i,j) = sqrt(m1(i,j)); - VERIFY_IS_APPROX(m1.sqrt(), m2); - VERIFY_IS_APPROX(m1.sqrt(), Eigen::sqrt(m1)); + // these tests are mostly to check possible compilation issues with free-functions. + VERIFY_IS_APPROX(m1.sin(), sin(m1)); + VERIFY_IS_APPROX(m1.cos(), cos(m1)); + VERIFY_IS_APPROX(m1.tan(), tan(m1)); + VERIFY_IS_APPROX(m1.sinh(), sinh(m1)); + VERIFY_IS_APPROX(m1.cosh(), cosh(m1)); + VERIFY_IS_APPROX(m1.tanh(), tanh(m1)); + VERIFY_IS_APPROX(m1.arg(), arg(m1)); + VERIFY((m1.isNaN() == (Eigen::isnan)(m1)).all()); + VERIFY((m1.isInf() == (Eigen::isinf)(m1)).all()); + VERIFY((m1.isFinite() == (Eigen::isfinite)(m1)).all()); + VERIFY_IS_APPROX(m1.inverse(), inverse(m1)); + VERIFY_IS_APPROX(m1.log(), log(m1)); + VERIFY_IS_APPROX(m1.log10(), log10(m1)); + VERIFY_IS_APPROX(m1.abs(), abs(m1)); + VERIFY_IS_APPROX(m1.abs2(), abs2(m1)); + VERIFY_IS_APPROX(m1.sqrt(), sqrt(m1)); + VERIFY_IS_APPROX(m1.square(), square(m1)); + VERIFY_IS_APPROX(m1.cube(), cube(m1)); + VERIFY_IS_APPROX(cos(m1+RealScalar(3)*m2), cos((m1+RealScalar(3)*m2).eval())); + VERIFY_IS_APPROX(m1.sign(), sign(m1)); + + + VERIFY_IS_APPROX(m1.exp() * m2.exp(), exp(m1+m2)); + VERIFY_IS_APPROX(m1.exp(), exp(m1)); + VERIFY_IS_APPROX(m1.exp() / m2.exp(),(m1-m2).exp()); + + VERIFY_IS_APPROX(sinh(m1), 0.5*(exp(m1)-exp(-m1))); + VERIFY_IS_APPROX(cosh(m1), 0.5*(exp(m1)+exp(-m1))); + VERIFY_IS_APPROX(tanh(m1), (0.5*(exp(m1)-exp(-m1)))/(0.5*(exp(m1)+exp(-m1)))); + + for (Index i = 0; i < m.rows(); ++i) + for (Index j = 0; j < m.cols(); ++j) + m3(i,j) = std::atan2(imag(m1(i,j)), real(m1(i,j))); + VERIFY_IS_APPROX(arg(m1), m3); + + std::complex zero(0.0,0.0); + VERIFY((Eigen::isnan)(m1*zero/zero).all()); +#if EIGEN_COMP_MSVC + // msvc complex division is not robust + VERIFY((Eigen::isinf)(m4/RealScalar(0)).all()); +#else +#if EIGEN_COMP_CLANG + // clang's complex division is notoriously broken too + if((numext::isinf)(m4(0,0)/RealScalar(0))) { +#endif + VERIFY((Eigen::isinf)(m4/zero).all()); +#if EIGEN_COMP_CLANG + } + else + { + VERIFY((Eigen::isinf)(m4.real()/zero.real()).all()); + } +#endif +#endif // MSVC + + VERIFY(((Eigen::isfinite)(m1) && (!(Eigen::isfinite)(m1*zero/zero)) && (!(Eigen::isfinite)(m1/zero))).all()); + + VERIFY_IS_APPROX(inverse(inverse(m1)),m1); + VERIFY_IS_APPROX(conj(m1.conjugate()), m1); + VERIFY_IS_APPROX(abs(m1), sqrt(square(real(m1))+square(imag(m1)))); + VERIFY_IS_APPROX(abs(m1), sqrt(abs2(m1))); + VERIFY_IS_APPROX(log10(m1), log(m1)/log(10)); + + VERIFY_IS_APPROX( m1.sign(), -(-m1).sign() ); + VERIFY_IS_APPROX( m1.sign() * m1.abs(), m1); + + // scalar by array division + Scalar s1 = internal::random(); + const RealScalar tiny = std::sqrt(std::numeric_limits::epsilon()); + s1 += Scalar(tiny); + m1 += ArrayType::Constant(rows,cols,Scalar(tiny)); + VERIFY_IS_APPROX(s1/m1, s1 * m1.inverse()); + + // check inplace transpose + m2 = m1; + m2.transposeInPlace(); + VERIFY_IS_APPROX(m2, m1.transpose()); + m2.transposeInPlace(); + VERIFY_IS_APPROX(m2, m1); + } template void min_max(const ArrayType& m) @@ -299,7 +491,7 @@ void test_array() VERIFY((internal::is_same< internal::global_math_functions_filtering_base::type, int >::value)); VERIFY((internal::is_same< internal::global_math_functions_filtering_base::type, float >::value)); VERIFY((internal::is_same< internal::global_math_functions_filtering_base::type, ArrayBase >::value)); - typedef CwiseUnaryOp, ArrayXd > Xpr; + typedef CwiseUnaryOp, ArrayXd > Xpr; VERIFY((internal::is_same< internal::global_math_functions_filtering_base::type, ArrayBase >::value)); diff --git a/testbed/nanogui/ext/eigen/test/array_for_matrix.cpp b/testbed/nanogui/ext/eigen/test/array_for_matrix.cpp index 9a50f99a..c1501947 100644 --- a/testbed/nanogui/ext/eigen/test/array_for_matrix.cpp +++ b/testbed/nanogui/ext/eigen/test/array_for_matrix.cpp @@ -45,7 +45,7 @@ template void array_for_matrix(const MatrixType& m) VERIFY_IS_MUCH_SMALLER_THAN(m1.rowwise().sum().sum() - m1.sum(), m1.squaredNorm()); VERIFY_IS_MUCH_SMALLER_THAN(m1.colwise().sum() + m2.colwise().sum() - (m1+m2).colwise().sum(), (m1+m2).squaredNorm()); VERIFY_IS_MUCH_SMALLER_THAN(m1.rowwise().sum() - m2.rowwise().sum() - (m1-m2).rowwise().sum(), (m1-m2).squaredNorm()); - VERIFY_IS_APPROX(m1.colwise().sum(), m1.colwise().redux(internal::scalar_sum_op())); + VERIFY_IS_APPROX(m1.colwise().sum(), m1.colwise().redux(internal::scalar_sum_op())); // vector-wise ops m3 = m1; @@ -68,6 +68,16 @@ template void array_for_matrix(const MatrixType& m) const Scalar& ref_a2 = m.array().matrix().coeffRef(0,0); VERIFY(&ref_a1 == &ref_m1); VERIFY(&ref_a2 == &ref_m2); + + // Check write accessors: + m1.array().coeffRef(0,0) = 1; + VERIFY_IS_APPROX(m1(0,0),Scalar(1)); + m1.array()(0,0) = 2; + VERIFY_IS_APPROX(m1(0,0),Scalar(2)); + m1.array().matrix().coeffRef(0,0) = 3; + VERIFY_IS_APPROX(m1(0,0),Scalar(3)); + m1.array().matrix()(0,0) = 4; + VERIFY_IS_APPROX(m1(0,0),Scalar(4)); } template void comparisons(const MatrixType& m) @@ -102,6 +112,7 @@ template void comparisons(const MatrixType& m) VERIFY( (m1.array() > (m1(r,c)-1) ).any() ); VERIFY( (m1.array() < (m1(r,c)+1) ).any() ); VERIFY( (m1.array() == m1(r,c) ).any() ); + VERIFY( m1.cwiseEqual(m1(r,c)).any() ); // test Select VERIFY_IS_APPROX( (m1.array() void comparisons(const MatrixType& m) // count VERIFY(((m1.array().abs()+1)>RealScalar(0.1)).count() == rows*cols); + // and/or + VERIFY( ((m1.array()RealScalar(0)).matrix()).count() == 0); + VERIFY( ((m1.array()=RealScalar(0)).matrix()).count() == rows*cols); + RealScalar a = m1.cwiseAbs().mean(); + VERIFY( ((m1.array()<-a).matrix() || (m1.array()>a).matrix()).count() == (m1.cwiseAbs().array()>a).count()); + typedef Matrix VectorOfIndices; // TODO allows colwise/rowwise for array @@ -133,9 +150,21 @@ template void comparisons(const MatrixType& m) template void lpNorm(const VectorType& v) { using std::sqrt; + typedef typename VectorType::RealScalar RealScalar; VectorType u = VectorType::Random(v.size()); - VERIFY_IS_APPROX(u.template lpNorm(), u.cwiseAbs().maxCoeff()); + if(v.size()==0) + { + VERIFY_IS_APPROX(u.template lpNorm(), RealScalar(0)); + VERIFY_IS_APPROX(u.template lpNorm<1>(), RealScalar(0)); + VERIFY_IS_APPROX(u.template lpNorm<2>(), RealScalar(0)); + VERIFY_IS_APPROX(u.template lpNorm<5>(), RealScalar(0)); + } + else + { + VERIFY_IS_APPROX(u.template lpNorm(), u.cwiseAbs().maxCoeff()); + } + VERIFY_IS_APPROX(u.template lpNorm<1>(), u.cwiseAbs().sum()); VERIFY_IS_APPROX(u.template lpNorm<2>(), sqrt(u.array().abs().square().sum())); VERIFY_IS_APPROX(numext::pow(u.template lpNorm<5>(), typename VectorType::RealScalar(5)), u.array().abs().pow(5).sum()); @@ -244,6 +273,8 @@ void test_array_for_matrix() CALL_SUBTEST_5( lpNorm(VectorXf(internal::random(1,EIGEN_TEST_MAX_SIZE))) ); CALL_SUBTEST_4( lpNorm(VectorXcf(internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } + CALL_SUBTEST_5( lpNorm(VectorXf(0)) ); + CALL_SUBTEST_4( lpNorm(VectorXcf(0)) ); for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_4( resize(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); CALL_SUBTEST_5( resize(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); diff --git a/testbed/nanogui/ext/eigen/test/array_of_string.cpp b/testbed/nanogui/ext/eigen/test/array_of_string.cpp new file mode 100644 index 00000000..e23b7c59 --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/array_of_string.cpp @@ -0,0 +1,32 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2016 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "main.h" + +void test_array_of_string() +{ + typedef Array ArrayXs; + ArrayXs a1(3), a2(3), a3(3), a3ref(3); + a1 << "one", "two", "three"; + a2 << "1", "2", "3"; + a3ref << "one (1)", "two (2)", "three (3)"; + std::stringstream s1; + s1 << a1; + VERIFY_IS_EQUAL(s1.str(), std::string(" one two three")); + a3 = a1 + std::string(" (") + a2 + std::string(")"); + VERIFY((a3==a3ref).all()); + + a3 = a1; + a3 += std::string(" (") + a2 + std::string(")"); + VERIFY((a3==a3ref).all()); + + a1.swap(a3); + VERIFY((a1==a3ref).all()); + VERIFY((a3!=a3ref).all()); +} diff --git a/testbed/nanogui/ext/eigen/test/array_replicate.cpp b/testbed/nanogui/ext/eigen/test/array_replicate.cpp index f412d1ae..779c8fc2 100644 --- a/testbed/nanogui/ext/eigen/test/array_replicate.cpp +++ b/testbed/nanogui/ext/eigen/test/array_replicate.cpp @@ -44,6 +44,19 @@ template void replicate(const MatrixType& m) x2 << m2, m2, m2, m2, m2, m2; VERIFY_IS_APPROX(x2, (m2.template replicate<2,3>())); + + x2.resize(rows,3*cols); + x2 << m2, m2, m2; + VERIFY_IS_APPROX(x2, (m2.template replicate<1,3>())); + + vx1.resize(3*rows,cols); + vx1 << m2, m2, m2; + VERIFY_IS_APPROX(vx1+vx1, vx1+(m2.template replicate<3,1>())); + + vx1=m2+(m2.colwise().replicate(1)); + + if(m2.cols()==1) + VERIFY_IS_APPROX(m2.coeff(0), (m2.template replicate<3,1>().coeff(m2.rows()))); x2.resize(rows,f1); for (int j=0; j void reverse(const MatrixType& m) // this test relies a lot on Random.h, and there's not much more that we can do // to test it, hence I consider that we will have tested Random.h - MatrixType m1 = MatrixType::Random(rows, cols); + MatrixType m1 = MatrixType::Random(rows, cols), m2; VectorType v1 = VectorType::Random(rows); MatrixType m1_r = m1.reverse(); @@ -96,14 +96,32 @@ template void reverse(const MatrixType& m) m1.reverse()(r, c) = x; VERIFY_IS_APPROX(x, m1(rows - 1 - r, cols - 1 - c)); + + m2 = m1; + m2.reverseInPlace(); + VERIFY_IS_APPROX(m2,m1.reverse().eval()); + + m2 = m1; + m2.col(0).reverseInPlace(); + VERIFY_IS_APPROX(m2.col(0),m1.col(0).reverse().eval()); + + m2 = m1; + m2.row(0).reverseInPlace(); + VERIFY_IS_APPROX(m2.row(0),m1.row(0).reverse().eval()); + + m2 = m1; + m2.rowwise().reverseInPlace(); + VERIFY_IS_APPROX(m2,m1.rowwise().reverse().eval()); + + m2 = m1; + m2.colwise().reverseInPlace(); + VERIFY_IS_APPROX(m2,m1.colwise().reverse().eval()); - /* m1.colwise().reverse()(r, c) = x; VERIFY_IS_APPROX(x, m1(rows - 1 - r, c)); m1.rowwise().reverse()(r, c) = x; VERIFY_IS_APPROX(x, m1(r, cols - 1 - c)); - */ } void test_array_reverse() @@ -113,11 +131,11 @@ void test_array_reverse() CALL_SUBTEST_2( reverse(Matrix2f()) ); CALL_SUBTEST_3( reverse(Matrix4f()) ); CALL_SUBTEST_4( reverse(Matrix4d()) ); - CALL_SUBTEST_5( reverse(MatrixXcf(3, 3)) ); - CALL_SUBTEST_6( reverse(MatrixXi(6, 3)) ); - CALL_SUBTEST_7( reverse(MatrixXcd(20, 20)) ); + CALL_SUBTEST_5( reverse(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_6( reverse(MatrixXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_7( reverse(MatrixXcd(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); CALL_SUBTEST_8( reverse(Matrix()) ); - CALL_SUBTEST_9( reverse(Matrix(6,3)) ); + CALL_SUBTEST_9( reverse(Matrix(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } #ifdef EIGEN_TEST_PART_3 Vector4f x; x << 1, 2, 3, 4; diff --git a/testbed/nanogui/ext/eigen/test/bandmatrix.cpp b/testbed/nanogui/ext/eigen/test/bandmatrix.cpp index 5e4e8e07..f8c38f7c 100644 --- a/testbed/nanogui/ext/eigen/test/bandmatrix.cpp +++ b/testbed/nanogui/ext/eigen/test/bandmatrix.cpp @@ -11,7 +11,6 @@ template void bandmatrix(const MatrixType& _m) { - typedef typename MatrixType::Index Index; typedef typename MatrixType::Scalar Scalar; typedef typename NumTraits::Real RealScalar; typedef Matrix DenseMatrixType; @@ -62,8 +61,6 @@ using Eigen::internal::BandMatrix; void test_bandmatrix() { - typedef BandMatrix::Index Index; - for(int i = 0; i < 10*g_repeat ; i++) { Index rows = internal::random(1,10); Index cols = internal::random(1,10); diff --git a/testbed/nanogui/ext/eigen/test/basicstuff.cpp b/testbed/nanogui/ext/eigen/test/basicstuff.cpp index 8c0621ec..c346ce6c 100644 --- a/testbed/nanogui/ext/eigen/test/basicstuff.cpp +++ b/testbed/nanogui/ext/eigen/test/basicstuff.cpp @@ -49,6 +49,22 @@ template void basicStuff(const MatrixType& m) v1[r] = x; VERIFY_IS_APPROX(x, v1[r]); + // test fetching with various index types. + Index r1 = internal::random(0, numext::mini(Index(127),rows-1)); + x = v1(static_cast(r1)); + x = v1(static_cast(r1)); + x = v1(static_cast(r1)); + x = v1(static_cast(r1)); + x = v1(static_cast(r1)); + x = v1(static_cast(r1)); + x = v1(static_cast(r1)); + x = v1(static_cast(r1)); + x = v1(static_cast(r1)); +#if EIGEN_HAS_CXX11 + x = v1(static_cast(r1)); + x = v1(static_cast(r1)); +#endif + VERIFY_IS_APPROX( v1, v1); VERIFY_IS_NOT_APPROX( v1, 2*v1); VERIFY_IS_MUCH_SMALLER_THAN( vzero, v1); @@ -126,6 +142,20 @@ template void basicStuff(const MatrixType& m) for(typename MatrixType::Index i=0;i(0,10)>5; + m3 = b ? m1 : m2; + if(b) VERIFY_IS_APPROX(m3,m1); + else VERIFY_IS_APPROX(m3,m2); + m3 = b ? -m1 : m2; + if(b) VERIFY_IS_APPROX(m3,-m1); + else VERIFY_IS_APPROX(m3,m2); + m3 = b ? m1 : -m2; + if(b) VERIFY_IS_APPROX(m3,m1); + else VERIFY_IS_APPROX(m3,-m2); + } } template void basicStuffComplex(const MatrixType& m) @@ -180,15 +210,64 @@ void casting() template void fixedSizeMatrixConstruction() { - const Scalar raw[3] = {1,2,3}; - Matrix m(raw); - Array a(raw); - VERIFY(m(0) == 1); - VERIFY(m(1) == 2); - VERIFY(m(2) == 3); - VERIFY(a(0) == 1); - VERIFY(a(1) == 2); - VERIFY(a(2) == 3); + Scalar raw[4]; + for(int k=0; k<4; ++k) + raw[k] = internal::random(); + + { + Matrix m(raw); + Array a(raw); + for(int k=0; k<4; ++k) VERIFY(m(k) == raw[k]); + for(int k=0; k<4; ++k) VERIFY(a(k) == raw[k]); + VERIFY_IS_EQUAL(m,(Matrix(raw[0],raw[1],raw[2],raw[3]))); + VERIFY((a==(Array(raw[0],raw[1],raw[2],raw[3]))).all()); + } + { + Matrix m(raw); + Array a(raw); + for(int k=0; k<3; ++k) VERIFY(m(k) == raw[k]); + for(int k=0; k<3; ++k) VERIFY(a(k) == raw[k]); + VERIFY_IS_EQUAL(m,(Matrix(raw[0],raw[1],raw[2]))); + VERIFY((a==Array(raw[0],raw[1],raw[2])).all()); + } + { + Matrix m(raw), m2( (DenseIndex(raw[0])), (DenseIndex(raw[1])) ); + Array a(raw), a2( (DenseIndex(raw[0])), (DenseIndex(raw[1])) ); + for(int k=0; k<2; ++k) VERIFY(m(k) == raw[k]); + for(int k=0; k<2; ++k) VERIFY(a(k) == raw[k]); + VERIFY_IS_EQUAL(m,(Matrix(raw[0],raw[1]))); + VERIFY((a==Array(raw[0],raw[1])).all()); + for(int k=0; k<2; ++k) VERIFY(m2(k) == DenseIndex(raw[k])); + for(int k=0; k<2; ++k) VERIFY(a2(k) == DenseIndex(raw[k])); + } + { + Matrix m(raw), + m2( (DenseIndex(raw[0])), (DenseIndex(raw[1])) ), + m3( (int(raw[0])), (int(raw[1])) ), + m4( (float(raw[0])), (float(raw[1])) ); + Array a(raw), a2( (DenseIndex(raw[0])), (DenseIndex(raw[1])) ); + for(int k=0; k<2; ++k) VERIFY(m(k) == raw[k]); + for(int k=0; k<2; ++k) VERIFY(a(k) == raw[k]); + VERIFY_IS_EQUAL(m,(Matrix(raw[0],raw[1]))); + VERIFY((a==Array(raw[0],raw[1])).all()); + for(int k=0; k<2; ++k) VERIFY(m2(k) == DenseIndex(raw[k])); + for(int k=0; k<2; ++k) VERIFY(a2(k) == DenseIndex(raw[k])); + for(int k=0; k<2; ++k) VERIFY(m3(k) == int(raw[k])); + for(int k=0; k<2; ++k) VERIFY((m4(k)) == Scalar(float(raw[k]))); + } + { + Matrix m(raw), m1(raw[0]), m2( (DenseIndex(raw[0])) ), m3( (int(raw[0])) ); + Array a(raw), a1(raw[0]), a2( (DenseIndex(raw[0])) ); + VERIFY(m(0) == raw[0]); + VERIFY(a(0) == raw[0]); + VERIFY(m1(0) == raw[0]); + VERIFY(a1(0) == raw[0]); + VERIFY(m2(0) == DenseIndex(raw[0])); + VERIFY(a2(0) == DenseIndex(raw[0])); + VERIFY(m3(0) == int(raw[0])); + VERIFY_IS_EQUAL(m,(Matrix(raw[0]))); + VERIFY((a==Array(raw[0])).all()); + } } void test_basicstuff() @@ -207,8 +286,11 @@ void test_basicstuff() } CALL_SUBTEST_1(fixedSizeMatrixConstruction()); + CALL_SUBTEST_1(fixedSizeMatrixConstruction()); CALL_SUBTEST_1(fixedSizeMatrixConstruction()); - CALL_SUBTEST_1(fixedSizeMatrixConstruction()); + CALL_SUBTEST_1(fixedSizeMatrixConstruction()); + CALL_SUBTEST_1(fixedSizeMatrixConstruction()); + CALL_SUBTEST_1(fixedSizeMatrixConstruction()); CALL_SUBTEST_2(casting()); } diff --git a/testbed/nanogui/ext/eigen/test/bdcsvd.cpp b/testbed/nanogui/ext/eigen/test/bdcsvd.cpp new file mode 100644 index 00000000..f9f687aa --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/bdcsvd.cpp @@ -0,0 +1,111 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2013 Gauthier Brun +// Copyright (C) 2013 Nicolas Carre +// Copyright (C) 2013 Jean Ceccato +// Copyright (C) 2013 Pierre Zoppitelli +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/ + +// discard stack allocation as that too bypasses malloc +#define EIGEN_STACK_ALLOCATION_LIMIT 0 +#define EIGEN_RUNTIME_NO_MALLOC + +#include "main.h" +#include +#include +#include + + +#define SVD_DEFAULT(M) BDCSVD +#define SVD_FOR_MIN_NORM(M) BDCSVD +#include "svd_common.h" + +// Check all variants of JacobiSVD +template +void bdcsvd(const MatrixType& a = MatrixType(), bool pickrandom = true) +{ + MatrixType m = a; + if(pickrandom) + svd_fill_random(m); + + CALL_SUBTEST(( svd_test_all_computation_options >(m, false) )); +} + +template +void bdcsvd_method() +{ + enum { Size = MatrixType::RowsAtCompileTime }; + typedef typename MatrixType::RealScalar RealScalar; + typedef Matrix RealVecType; + MatrixType m = MatrixType::Identity(); + VERIFY_IS_APPROX(m.bdcSvd().singularValues(), RealVecType::Ones()); + VERIFY_RAISES_ASSERT(m.bdcSvd().matrixU()); + VERIFY_RAISES_ASSERT(m.bdcSvd().matrixV()); + VERIFY_IS_APPROX(m.bdcSvd(ComputeFullU|ComputeFullV).solve(m), m); +} + +// compare the Singular values returned with Jacobi and Bdc +template +void compare_bdc_jacobi(const MatrixType& a = MatrixType(), unsigned int computationOptions = 0) +{ + MatrixType m = MatrixType::Random(a.rows(), a.cols()); + BDCSVD bdc_svd(m); + JacobiSVD jacobi_svd(m); + VERIFY_IS_APPROX(bdc_svd.singularValues(), jacobi_svd.singularValues()); + if(computationOptions & ComputeFullU) VERIFY_IS_APPROX(bdc_svd.matrixU(), jacobi_svd.matrixU()); + if(computationOptions & ComputeThinU) VERIFY_IS_APPROX(bdc_svd.matrixU(), jacobi_svd.matrixU()); + if(computationOptions & ComputeFullV) VERIFY_IS_APPROX(bdc_svd.matrixV(), jacobi_svd.matrixV()); + if(computationOptions & ComputeThinV) VERIFY_IS_APPROX(bdc_svd.matrixV(), jacobi_svd.matrixV()); +} + +void test_bdcsvd() +{ + CALL_SUBTEST_3(( svd_verify_assert >(Matrix3f()) )); + CALL_SUBTEST_4(( svd_verify_assert >(Matrix4d()) )); + CALL_SUBTEST_7(( svd_verify_assert >(MatrixXf(10,12)) )); + CALL_SUBTEST_8(( svd_verify_assert >(MatrixXcd(7,5)) )); + + CALL_SUBTEST_101(( svd_all_trivial_2x2(bdcsvd) )); + CALL_SUBTEST_102(( svd_all_trivial_2x2(bdcsvd) )); + + for(int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_3(( bdcsvd() )); + CALL_SUBTEST_4(( bdcsvd() )); + CALL_SUBTEST_5(( bdcsvd >() )); + + int r = internal::random(1, EIGEN_TEST_MAX_SIZE/2), + c = internal::random(1, EIGEN_TEST_MAX_SIZE/2); + + TEST_SET_BUT_UNUSED_VARIABLE(r) + TEST_SET_BUT_UNUSED_VARIABLE(c) + + CALL_SUBTEST_6(( bdcsvd(Matrix(r,2)) )); + CALL_SUBTEST_7(( bdcsvd(MatrixXf(r,c)) )); + CALL_SUBTEST_7(( compare_bdc_jacobi(MatrixXf(r,c)) )); + CALL_SUBTEST_10(( bdcsvd(MatrixXd(r,c)) )); + CALL_SUBTEST_10(( compare_bdc_jacobi(MatrixXd(r,c)) )); + CALL_SUBTEST_8(( bdcsvd(MatrixXcd(r,c)) )); + CALL_SUBTEST_8(( compare_bdc_jacobi(MatrixXcd(r,c)) )); + + // Test on inf/nan matrix + CALL_SUBTEST_7( (svd_inf_nan, MatrixXf>()) ); + CALL_SUBTEST_10( (svd_inf_nan, MatrixXd>()) ); + } + + // test matrixbase method + CALL_SUBTEST_1(( bdcsvd_method() )); + CALL_SUBTEST_3(( bdcsvd_method() )); + + // Test problem size constructors + CALL_SUBTEST_7( BDCSVD(10,10) ); + + // Check that preallocation avoids subsequent mallocs + CALL_SUBTEST_9( svd_preallocate() ); + + CALL_SUBTEST_2( svd_underoverflow() ); +} + diff --git a/testbed/nanogui/ext/eigen/test/bicgstab.cpp b/testbed/nanogui/ext/eigen/test/bicgstab.cpp index f327e2fa..4cc0dd31 100644 --- a/testbed/nanogui/ext/eigen/test/bicgstab.cpp +++ b/testbed/nanogui/ext/eigen/test/bicgstab.cpp @@ -10,13 +10,16 @@ #include "sparse_solver.h" #include -template void test_bicgstab_T() +template void test_bicgstab_T() { - BiCGSTAB, DiagonalPreconditioner > bicgstab_colmajor_diag; - BiCGSTAB, IdentityPreconditioner > bicgstab_colmajor_I; - BiCGSTAB, IncompleteLUT > bicgstab_colmajor_ilut; + BiCGSTAB, DiagonalPreconditioner > bicgstab_colmajor_diag; + BiCGSTAB, IdentityPreconditioner > bicgstab_colmajor_I; + BiCGSTAB, IncompleteLUT > bicgstab_colmajor_ilut; //BiCGSTAB, SSORPreconditioner > bicgstab_colmajor_ssor; + bicgstab_colmajor_diag.setTolerance(NumTraits::epsilon()*4); + bicgstab_colmajor_ilut.setTolerance(NumTraits::epsilon()*4); + CALL_SUBTEST( check_sparse_square_solving(bicgstab_colmajor_diag) ); // CALL_SUBTEST( check_sparse_square_solving(bicgstab_colmajor_I) ); CALL_SUBTEST( check_sparse_square_solving(bicgstab_colmajor_ilut) ); @@ -25,6 +28,7 @@ template void test_bicgstab_T() void test_bicgstab() { - CALL_SUBTEST_1(test_bicgstab_T()); - CALL_SUBTEST_2(test_bicgstab_T >()); + CALL_SUBTEST_1((test_bicgstab_T()) ); + CALL_SUBTEST_2((test_bicgstab_T, int>())); + CALL_SUBTEST_3((test_bicgstab_T())); } diff --git a/testbed/nanogui/ext/eigen/test/block.cpp b/testbed/nanogui/ext/eigen/test/block.cpp index 9ed5d7bc..d6105987 100644 --- a/testbed/nanogui/ext/eigen/test/block.cpp +++ b/testbed/nanogui/ext/eigen/test/block.cpp @@ -29,6 +29,13 @@ block_real_only(const MatrixType &, Index, Index, Index, Index, const Scalar&) { return Scalar(0); } +// Check at compile-time that T1==T2, and at runtime-time that a==b +template +typename internal::enable_if::value,bool>::type +is_same_block(const T1& a, const T2& b) +{ + return a.isApprox(b); +} template void block(const MatrixType& m) { @@ -87,10 +94,9 @@ template void block(const MatrixType& m) m1.block(r1,c1,r2-r1+1,c2-c1+1) = s1 * m2.block(0, 0, r2-r1+1,c2-c1+1); m1.block(r1,c1,r2-r1+1,c2-c1+1)(r2-r1,c2-c1) = m2.block(0, 0, r2-r1+1,c2-c1+1)(0,0); - enum { - BlockRows = 2, - BlockCols = 5 - }; + const Index BlockRows = 2; + const Index BlockCols = 5; + if (rows>=5 && cols>=8) { // test fixed block() as lvalue @@ -106,6 +112,11 @@ template void block(const MatrixType& m) m1.template block(1,1,BlockRows,BlockCols)(0,3) = m1.template block<2,5>(1,1)(1,2); Matrix b2 = m1.template block(3,3,2,5); VERIFY_IS_EQUAL(b2, m1.block(3,3,BlockRows,BlockCols)); + + VERIFY(is_same_block(m1.block(3,3,BlockRows,BlockCols), m1.block(3,3,fix(BlockRows),fix(BlockCols)))); + VERIFY(is_same_block(m1.template block(1,1,BlockRows,BlockCols), m1.block(1,1,fix,BlockCols))); + VERIFY(is_same_block(m1.template block(1,1,BlockRows,BlockCols), m1.block(1,1,fix(),fix))); + VERIFY(is_same_block(m1.template block(1,1,BlockRows,BlockCols), m1.block(1,1,fix,fix(BlockCols)))); } if (rows>2) @@ -130,6 +141,14 @@ template void block(const MatrixType& m) VERIFY(numext::real(ones.col(c1).dot(ones.col(c2))) == RealScalar(rows)); VERIFY(numext::real(ones.row(r1).dot(ones.row(r2))) == RealScalar(cols)); + + // chekc that linear acccessors works on blocks + m1 = m1_copy; + if((MatrixType::Flags&RowMajorBit)==0) + VERIFY_IS_EQUAL(m1.leftCols(c1).coeff(r1+c1*rows), m1(r1,c1)); + else + VERIFY_IS_EQUAL(m1.topRows(r1).coeff(c1+r1*cols), m1(r1,c1)); + // now test some block-inside-of-block. @@ -141,11 +160,11 @@ template void block(const MatrixType& m) VERIFY_IS_EQUAL( (m1.transpose().block(c1,r1,c2-c1+1,r2-r1+1).col(0)) , (m1.row(r1).segment(c1,c2-c1+1)).transpose() ); // expressions without direct access - VERIFY_IS_EQUAL( ((m1+m2).block(r1,c1,rows-r1,cols-c1).block(r2-r1,c2-c1,rows-r2,cols-c2)) , ((m1+m2).block(r2,c2,rows-r2,cols-c2)) ); - VERIFY_IS_EQUAL( ((m1+m2).block(r1,c1,r2-r1+1,c2-c1+1).row(0)) , ((m1+m2).row(r1).segment(c1,c2-c1+1)) ); - VERIFY_IS_EQUAL( ((m1+m2).block(r1,c1,r2-r1+1,c2-c1+1).col(0)) , ((m1+m2).col(c1).segment(r1,r2-r1+1)) ); - VERIFY_IS_EQUAL( ((m1+m2).block(r1,c1,r2-r1+1,c2-c1+1).transpose().col(0)) , ((m1+m2).row(r1).segment(c1,c2-c1+1)).transpose() ); - VERIFY_IS_EQUAL( ((m1+m2).transpose().block(c1,r1,c2-c1+1,r2-r1+1).col(0)) , ((m1+m2).row(r1).segment(c1,c2-c1+1)).transpose() ); + VERIFY_IS_APPROX( ((m1+m2).block(r1,c1,rows-r1,cols-c1).block(r2-r1,c2-c1,rows-r2,cols-c2)) , ((m1+m2).block(r2,c2,rows-r2,cols-c2)) ); + VERIFY_IS_APPROX( ((m1+m2).block(r1,c1,r2-r1+1,c2-c1+1).row(0)) , ((m1+m2).row(r1).segment(c1,c2-c1+1)) ); + VERIFY_IS_APPROX( ((m1+m2).block(r1,c1,r2-r1+1,c2-c1+1).col(0)) , ((m1+m2).col(c1).segment(r1,r2-r1+1)) ); + VERIFY_IS_APPROX( ((m1+m2).block(r1,c1,r2-r1+1,c2-c1+1).transpose().col(0)) , ((m1+m2).row(r1).segment(c1,c2-c1+1)).transpose() ); + VERIFY_IS_APPROX( ((m1+m2).transpose().block(c1,r1,c2-c1+1,r2-r1+1).col(0)) , ((m1+m2).row(r1).segment(c1,c2-c1+1)).transpose() ); // evaluation into plain matrices from expressions with direct access (stress MapBase) DynamicMatrixType dm; @@ -173,6 +192,19 @@ template void block(const MatrixType& m) dm = m1.row(r1).segment(c1,c2-c1+1).transpose(); dv = m1.transpose().block(c1,r1,c2-c1+1,r2-r1+1).col(0); VERIFY_IS_EQUAL(dv, dm); + + VERIFY_IS_EQUAL( (m1.template block(1,0,0,1)), m1.block(1,0,0,1)); + VERIFY_IS_EQUAL( (m1.template block<1,Dynamic>(0,1,1,0)), m1.block(0,1,1,0)); + VERIFY_IS_EQUAL( ((m1*1).template block(1,0,0,1)), m1.block(1,0,0,1)); + VERIFY_IS_EQUAL( ((m1*1).template block<1,Dynamic>(0,1,1,0)), m1.block(0,1,1,0)); + + if (rows>=2 && cols>=2) + { + VERIFY_RAISES_ASSERT( m1 += m1.col(0) ); + VERIFY_RAISES_ASSERT( m1 -= m1.col(0) ); + VERIFY_RAISES_ASSERT( m1.array() *= m1.col(0).array() ); + VERIFY_RAISES_ASSERT( m1.array() /= m1.col(0).array() ); + } } diff --git a/testbed/nanogui/ext/eigen/test/boostmultiprec.cpp b/testbed/nanogui/ext/eigen/test/boostmultiprec.cpp new file mode 100644 index 00000000..e06e9bda --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/boostmultiprec.cpp @@ -0,0 +1,201 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2016 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include + +#ifdef EIGEN_TEST_MAX_SIZE +#undef EIGEN_TEST_MAX_SIZE +#endif + +#define EIGEN_TEST_MAX_SIZE 50 + +#ifdef EIGEN_TEST_PART_1 +#include "cholesky.cpp" +#endif + +#ifdef EIGEN_TEST_PART_2 +#include "lu.cpp" +#endif + +#ifdef EIGEN_TEST_PART_3 +#include "qr.cpp" +#endif + +#ifdef EIGEN_TEST_PART_4 +#include "qr_colpivoting.cpp" +#endif + +#ifdef EIGEN_TEST_PART_5 +#include "qr_fullpivoting.cpp" +#endif + +#ifdef EIGEN_TEST_PART_6 +#include "eigensolver_selfadjoint.cpp" +#endif + +#ifdef EIGEN_TEST_PART_7 +#include "eigensolver_generic.cpp" +#endif + +#ifdef EIGEN_TEST_PART_8 +#include "eigensolver_generalized_real.cpp" +#endif + +#ifdef EIGEN_TEST_PART_9 +#include "jacobisvd.cpp" +#endif + +#ifdef EIGEN_TEST_PART_10 +#include "bdcsvd.cpp" +#endif + +#include + +#undef min +#undef max +#undef isnan +#undef isinf +#undef isfinite + +#include +#include +#include +#include + +namespace mp = boost::multiprecision; +typedef mp::number, mp::et_on> Real; + +namespace Eigen { + template<> struct NumTraits : GenericNumTraits { + static inline Real dummy_precision() { return 1e-50; } + }; + + template + struct NumTraits > : NumTraits {}; + + template<> + Real test_precision() { return 1e-50; } + + // needed in C++93 mode where number does not support explicit cast. + namespace internal { + template + struct cast_impl { + static inline NewType run(const Real& x) { + return x.template convert_to(); + } + }; + + template<> + struct cast_impl > { + static inline std::complex run(const Real& x) { + return std::complex(x); + } + }; + } +} + +namespace boost { +namespace multiprecision { + // to make ADL works as expected: + using boost::math::isfinite; + using boost::math::isnan; + using boost::math::isinf; + using boost::math::copysign; + using boost::math::hypot; + + // The following is needed for std::complex: + Real fabs(const Real& a) { return abs EIGEN_NOT_A_MACRO (a); } + Real fmax(const Real& a, const Real& b) { using std::max; return max(a,b); } + + // some specialization for the unit tests: + inline bool test_isMuchSmallerThan(const Real& a, const Real& b) { + return internal::isMuchSmallerThan(a, b, test_precision()); + } + + inline bool test_isApprox(const Real& a, const Real& b) { + return internal::isApprox(a, b, test_precision()); + } + + inline bool test_isApproxOrLessThan(const Real& a, const Real& b) { + return internal::isApproxOrLessThan(a, b, test_precision()); + } + + Real get_test_precision(const Real&) { + return test_precision(); + } + + Real test_relative_error(const Real &a, const Real &b) { + using Eigen::numext::abs2; + return sqrt(abs2(a-b)/Eigen::numext::mini(abs2(a),abs2(b))); + } +} +} + +namespace Eigen { + +} + +void test_boostmultiprec() +{ + typedef Matrix Mat; + typedef Matrix,Dynamic,Dynamic> MatC; + + std::cout << "NumTraits::epsilon() = " << NumTraits::epsilon() << std::endl; + std::cout << "NumTraits::dummy_precision() = " << NumTraits::dummy_precision() << std::endl; + std::cout << "NumTraits::lowest() = " << NumTraits::lowest() << std::endl; + std::cout << "NumTraits::highest() = " << NumTraits::highest() << std::endl; + std::cout << "NumTraits::digits10() = " << NumTraits::digits10() << std::endl; + + // chekc stream output + { + Mat A(10,10); + A.setRandom(); + std::stringstream ss; + ss << A; + } + { + MatC A(10,10); + A.setRandom(); + std::stringstream ss; + ss << A; + } + + for(int i = 0; i < g_repeat; i++) { + int s = internal::random(1,EIGEN_TEST_MAX_SIZE); + + CALL_SUBTEST_1( cholesky(Mat(s,s)) ); + + CALL_SUBTEST_2( lu_non_invertible() ); + CALL_SUBTEST_2( lu_invertible() ); + CALL_SUBTEST_2( lu_non_invertible() ); + CALL_SUBTEST_2( lu_invertible() ); + + CALL_SUBTEST_3( qr(Mat(internal::random(1,EIGEN_TEST_MAX_SIZE),internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_3( qr_invertible() ); + + CALL_SUBTEST_4( qr() ); + CALL_SUBTEST_4( cod() ); + CALL_SUBTEST_4( qr_invertible() ); + + CALL_SUBTEST_5( qr() ); + CALL_SUBTEST_5( qr_invertible() ); + + CALL_SUBTEST_6( selfadjointeigensolver(Mat(s,s)) ); + + CALL_SUBTEST_7( eigensolver(Mat(s,s)) ); + + CALL_SUBTEST_8( generalized_eigensolver_real(Mat(s,s)) ); + + TEST_SET_BUT_UNUSED_VARIABLE(s) + } + + CALL_SUBTEST_9(( jacobisvd(Mat(internal::random(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE), internal::random(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/2))) )); + CALL_SUBTEST_10(( bdcsvd(Mat(internal::random(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE), internal::random(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/2))) )); +} + diff --git a/testbed/nanogui/ext/eigen/test/bug1213.cpp b/testbed/nanogui/ext/eigen/test/bug1213.cpp new file mode 100644 index 00000000..581760c1 --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/bug1213.cpp @@ -0,0 +1,13 @@ + +// This anonymous enum is essential to trigger the linking issue +enum { + Foo +}; + +#include "bug1213.h" + +bool bug1213_1(const Eigen::Vector3f& x) +{ + return bug1213_2(x); +} + diff --git a/testbed/nanogui/ext/eigen/test/bug1213.h b/testbed/nanogui/ext/eigen/test/bug1213.h new file mode 100644 index 00000000..040e5a47 --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/bug1213.h @@ -0,0 +1,8 @@ + +#include + +template +bool bug1213_2(const Eigen::Matrix& x); + +bool bug1213_1(const Eigen::Vector3f& x); + diff --git a/testbed/nanogui/ext/eigen/test/bug1213_main.cpp b/testbed/nanogui/ext/eigen/test/bug1213_main.cpp new file mode 100644 index 00000000..4802c000 --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/bug1213_main.cpp @@ -0,0 +1,18 @@ + +// This is a regression unit regarding a weird linking issue with gcc. + +#include "bug1213.h" + +int main() +{ + return 0; +} + + +template +bool bug1213_2(const Eigen::Matrix& ) +{ + return true; +} + +template bool bug1213_2(const Eigen::Vector3f&); diff --git a/testbed/nanogui/ext/eigen/test/cholesky.cpp b/testbed/nanogui/ext/eigen/test/cholesky.cpp index 56885deb..8ad5ac63 100644 --- a/testbed/nanogui/ext/eigen/test/cholesky.cpp +++ b/testbed/nanogui/ext/eigen/test/cholesky.cpp @@ -11,20 +11,17 @@ #define EIGEN_NO_ASSERTION_CHECKING #endif -static int nb_temporaries; - -#define EIGEN_DENSE_STORAGE_CTOR_PLUGIN { if(size!=0) nb_temporaries++; } +#define TEST_ENABLE_TEMPORARY_TRACKING #include "main.h" #include #include -#define VERIFY_EVALUATION_COUNT(XPR,N) {\ - nb_temporaries = 0; \ - XPR; \ - if(nb_temporaries!=N) std::cerr << "nb_temporaries == " << nb_temporaries << "\n"; \ - VERIFY( (#XPR) && nb_temporaries==N ); \ - } +template +typename MatrixType::RealScalar matrix_l1_norm(const MatrixType& m) { + MatrixType symm = m.template selfadjointView(); + return symm.cwiseAbs().colwise().sum().maxCoeff(); +} template class CholType> void test_chol_update(const MatrixType& symm) { @@ -83,14 +80,10 @@ template void cholesky(const MatrixType& m) symm += a1 * a1.adjoint(); } - // to test if really Cholesky only uses the upper triangular part, uncomment the following - // FIXME: currently that fails !! - //symm.template part().setZero(); - { SquareMatrixType symmUp = symm.template triangularView(); SquareMatrixType symmLo = symm.template triangularView(); - + LLT chollo(symmLo); VERIFY_IS_APPROX(symm, chollo.reconstructedMatrix()); vecX = chollo.solve(vecB); @@ -98,6 +91,14 @@ template void cholesky(const MatrixType& m) matX = chollo.solve(matB); VERIFY_IS_APPROX(symm * matX, matB); + const MatrixType symmLo_inverse = chollo.solve(MatrixType::Identity(rows,cols)); + RealScalar rcond = (RealScalar(1) / matrix_l1_norm(symmLo)) / + matrix_l1_norm(symmLo_inverse); + RealScalar rcond_est = chollo.rcond(); + // Verify that the estimated condition number is within a factor of 10 of the + // truth. + VERIFY(rcond_est > rcond / 10 && rcond_est < rcond * 10); + // test the upper mode LLT cholup(symmUp); VERIFY_IS_APPROX(symm, cholup.reconstructedMatrix()); @@ -106,6 +107,15 @@ template void cholesky(const MatrixType& m) matX = cholup.solve(matB); VERIFY_IS_APPROX(symm * matX, matB); + // Verify that the estimated condition number is within a factor of 10 of the + // truth. + const MatrixType symmUp_inverse = cholup.solve(MatrixType::Identity(rows,cols)); + rcond = (RealScalar(1) / matrix_l1_norm(symmUp)) / + matrix_l1_norm(symmUp_inverse); + rcond_est = cholup.rcond(); + VERIFY(rcond_est > rcond / 10 && rcond_est < rcond * 10); + + MatrixType neg = -symmLo; chollo.compute(neg); VERIFY(chollo.info()==NumericalIssue); @@ -114,7 +124,7 @@ template void cholesky(const MatrixType& m) VERIFY_IS_APPROX(MatrixType(chollo.matrixU().transpose().conjugate()), MatrixType(chollo.matrixL())); VERIFY_IS_APPROX(MatrixType(cholup.matrixL().transpose().conjugate()), MatrixType(cholup.matrixU())); VERIFY_IS_APPROX(MatrixType(cholup.matrixU().transpose().conjugate()), MatrixType(cholup.matrixL())); - + // test some special use cases of SelfCwiseBinaryOp: MatrixType m1 = MatrixType::Random(rows,cols), m2(rows,cols); m2 = m1; @@ -144,19 +154,38 @@ template void cholesky(const MatrixType& m) SquareMatrixType symmLo = symm.template triangularView(); LDLT ldltlo(symmLo); + VERIFY(ldltlo.info()==Success); VERIFY_IS_APPROX(symm, ldltlo.reconstructedMatrix()); vecX = ldltlo.solve(vecB); VERIFY_IS_APPROX(symm * vecX, vecB); matX = ldltlo.solve(matB); VERIFY_IS_APPROX(symm * matX, matB); + const MatrixType symmLo_inverse = ldltlo.solve(MatrixType::Identity(rows,cols)); + RealScalar rcond = (RealScalar(1) / matrix_l1_norm(symmLo)) / + matrix_l1_norm(symmLo_inverse); + RealScalar rcond_est = ldltlo.rcond(); + // Verify that the estimated condition number is within a factor of 10 of the + // truth. + VERIFY(rcond_est > rcond / 10 && rcond_est < rcond * 10); + + LDLT ldltup(symmUp); + VERIFY(ldltup.info()==Success); VERIFY_IS_APPROX(symm, ldltup.reconstructedMatrix()); vecX = ldltup.solve(vecB); VERIFY_IS_APPROX(symm * vecX, vecB); matX = ldltup.solve(matB); VERIFY_IS_APPROX(symm * matX, matB); + // Verify that the estimated condition number is within a factor of 10 of the + // truth. + const MatrixType symmUp_inverse = ldltup.solve(MatrixType::Identity(rows,cols)); + rcond = (RealScalar(1) / matrix_l1_norm(symmUp)) / + matrix_l1_norm(symmUp_inverse); + rcond_est = ldltup.rcond(); + VERIFY(rcond_est > rcond / 10 && rcond_est < rcond * 10); + VERIFY_IS_APPROX(MatrixType(ldltlo.matrixL().transpose().conjugate()), MatrixType(ldltlo.matrixU())); VERIFY_IS_APPROX(MatrixType(ldltlo.matrixU().transpose().conjugate()), MatrixType(ldltlo.matrixL())); VERIFY_IS_APPROX(MatrixType(ldltup.matrixL().transpose().conjugate()), MatrixType(ldltup.matrixU())); @@ -185,7 +214,7 @@ template void cholesky(const MatrixType& m) if(rows>=3) { SquareMatrixType A = symm; - int c = internal::random(0,rows-2); + Index c = internal::random(0,rows-2); A.bottomRightCorner(c,c).setZero(); // Make sure a solution exists: vecX.setRandom(); @@ -196,11 +225,11 @@ template void cholesky(const MatrixType& m) vecX = ldltlo.solve(vecB); VERIFY_IS_APPROX(A * vecX, vecB); } - + // check non-full rank matrices if(rows>=3) { - int r = internal::random(1,rows-1); + Index r = internal::random(1,rows-1); Matrix a = Matrix::Random(rows,r); SquareMatrixType A = a * a.adjoint(); // Make sure a solution exists: @@ -212,15 +241,17 @@ template void cholesky(const MatrixType& m) vecX = ldltlo.solve(vecB); VERIFY_IS_APPROX(A * vecX, vecB); } - + // check matrices with a wide spectrum if(rows>=3) { + using std::pow; + using std::sqrt; RealScalar s = (std::min)(16,std::numeric_limits::max_exponent10/8); Matrix a = Matrix::Random(rows,rows); Matrix d = Matrix::Random(rows); - for(int k=0; k(-s,s)); + for(Index k=0; k(-s,s)); SquareMatrixType A = a * d.asDiagonal() * a.adjoint(); // Make sure a solution exists: vecX.setRandom(); @@ -229,7 +260,20 @@ template void cholesky(const MatrixType& m) ldltlo.compute(A); VERIFY_IS_APPROX(A, ldltlo.reconstructedMatrix()); vecX = ldltlo.solve(vecB); - VERIFY_IS_APPROX(A * vecX, vecB); + + if(ldltlo.vectorD().real().cwiseAbs().minCoeff()>RealScalar(0)) + { + VERIFY_IS_APPROX(A * vecX,vecB); + } + else + { + RealScalar large_tol = sqrt(test_precision()); + VERIFY((A * vecX).isApprox(vecB, large_tol)); + + ++g_test_level; + VERIFY_IS_APPROX(A * vecX,vecB); + --g_test_level; + } } } @@ -289,6 +333,7 @@ template void cholesky_cplx(const MatrixType& m) RealMatrixType symmLo = symm.template triangularView(); LDLT ldltlo(symmLo); + VERIFY(ldltlo.info()==Success); VERIFY_IS_APPROX(symm, ldltlo.reconstructedMatrix()); vecX = ldltlo.solve(vecB); VERIFY_IS_APPROX(symm * vecX, vecB); @@ -314,46 +359,101 @@ template void cholesky_bug241(const MatrixType& m) } // LDLT is not guaranteed to work for indefinite matrices, but happens to work fine if matrix is diagonal. -// This test checks that LDLT reports correctly that matrix is indefinite. +// This test checks that LDLT reports correctly that matrix is indefinite. // See http://forum.kde.org/viewtopic.php?f=74&t=106942 and bug 736 template void cholesky_definiteness(const MatrixType& m) { eigen_assert(m.rows() == 2 && m.cols() == 2); MatrixType mat; LDLT ldlt(2); - + { mat << 1, 0, 0, -1; ldlt.compute(mat); + VERIFY(ldlt.info()==Success); VERIFY(!ldlt.isNegative()); VERIFY(!ldlt.isPositive()); } { mat << 1, 2, 2, 1; ldlt.compute(mat); + VERIFY(ldlt.info()==Success); VERIFY(!ldlt.isNegative()); VERIFY(!ldlt.isPositive()); } { mat << 0, 0, 0, 0; ldlt.compute(mat); + VERIFY(ldlt.info()==Success); VERIFY(ldlt.isNegative()); VERIFY(ldlt.isPositive()); } { mat << 0, 0, 0, 1; ldlt.compute(mat); + VERIFY(ldlt.info()==Success); VERIFY(!ldlt.isNegative()); VERIFY(ldlt.isPositive()); } { mat << -1, 0, 0, 0; ldlt.compute(mat); + VERIFY(ldlt.info()==Success); VERIFY(ldlt.isNegative()); VERIFY(!ldlt.isPositive()); } } +template +void cholesky_faillure_cases() +{ + MatrixXd mat; + LDLT ldlt; + + { + mat.resize(2,2); + mat << 0, 1, 1, 0; + ldlt.compute(mat); + VERIFY_IS_NOT_APPROX(mat,ldlt.reconstructedMatrix()); + VERIFY(ldlt.info()==NumericalIssue); + } +#if (!EIGEN_ARCH_i386) || defined(EIGEN_VECTORIZE_SSE2) + { + mat.resize(3,3); + mat << -1, -3, 3, + -3, -8.9999999999999999999, 1, + 3, 1, 0; + ldlt.compute(mat); + VERIFY(ldlt.info()==NumericalIssue); + VERIFY_IS_NOT_APPROX(mat,ldlt.reconstructedMatrix()); + } +#endif + { + mat.resize(3,3); + mat << 1, 2, 3, + 2, 4, 1, + 3, 1, 0; + ldlt.compute(mat); + VERIFY(ldlt.info()==NumericalIssue); + VERIFY_IS_NOT_APPROX(mat,ldlt.reconstructedMatrix()); + } + + { + mat.resize(8,8); + mat << 0.1, 0, -0.1, 0, 0, 0, 1, 0, + 0, 4.24667, 0, 2.00333, 0, 0, 0, 0, + -0.1, 0, 0.2, 0, -0.1, 0, 0, 0, + 0, 2.00333, 0, 8.49333, 0, 2.00333, 0, 0, + 0, 0, -0.1, 0, 0.1, 0, 0, 1, + 0, 0, 0, 2.00333, 0, 4.24667, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 0, 0; + ldlt.compute(mat); + VERIFY(ldlt.info()==NumericalIssue); + VERIFY_IS_NOT_APPROX(mat,ldlt.reconstructedMatrix()); + } +} + template void cholesky_verify_assert() { MatrixType tmp; @@ -384,10 +484,14 @@ void test_cholesky() CALL_SUBTEST_3( cholesky_definiteness(Matrix2d()) ); CALL_SUBTEST_4( cholesky(Matrix3f()) ); CALL_SUBTEST_5( cholesky(Matrix4d()) ); + s = internal::random(1,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_2( cholesky(MatrixXd(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) + s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_6( cholesky_cplx(MatrixXcd(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) } CALL_SUBTEST_4( cholesky_verify_assert() ); @@ -398,7 +502,8 @@ void test_cholesky() // Test problem size constructors CALL_SUBTEST_9( LLT(10) ); CALL_SUBTEST_9( LDLT(10) ); - - TEST_SET_BUT_UNUSED_VARIABLE(s) + + CALL_SUBTEST_2( cholesky_faillure_cases() ); + TEST_SET_BUT_UNUSED_VARIABLE(nb_temporaries) } diff --git a/testbed/nanogui/ext/eigen/test/cholmod_support.cpp b/testbed/nanogui/ext/eigen/test/cholmod_support.cpp index 8f8be3c0..93120733 100644 --- a/testbed/nanogui/ext/eigen/test/cholmod_support.cpp +++ b/testbed/nanogui/ext/eigen/test/cholmod_support.cpp @@ -7,25 +7,26 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS #include "sparse_solver.h" #include -template void test_cholmod_T() +template void test_cholmod_ST() { - CholmodDecomposition, Lower> g_chol_colmajor_lower; g_chol_colmajor_lower.setMode(CholmodSupernodalLLt); - CholmodDecomposition, Upper> g_chol_colmajor_upper; g_chol_colmajor_upper.setMode(CholmodSupernodalLLt); - CholmodDecomposition, Lower> g_llt_colmajor_lower; g_llt_colmajor_lower.setMode(CholmodSimplicialLLt); - CholmodDecomposition, Upper> g_llt_colmajor_upper; g_llt_colmajor_upper.setMode(CholmodSimplicialLLt); - CholmodDecomposition, Lower> g_ldlt_colmajor_lower; g_ldlt_colmajor_lower.setMode(CholmodLDLt); - CholmodDecomposition, Upper> g_ldlt_colmajor_upper; g_ldlt_colmajor_upper.setMode(CholmodLDLt); + CholmodDecomposition g_chol_colmajor_lower; g_chol_colmajor_lower.setMode(CholmodSupernodalLLt); + CholmodDecomposition g_chol_colmajor_upper; g_chol_colmajor_upper.setMode(CholmodSupernodalLLt); + CholmodDecomposition g_llt_colmajor_lower; g_llt_colmajor_lower.setMode(CholmodSimplicialLLt); + CholmodDecomposition g_llt_colmajor_upper; g_llt_colmajor_upper.setMode(CholmodSimplicialLLt); + CholmodDecomposition g_ldlt_colmajor_lower; g_ldlt_colmajor_lower.setMode(CholmodLDLt); + CholmodDecomposition g_ldlt_colmajor_upper; g_ldlt_colmajor_upper.setMode(CholmodLDLt); - CholmodSupernodalLLT, Lower> chol_colmajor_lower; - CholmodSupernodalLLT, Upper> chol_colmajor_upper; - CholmodSimplicialLLT, Lower> llt_colmajor_lower; - CholmodSimplicialLLT, Upper> llt_colmajor_upper; - CholmodSimplicialLDLT, Lower> ldlt_colmajor_lower; - CholmodSimplicialLDLT, Upper> ldlt_colmajor_upper; + CholmodSupernodalLLT chol_colmajor_lower; + CholmodSupernodalLLT chol_colmajor_upper; + CholmodSimplicialLLT llt_colmajor_lower; + CholmodSimplicialLLT llt_colmajor_upper; + CholmodSimplicialLDLT ldlt_colmajor_lower; + CholmodSimplicialLDLT ldlt_colmajor_upper; check_sparse_spd_solving(g_chol_colmajor_lower); check_sparse_spd_solving(g_chol_colmajor_upper); @@ -40,17 +41,29 @@ template void test_cholmod_T() check_sparse_spd_solving(llt_colmajor_upper); check_sparse_spd_solving(ldlt_colmajor_lower); check_sparse_spd_solving(ldlt_colmajor_upper); - -// check_sparse_spd_determinant(chol_colmajor_lower); -// check_sparse_spd_determinant(chol_colmajor_upper); -// check_sparse_spd_determinant(llt_colmajor_lower); -// check_sparse_spd_determinant(llt_colmajor_upper); -// check_sparse_spd_determinant(ldlt_colmajor_lower); -// check_sparse_spd_determinant(ldlt_colmajor_upper); + + check_sparse_spd_determinant(chol_colmajor_lower); + check_sparse_spd_determinant(chol_colmajor_upper); + check_sparse_spd_determinant(llt_colmajor_lower); + check_sparse_spd_determinant(llt_colmajor_upper); + check_sparse_spd_determinant(ldlt_colmajor_lower); + check_sparse_spd_determinant(ldlt_colmajor_upper); +} + +template void test_cholmod_T() +{ + test_cholmod_ST >(); } void test_cholmod_support() { - CALL_SUBTEST_1(test_cholmod_T()); - CALL_SUBTEST_2(test_cholmod_T >()); + CALL_SUBTEST_11( (test_cholmod_T()) ); + CALL_SUBTEST_12( (test_cholmod_T()) ); + CALL_SUBTEST_13( (test_cholmod_T()) ); + CALL_SUBTEST_14( (test_cholmod_T()) ); + CALL_SUBTEST_21( (test_cholmod_T, ColMajor, int >()) ); + CALL_SUBTEST_22( (test_cholmod_T, ColMajor, long>()) ); + // TODO complex row-major matrices do not work at the moment: + // CALL_SUBTEST_23( (test_cholmod_T, RowMajor, int >()) ); + // CALL_SUBTEST_24( (test_cholmod_T, RowMajor, long>()) ); } diff --git a/testbed/nanogui/ext/eigen/test/commainitializer.cpp b/testbed/nanogui/ext/eigen/test/commainitializer.cpp index 99102b96..9844adbd 100644 --- a/testbed/nanogui/ext/eigen/test/commainitializer.cpp +++ b/testbed/nanogui/ext/eigen/test/commainitializer.cpp @@ -9,6 +9,62 @@ #include "main.h" + +template +void test_blocks() +{ + Matrix m_fixed; + MatrixXi m_dynamic(M1+M2, N1+N2); + + Matrix mat11; mat11.setRandom(); + Matrix mat12; mat12.setRandom(); + Matrix mat21; mat21.setRandom(); + Matrix mat22; mat22.setRandom(); + + MatrixXi matx11 = mat11, matx12 = mat12, matx21 = mat21, matx22 = mat22; + + { + VERIFY_IS_EQUAL((m_fixed << mat11, mat12, mat21, matx22).finished(), (m_dynamic << mat11, matx12, mat21, matx22).finished()); + VERIFY_IS_EQUAL((m_fixed.template topLeftCorner()), mat11); + VERIFY_IS_EQUAL((m_fixed.template topRightCorner()), mat12); + VERIFY_IS_EQUAL((m_fixed.template bottomLeftCorner()), mat21); + VERIFY_IS_EQUAL((m_fixed.template bottomRightCorner()), mat22); + VERIFY_IS_EQUAL((m_fixed << mat12, mat11, matx21, mat22).finished(), (m_dynamic << mat12, matx11, matx21, mat22).finished()); + } + + if(N1 > 0) + { + VERIFY_RAISES_ASSERT((m_fixed << mat11, mat12, mat11, mat21, mat22)); + VERIFY_RAISES_ASSERT((m_fixed << mat11, mat12, mat21, mat21, mat22)); + } + else + { + // allow insertion of zero-column blocks: + VERIFY_IS_EQUAL((m_fixed << mat11, mat12, mat11, mat11, mat21, mat21, mat22).finished(), (m_dynamic << mat12, mat22).finished()); + } + if(M1 != M2) + { + VERIFY_RAISES_ASSERT((m_fixed << mat11, mat21, mat12, mat22)); + } +} + + +template +struct test_block_recursion +{ + static void run() + { + test_blocks<(N>>6)&3, (N>>4)&3, (N>>2)&3, N & 3>(); + test_block_recursion::run(); + } +}; + +template<> +struct test_block_recursion<-1> +{ + static void run() { } +}; + void test_commainitializer() { Matrix3d m3; @@ -43,4 +99,8 @@ void test_commainitializer() 4, 5, 6, vec[2].transpose(); VERIFY_IS_APPROX(m3, ref); + + + // recursively test all block-sizes from 0 to 3: + test_block_recursion<(1<<8) - 1>(); } diff --git a/testbed/nanogui/ext/eigen/test/conjugate_gradient.cpp b/testbed/nanogui/ext/eigen/test/conjugate_gradient.cpp index 869051b3..9622fd86 100644 --- a/testbed/nanogui/ext/eigen/test/conjugate_gradient.cpp +++ b/testbed/nanogui/ext/eigen/test/conjugate_gradient.cpp @@ -10,21 +10,25 @@ #include "sparse_solver.h" #include -template void test_conjugate_gradient_T() +template void test_conjugate_gradient_T() { - ConjugateGradient, Lower> cg_colmajor_lower_diag; - ConjugateGradient, Upper> cg_colmajor_upper_diag; - ConjugateGradient, Lower, IdentityPreconditioner> cg_colmajor_lower_I; - ConjugateGradient, Upper, IdentityPreconditioner> cg_colmajor_upper_I; + typedef SparseMatrix SparseMatrixType; + ConjugateGradient cg_colmajor_lower_diag; + ConjugateGradient cg_colmajor_upper_diag; + ConjugateGradient cg_colmajor_loup_diag; + ConjugateGradient cg_colmajor_lower_I; + ConjugateGradient cg_colmajor_upper_I; CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_lower_diag) ); CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_upper_diag) ); + CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_loup_diag) ); CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_lower_I) ); CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_upper_I) ); } void test_conjugate_gradient() { - CALL_SUBTEST_1(test_conjugate_gradient_T()); - CALL_SUBTEST_2(test_conjugate_gradient_T >()); + CALL_SUBTEST_1(( test_conjugate_gradient_T() )); + CALL_SUBTEST_2(( test_conjugate_gradient_T, int>() )); + CALL_SUBTEST_3(( test_conjugate_gradient_T() )); } diff --git a/testbed/nanogui/ext/eigen/test/constructor.cpp b/testbed/nanogui/ext/eigen/test/constructor.cpp new file mode 100644 index 00000000..eec9e219 --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/constructor.cpp @@ -0,0 +1,84 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2017 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + + +#define TEST_ENABLE_TEMPORARY_TRACKING + +#include "main.h" + +template struct Wrapper +{ + MatrixType m_mat; + inline Wrapper(const MatrixType &x) : m_mat(x) {} + inline operator const MatrixType& () const { return m_mat; } + inline operator MatrixType& () { return m_mat; } +}; + +template void ctor_init1(const MatrixType& m) +{ + // Check logic in PlainObjectBase::_init1 + Index rows = m.rows(); + Index cols = m.cols(); + + MatrixType m0 = MatrixType::Random(rows,cols); + + VERIFY_EVALUATION_COUNT( MatrixType m1(m0), 1); + VERIFY_EVALUATION_COUNT( MatrixType m2(m0+m0), 1); + VERIFY_EVALUATION_COUNT( MatrixType m2(m0.block(0,0,rows,cols)) , 1); + + Wrapper wrapper(m0); + VERIFY_EVALUATION_COUNT( MatrixType m3(wrapper) , 1); +} + + +void test_constructor() +{ + for(int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_1( ctor_init1(Matrix()) ); + CALL_SUBTEST_1( ctor_init1(Matrix4d()) ); + CALL_SUBTEST_1( ctor_init1(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_1( ctor_init1(MatrixXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + } + { + Matrix a(123); + VERIFY_IS_EQUAL(a[0], 123); + } + { + Matrix a(123.0); + VERIFY_IS_EQUAL(a[0], 123); + } + { + Matrix a(123); + VERIFY_IS_EQUAL(a[0], 123.f); + } + { + Array a(123); + VERIFY_IS_EQUAL(a[0], 123); + } + { + Array a(123.0); + VERIFY_IS_EQUAL(a[0], 123); + } + { + Array a(123); + VERIFY_IS_EQUAL(a[0], 123.f); + } + { + Array a(123); + VERIFY_IS_EQUAL(a(4), 123); + } + { + Array a(123.0); + VERIFY_IS_EQUAL(a(4), 123); + } + { + Array a(123); + VERIFY_IS_EQUAL(a(4), 123.f); + } +} diff --git a/testbed/nanogui/ext/eigen/test/ctorleak.cpp b/testbed/nanogui/ext/eigen/test/ctorleak.cpp new file mode 100644 index 00000000..c158f5e4 --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/ctorleak.cpp @@ -0,0 +1,69 @@ +#include "main.h" + +#include // std::exception + +struct Foo +{ + static Index object_count; + static Index object_limit; + int dummy; + + Foo() + { +#ifdef EIGEN_EXCEPTIONS + // TODO: Is this the correct way to handle this? + if (Foo::object_count > Foo::object_limit) { std::cout << "\nThrow!\n"; throw Foo::Fail(); } +#endif + std::cout << '+'; + ++Foo::object_count; + } + + ~Foo() + { + std::cout << '-'; + --Foo::object_count; + } + + class Fail : public std::exception {}; +}; + +Index Foo::object_count = 0; +Index Foo::object_limit = 0; + +#undef EIGEN_TEST_MAX_SIZE +#define EIGEN_TEST_MAX_SIZE 3 + +void test_ctorleak() +{ + typedef Matrix MatrixX; + typedef Matrix VectorX; + Foo::object_count = 0; + for(int i = 0; i < g_repeat; i++) { + Index rows = internal::random(2,EIGEN_TEST_MAX_SIZE), cols = internal::random(2,EIGEN_TEST_MAX_SIZE); + Foo::object_limit = internal::random(0, rows*cols - 2); + std::cout << "object_limit =" << Foo::object_limit << std::endl; +#ifdef EIGEN_EXCEPTIONS + try + { +#endif + std::cout << "\nMatrixX m(" << rows << ", " << cols << ");\n"; + MatrixX m(rows, cols); +#ifdef EIGEN_EXCEPTIONS + VERIFY(false); // not reached if exceptions are enabled + } + catch (const Foo::Fail&) { /* ignore */ } +#endif + VERIFY_IS_EQUAL(Index(0), Foo::object_count); + + { + Foo::object_limit = (rows+1)*(cols+1); + MatrixX A(rows, cols); + VERIFY_IS_EQUAL(Foo::object_count, rows*cols); + VectorX v=A.row(0); + VERIFY_IS_EQUAL(Foo::object_count, (rows+1)*cols); + v = A.col(0); + VERIFY_IS_EQUAL(Foo::object_count, rows*(cols+1)); + } + VERIFY_IS_EQUAL(Index(0), Foo::object_count); + } +} diff --git a/testbed/nanogui/ext/eigen/test/cuda_basic.cu b/testbed/nanogui/ext/eigen/test/cuda_basic.cu new file mode 100644 index 00000000..cb2e4167 --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/cuda_basic.cu @@ -0,0 +1,173 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015-2016 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +// workaround issue between gcc >= 4.7 and cuda 5.5 +#if (defined __GNUC__) && (__GNUC__>4 || __GNUC_MINOR__>=7) + #undef _GLIBCXX_ATOMIC_BUILTINS + #undef _GLIBCXX_USE_INT128 +#endif + +#define EIGEN_TEST_NO_LONGDOUBLE +#define EIGEN_TEST_NO_COMPLEX +#define EIGEN_TEST_FUNC cuda_basic +#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int + +#include +#include +#if defined __CUDACC_VER__ && __CUDACC_VER__ >= 70500 +#include +#endif +#include "main.h" +#include "cuda_common.h" + +// Check that dense modules can be properly parsed by nvcc +#include + +// struct Foo{ +// EIGEN_DEVICE_FUNC +// void operator()(int i, const float* mats, float* vecs) const { +// using namespace Eigen; +// // Matrix3f M(data); +// // Vector3f x(data+9); +// // Map(data+9) = M.inverse() * x; +// Matrix3f M(mats+i/16); +// Vector3f x(vecs+i*3); +// // using std::min; +// // using std::sqrt; +// Map(vecs+i*3) << x.minCoeff(), 1, 2;// / x.dot(x);//(M.inverse() * x) / x.x(); +// //x = x*2 + x.y() * x + x * x.maxCoeff() - x / x.sum(); +// } +// }; + +template +struct coeff_wise { + EIGEN_DEVICE_FUNC + void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const + { + using namespace Eigen; + T x1(in+i); + T x2(in+i+1); + T x3(in+i+2); + Map res(out+i*T::MaxSizeAtCompileTime); + + res.array() += (in[0] * x1 + x2).array() * x3.array(); + } +}; + +template +struct replicate { + EIGEN_DEVICE_FUNC + void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const + { + using namespace Eigen; + T x1(in+i); + int step = x1.size() * 4; + int stride = 3 * step; + + typedef Map > MapType; + MapType(out+i*stride+0*step, x1.rows()*2, x1.cols()*2) = x1.replicate(2,2); + MapType(out+i*stride+1*step, x1.rows()*3, x1.cols()) = in[i] * x1.colwise().replicate(3); + MapType(out+i*stride+2*step, x1.rows(), x1.cols()*3) = in[i] * x1.rowwise().replicate(3); + } +}; + +template +struct redux { + EIGEN_DEVICE_FUNC + void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const + { + using namespace Eigen; + int N = 10; + T x1(in+i); + out[i*N+0] = x1.minCoeff(); + out[i*N+1] = x1.maxCoeff(); + out[i*N+2] = x1.sum(); + out[i*N+3] = x1.prod(); + out[i*N+4] = x1.matrix().squaredNorm(); + out[i*N+5] = x1.matrix().norm(); + out[i*N+6] = x1.colwise().sum().maxCoeff(); + out[i*N+7] = x1.rowwise().maxCoeff().sum(); + out[i*N+8] = x1.matrix().colwise().squaredNorm().sum(); + } +}; + +template +struct prod_test { + EIGEN_DEVICE_FUNC + void operator()(int i, const typename T1::Scalar* in, typename T1::Scalar* out) const + { + using namespace Eigen; + typedef Matrix T3; + T1 x1(in+i); + T2 x2(in+i+1); + Map res(out+i*T3::MaxSizeAtCompileTime); + res += in[i] * x1 * x2; + } +}; + +template +struct diagonal { + EIGEN_DEVICE_FUNC + void operator()(int i, const typename T1::Scalar* in, typename T1::Scalar* out) const + { + using namespace Eigen; + T1 x1(in+i); + Map res(out+i*T2::MaxSizeAtCompileTime); + res += x1.diagonal(); + } +}; + +template +struct eigenvalues { + EIGEN_DEVICE_FUNC + void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const + { + using namespace Eigen; + typedef Matrix Vec; + T M(in+i); + Map res(out+i*Vec::MaxSizeAtCompileTime); + T A = M*M.adjoint(); + SelfAdjointEigenSolver eig; + eig.computeDirect(M); + res = eig.eigenvalues(); + } +}; + +void test_cuda_basic() +{ + ei_test_init_cuda(); + + int nthreads = 100; + Eigen::VectorXf in, out; + + #ifndef __CUDA_ARCH__ + int data_size = nthreads * 512; + in.setRandom(data_size); + out.setRandom(data_size); + #endif + + CALL_SUBTEST( run_and_compare_to_cuda(coeff_wise(), nthreads, in, out) ); + CALL_SUBTEST( run_and_compare_to_cuda(coeff_wise(), nthreads, in, out) ); + + CALL_SUBTEST( run_and_compare_to_cuda(replicate(), nthreads, in, out) ); + CALL_SUBTEST( run_and_compare_to_cuda(replicate(), nthreads, in, out) ); + + CALL_SUBTEST( run_and_compare_to_cuda(redux(), nthreads, in, out) ); + CALL_SUBTEST( run_and_compare_to_cuda(redux(), nthreads, in, out) ); + + CALL_SUBTEST( run_and_compare_to_cuda(prod_test(), nthreads, in, out) ); + CALL_SUBTEST( run_and_compare_to_cuda(prod_test(), nthreads, in, out) ); + + CALL_SUBTEST( run_and_compare_to_cuda(diagonal(), nthreads, in, out) ); + CALL_SUBTEST( run_and_compare_to_cuda(diagonal(), nthreads, in, out) ); + + CALL_SUBTEST( run_and_compare_to_cuda(eigenvalues(), nthreads, in, out) ); + CALL_SUBTEST( run_and_compare_to_cuda(eigenvalues(), nthreads, in, out) ); + +} diff --git a/testbed/nanogui/ext/eigen/test/cuda_common.h b/testbed/nanogui/ext/eigen/test/cuda_common.h new file mode 100644 index 00000000..9737693a --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/cuda_common.h @@ -0,0 +1,101 @@ + +#ifndef EIGEN_TEST_CUDA_COMMON_H +#define EIGEN_TEST_CUDA_COMMON_H + +#include +#include +#include +#include + +#ifndef __CUDACC__ +dim3 threadIdx, blockDim, blockIdx; +#endif + +template +void run_on_cpu(const Kernel& ker, int n, const Input& in, Output& out) +{ + for(int i=0; i +__global__ +void run_on_cuda_meta_kernel(const Kernel ker, int n, const Input* in, Output* out) +{ + int i = threadIdx.x + blockIdx.x*blockDim.x; + if(i +void run_on_cuda(const Kernel& ker, int n, const Input& in, Output& out) +{ + typename Input::Scalar* d_in; + typename Output::Scalar* d_out; + std::ptrdiff_t in_bytes = in.size() * sizeof(typename Input::Scalar); + std::ptrdiff_t out_bytes = out.size() * sizeof(typename Output::Scalar); + + cudaMalloc((void**)(&d_in), in_bytes); + cudaMalloc((void**)(&d_out), out_bytes); + + cudaMemcpy(d_in, in.data(), in_bytes, cudaMemcpyHostToDevice); + cudaMemcpy(d_out, out.data(), out_bytes, cudaMemcpyHostToDevice); + + // Simple and non-optimal 1D mapping assuming n is not too large + // That's only for unit testing! + dim3 Blocks(128); + dim3 Grids( (n+int(Blocks.x)-1)/int(Blocks.x) ); + + cudaThreadSynchronize(); + run_on_cuda_meta_kernel<<>>(ker, n, d_in, d_out); + cudaThreadSynchronize(); + + // check inputs have not been modified + cudaMemcpy(const_cast(in.data()), d_in, in_bytes, cudaMemcpyDeviceToHost); + cudaMemcpy(out.data(), d_out, out_bytes, cudaMemcpyDeviceToHost); + + cudaFree(d_in); + cudaFree(d_out); +} + + +template +void run_and_compare_to_cuda(const Kernel& ker, int n, const Input& in, Output& out) +{ + Input in_ref, in_cuda; + Output out_ref, out_cuda; + #ifndef __CUDA_ARCH__ + in_ref = in_cuda = in; + out_ref = out_cuda = out; + #endif + run_on_cpu (ker, n, in_ref, out_ref); + run_on_cuda(ker, n, in_cuda, out_cuda); + #ifndef __CUDA_ARCH__ + VERIFY_IS_APPROX(in_ref, in_cuda); + VERIFY_IS_APPROX(out_ref, out_cuda); + #endif +} + + +void ei_test_init_cuda() +{ + int device = 0; + cudaDeviceProp deviceProp; + cudaGetDeviceProperties(&deviceProp, device); + std::cout << "CUDA device info:\n"; + std::cout << " name: " << deviceProp.name << "\n"; + std::cout << " capability: " << deviceProp.major << "." << deviceProp.minor << "\n"; + std::cout << " multiProcessorCount: " << deviceProp.multiProcessorCount << "\n"; + std::cout << " maxThreadsPerMultiProcessor: " << deviceProp.maxThreadsPerMultiProcessor << "\n"; + std::cout << " warpSize: " << deviceProp.warpSize << "\n"; + std::cout << " regsPerBlock: " << deviceProp.regsPerBlock << "\n"; + std::cout << " concurrentKernels: " << deviceProp.concurrentKernels << "\n"; + std::cout << " clockRate: " << deviceProp.clockRate << "\n"; + std::cout << " canMapHostMemory: " << deviceProp.canMapHostMemory << "\n"; + std::cout << " computeMode: " << deviceProp.computeMode << "\n"; +} + +#endif // EIGEN_TEST_CUDA_COMMON_H diff --git a/testbed/nanogui/ext/eigen/test/cwiseop.cpp b/testbed/nanogui/ext/eigen/test/cwiseop.cpp deleted file mode 100644 index e3361da1..00000000 --- a/testbed/nanogui/ext/eigen/test/cwiseop.cpp +++ /dev/null @@ -1,184 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008 Gael Guennebaud -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#define EIGEN2_SUPPORT -#define EIGEN_NO_EIGEN2_DEPRECATED_WARNING - -#define EIGEN_NO_STATIC_ASSERT -#include "main.h" -#include - -#ifdef min -#undef min -#endif - -#ifdef max -#undef max -#endif - -using namespace std; - -template struct AddIfNull { - const Scalar operator() (const Scalar a, const Scalar b) const {return a<=1e-3 ? b : a;} - enum { Cost = NumTraits::AddCost }; -}; - -template -typename Eigen::internal::enable_if::IsInteger,typename MatrixType::Scalar>::type -cwiseops_real_only(MatrixType& m1, MatrixType& m2, MatrixType& m3, MatrixType& mones) -{ - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - - VERIFY_IS_APPROX(m1.cwise() / m2, m1.cwise() * (m2.cwise().inverse())); - m3 = m1.cwise().abs().cwise().sqrt(); - VERIFY_IS_APPROX(m3.cwise().square(), m1.cwise().abs()); - VERIFY_IS_APPROX(m1.cwise().square().cwise().sqrt(), m1.cwise().abs()); - VERIFY_IS_APPROX(m1.cwise().abs().cwise().log().cwise().exp() , m1.cwise().abs()); - - VERIFY_IS_APPROX(m1.cwise().pow(2), m1.cwise().square()); - m3 = (m1.cwise().abs().cwise()<=RealScalar(0.01)).select(mones,m1); - VERIFY_IS_APPROX(m3.cwise().pow(-1), m3.cwise().inverse()); - m3 = m1.cwise().abs(); - VERIFY_IS_APPROX(m3.cwise().pow(RealScalar(0.5)), m3.cwise().sqrt()); - -// VERIFY_IS_APPROX(m1.cwise().tan(), m1.cwise().sin().cwise() / m1.cwise().cos()); - VERIFY_IS_APPROX(mones, m1.cwise().sin().cwise().square() + m1.cwise().cos().cwise().square()); - m3 = m1; - m3.cwise() /= m2; - VERIFY_IS_APPROX(m3, m1.cwise() / m2); - - return Scalar(0); -} - -template -typename Eigen::internal::enable_if::IsInteger,typename MatrixType::Scalar>::type -cwiseops_real_only(MatrixType& , MatrixType& , MatrixType& , MatrixType& ) -{ - return 0; -} - -template void cwiseops(const MatrixType& m) -{ - typedef typename MatrixType::Index Index; - typedef typename MatrixType::Scalar Scalar; - typedef Matrix VectorType; - - Index rows = m.rows(); - Index cols = m.cols(); - - MatrixType m1 = MatrixType::Random(rows, cols), - m1bis = m1, - m2 = MatrixType::Random(rows, cols), - m3(rows, cols), - m4(rows, cols), - mzero = MatrixType::Zero(rows, cols), - mones = MatrixType::Ones(rows, cols), - identity = Matrix - ::Identity(rows, rows); - VectorType vzero = VectorType::Zero(rows), - vones = VectorType::Ones(rows), - v3(rows); - - Index r = internal::random(0, rows-1), - c = internal::random(0, cols-1); - - Scalar s1 = internal::random(); - - // test Zero, Ones, Constant, and the set* variants - m3 = MatrixType::Constant(rows, cols, s1); - for (int j=0; j >(mones); - - VERIFY_IS_APPROX(m1.cwise().pow(2), m1.cwise().abs2()); - VERIFY_IS_APPROX(m1.cwise().pow(2), m1.cwise().square()); - VERIFY_IS_APPROX(m1.cwise().pow(3), m1.cwise().cube()); - - VERIFY_IS_APPROX(m1 + mones, m1.cwise()+Scalar(1)); - VERIFY_IS_APPROX(m1 - mones, m1.cwise()-Scalar(1)); - m3 = m1; m3.cwise() += 1; - VERIFY_IS_APPROX(m1 + mones, m3); - m3 = m1; m3.cwise() -= 1; - VERIFY_IS_APPROX(m1 - mones, m3); - - VERIFY_IS_APPROX(m2, m2.cwise() * mones); - VERIFY_IS_APPROX(m1.cwise() * m2, m2.cwise() * m1); - m3 = m1; - m3.cwise() *= m2; - VERIFY_IS_APPROX(m3, m1.cwise() * m2); - - VERIFY_IS_APPROX(mones, m2.cwise()/m2); - - // check min - VERIFY_IS_APPROX( m1.cwise().min(m2), m2.cwise().min(m1) ); - VERIFY_IS_APPROX( m1.cwise().min(m1+mones), m1 ); - VERIFY_IS_APPROX( m1.cwise().min(m1-mones), m1-mones ); - - // check max - VERIFY_IS_APPROX( m1.cwise().max(m2), m2.cwise().max(m1) ); - VERIFY_IS_APPROX( m1.cwise().max(m1-mones), m1 ); - VERIFY_IS_APPROX( m1.cwise().max(m1+mones), m1+mones ); - - VERIFY( (m1.cwise() == m1).all() ); - VERIFY( (m1.cwise() != m2).any() ); - VERIFY(!(m1.cwise() == (m1+mones)).any() ); - if (rows*cols>1) - { - m3 = m1; - m3(r,c) += 1; - VERIFY( (m1.cwise() == m3).any() ); - VERIFY( !(m1.cwise() == m3).all() ); - } - VERIFY( (m1.cwise().min(m2).cwise() <= m2).all() ); - VERIFY( (m1.cwise().max(m2).cwise() >= m2).all() ); - VERIFY( (m1.cwise().min(m2).cwise() < (m1+mones)).all() ); - VERIFY( (m1.cwise().max(m2).cwise() > (m1-mones)).all() ); - - VERIFY( (m1.cwise()(), Scalar(1)))).all() ); - VERIFY( !(m1.cwise()(), Scalar(1)))).all() ); - VERIFY( !(m1.cwise()>m1bis.unaryExpr(bind2nd(plus(), Scalar(1)))).any() ); - - cwiseops_real_only(m1, m2, m3, mones); -} - -void test_cwiseop() -{ - for(int i = 0; i < g_repeat ; i++) { - CALL_SUBTEST_1( cwiseops(Matrix()) ); - CALL_SUBTEST_2( cwiseops(Matrix4d()) ); - CALL_SUBTEST_3( cwiseops(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); - CALL_SUBTEST_4( cwiseops(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); - CALL_SUBTEST_5( cwiseops(MatrixXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); - CALL_SUBTEST_6( cwiseops(MatrixXd(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/dense_storage.cpp b/testbed/nanogui/ext/eigen/test/dense_storage.cpp new file mode 100644 index 00000000..e63712b1 --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/dense_storage.cpp @@ -0,0 +1,76 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2013 Hauke Heibel +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "main.h" + +#include + +template +void dense_storage_copy() +{ + static const int Size = ((Rows==Dynamic || Cols==Dynamic) ? Dynamic : Rows*Cols); + typedef DenseStorage DenseStorageType; + + const int rows = (Rows==Dynamic) ? 4 : Rows; + const int cols = (Cols==Dynamic) ? 3 : Cols; + const int size = rows*cols; + DenseStorageType reference(size, rows, cols); + T* raw_reference = reference.data(); + for (int i=0; i(i); + + DenseStorageType copied_reference(reference); + const T* raw_copied_reference = copied_reference.data(); + for (int i=0; i +void dense_storage_assignment() +{ + static const int Size = ((Rows==Dynamic || Cols==Dynamic) ? Dynamic : Rows*Cols); + typedef DenseStorage DenseStorageType; + + const int rows = (Rows==Dynamic) ? 4 : Rows; + const int cols = (Cols==Dynamic) ? 3 : Cols; + const int size = rows*cols; + DenseStorageType reference(size, rows, cols); + T* raw_reference = reference.data(); + for (int i=0; i(i); + + DenseStorageType copied_reference; + copied_reference = reference; + const T* raw_copied_reference = copied_reference.data(); + for (int i=0; i(); + dense_storage_copy(); + dense_storage_copy(); + dense_storage_copy(); + + dense_storage_copy(); + dense_storage_copy(); + dense_storage_copy(); + dense_storage_copy(); + + dense_storage_assignment(); + dense_storage_assignment(); + dense_storage_assignment(); + dense_storage_assignment(); + + dense_storage_assignment(); + dense_storage_assignment(); + dense_storage_assignment(); + dense_storage_assignment(); +} diff --git a/testbed/nanogui/ext/eigen/test/diagonal.cpp b/testbed/nanogui/ext/eigen/test/diagonal.cpp index 53814a58..c1546e97 100644 --- a/testbed/nanogui/ext/eigen/test/diagonal.cpp +++ b/testbed/nanogui/ext/eigen/test/diagonal.cpp @@ -20,6 +20,8 @@ template void diagonal(const MatrixType& m) MatrixType m1 = MatrixType::Random(rows, cols), m2 = MatrixType::Random(rows, cols); + Scalar s1 = internal::random(); + //check diagonal() VERIFY_IS_APPROX(m1.diagonal(), m1.transpose().diagonal()); m2.diagonal() = 2 * m1.diagonal(); @@ -58,6 +60,26 @@ template void diagonal(const MatrixType& m) VERIFY_IS_APPROX(m2.template diagonal(), static_cast(2) * m1.diagonal(N2)); m2.diagonal(N2)[0] *= 3; VERIFY_IS_APPROX(m2.diagonal(N2)[0], static_cast(6) * m1.diagonal(N2)[0]); + + m2.diagonal(N2).x() = s1; + VERIFY_IS_APPROX(m2.diagonal(N2).x(), s1); + m2.diagonal(N2).coeffRef(0) = Scalar(2)*s1; + VERIFY_IS_APPROX(m2.diagonal(N2).coeff(0), Scalar(2)*s1); + } +} + +template void diagonal_assert(const MatrixType& m) { + Index rows = m.rows(); + Index cols = m.cols(); + + MatrixType m1 = MatrixType::Random(rows, cols); + + if (rows>=2 && cols>=2) + { + VERIFY_RAISES_ASSERT( m1 += m1.diagonal() ); + VERIFY_RAISES_ASSERT( m1 -= m1.diagonal() ); + VERIFY_RAISES_ASSERT( m1.array() *= m1.diagonal().array() ); + VERIFY_RAISES_ASSERT( m1.array() /= m1.diagonal().array() ); } } @@ -74,4 +96,6 @@ void test_diagonal() CALL_SUBTEST_1( diagonal(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); CALL_SUBTEST_1( diagonal(Matrix(3, 4)) ); } + + CALL_SUBTEST_1( diagonal_assert(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } diff --git a/testbed/nanogui/ext/eigen/test/diagonalmatrices.cpp b/testbed/nanogui/ext/eigen/test/diagonalmatrices.cpp index 149f1db2..cd6dc8cf 100644 --- a/testbed/nanogui/ext/eigen/test/diagonalmatrices.cpp +++ b/testbed/nanogui/ext/eigen/test/diagonalmatrices.cpp @@ -17,6 +17,7 @@ template void diagonalmatrices(const MatrixType& m) typedef Matrix VectorType; typedef Matrix RowVectorType; typedef Matrix SquareMatrixType; + typedef Matrix DynMatrixType; typedef DiagonalMatrix LeftDiagonalMatrix; typedef DiagonalMatrix RightDiagonalMatrix; typedef Matrix BigMatrix; @@ -64,6 +65,13 @@ template void diagonalmatrices(const MatrixType& m) VERIFY_IS_APPROX( (((v1+v2).asDiagonal() * (m1+m2))(i,j)) , (v1+v2)(i) * (m1+m2)(i,j) ); VERIFY_IS_APPROX( ((m1 * (rv1+rv2).asDiagonal())(i,j)) , (rv1+rv2)(j) * m1(i,j) ); VERIFY_IS_APPROX( (((m1+m2) * (rv1+rv2).asDiagonal())(i,j)) , (rv1+rv2)(j) * (m1+m2)(i,j) ); + + if(rows>1) + { + DynMatrixType tmp = m1.topRows(rows/2), res; + VERIFY_IS_APPROX( (res = m1.topRows(rows/2) * rv1.asDiagonal()), tmp * rv1.asDiagonal() ); + VERIFY_IS_APPROX( (res = v1.head(rows/2).asDiagonal()*m1.topRows(rows/2)), v1.head(rows/2).asDiagonal()*tmp ); + } BigMatrix big; big.setZero(2*rows, 2*cols); @@ -84,6 +92,24 @@ template void diagonalmatrices(const MatrixType& m) VERIFY_IS_APPROX(m1 * (rdm1 * s1), (m1 * rdm1) * s1); VERIFY_IS_APPROX(m1 * (s1 * rdm1), (m1 * rdm1) * s1); + + // Diagonal to dense + sq_m1.setRandom(); + sq_m2 = sq_m1; + VERIFY_IS_APPROX( (sq_m1 += (s1*v1).asDiagonal()), sq_m2 += (s1*v1).asDiagonal().toDenseMatrix() ); + VERIFY_IS_APPROX( (sq_m1 -= (s1*v1).asDiagonal()), sq_m2 -= (s1*v1).asDiagonal().toDenseMatrix() ); + VERIFY_IS_APPROX( (sq_m1 = (s1*v1).asDiagonal()), (s1*v1).asDiagonal().toDenseMatrix() ); +} + +template +void bug987() +{ + Matrix3Xd points = Matrix3Xd::Random(3, 3); + Vector2d diag = Vector2d::Random(); + Matrix2Xd tmp1 = points.topRows<2>(), res1, res2; + VERIFY_IS_APPROX( res1 = diag.asDiagonal() * points.topRows<2>(), res2 = diag.asDiagonal() * tmp1 ); + Matrix2d tmp2 = points.topLeftCorner<2,2>(); + VERIFY_IS_APPROX(( res1 = points.topLeftCorner<2,2>()*diag.asDiagonal()) , res2 = tmp2*diag.asDiagonal() ); } void test_diagonalmatrices() @@ -99,4 +125,5 @@ void test_diagonalmatrices() CALL_SUBTEST_8( diagonalmatrices(Matrix(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); CALL_SUBTEST_9( diagonalmatrices(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } + CALL_SUBTEST_10( bug987<0>() ); } diff --git a/testbed/nanogui/ext/eigen/test/dynalloc.cpp b/testbed/nanogui/ext/eigen/test/dynalloc.cpp index 7e41bfa9..f1cc70be 100644 --- a/testbed/nanogui/ext/eigen/test/dynalloc.cpp +++ b/testbed/nanogui/ext/eigen/test/dynalloc.cpp @@ -9,18 +9,20 @@ #include "main.h" -#if EIGEN_ALIGN -#define ALIGNMENT 16 +#if EIGEN_MAX_ALIGN_BYTES>0 +#define ALIGNMENT EIGEN_MAX_ALIGN_BYTES #else #define ALIGNMENT 1 #endif +typedef Matrix Vector8f; + void check_handmade_aligned_malloc() { for(int i = 1; i < 1000; i++) { char *p = (char*)internal::handmade_aligned_malloc(i); - VERIFY(size_t(p)%ALIGNMENT==0); + VERIFY(internal::UIntPtr(p)%ALIGNMENT==0); // if the buffer is wrongly allocated this will give a bad write --> check with valgrind for(int j = 0; j < i; j++) p[j]=0; internal::handmade_aligned_free(p); @@ -29,10 +31,10 @@ void check_handmade_aligned_malloc() void check_aligned_malloc() { - for(int i = 1; i < 1000; i++) + for(int i = ALIGNMENT; i < 1000; i++) { char *p = (char*)internal::aligned_malloc(i); - VERIFY(size_t(p)%ALIGNMENT==0); + VERIFY(internal::UIntPtr(p)%ALIGNMENT==0); // if the buffer is wrongly allocated this will give a bad write --> check with valgrind for(int j = 0; j < i; j++) p[j]=0; internal::aligned_free(p); @@ -41,10 +43,10 @@ void check_aligned_malloc() void check_aligned_new() { - for(int i = 1; i < 1000; i++) + for(int i = ALIGNMENT; i < 1000; i++) { float *p = internal::aligned_new(i); - VERIFY(size_t(p)%ALIGNMENT==0); + VERIFY(internal::UIntPtr(p)%ALIGNMENT==0); // if the buffer is wrongly allocated this will give a bad write --> check with valgrind for(int j = 0; j < i; j++) p[j]=0; internal::aligned_delete(p,i); @@ -53,10 +55,10 @@ void check_aligned_new() void check_aligned_stack_alloc() { - for(int i = 1; i < 400; i++) + for(int i = ALIGNMENT; i < 400; i++) { ei_declare_aligned_stack_constructed_variable(float,p,i,0); - VERIFY(size_t(p)%ALIGNMENT==0); + VERIFY(internal::UIntPtr(p)%ALIGNMENT==0); // if the buffer is wrongly allocated this will give a bad write --> check with valgrind for(int j = 0; j < i; j++) p[j]=0; } @@ -68,7 +70,7 @@ struct MyStruct { EIGEN_MAKE_ALIGNED_OPERATOR_NEW char dummychar; - Vector4f avec; + Vector8f avec; }; class MyClassA @@ -76,15 +78,45 @@ class MyClassA public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW char dummychar; - Vector4f avec; + Vector8f avec; }; template void check_dynaligned() { - T* obj = new T; - VERIFY(T::NeedsToAlign==1); - VERIFY(size_t(obj)%ALIGNMENT==0); - delete obj; + // TODO have to be updated once we support multiple alignment values + if(T::SizeAtCompileTime % ALIGNMENT == 0) + { + T* obj = new T; + VERIFY(T::NeedsToAlign==1); + VERIFY(internal::UIntPtr(obj)%ALIGNMENT==0); + delete obj; + } +} + +template void check_custom_new_delete() +{ + { + T* t = new T; + delete t; + } + + { + std::size_t N = internal::random(1,10); + T* t = new T[N]; + delete[] t; + } + +#if EIGEN_MAX_ALIGN_BYTES>0 + { + T* t = static_cast((T::operator new)(sizeof(T))); + (T::operator delete)(t, sizeof(T)); + } + + { + T* t = static_cast((T::operator new)(sizeof(T))); + (T::operator delete)(t); + } +#endif } void test_dynalloc() @@ -95,6 +127,16 @@ void test_dynalloc() CALL_SUBTEST(check_aligned_new()); CALL_SUBTEST(check_aligned_stack_alloc()); + for (int i=0; i() ); + CALL_SUBTEST( check_custom_new_delete() ); + CALL_SUBTEST( check_custom_new_delete() ); + CALL_SUBTEST( check_custom_new_delete() ); + } + + // check static allocation, who knows ? + #if EIGEN_MAX_STATIC_ALIGN_BYTES for (int i=0; i() ); @@ -102,20 +144,19 @@ void test_dynalloc() CALL_SUBTEST(check_dynaligned() ); CALL_SUBTEST(check_dynaligned() ); CALL_SUBTEST(check_dynaligned() ); + CALL_SUBTEST(check_dynaligned() ); } - - // check static allocation, who knows ? - #if EIGEN_ALIGN_STATICALLY + { - MyStruct foo0; VERIFY(size_t(foo0.avec.data())%ALIGNMENT==0); - MyClassA fooA; VERIFY(size_t(fooA.avec.data())%ALIGNMENT==0); + MyStruct foo0; VERIFY(internal::UIntPtr(foo0.avec.data())%ALIGNMENT==0); + MyClassA fooA; VERIFY(internal::UIntPtr(fooA.avec.data())%ALIGNMENT==0); } // dynamic allocation, single object for (int i=0; iavec.data())%ALIGNMENT==0); - MyClassA *fooA = new MyClassA(); VERIFY(size_t(fooA->avec.data())%ALIGNMENT==0); + MyStruct *foo0 = new MyStruct(); VERIFY(internal::UIntPtr(foo0->avec.data())%ALIGNMENT==0); + MyClassA *fooA = new MyClassA(); VERIFY(internal::UIntPtr(fooA->avec.data())%ALIGNMENT==0); delete foo0; delete fooA; } @@ -124,8 +165,8 @@ void test_dynalloc() const int N = 10; for (int i=0; iavec.data())%ALIGNMENT==0); - MyClassA *fooA = new MyClassA[N]; VERIFY(size_t(fooA->avec.data())%ALIGNMENT==0); + MyStruct *foo0 = new MyStruct[N]; VERIFY(internal::UIntPtr(foo0->avec.data())%ALIGNMENT==0); + MyClassA *fooA = new MyClassA[N]; VERIFY(internal::UIntPtr(fooA->avec.data())%ALIGNMENT==0); delete[] foo0; delete[] fooA; } diff --git a/testbed/nanogui/ext/eigen/test/eigen2/CMakeLists.txt b/testbed/nanogui/ext/eigen/test/eigen2/CMakeLists.txt deleted file mode 100644 index 9615a602..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/CMakeLists.txt +++ /dev/null @@ -1,61 +0,0 @@ -add_custom_target(eigen2_buildtests) -add_custom_target(eigen2_check COMMAND "ctest -R eigen2") -add_dependencies(eigen2_check eigen2_buildtests) -add_dependencies(buildtests eigen2_buildtests) - -add_definitions("-DEIGEN2_SUPPORT_STAGE10_FULL_EIGEN2_API") -add_definitions("-DEIGEN_NO_EIGEN2_DEPRECATED_WARNING") - -ei_add_test(eigen2_meta) -ei_add_test(eigen2_sizeof) -ei_add_test(eigen2_dynalloc) -ei_add_test(eigen2_nomalloc) -#ei_add_test(eigen2_first_aligned) -ei_add_test(eigen2_mixingtypes) -#ei_add_test(eigen2_packetmath) -ei_add_test(eigen2_unalignedassert) -#ei_add_test(eigen2_vectorization_logic) -ei_add_test(eigen2_basicstuff) -ei_add_test(eigen2_linearstructure) -ei_add_test(eigen2_cwiseop) -ei_add_test(eigen2_sum) -ei_add_test(eigen2_product_small) -ei_add_test(eigen2_product_large ${EI_OFLAG}) -ei_add_test(eigen2_adjoint) -ei_add_test(eigen2_submatrices) -ei_add_test(eigen2_miscmatrices) -ei_add_test(eigen2_commainitializer) -ei_add_test(eigen2_smallvectors) -ei_add_test(eigen2_map) -ei_add_test(eigen2_array) -ei_add_test(eigen2_triangular) -ei_add_test(eigen2_cholesky " " "${GSL_LIBRARIES}") -ei_add_test(eigen2_lu ${EI_OFLAG}) -ei_add_test(eigen2_determinant ${EI_OFLAG}) -ei_add_test(eigen2_inverse) -ei_add_test(eigen2_qr) -ei_add_test(eigen2_eigensolver " " "${GSL_LIBRARIES}") -ei_add_test(eigen2_svd) -ei_add_test(eigen2_geometry) -ei_add_test(eigen2_geometry_with_eigen2_prefix) -ei_add_test(eigen2_hyperplane) -ei_add_test(eigen2_parametrizedline) -ei_add_test(eigen2_alignedbox) -ei_add_test(eigen2_regression) -ei_add_test(eigen2_stdvector) -ei_add_test(eigen2_newstdvector) -if(QT4_FOUND) - ei_add_test(eigen2_qtvector " " "${QT_QTCORE_LIBRARY}") -endif(QT4_FOUND) -# no support for eigen2 sparse module -# if(NOT EIGEN_DEFAULT_TO_ROW_MAJOR) -# ei_add_test(eigen2_sparse_vector) -# ei_add_test(eigen2_sparse_basic) -# ei_add_test(eigen2_sparse_solvers " " "${SPARSE_LIBS}") -# ei_add_test(eigen2_sparse_product) -# endif() -ei_add_test(eigen2_swap) -ei_add_test(eigen2_visitor) -ei_add_test(eigen2_bug_132) - -ei_add_test(eigen2_prec_inverse_4x4 ${EI_OFLAG}) diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_adjoint.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_adjoint.cpp deleted file mode 100644 index c0f81145..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_adjoint.cpp +++ /dev/null @@ -1,99 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template void adjoint(const MatrixType& m) -{ - /* this test covers the following files: - Transpose.h Conjugate.h Dot.h - */ - - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix VectorType; - typedef Matrix SquareMatrixType; - int rows = m.rows(); - int cols = m.cols(); - - RealScalar largerEps = test_precision(); - if (ei_is_same_type::ret) - largerEps = RealScalar(1e-3f); - - MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols), - m3(rows, cols), - square = SquareMatrixType::Random(rows, rows); - VectorType v1 = VectorType::Random(rows), - v2 = VectorType::Random(rows), - v3 = VectorType::Random(rows), - vzero = VectorType::Zero(rows); - - Scalar s1 = ei_random(), - s2 = ei_random(); - - // check basic compatibility of adjoint, transpose, conjugate - VERIFY_IS_APPROX(m1.transpose().conjugate().adjoint(), m1); - VERIFY_IS_APPROX(m1.adjoint().conjugate().transpose(), m1); - - // check multiplicative behavior - VERIFY_IS_APPROX((m1.adjoint() * m2).adjoint(), m2.adjoint() * m1); - VERIFY_IS_APPROX((s1 * m1).adjoint(), ei_conj(s1) * m1.adjoint()); - - // check basic properties of dot, norm, norm2 - typedef typename NumTraits::Real RealScalar; - VERIFY(ei_isApprox((s1 * v1 + s2 * v2).eigen2_dot(v3), s1 * v1.eigen2_dot(v3) + s2 * v2.eigen2_dot(v3), largerEps)); - VERIFY(ei_isApprox(v3.eigen2_dot(s1 * v1 + s2 * v2), ei_conj(s1)*v3.eigen2_dot(v1)+ei_conj(s2)*v3.eigen2_dot(v2), largerEps)); - VERIFY_IS_APPROX(ei_conj(v1.eigen2_dot(v2)), v2.eigen2_dot(v1)); - VERIFY_IS_APPROX(ei_real(v1.eigen2_dot(v1)), v1.squaredNorm()); - if(NumTraits::HasFloatingPoint) - VERIFY_IS_APPROX(v1.squaredNorm(), v1.norm() * v1.norm()); - VERIFY_IS_MUCH_SMALLER_THAN(ei_abs(vzero.eigen2_dot(v1)), static_cast(1)); - if(NumTraits::HasFloatingPoint) - VERIFY_IS_MUCH_SMALLER_THAN(vzero.norm(), static_cast(1)); - - // check compatibility of dot and adjoint - VERIFY(ei_isApprox(v1.eigen2_dot(square * v2), (square.adjoint() * v1).eigen2_dot(v2), largerEps)); - - // like in testBasicStuff, test operator() to check const-qualification - int r = ei_random(0, rows-1), - c = ei_random(0, cols-1); - VERIFY_IS_APPROX(m1.conjugate()(r,c), ei_conj(m1(r,c))); - VERIFY_IS_APPROX(m1.adjoint()(c,r), ei_conj(m1(r,c))); - - if(NumTraits::HasFloatingPoint) - { - // check that Random().normalized() works: tricky as the random xpr must be evaluated by - // normalized() in order to produce a consistent result. - VERIFY_IS_APPROX(VectorType::Random(rows).normalized().norm(), RealScalar(1)); - } - - // check inplace transpose - m3 = m1; - m3.transposeInPlace(); - VERIFY_IS_APPROX(m3,m1.transpose()); - m3.transposeInPlace(); - VERIFY_IS_APPROX(m3,m1); - -} - -void test_eigen2_adjoint() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( adjoint(Matrix()) ); - CALL_SUBTEST_2( adjoint(Matrix3d()) ); - CALL_SUBTEST_3( adjoint(Matrix4f()) ); - CALL_SUBTEST_4( adjoint(MatrixXcf(4, 4)) ); - CALL_SUBTEST_5( adjoint(MatrixXi(8, 12)) ); - CALL_SUBTEST_6( adjoint(MatrixXf(21, 21)) ); - } - // test a large matrix only once - CALL_SUBTEST_7( adjoint(Matrix()) ); -} - diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_alignedbox.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_alignedbox.cpp deleted file mode 100644 index 35043b95..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_alignedbox.cpp +++ /dev/null @@ -1,60 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include -#include -#include - -template void alignedbox(const BoxType& _box) -{ - /* this test covers the following files: - AlignedBox.h - */ - - const int dim = _box.dim(); - typedef typename BoxType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix VectorType; - - VectorType p0 = VectorType::Random(dim); - VectorType p1 = VectorType::Random(dim); - RealScalar s1 = ei_random(0,1); - - BoxType b0(dim); - BoxType b1(VectorType::Random(dim),VectorType::Random(dim)); - BoxType b2; - - b0.extend(p0); - b0.extend(p1); - VERIFY(b0.contains(p0*s1+(Scalar(1)-s1)*p1)); - VERIFY(!b0.contains(p0 + (1+s1)*(p1-p0))); - - (b2 = b0).extend(b1); - VERIFY(b2.contains(b0)); - VERIFY(b2.contains(b1)); - VERIFY_IS_APPROX(b2.clamp(b0), b0); - - // casting - const int Dim = BoxType::AmbientDimAtCompileTime; - typedef typename GetDifferentType::type OtherScalar; - AlignedBox hp1f = b0.template cast(); - VERIFY_IS_APPROX(hp1f.template cast(),b0); - AlignedBox hp1d = b0.template cast(); - VERIFY_IS_APPROX(hp1d.template cast(),b0); -} - -void test_eigen2_alignedbox() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( alignedbox(AlignedBox()) ); - CALL_SUBTEST_2( alignedbox(AlignedBox()) ); - CALL_SUBTEST_3( alignedbox(AlignedBox()) ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_array.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_array.cpp deleted file mode 100644 index c1ff40ce..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_array.cpp +++ /dev/null @@ -1,142 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include - -template void array(const MatrixType& m) -{ - /* this test covers the following files: - Array.cpp - */ - - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix VectorType; - - int rows = m.rows(); - int cols = m.cols(); - - MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols), - m3(rows, cols); - - Scalar s1 = ei_random(), - s2 = ei_random(); - - // scalar addition - VERIFY_IS_APPROX(m1.cwise() + s1, s1 + m1.cwise()); - VERIFY_IS_APPROX(m1.cwise() + s1, MatrixType::Constant(rows,cols,s1) + m1); - VERIFY_IS_APPROX((m1*Scalar(2)).cwise() - s2, (m1+m1) - MatrixType::Constant(rows,cols,s2) ); - m3 = m1; - m3.cwise() += s2; - VERIFY_IS_APPROX(m3, m1.cwise() + s2); - m3 = m1; - m3.cwise() -= s1; - VERIFY_IS_APPROX(m3, m1.cwise() - s1); - - // reductions - VERIFY_IS_APPROX(m1.colwise().sum().sum(), m1.sum()); - VERIFY_IS_APPROX(m1.rowwise().sum().sum(), m1.sum()); - if (!ei_isApprox(m1.sum(), (m1+m2).sum())) - VERIFY_IS_NOT_APPROX(((m1+m2).rowwise().sum()).sum(), m1.sum()); - VERIFY_IS_APPROX(m1.colwise().sum(), m1.colwise().redux(internal::scalar_sum_op())); -} - -template void comparisons(const MatrixType& m) -{ - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix VectorType; - - int rows = m.rows(); - int cols = m.cols(); - - int r = ei_random(0, rows-1), - c = ei_random(0, cols-1); - - MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols), - m3(rows, cols); - - VERIFY(((m1.cwise() + Scalar(1)).cwise() > m1).all()); - VERIFY(((m1.cwise() - Scalar(1)).cwise() < m1).all()); - if (rows*cols>1) - { - m3 = m1; - m3(r,c) += 1; - VERIFY(! (m1.cwise() < m3).all() ); - VERIFY(! (m1.cwise() > m3).all() ); - } - - // comparisons to scalar - VERIFY( (m1.cwise() != (m1(r,c)+1) ).any() ); - VERIFY( (m1.cwise() > (m1(r,c)-1) ).any() ); - VERIFY( (m1.cwise() < (m1(r,c)+1) ).any() ); - VERIFY( (m1.cwise() == m1(r,c) ).any() ); - - // test Select - VERIFY_IS_APPROX( (m1.cwise()m2).select(m1,m2), m1.cwise().max(m2) ); - Scalar mid = (m1.cwise().abs().minCoeff() + m1.cwise().abs().maxCoeff())/Scalar(2); - for (int j=0; j=MatrixType::Constant(rows,cols,mid)) - .select(m1,0), m3); - // even shorter version: - VERIFY_IS_APPROX( (m1.cwise().abs().cwise()RealScalar(0.1)).count() == rows*cols); - VERIFY_IS_APPROX(((m1.cwise().abs().cwise()+1).cwise()>RealScalar(0.1)).colwise().count().template cast(), RowVectorXi::Constant(cols,rows)); - VERIFY_IS_APPROX(((m1.cwise().abs().cwise()+1).cwise()>RealScalar(0.1)).rowwise().count().template cast(), VectorXi::Constant(rows, cols)); -} - -template void lpNorm(const VectorType& v) -{ - VectorType u = VectorType::Random(v.size()); - - VERIFY_IS_APPROX(u.template lpNorm(), u.cwise().abs().maxCoeff()); - VERIFY_IS_APPROX(u.template lpNorm<1>(), u.cwise().abs().sum()); - VERIFY_IS_APPROX(u.template lpNorm<2>(), ei_sqrt(u.cwise().abs().cwise().square().sum())); - VERIFY_IS_APPROX(ei_pow(u.template lpNorm<5>(), typename VectorType::RealScalar(5)), u.cwise().abs().cwise().pow(5).sum()); -} - -void test_eigen2_array() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( array(Matrix()) ); - CALL_SUBTEST_2( array(Matrix2f()) ); - CALL_SUBTEST_3( array(Matrix4d()) ); - CALL_SUBTEST_4( array(MatrixXcf(3, 3)) ); - CALL_SUBTEST_5( array(MatrixXf(8, 12)) ); - CALL_SUBTEST_6( array(MatrixXi(8, 12)) ); - } - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( comparisons(Matrix()) ); - CALL_SUBTEST_2( comparisons(Matrix2f()) ); - CALL_SUBTEST_3( comparisons(Matrix4d()) ); - CALL_SUBTEST_5( comparisons(MatrixXf(8, 12)) ); - CALL_SUBTEST_6( comparisons(MatrixXi(8, 12)) ); - } - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( lpNorm(Matrix()) ); - CALL_SUBTEST_2( lpNorm(Vector2f()) ); - CALL_SUBTEST_3( lpNorm(Vector3d()) ); - CALL_SUBTEST_4( lpNorm(Vector4f()) ); - CALL_SUBTEST_5( lpNorm(VectorXf(16)) ); - CALL_SUBTEST_7( lpNorm(VectorXcd(10)) ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_basicstuff.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_basicstuff.cpp deleted file mode 100644 index dd2dec1e..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_basicstuff.cpp +++ /dev/null @@ -1,105 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template void basicStuff(const MatrixType& m) -{ - typedef typename MatrixType::Scalar Scalar; - typedef Matrix VectorType; - - int rows = m.rows(); - int cols = m.cols(); - - // this test relies a lot on Random.h, and there's not much more that we can do - // to test it, hence I consider that we will have tested Random.h - MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols), - m3(rows, cols), - mzero = MatrixType::Zero(rows, cols), - square = Matrix::Random(rows, rows); - VectorType v1 = VectorType::Random(rows), - vzero = VectorType::Zero(rows); - - Scalar x = ei_random(); - - int r = ei_random(0, rows-1), - c = ei_random(0, cols-1); - - m1.coeffRef(r,c) = x; - VERIFY_IS_APPROX(x, m1.coeff(r,c)); - m1(r,c) = x; - VERIFY_IS_APPROX(x, m1(r,c)); - v1.coeffRef(r) = x; - VERIFY_IS_APPROX(x, v1.coeff(r)); - v1(r) = x; - VERIFY_IS_APPROX(x, v1(r)); - v1[r] = x; - VERIFY_IS_APPROX(x, v1[r]); - - VERIFY_IS_APPROX( v1, v1); - VERIFY_IS_NOT_APPROX( v1, 2*v1); - VERIFY_IS_MUCH_SMALLER_THAN( vzero, v1); - if(NumTraits::HasFloatingPoint) - VERIFY_IS_MUCH_SMALLER_THAN( vzero, v1.norm()); - VERIFY_IS_NOT_MUCH_SMALLER_THAN(v1, v1); - VERIFY_IS_APPROX( vzero, v1-v1); - VERIFY_IS_APPROX( m1, m1); - VERIFY_IS_NOT_APPROX( m1, 2*m1); - VERIFY_IS_MUCH_SMALLER_THAN( mzero, m1); - VERIFY_IS_NOT_MUCH_SMALLER_THAN(m1, m1); - VERIFY_IS_APPROX( mzero, m1-m1); - - // always test operator() on each read-only expression class, - // in order to check const-qualifiers. - // indeed, if an expression class (here Zero) is meant to be read-only, - // hence has no _write() method, the corresponding MatrixBase method (here zero()) - // should return a const-qualified object so that it is the const-qualified - // operator() that gets called, which in turn calls _read(). - VERIFY_IS_MUCH_SMALLER_THAN(MatrixType::Zero(rows,cols)(r,c), static_cast(1)); - - // now test copying a row-vector into a (column-)vector and conversely. - square.col(r) = square.row(r).eval(); - Matrix rv(rows); - Matrix cv(rows); - rv = square.row(r); - cv = square.col(r); - VERIFY_IS_APPROX(rv, cv.transpose()); - - if(cols!=1 && rows!=1 && MatrixType::SizeAtCompileTime!=Dynamic) - { - VERIFY_RAISES_ASSERT(m1 = (m2.block(0,0, rows-1, cols-1))); - } - - VERIFY_IS_APPROX(m3 = m1,m1); - MatrixType m4; - VERIFY_IS_APPROX(m4 = m1,m1); - - // test swap - m3 = m1; - m1.swap(m2); - VERIFY_IS_APPROX(m3, m2); - if(rows*cols>=3) - { - VERIFY_IS_NOT_APPROX(m3, m1); - } -} - -void test_eigen2_basicstuff() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( basicStuff(Matrix()) ); - CALL_SUBTEST_2( basicStuff(Matrix4d()) ); - CALL_SUBTEST_3( basicStuff(MatrixXcf(3, 3)) ); - CALL_SUBTEST_4( basicStuff(MatrixXi(8, 12)) ); - CALL_SUBTEST_5( basicStuff(MatrixXcd(20, 20)) ); - CALL_SUBTEST_6( basicStuff(Matrix()) ); - CALL_SUBTEST_7( basicStuff(Matrix(10,10)) ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_bug_132.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_bug_132.cpp deleted file mode 100644 index 7fe3610c..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_bug_132.cpp +++ /dev/null @@ -1,26 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2010 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -void test_eigen2_bug_132() { - int size = 100; - MatrixXd A(size, size); - VectorXd b(size), c(size); - { - VectorXd y = A.transpose() * (b-c); // bug 132: infinite recursion in coeffRef - VectorXd z = (b-c).transpose() * A; // bug 132: infinite recursion in coeffRef - } - - // the following ones weren't failing, but let's include them for completeness: - { - VectorXd y = A * (b-c); - VectorXd z = (b-c).transpose() * A.transpose(); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_cholesky.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_cholesky.cpp deleted file mode 100644 index 9c4b6f56..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_cholesky.cpp +++ /dev/null @@ -1,113 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#define EIGEN_NO_ASSERTION_CHECKING -#include "main.h" -#include -#include - -#ifdef HAS_GSL -#include "gsl_helper.h" -#endif - -template void cholesky(const MatrixType& m) -{ - /* this test covers the following files: - LLT.h LDLT.h - */ - int rows = m.rows(); - int cols = m.cols(); - - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix SquareMatrixType; - typedef Matrix VectorType; - - MatrixType a0 = MatrixType::Random(rows,cols); - VectorType vecB = VectorType::Random(rows), vecX(rows); - MatrixType matB = MatrixType::Random(rows,cols), matX(rows,cols); - SquareMatrixType symm = a0 * a0.adjoint(); - // let's make sure the matrix is not singular or near singular - MatrixType a1 = MatrixType::Random(rows,cols); - symm += a1 * a1.adjoint(); - - #ifdef HAS_GSL - if (ei_is_same_type::ret) - { - typedef GslTraits Gsl; - typename Gsl::Matrix gMatA=0, gSymm=0; - typename Gsl::Vector gVecB=0, gVecX=0; - convert(symm, gSymm); - convert(symm, gMatA); - convert(vecB, gVecB); - convert(vecB, gVecX); - Gsl::cholesky(gMatA); - Gsl::cholesky_solve(gMatA, gVecB, gVecX); - VectorType vecX(rows), _vecX, _vecB; - convert(gVecX, _vecX); - symm.llt().solve(vecB, &vecX); - Gsl::prod(gSymm, gVecX, gVecB); - convert(gVecB, _vecB); - // test gsl itself ! - VERIFY_IS_APPROX(vecB, _vecB); - VERIFY_IS_APPROX(vecX, _vecX); - - Gsl::free(gMatA); - Gsl::free(gSymm); - Gsl::free(gVecB); - Gsl::free(gVecX); - } - #endif - - { - LDLT ldlt(symm); - VERIFY(ldlt.isPositiveDefinite()); - // in eigen3, LDLT is pivoting - //VERIFY_IS_APPROX(symm, ldlt.matrixL() * ldlt.vectorD().asDiagonal() * ldlt.matrixL().adjoint()); - ldlt.solve(vecB, &vecX); - VERIFY_IS_APPROX(symm * vecX, vecB); - ldlt.solve(matB, &matX); - VERIFY_IS_APPROX(symm * matX, matB); - } - - { - LLT chol(symm); - VERIFY(chol.isPositiveDefinite()); - VERIFY_IS_APPROX(symm, chol.matrixL() * chol.matrixL().adjoint()); - chol.solve(vecB, &vecX); - VERIFY_IS_APPROX(symm * vecX, vecB); - chol.solve(matB, &matX); - VERIFY_IS_APPROX(symm * matX, matB); - } - -#if 0 // cholesky is not rank-revealing anyway - // test isPositiveDefinite on non definite matrix - if (rows>4) - { - SquareMatrixType symm = a0.block(0,0,rows,cols-4) * a0.block(0,0,rows,cols-4).adjoint(); - LLT chol(symm); - VERIFY(!chol.isPositiveDefinite()); - LDLT cholnosqrt(symm); - VERIFY(!cholnosqrt.isPositiveDefinite()); - } -#endif -} - -void test_eigen2_cholesky() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( cholesky(Matrix()) ); - CALL_SUBTEST_2( cholesky(Matrix2d()) ); - CALL_SUBTEST_3( cholesky(Matrix3f()) ); - CALL_SUBTEST_4( cholesky(Matrix4d()) ); - CALL_SUBTEST_5( cholesky(MatrixXcd(7,7)) ); - CALL_SUBTEST_6( cholesky(MatrixXf(17,17)) ); - CALL_SUBTEST_7( cholesky(MatrixXd(33,33)) ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_commainitializer.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_commainitializer.cpp deleted file mode 100644 index e0f901e0..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_commainitializer.cpp +++ /dev/null @@ -1,46 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -void test_eigen2_commainitializer() -{ - Matrix3d m3; - Matrix4d m4; - - VERIFY_RAISES_ASSERT( (m3 << 1, 2, 3, 4, 5, 6, 7, 8) ); - - #ifndef _MSC_VER - VERIFY_RAISES_ASSERT( (m3 << 1, 2, 3, 4, 5, 6, 7, 8, 9, 10) ); - #endif - - double data[] = {1, 2, 3, 4, 5, 6, 7, 8, 9}; - Matrix3d ref = Map >(data); - - m3 = Matrix3d::Random(); - m3 << 1, 2, 3, 4, 5, 6, 7, 8, 9; - VERIFY_IS_APPROX(m3, ref ); - - Vector3d vec[3]; - vec[0] << 1, 4, 7; - vec[1] << 2, 5, 8; - vec[2] << 3, 6, 9; - m3 = Matrix3d::Random(); - m3 << vec[0], vec[1], vec[2]; - VERIFY_IS_APPROX(m3, ref); - - vec[0] << 1, 2, 3; - vec[1] << 4, 5, 6; - vec[2] << 7, 8, 9; - m3 = Matrix3d::Random(); - m3 << vec[0].transpose(), - 4, 5, 6, - vec[2].transpose(); - VERIFY_IS_APPROX(m3, ref); -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_cwiseop.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_cwiseop.cpp deleted file mode 100644 index 22e1cc34..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_cwiseop.cpp +++ /dev/null @@ -1,155 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include -#include - -using namespace std; - -template struct AddIfNull { - const Scalar operator() (const Scalar a, const Scalar b) const {return a<=1e-3 ? b : a;} - enum { Cost = NumTraits::AddCost }; -}; - -template void cwiseops(const MatrixType& m) -{ - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix VectorType; - - int rows = m.rows(); - int cols = m.cols(); - - MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols), - m3(rows, cols), - m4(rows, cols), - mzero = MatrixType::Zero(rows, cols), - mones = MatrixType::Ones(rows, cols), - identity = Matrix - ::Identity(rows, rows); - VectorType vzero = VectorType::Zero(rows), - vones = VectorType::Ones(rows), - v3(rows); - - int r = ei_random(0, rows-1), - c = ei_random(0, cols-1); - - Scalar s1 = ei_random(); - - // test Zero, Ones, Constant, and the set* variants - m3 = MatrixType::Constant(rows, cols, s1); - for (int j=0; j >(mones); - - VERIFY_IS_APPROX(m1.cwise().pow(2), m1.cwise().abs2()); - VERIFY_IS_APPROX(m1.cwise().pow(2), m1.cwise().square()); - VERIFY_IS_APPROX(m1.cwise().pow(3), m1.cwise().cube()); - - VERIFY_IS_APPROX(m1 + mones, m1.cwise()+Scalar(1)); - VERIFY_IS_APPROX(m1 - mones, m1.cwise()-Scalar(1)); - m3 = m1; m3.cwise() += 1; - VERIFY_IS_APPROX(m1 + mones, m3); - m3 = m1; m3.cwise() -= 1; - VERIFY_IS_APPROX(m1 - mones, m3); - - VERIFY_IS_APPROX(m2, m2.cwise() * mones); - VERIFY_IS_APPROX(m1.cwise() * m2, m2.cwise() * m1); - m3 = m1; - m3.cwise() *= m2; - VERIFY_IS_APPROX(m3, m1.cwise() * m2); - - VERIFY_IS_APPROX(mones, m2.cwise()/m2); - if(NumTraits::HasFloatingPoint) - { - VERIFY_IS_APPROX(m1.cwise() / m2, m1.cwise() * (m2.cwise().inverse())); - m3 = m1.cwise().abs().cwise().sqrt(); - VERIFY_IS_APPROX(m3.cwise().square(), m1.cwise().abs()); - VERIFY_IS_APPROX(m1.cwise().square().cwise().sqrt(), m1.cwise().abs()); - VERIFY_IS_APPROX(m1.cwise().abs().cwise().log().cwise().exp() , m1.cwise().abs()); - - VERIFY_IS_APPROX(m1.cwise().pow(2), m1.cwise().square()); - m3 = (m1.cwise().abs().cwise()<=RealScalar(0.01)).select(mones,m1); - VERIFY_IS_APPROX(m3.cwise().pow(-1), m3.cwise().inverse()); - m3 = m1.cwise().abs(); - VERIFY_IS_APPROX(m3.cwise().pow(RealScalar(0.5)), m3.cwise().sqrt()); - -// VERIFY_IS_APPROX(m1.cwise().tan(), m1.cwise().sin().cwise() / m1.cwise().cos()); - VERIFY_IS_APPROX(mones, m1.cwise().sin().cwise().square() + m1.cwise().cos().cwise().square()); - m3 = m1; - m3.cwise() /= m2; - VERIFY_IS_APPROX(m3, m1.cwise() / m2); - } - - // check min - VERIFY_IS_APPROX( m1.cwise().min(m2), m2.cwise().min(m1) ); - VERIFY_IS_APPROX( m1.cwise().min(m1+mones), m1 ); - VERIFY_IS_APPROX( m1.cwise().min(m1-mones), m1-mones ); - - // check max - VERIFY_IS_APPROX( m1.cwise().max(m2), m2.cwise().max(m1) ); - VERIFY_IS_APPROX( m1.cwise().max(m1-mones), m1 ); - VERIFY_IS_APPROX( m1.cwise().max(m1+mones), m1+mones ); - - VERIFY( (m1.cwise() == m1).all() ); - VERIFY( (m1.cwise() != m2).any() ); - VERIFY(!(m1.cwise() == (m1+mones)).any() ); - if (rows*cols>1) - { - m3 = m1; - m3(r,c) += 1; - VERIFY( (m1.cwise() == m3).any() ); - VERIFY( !(m1.cwise() == m3).all() ); - } - VERIFY( (m1.cwise().min(m2).cwise() <= m2).all() ); - VERIFY( (m1.cwise().max(m2).cwise() >= m2).all() ); - VERIFY( (m1.cwise().min(m2).cwise() < (m1+mones)).all() ); - VERIFY( (m1.cwise().max(m2).cwise() > (m1-mones)).all() ); - - VERIFY( (m1.cwise()(), Scalar(1)))).all() ); - VERIFY( !(m1.cwise()(), Scalar(1)))).all() ); - VERIFY( !(m1.cwise()>m1.unaryExpr(bind2nd(plus(), Scalar(1)))).any() ); -} - -void test_eigen2_cwiseop() -{ - for(int i = 0; i < g_repeat ; i++) { - CALL_SUBTEST_1( cwiseops(Matrix()) ); - CALL_SUBTEST_2( cwiseops(Matrix4d()) ); - CALL_SUBTEST_3( cwiseops(MatrixXf(3, 3)) ); - CALL_SUBTEST_3( cwiseops(MatrixXf(22, 22)) ); - CALL_SUBTEST_4( cwiseops(MatrixXi(8, 12)) ); - CALL_SUBTEST_5( cwiseops(MatrixXd(20, 20)) ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_determinant.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_determinant.cpp deleted file mode 100644 index c7b4ad05..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_determinant.cpp +++ /dev/null @@ -1,61 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Benoit Jacob -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include - -template void determinant(const MatrixType& m) -{ - /* this test covers the following files: - Determinant.h - */ - int size = m.rows(); - - MatrixType m1(size, size), m2(size, size); - m1.setRandom(); - m2.setRandom(); - typedef typename MatrixType::Scalar Scalar; - Scalar x = ei_random(); - VERIFY_IS_APPROX(MatrixType::Identity(size, size).determinant(), Scalar(1)); - VERIFY_IS_APPROX((m1*m2).determinant(), m1.determinant() * m2.determinant()); - if(size==1) return; - int i = ei_random(0, size-1); - int j; - do { - j = ei_random(0, size-1); - } while(j==i); - m2 = m1; - m2.row(i).swap(m2.row(j)); - VERIFY_IS_APPROX(m2.determinant(), -m1.determinant()); - m2 = m1; - m2.col(i).swap(m2.col(j)); - VERIFY_IS_APPROX(m2.determinant(), -m1.determinant()); - VERIFY_IS_APPROX(m2.determinant(), m2.transpose().determinant()); - VERIFY_IS_APPROX(ei_conj(m2.determinant()), m2.adjoint().determinant()); - m2 = m1; - m2.row(i) += x*m2.row(j); - VERIFY_IS_APPROX(m2.determinant(), m1.determinant()); - m2 = m1; - m2.row(i) *= x; - VERIFY_IS_APPROX(m2.determinant(), m1.determinant() * x); -} - -void test_eigen2_determinant() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( determinant(Matrix()) ); - CALL_SUBTEST_2( determinant(Matrix()) ); - CALL_SUBTEST_3( determinant(Matrix()) ); - CALL_SUBTEST_4( determinant(Matrix()) ); - CALL_SUBTEST_5( determinant(Matrix, 10, 10>()) ); - CALL_SUBTEST_6( determinant(MatrixXd(20, 20)) ); - } - CALL_SUBTEST_6( determinant(MatrixXd(200, 200)) ); -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_dynalloc.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_dynalloc.cpp deleted file mode 100644 index 1891a9e3..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_dynalloc.cpp +++ /dev/null @@ -1,131 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -#if EIGEN_ARCH_WANTS_ALIGNMENT -#define ALIGNMENT 16 -#else -#define ALIGNMENT 1 -#endif - -void check_handmade_aligned_malloc() -{ - for(int i = 1; i < 1000; i++) - { - char *p = (char*)ei_handmade_aligned_malloc(i); - VERIFY(std::size_t(p)%ALIGNMENT==0); - // if the buffer is wrongly allocated this will give a bad write --> check with valgrind - for(int j = 0; j < i; j++) p[j]=0; - ei_handmade_aligned_free(p); - } -} - -void check_aligned_malloc() -{ - for(int i = 1; i < 1000; i++) - { - char *p = (char*)ei_aligned_malloc(i); - VERIFY(std::size_t(p)%ALIGNMENT==0); - // if the buffer is wrongly allocated this will give a bad write --> check with valgrind - for(int j = 0; j < i; j++) p[j]=0; - ei_aligned_free(p); - } -} - -void check_aligned_new() -{ - for(int i = 1; i < 1000; i++) - { - float *p = ei_aligned_new(i); - VERIFY(std::size_t(p)%ALIGNMENT==0); - // if the buffer is wrongly allocated this will give a bad write --> check with valgrind - for(int j = 0; j < i; j++) p[j]=0; - ei_aligned_delete(p,i); - } -} - -void check_aligned_stack_alloc() -{ - for(int i = 1; i < 1000; i++) - { - ei_declare_aligned_stack_constructed_variable(float, p, i, 0); - VERIFY(std::size_t(p)%ALIGNMENT==0); - // if the buffer is wrongly allocated this will give a bad write --> check with valgrind - for(int j = 0; j < i; j++) p[j]=0; - } -} - - -// test compilation with both a struct and a class... -struct MyStruct -{ - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - char dummychar; - Vector4f avec; -}; - -class MyClassA -{ - public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - char dummychar; - Vector4f avec; -}; - -template void check_dynaligned() -{ - T* obj = new T; - VERIFY(std::size_t(obj)%ALIGNMENT==0); - delete obj; -} - -void test_eigen2_dynalloc() -{ - // low level dynamic memory allocation - CALL_SUBTEST(check_handmade_aligned_malloc()); - CALL_SUBTEST(check_aligned_malloc()); - CALL_SUBTEST(check_aligned_new()); - CALL_SUBTEST(check_aligned_stack_alloc()); - - for (int i=0; i() ); - CALL_SUBTEST( check_dynaligned() ); - CALL_SUBTEST( check_dynaligned() ); - CALL_SUBTEST( check_dynaligned() ); - CALL_SUBTEST( check_dynaligned() ); - } - - // check static allocation, who knows ? - { - MyStruct foo0; VERIFY(std::size_t(foo0.avec.data())%ALIGNMENT==0); - MyClassA fooA; VERIFY(std::size_t(fooA.avec.data())%ALIGNMENT==0); - } - - // dynamic allocation, single object - for (int i=0; iavec.data())%ALIGNMENT==0); - MyClassA *fooA = new MyClassA(); VERIFY(std::size_t(fooA->avec.data())%ALIGNMENT==0); - delete foo0; - delete fooA; - } - - // dynamic allocation, array - const int N = 10; - for (int i=0; iavec.data())%ALIGNMENT==0); - MyClassA *fooA = new MyClassA[N]; VERIFY(std::size_t(fooA->avec.data())%ALIGNMENT==0); - delete[] foo0; - delete[] fooA; - } - -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_eigensolver.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_eigensolver.cpp deleted file mode 100644 index 48b4ace4..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_eigensolver.cpp +++ /dev/null @@ -1,146 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include - -#ifdef HAS_GSL -#include "gsl_helper.h" -#endif - -template void selfadjointeigensolver(const MatrixType& m) -{ - /* this test covers the following files: - EigenSolver.h, SelfAdjointEigenSolver.h (and indirectly: Tridiagonalization.h) - */ - int rows = m.rows(); - int cols = m.cols(); - - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix VectorType; - typedef Matrix RealVectorType; - typedef typename std::complex::Real> Complex; - - RealScalar largerEps = 10*test_precision(); - - MatrixType a = MatrixType::Random(rows,cols); - MatrixType a1 = MatrixType::Random(rows,cols); - MatrixType symmA = a.adjoint() * a + a1.adjoint() * a1; - - MatrixType b = MatrixType::Random(rows,cols); - MatrixType b1 = MatrixType::Random(rows,cols); - MatrixType symmB = b.adjoint() * b + b1.adjoint() * b1; - - SelfAdjointEigenSolver eiSymm(symmA); - // generalized eigen pb - SelfAdjointEigenSolver eiSymmGen(symmA, symmB); - - #ifdef HAS_GSL - if (ei_is_same_type::ret) - { - typedef GslTraits Gsl; - typename Gsl::Matrix gEvec=0, gSymmA=0, gSymmB=0; - typename GslTraits::Vector gEval=0; - RealVectorType _eval; - MatrixType _evec; - convert(symmA, gSymmA); - convert(symmB, gSymmB); - convert(symmA, gEvec); - gEval = GslTraits::createVector(rows); - - Gsl::eigen_symm(gSymmA, gEval, gEvec); - convert(gEval, _eval); - convert(gEvec, _evec); - - // test gsl itself ! - VERIFY((symmA * _evec).isApprox(_evec * _eval.asDiagonal(), largerEps)); - - // compare with eigen - VERIFY_IS_APPROX(_eval, eiSymm.eigenvalues()); - VERIFY_IS_APPROX(_evec.cwise().abs(), eiSymm.eigenvectors().cwise().abs()); - - // generalized pb - Gsl::eigen_symm_gen(gSymmA, gSymmB, gEval, gEvec); - convert(gEval, _eval); - convert(gEvec, _evec); - // test GSL itself: - VERIFY((symmA * _evec).isApprox(symmB * (_evec * _eval.asDiagonal()), largerEps)); - - // compare with eigen - MatrixType normalized_eivec = eiSymmGen.eigenvectors()*eiSymmGen.eigenvectors().colwise().norm().asDiagonal().inverse(); - VERIFY_IS_APPROX(_eval, eiSymmGen.eigenvalues()); - VERIFY_IS_APPROX(_evec.cwiseAbs(), normalized_eivec.cwiseAbs()); - - Gsl::free(gSymmA); - Gsl::free(gSymmB); - GslTraits::free(gEval); - Gsl::free(gEvec); - } - #endif - - VERIFY((symmA * eiSymm.eigenvectors()).isApprox( - eiSymm.eigenvectors() * eiSymm.eigenvalues().asDiagonal(), largerEps)); - - // generalized eigen problem Ax = lBx - VERIFY((symmA * eiSymmGen.eigenvectors()).isApprox( - symmB * (eiSymmGen.eigenvectors() * eiSymmGen.eigenvalues().asDiagonal()), largerEps)); - - MatrixType sqrtSymmA = eiSymm.operatorSqrt(); - VERIFY_IS_APPROX(symmA, sqrtSymmA*sqrtSymmA); - VERIFY_IS_APPROX(sqrtSymmA, symmA*eiSymm.operatorInverseSqrt()); -} - -template void eigensolver(const MatrixType& m) -{ - /* this test covers the following files: - EigenSolver.h - */ - int rows = m.rows(); - int cols = m.cols(); - - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix VectorType; - typedef Matrix RealVectorType; - typedef typename std::complex::Real> Complex; - - // RealScalar largerEps = 10*test_precision(); - - MatrixType a = MatrixType::Random(rows,cols); - MatrixType a1 = MatrixType::Random(rows,cols); - MatrixType symmA = a.adjoint() * a + a1.adjoint() * a1; - - EigenSolver ei0(symmA); - VERIFY_IS_APPROX(symmA * ei0.pseudoEigenvectors(), ei0.pseudoEigenvectors() * ei0.pseudoEigenvalueMatrix()); - VERIFY_IS_APPROX((symmA.template cast()) * (ei0.pseudoEigenvectors().template cast()), - (ei0.pseudoEigenvectors().template cast()) * (ei0.eigenvalues().asDiagonal())); - - EigenSolver ei1(a); - VERIFY_IS_APPROX(a * ei1.pseudoEigenvectors(), ei1.pseudoEigenvectors() * ei1.pseudoEigenvalueMatrix()); - VERIFY_IS_APPROX(a.template cast() * ei1.eigenvectors(), - ei1.eigenvectors() * ei1.eigenvalues().asDiagonal()); - -} - -void test_eigen2_eigensolver() -{ - for(int i = 0; i < g_repeat; i++) { - // very important to test a 3x3 matrix since we provide a special path for it - CALL_SUBTEST_1( selfadjointeigensolver(Matrix3f()) ); - CALL_SUBTEST_2( selfadjointeigensolver(Matrix4d()) ); - CALL_SUBTEST_3( selfadjointeigensolver(MatrixXf(7,7)) ); - CALL_SUBTEST_4( selfadjointeigensolver(MatrixXcd(5,5)) ); - CALL_SUBTEST_5( selfadjointeigensolver(MatrixXd(19,19)) ); - - CALL_SUBTEST_6( eigensolver(Matrix4f()) ); - CALL_SUBTEST_5( eigensolver(MatrixXd(17,17)) ); - } -} - diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_first_aligned.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_first_aligned.cpp deleted file mode 100644 index 51bb3cad..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_first_aligned.cpp +++ /dev/null @@ -1,49 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2009 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template -void test_eigen2_first_aligned_helper(Scalar *array, int size) -{ - const int packet_size = sizeof(Scalar) * ei_packet_traits::size; - VERIFY(((std::size_t(array) + sizeof(Scalar) * ei_alignmentOffset(array, size)) % packet_size) == 0); -} - -template -void test_eigen2_none_aligned_helper(Scalar *array, int size) -{ - VERIFY(ei_packet_traits::size == 1 || ei_alignmentOffset(array, size) == size); -} - -struct some_non_vectorizable_type { float x; }; - -void test_eigen2_first_aligned() -{ - EIGEN_ALIGN_128 float array_float[100]; - test_first_aligned_helper(array_float, 50); - test_first_aligned_helper(array_float+1, 50); - test_first_aligned_helper(array_float+2, 50); - test_first_aligned_helper(array_float+3, 50); - test_first_aligned_helper(array_float+4, 50); - test_first_aligned_helper(array_float+5, 50); - - EIGEN_ALIGN_128 double array_double[100]; - test_first_aligned_helper(array_double, 50); - test_first_aligned_helper(array_double+1, 50); - test_first_aligned_helper(array_double+2, 50); - - double *array_double_plus_4_bytes = (double*)(std::size_t(array_double)+4); - test_none_aligned_helper(array_double_plus_4_bytes, 50); - test_none_aligned_helper(array_double_plus_4_bytes+1, 50); - - some_non_vectorizable_type array_nonvec[100]; - test_first_aligned_helper(array_nonvec, 100); - test_none_aligned_helper(array_nonvec, 100); -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_geometry.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_geometry.cpp deleted file mode 100644 index 51404077..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_geometry.cpp +++ /dev/null @@ -1,432 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include -#include -#include - -template void geometry(void) -{ - /* this test covers the following files: - Cross.h Quaternion.h, Transform.cpp - */ - - typedef Matrix Matrix2; - typedef Matrix Matrix3; - typedef Matrix Matrix4; - typedef Matrix Vector2; - typedef Matrix Vector3; - typedef Matrix Vector4; - typedef Quaternion Quaternionx; - typedef AngleAxis AngleAxisx; - typedef Transform Transform2; - typedef Transform Transform3; - typedef Scaling Scaling2; - typedef Scaling Scaling3; - typedef Translation Translation2; - typedef Translation Translation3; - - Scalar largeEps = test_precision(); - if (ei_is_same_type::ret) - largeEps = 1e-2f; - - Vector3 v0 = Vector3::Random(), - v1 = Vector3::Random(), - v2 = Vector3::Random(); - Vector2 u0 = Vector2::Random(); - Matrix3 matrot1; - - Scalar a = ei_random(-Scalar(M_PI), Scalar(M_PI)); - - // cross product - VERIFY_IS_MUCH_SMALLER_THAN(v1.cross(v2).eigen2_dot(v1), Scalar(1)); - Matrix3 m; - m << v0.normalized(), - (v0.cross(v1)).normalized(), - (v0.cross(v1).cross(v0)).normalized(); - VERIFY(m.isUnitary()); - - // Quaternion: Identity(), setIdentity(); - Quaternionx q1, q2; - q2.setIdentity(); - VERIFY_IS_APPROX(Quaternionx(Quaternionx::Identity()).coeffs(), q2.coeffs()); - q1.coeffs().setRandom(); - VERIFY_IS_APPROX(q1.coeffs(), (q1*q2).coeffs()); - - // unitOrthogonal - VERIFY_IS_MUCH_SMALLER_THAN(u0.unitOrthogonal().eigen2_dot(u0), Scalar(1)); - VERIFY_IS_MUCH_SMALLER_THAN(v0.unitOrthogonal().eigen2_dot(v0), Scalar(1)); - VERIFY_IS_APPROX(u0.unitOrthogonal().norm(), Scalar(1)); - VERIFY_IS_APPROX(v0.unitOrthogonal().norm(), Scalar(1)); - - - VERIFY_IS_APPROX(v0, AngleAxisx(a, v0.normalized()) * v0); - VERIFY_IS_APPROX(-v0, AngleAxisx(Scalar(M_PI), v0.unitOrthogonal()) * v0); - VERIFY_IS_APPROX(ei_cos(a)*v0.squaredNorm(), v0.eigen2_dot(AngleAxisx(a, v0.unitOrthogonal()) * v0)); - m = AngleAxisx(a, v0.normalized()).toRotationMatrix().adjoint(); - VERIFY_IS_APPROX(Matrix3::Identity(), m * AngleAxisx(a, v0.normalized())); - VERIFY_IS_APPROX(Matrix3::Identity(), AngleAxisx(a, v0.normalized()) * m); - - q1 = AngleAxisx(a, v0.normalized()); - q2 = AngleAxisx(a, v1.normalized()); - - // angular distance - Scalar refangle = ei_abs(AngleAxisx(q1.inverse()*q2).angle()); - if (refangle>Scalar(M_PI)) - refangle = Scalar(2)*Scalar(M_PI) - refangle; - - if((q1.coeffs()-q2.coeffs()).norm() > 10*largeEps) - { - VERIFY(ei_isApprox(q1.angularDistance(q2), refangle, largeEps)); - } - - // rotation matrix conversion - VERIFY_IS_APPROX(q1 * v2, q1.toRotationMatrix() * v2); - VERIFY_IS_APPROX(q1 * q2 * v2, - q1.toRotationMatrix() * q2.toRotationMatrix() * v2); - - VERIFY( (q2*q1).isApprox(q1*q2, largeEps) || !(q2 * q1 * v2).isApprox( - q1.toRotationMatrix() * q2.toRotationMatrix() * v2)); - - q2 = q1.toRotationMatrix(); - VERIFY_IS_APPROX(q1*v1,q2*v1); - - matrot1 = AngleAxisx(Scalar(0.1), Vector3::UnitX()) - * AngleAxisx(Scalar(0.2), Vector3::UnitY()) - * AngleAxisx(Scalar(0.3), Vector3::UnitZ()); - VERIFY_IS_APPROX(matrot1 * v1, - AngleAxisx(Scalar(0.1), Vector3(1,0,0)).toRotationMatrix() - * (AngleAxisx(Scalar(0.2), Vector3(0,1,0)).toRotationMatrix() - * (AngleAxisx(Scalar(0.3), Vector3(0,0,1)).toRotationMatrix() * v1))); - - // angle-axis conversion - AngleAxisx aa = q1; - VERIFY_IS_APPROX(q1 * v1, Quaternionx(aa) * v1); - VERIFY_IS_NOT_APPROX(q1 * v1, Quaternionx(AngleAxisx(aa.angle()*2,aa.axis())) * v1); - - // from two vector creation - VERIFY_IS_APPROX(v2.normalized(),(q2.setFromTwoVectors(v1,v2)*v1).normalized()); - VERIFY_IS_APPROX(v2.normalized(),(q2.setFromTwoVectors(v1,v2)*v1).normalized()); - - // inverse and conjugate - VERIFY_IS_APPROX(q1 * (q1.inverse() * v1), v1); - VERIFY_IS_APPROX(q1 * (q1.conjugate() * v1), v1); - - // AngleAxis - VERIFY_IS_APPROX(AngleAxisx(a,v1.normalized()).toRotationMatrix(), - Quaternionx(AngleAxisx(a,v1.normalized())).toRotationMatrix()); - - AngleAxisx aa1; - m = q1.toRotationMatrix(); - aa1 = m; - VERIFY_IS_APPROX(AngleAxisx(m).toRotationMatrix(), - Quaternionx(m).toRotationMatrix()); - - // Transform - // TODO complete the tests ! - a = 0; - while (ei_abs(a)(-Scalar(0.4)*Scalar(M_PI), Scalar(0.4)*Scalar(M_PI)); - q1 = AngleAxisx(a, v0.normalized()); - Transform3 t0, t1, t2; - // first test setIdentity() and Identity() - t0.setIdentity(); - VERIFY_IS_APPROX(t0.matrix(), Transform3::MatrixType::Identity()); - t0.matrix().setZero(); - t0 = Transform3::Identity(); - VERIFY_IS_APPROX(t0.matrix(), Transform3::MatrixType::Identity()); - - t0.linear() = q1.toRotationMatrix(); - t1.setIdentity(); - t1.linear() = q1.toRotationMatrix(); - - v0 << 50, 2, 1;//= ei_random_matrix().cwiseProduct(Vector3(10,2,0.5)); - t0.scale(v0); - t1.prescale(v0); - - VERIFY_IS_APPROX( (t0 * Vector3(1,0,0)).norm(), v0.x()); - //VERIFY(!ei_isApprox((t1 * Vector3(1,0,0)).norm(), v0.x())); - - t0.setIdentity(); - t1.setIdentity(); - v1 << 1, 2, 3; - t0.linear() = q1.toRotationMatrix(); - t0.pretranslate(v0); - t0.scale(v1); - t1.linear() = q1.conjugate().toRotationMatrix(); - t1.prescale(v1.cwise().inverse()); - t1.translate(-v0); - - VERIFY((t0.matrix() * t1.matrix()).isIdentity(test_precision())); - - t1.fromPositionOrientationScale(v0, q1, v1); - VERIFY_IS_APPROX(t1.matrix(), t0.matrix()); - VERIFY_IS_APPROX(t1*v1, t0*v1); - - t0.setIdentity(); t0.scale(v0).rotate(q1.toRotationMatrix()); - t1.setIdentity(); t1.scale(v0).rotate(q1); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - t0.setIdentity(); t0.scale(v0).rotate(AngleAxisx(q1)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - VERIFY_IS_APPROX(t0.scale(a).matrix(), t1.scale(Vector3::Constant(a)).matrix()); - VERIFY_IS_APPROX(t0.prescale(a).matrix(), t1.prescale(Vector3::Constant(a)).matrix()); - - // More transform constructors, operator=, operator*= - - Matrix3 mat3 = Matrix3::Random(); - Matrix4 mat4; - mat4 << mat3 , Vector3::Zero() , Vector4::Zero().transpose(); - Transform3 tmat3(mat3), tmat4(mat4); - tmat4.matrix()(3,3) = Scalar(1); - VERIFY_IS_APPROX(tmat3.matrix(), tmat4.matrix()); - - Scalar a3 = ei_random(-Scalar(M_PI), Scalar(M_PI)); - Vector3 v3 = Vector3::Random().normalized(); - AngleAxisx aa3(a3, v3); - Transform3 t3(aa3); - Transform3 t4; - t4 = aa3; - VERIFY_IS_APPROX(t3.matrix(), t4.matrix()); - t4.rotate(AngleAxisx(-a3,v3)); - VERIFY_IS_APPROX(t4.matrix(), Matrix4::Identity()); - t4 *= aa3; - VERIFY_IS_APPROX(t3.matrix(), t4.matrix()); - - v3 = Vector3::Random(); - Translation3 tv3(v3); - Transform3 t5(tv3); - t4 = tv3; - VERIFY_IS_APPROX(t5.matrix(), t4.matrix()); - t4.translate(-v3); - VERIFY_IS_APPROX(t4.matrix(), Matrix4::Identity()); - t4 *= tv3; - VERIFY_IS_APPROX(t5.matrix(), t4.matrix()); - - Scaling3 sv3(v3); - Transform3 t6(sv3); - t4 = sv3; - VERIFY_IS_APPROX(t6.matrix(), t4.matrix()); - t4.scale(v3.cwise().inverse()); - VERIFY_IS_APPROX(t4.matrix(), Matrix4::Identity()); - t4 *= sv3; - VERIFY_IS_APPROX(t6.matrix(), t4.matrix()); - - // matrix * transform - VERIFY_IS_APPROX(Transform3(t3.matrix()*t4).matrix(), Transform3(t3*t4).matrix()); - - // chained Transform product - VERIFY_IS_APPROX(((t3*t4)*t5).matrix(), (t3*(t4*t5)).matrix()); - - // check that Transform product doesn't have aliasing problems - t5 = t4; - t5 = t5*t5; - VERIFY_IS_APPROX(t5, t4*t4); - - // 2D transformation - Transform2 t20, t21; - Vector2 v20 = Vector2::Random(); - Vector2 v21 = Vector2::Random(); - for (int k=0; k<2; ++k) - if (ei_abs(v21[k])(a).toRotationMatrix(); - VERIFY_IS_APPROX(t20.fromPositionOrientationScale(v20,a,v21).matrix(), - t21.pretranslate(v20).scale(v21).matrix()); - - t21.setIdentity(); - t21.linear() = Rotation2D(-a).toRotationMatrix(); - VERIFY( (t20.fromPositionOrientationScale(v20,a,v21) - * (t21.prescale(v21.cwise().inverse()).translate(-v20))).matrix().isIdentity(test_precision()) ); - - // Transform - new API - // 3D - t0.setIdentity(); - t0.rotate(q1).scale(v0).translate(v0); - // mat * scaling and mat * translation - t1 = (Matrix3(q1) * Scaling3(v0)) * Translation3(v0); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - // mat * transformation and scaling * translation - t1 = Matrix3(q1) * (Scaling3(v0) * Translation3(v0)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - t0.setIdentity(); - t0.prerotate(q1).prescale(v0).pretranslate(v0); - // translation * scaling and transformation * mat - t1 = (Translation3(v0) * Scaling3(v0)) * Matrix3(q1); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - // scaling * mat and translation * mat - t1 = Translation3(v0) * (Scaling3(v0) * Matrix3(q1)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - t0.setIdentity(); - t0.scale(v0).translate(v0).rotate(q1); - // translation * mat and scaling * transformation - t1 = Scaling3(v0) * (Translation3(v0) * Matrix3(q1)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - // transformation * scaling - t0.scale(v0); - t1 = t1 * Scaling3(v0); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - // transformation * translation - t0.translate(v0); - t1 = t1 * Translation3(v0); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - // translation * transformation - t0.pretranslate(v0); - t1 = Translation3(v0) * t1; - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // transform * quaternion - t0.rotate(q1); - t1 = t1 * q1; - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // translation * quaternion - t0.translate(v1).rotate(q1); - t1 = t1 * (Translation3(v1) * q1); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // scaling * quaternion - t0.scale(v1).rotate(q1); - t1 = t1 * (Scaling3(v1) * q1); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // quaternion * transform - t0.prerotate(q1); - t1 = q1 * t1; - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // quaternion * translation - t0.rotate(q1).translate(v1); - t1 = t1 * (q1 * Translation3(v1)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // quaternion * scaling - t0.rotate(q1).scale(v1); - t1 = t1 * (q1 * Scaling3(v1)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // translation * vector - t0.setIdentity(); - t0.translate(v0); - VERIFY_IS_APPROX(t0 * v1, Translation3(v0) * v1); - - // scaling * vector - t0.setIdentity(); - t0.scale(v0); - VERIFY_IS_APPROX(t0 * v1, Scaling3(v0) * v1); - - // test transform inversion - t0.setIdentity(); - t0.translate(v0); - t0.linear().setRandom(); - VERIFY_IS_APPROX(t0.inverse(Affine), t0.matrix().inverse()); - t0.setIdentity(); - t0.translate(v0).rotate(q1); - VERIFY_IS_APPROX(t0.inverse(Isometry), t0.matrix().inverse()); - - // test extract rotation and scaling - t0.setIdentity(); - t0.translate(v0).rotate(q1).scale(v1); - VERIFY_IS_APPROX(t0.rotation() * v1, Matrix3(q1) * v1); - - Matrix3 mat_rotation, mat_scaling; - t0.setIdentity(); - t0.translate(v0).rotate(q1).scale(v1); - t0.computeRotationScaling(&mat_rotation, &mat_scaling); - VERIFY_IS_APPROX(t0.linear(), mat_rotation * mat_scaling); - VERIFY_IS_APPROX(mat_rotation*mat_rotation.adjoint(), Matrix3::Identity()); - VERIFY_IS_APPROX(mat_rotation.determinant(), Scalar(1)); - t0.computeScalingRotation(&mat_scaling, &mat_rotation); - VERIFY_IS_APPROX(t0.linear(), mat_scaling * mat_rotation); - VERIFY_IS_APPROX(mat_rotation*mat_rotation.adjoint(), Matrix3::Identity()); - VERIFY_IS_APPROX(mat_rotation.determinant(), Scalar(1)); - - // test casting - Transform t1f = t1.template cast(); - VERIFY_IS_APPROX(t1f.template cast(),t1); - Transform t1d = t1.template cast(); - VERIFY_IS_APPROX(t1d.template cast(),t1); - - Translation3 tr1(v0); - Translation tr1f = tr1.template cast(); - VERIFY_IS_APPROX(tr1f.template cast(),tr1); - Translation tr1d = tr1.template cast(); - VERIFY_IS_APPROX(tr1d.template cast(),tr1); - - Scaling3 sc1(v0); - Scaling sc1f = sc1.template cast(); - VERIFY_IS_APPROX(sc1f.template cast(),sc1); - Scaling sc1d = sc1.template cast(); - VERIFY_IS_APPROX(sc1d.template cast(),sc1); - - Quaternion q1f = q1.template cast(); - VERIFY_IS_APPROX(q1f.template cast(),q1); - Quaternion q1d = q1.template cast(); - VERIFY_IS_APPROX(q1d.template cast(),q1); - - AngleAxis aa1f = aa1.template cast(); - VERIFY_IS_APPROX(aa1f.template cast(),aa1); - AngleAxis aa1d = aa1.template cast(); - VERIFY_IS_APPROX(aa1d.template cast(),aa1); - - Rotation2D r2d1(ei_random()); - Rotation2D r2d1f = r2d1.template cast(); - VERIFY_IS_APPROX(r2d1f.template cast(),r2d1); - Rotation2D r2d1d = r2d1.template cast(); - VERIFY_IS_APPROX(r2d1d.template cast(),r2d1); - - m = q1; -// m.col(1) = Vector3(0,ei_random(),ei_random()).normalized(); -// m.col(0) = Vector3(-1,0,0).normalized(); -// m.col(2) = m.col(0).cross(m.col(1)); - #define VERIFY_EULER(I,J,K, X,Y,Z) { \ - Vector3 ea = m.eulerAngles(I,J,K); \ - Matrix3 m1 = Matrix3(AngleAxisx(ea[0], Vector3::Unit##X()) * AngleAxisx(ea[1], Vector3::Unit##Y()) * AngleAxisx(ea[2], Vector3::Unit##Z())); \ - VERIFY_IS_APPROX(m, m1); \ - VERIFY_IS_APPROX(m, Matrix3(AngleAxisx(ea[0], Vector3::Unit##X()) * AngleAxisx(ea[1], Vector3::Unit##Y()) * AngleAxisx(ea[2], Vector3::Unit##Z()))); \ - } - VERIFY_EULER(0,1,2, X,Y,Z); - VERIFY_EULER(0,1,0, X,Y,X); - VERIFY_EULER(0,2,1, X,Z,Y); - VERIFY_EULER(0,2,0, X,Z,X); - - VERIFY_EULER(1,2,0, Y,Z,X); - VERIFY_EULER(1,2,1, Y,Z,Y); - VERIFY_EULER(1,0,2, Y,X,Z); - VERIFY_EULER(1,0,1, Y,X,Y); - - VERIFY_EULER(2,0,1, Z,X,Y); - VERIFY_EULER(2,0,2, Z,X,Z); - VERIFY_EULER(2,1,0, Z,Y,X); - VERIFY_EULER(2,1,2, Z,Y,Z); - - // colwise/rowwise cross product - mat3.setRandom(); - Vector3 vec3 = Vector3::Random(); - Matrix3 mcross; - int i = ei_random(0,2); - mcross = mat3.colwise().cross(vec3); - VERIFY_IS_APPROX(mcross.col(i), mat3.col(i).cross(vec3)); - mcross = mat3.rowwise().cross(vec3); - VERIFY_IS_APPROX(mcross.row(i), mat3.row(i).cross(vec3)); - - -} - -void test_eigen2_geometry() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( geometry() ); - CALL_SUBTEST_2( geometry() ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_geometry_with_eigen2_prefix.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_geometry_with_eigen2_prefix.cpp deleted file mode 100644 index 12d4a71c..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_geometry_with_eigen2_prefix.cpp +++ /dev/null @@ -1,435 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#define EIGEN2_SUPPORT_STAGE15_RESOLVE_API_CONFLICTS_WARN - -#include "main.h" -#include -#include -#include - -template void geometry(void) -{ - /* this test covers the following files: - Cross.h Quaternion.h, Transform.cpp - */ - - typedef Matrix Matrix2; - typedef Matrix Matrix3; - typedef Matrix Matrix4; - typedef Matrix Vector2; - typedef Matrix Vector3; - typedef Matrix Vector4; - typedef eigen2_Quaternion Quaternionx; - typedef eigen2_AngleAxis AngleAxisx; - typedef eigen2_Transform Transform2; - typedef eigen2_Transform Transform3; - typedef eigen2_Scaling Scaling2; - typedef eigen2_Scaling Scaling3; - typedef eigen2_Translation Translation2; - typedef eigen2_Translation Translation3; - - Scalar largeEps = test_precision(); - if (ei_is_same_type::ret) - largeEps = 1e-2f; - - Vector3 v0 = Vector3::Random(), - v1 = Vector3::Random(), - v2 = Vector3::Random(); - Vector2 u0 = Vector2::Random(); - Matrix3 matrot1; - - Scalar a = ei_random(-Scalar(M_PI), Scalar(M_PI)); - - // cross product - VERIFY_IS_MUCH_SMALLER_THAN(v1.cross(v2).eigen2_dot(v1), Scalar(1)); - Matrix3 m; - m << v0.normalized(), - (v0.cross(v1)).normalized(), - (v0.cross(v1).cross(v0)).normalized(); - VERIFY(m.isUnitary()); - - // Quaternion: Identity(), setIdentity(); - Quaternionx q1, q2; - q2.setIdentity(); - VERIFY_IS_APPROX(Quaternionx(Quaternionx::Identity()).coeffs(), q2.coeffs()); - q1.coeffs().setRandom(); - VERIFY_IS_APPROX(q1.coeffs(), (q1*q2).coeffs()); - - // unitOrthogonal - VERIFY_IS_MUCH_SMALLER_THAN(u0.unitOrthogonal().eigen2_dot(u0), Scalar(1)); - VERIFY_IS_MUCH_SMALLER_THAN(v0.unitOrthogonal().eigen2_dot(v0), Scalar(1)); - VERIFY_IS_APPROX(u0.unitOrthogonal().norm(), Scalar(1)); - VERIFY_IS_APPROX(v0.unitOrthogonal().norm(), Scalar(1)); - - - VERIFY_IS_APPROX(v0, AngleAxisx(a, v0.normalized()) * v0); - VERIFY_IS_APPROX(-v0, AngleAxisx(Scalar(M_PI), v0.unitOrthogonal()) * v0); - VERIFY_IS_APPROX(ei_cos(a)*v0.squaredNorm(), v0.eigen2_dot(AngleAxisx(a, v0.unitOrthogonal()) * v0)); - m = AngleAxisx(a, v0.normalized()).toRotationMatrix().adjoint(); - VERIFY_IS_APPROX(Matrix3::Identity(), m * AngleAxisx(a, v0.normalized())); - VERIFY_IS_APPROX(Matrix3::Identity(), AngleAxisx(a, v0.normalized()) * m); - - q1 = AngleAxisx(a, v0.normalized()); - q2 = AngleAxisx(a, v1.normalized()); - - // angular distance - Scalar refangle = ei_abs(AngleAxisx(q1.inverse()*q2).angle()); - if (refangle>Scalar(M_PI)) - refangle = Scalar(2)*Scalar(M_PI) - refangle; - - if((q1.coeffs()-q2.coeffs()).norm() > 10*largeEps) - { - VERIFY(ei_isApprox(q1.angularDistance(q2), refangle, largeEps)); - } - - // rotation matrix conversion - VERIFY_IS_APPROX(q1 * v2, q1.toRotationMatrix() * v2); - VERIFY_IS_APPROX(q1 * q2 * v2, - q1.toRotationMatrix() * q2.toRotationMatrix() * v2); - - VERIFY( (q2*q1).isApprox(q1*q2, largeEps) || !(q2 * q1 * v2).isApprox( - q1.toRotationMatrix() * q2.toRotationMatrix() * v2)); - - q2 = q1.toRotationMatrix(); - VERIFY_IS_APPROX(q1*v1,q2*v1); - - matrot1 = AngleAxisx(Scalar(0.1), Vector3::UnitX()) - * AngleAxisx(Scalar(0.2), Vector3::UnitY()) - * AngleAxisx(Scalar(0.3), Vector3::UnitZ()); - VERIFY_IS_APPROX(matrot1 * v1, - AngleAxisx(Scalar(0.1), Vector3(1,0,0)).toRotationMatrix() - * (AngleAxisx(Scalar(0.2), Vector3(0,1,0)).toRotationMatrix() - * (AngleAxisx(Scalar(0.3), Vector3(0,0,1)).toRotationMatrix() * v1))); - - // angle-axis conversion - AngleAxisx aa = q1; - VERIFY_IS_APPROX(q1 * v1, Quaternionx(aa) * v1); - VERIFY_IS_NOT_APPROX(q1 * v1, Quaternionx(AngleAxisx(aa.angle()*2,aa.axis())) * v1); - - // from two vector creation - VERIFY_IS_APPROX(v2.normalized(),(q2.setFromTwoVectors(v1,v2)*v1).normalized()); - VERIFY_IS_APPROX(v2.normalized(),(q2.setFromTwoVectors(v1,v2)*v1).normalized()); - - // inverse and conjugate - VERIFY_IS_APPROX(q1 * (q1.inverse() * v1), v1); - VERIFY_IS_APPROX(q1 * (q1.conjugate() * v1), v1); - - // AngleAxis - VERIFY_IS_APPROX(AngleAxisx(a,v1.normalized()).toRotationMatrix(), - Quaternionx(AngleAxisx(a,v1.normalized())).toRotationMatrix()); - - AngleAxisx aa1; - m = q1.toRotationMatrix(); - aa1 = m; - VERIFY_IS_APPROX(AngleAxisx(m).toRotationMatrix(), - Quaternionx(m).toRotationMatrix()); - - // Transform - // TODO complete the tests ! - a = 0; - while (ei_abs(a)(-Scalar(0.4)*Scalar(M_PI), Scalar(0.4)*Scalar(M_PI)); - q1 = AngleAxisx(a, v0.normalized()); - Transform3 t0, t1, t2; - // first test setIdentity() and Identity() - t0.setIdentity(); - VERIFY_IS_APPROX(t0.matrix(), Transform3::MatrixType::Identity()); - t0.matrix().setZero(); - t0 = Transform3::Identity(); - VERIFY_IS_APPROX(t0.matrix(), Transform3::MatrixType::Identity()); - - t0.linear() = q1.toRotationMatrix(); - t1.setIdentity(); - t1.linear() = q1.toRotationMatrix(); - - v0 << 50, 2, 1;//= ei_random_matrix().cwiseProduct(Vector3(10,2,0.5)); - t0.scale(v0); - t1.prescale(v0); - - VERIFY_IS_APPROX( (t0 * Vector3(1,0,0)).norm(), v0.x()); - //VERIFY(!ei_isApprox((t1 * Vector3(1,0,0)).norm(), v0.x())); - - t0.setIdentity(); - t1.setIdentity(); - v1 << 1, 2, 3; - t0.linear() = q1.toRotationMatrix(); - t0.pretranslate(v0); - t0.scale(v1); - t1.linear() = q1.conjugate().toRotationMatrix(); - t1.prescale(v1.cwise().inverse()); - t1.translate(-v0); - - VERIFY((t0.matrix() * t1.matrix()).isIdentity(test_precision())); - - t1.fromPositionOrientationScale(v0, q1, v1); - VERIFY_IS_APPROX(t1.matrix(), t0.matrix()); - VERIFY_IS_APPROX(t1*v1, t0*v1); - - t0.setIdentity(); t0.scale(v0).rotate(q1.toRotationMatrix()); - t1.setIdentity(); t1.scale(v0).rotate(q1); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - t0.setIdentity(); t0.scale(v0).rotate(AngleAxisx(q1)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - VERIFY_IS_APPROX(t0.scale(a).matrix(), t1.scale(Vector3::Constant(a)).matrix()); - VERIFY_IS_APPROX(t0.prescale(a).matrix(), t1.prescale(Vector3::Constant(a)).matrix()); - - // More transform constructors, operator=, operator*= - - Matrix3 mat3 = Matrix3::Random(); - Matrix4 mat4; - mat4 << mat3 , Vector3::Zero() , Vector4::Zero().transpose(); - Transform3 tmat3(mat3), tmat4(mat4); - tmat4.matrix()(3,3) = Scalar(1); - VERIFY_IS_APPROX(tmat3.matrix(), tmat4.matrix()); - - Scalar a3 = ei_random(-Scalar(M_PI), Scalar(M_PI)); - Vector3 v3 = Vector3::Random().normalized(); - AngleAxisx aa3(a3, v3); - Transform3 t3(aa3); - Transform3 t4; - t4 = aa3; - VERIFY_IS_APPROX(t3.matrix(), t4.matrix()); - t4.rotate(AngleAxisx(-a3,v3)); - VERIFY_IS_APPROX(t4.matrix(), Matrix4::Identity()); - t4 *= aa3; - VERIFY_IS_APPROX(t3.matrix(), t4.matrix()); - - v3 = Vector3::Random(); - Translation3 tv3(v3); - Transform3 t5(tv3); - t4 = tv3; - VERIFY_IS_APPROX(t5.matrix(), t4.matrix()); - t4.translate(-v3); - VERIFY_IS_APPROX(t4.matrix(), Matrix4::Identity()); - t4 *= tv3; - VERIFY_IS_APPROX(t5.matrix(), t4.matrix()); - - Scaling3 sv3(v3); - Transform3 t6(sv3); - t4 = sv3; - VERIFY_IS_APPROX(t6.matrix(), t4.matrix()); - t4.scale(v3.cwise().inverse()); - VERIFY_IS_APPROX(t4.matrix(), Matrix4::Identity()); - t4 *= sv3; - VERIFY_IS_APPROX(t6.matrix(), t4.matrix()); - - // matrix * transform - VERIFY_IS_APPROX(Transform3(t3.matrix()*t4).matrix(), Transform3(t3*t4).matrix()); - - // chained Transform product - VERIFY_IS_APPROX(((t3*t4)*t5).matrix(), (t3*(t4*t5)).matrix()); - - // check that Transform product doesn't have aliasing problems - t5 = t4; - t5 = t5*t5; - VERIFY_IS_APPROX(t5, t4*t4); - - // 2D transformation - Transform2 t20, t21; - Vector2 v20 = Vector2::Random(); - Vector2 v21 = Vector2::Random(); - for (int k=0; k<2; ++k) - if (ei_abs(v21[k])(a).toRotationMatrix(); - VERIFY_IS_APPROX(t20.fromPositionOrientationScale(v20,a,v21).matrix(), - t21.pretranslate(v20).scale(v21).matrix()); - - t21.setIdentity(); - t21.linear() = Rotation2D(-a).toRotationMatrix(); - VERIFY( (t20.fromPositionOrientationScale(v20,a,v21) - * (t21.prescale(v21.cwise().inverse()).translate(-v20))).matrix().isIdentity(test_precision()) ); - - // Transform - new API - // 3D - t0.setIdentity(); - t0.rotate(q1).scale(v0).translate(v0); - // mat * scaling and mat * translation - t1 = (Matrix3(q1) * Scaling3(v0)) * Translation3(v0); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - // mat * transformation and scaling * translation - t1 = Matrix3(q1) * (Scaling3(v0) * Translation3(v0)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - t0.setIdentity(); - t0.prerotate(q1).prescale(v0).pretranslate(v0); - // translation * scaling and transformation * mat - t1 = (Translation3(v0) * Scaling3(v0)) * Matrix3(q1); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - // scaling * mat and translation * mat - t1 = Translation3(v0) * (Scaling3(v0) * Matrix3(q1)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - t0.setIdentity(); - t0.scale(v0).translate(v0).rotate(q1); - // translation * mat and scaling * transformation - t1 = Scaling3(v0) * (Translation3(v0) * Matrix3(q1)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - // transformation * scaling - t0.scale(v0); - t1 = t1 * Scaling3(v0); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - // transformation * translation - t0.translate(v0); - t1 = t1 * Translation3(v0); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - // translation * transformation - t0.pretranslate(v0); - t1 = Translation3(v0) * t1; - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // transform * quaternion - t0.rotate(q1); - t1 = t1 * q1; - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // translation * quaternion - t0.translate(v1).rotate(q1); - t1 = t1 * (Translation3(v1) * q1); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // scaling * quaternion - t0.scale(v1).rotate(q1); - t1 = t1 * (Scaling3(v1) * q1); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // quaternion * transform - t0.prerotate(q1); - t1 = q1 * t1; - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // quaternion * translation - t0.rotate(q1).translate(v1); - t1 = t1 * (q1 * Translation3(v1)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // quaternion * scaling - t0.rotate(q1).scale(v1); - t1 = t1 * (q1 * Scaling3(v1)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // translation * vector - t0.setIdentity(); - t0.translate(v0); - VERIFY_IS_APPROX(t0 * v1, Translation3(v0) * v1); - - // scaling * vector - t0.setIdentity(); - t0.scale(v0); - VERIFY_IS_APPROX(t0 * v1, Scaling3(v0) * v1); - - // test transform inversion - t0.setIdentity(); - t0.translate(v0); - t0.linear().setRandom(); - VERIFY_IS_APPROX(t0.inverse(Affine), t0.matrix().inverse()); - t0.setIdentity(); - t0.translate(v0).rotate(q1); - VERIFY_IS_APPROX(t0.inverse(Isometry), t0.matrix().inverse()); - - // test extract rotation and scaling - t0.setIdentity(); - t0.translate(v0).rotate(q1).scale(v1); - VERIFY_IS_APPROX(t0.rotation() * v1, Matrix3(q1) * v1); - - Matrix3 mat_rotation, mat_scaling; - t0.setIdentity(); - t0.translate(v0).rotate(q1).scale(v1); - t0.computeRotationScaling(&mat_rotation, &mat_scaling); - VERIFY_IS_APPROX(t0.linear(), mat_rotation * mat_scaling); - VERIFY_IS_APPROX(mat_rotation*mat_rotation.adjoint(), Matrix3::Identity()); - VERIFY_IS_APPROX(mat_rotation.determinant(), Scalar(1)); - t0.computeScalingRotation(&mat_scaling, &mat_rotation); - VERIFY_IS_APPROX(t0.linear(), mat_scaling * mat_rotation); - VERIFY_IS_APPROX(mat_rotation*mat_rotation.adjoint(), Matrix3::Identity()); - VERIFY_IS_APPROX(mat_rotation.determinant(), Scalar(1)); - - // test casting - eigen2_Transform t1f = t1.template cast(); - VERIFY_IS_APPROX(t1f.template cast(),t1); - eigen2_Transform t1d = t1.template cast(); - VERIFY_IS_APPROX(t1d.template cast(),t1); - - Translation3 tr1(v0); - eigen2_Translation tr1f = tr1.template cast(); - VERIFY_IS_APPROX(tr1f.template cast(),tr1); - eigen2_Translation tr1d = tr1.template cast(); - VERIFY_IS_APPROX(tr1d.template cast(),tr1); - - Scaling3 sc1(v0); - eigen2_Scaling sc1f = sc1.template cast(); - VERIFY_IS_APPROX(sc1f.template cast(),sc1); - eigen2_Scaling sc1d = sc1.template cast(); - VERIFY_IS_APPROX(sc1d.template cast(),sc1); - - eigen2_Quaternion q1f = q1.template cast(); - VERIFY_IS_APPROX(q1f.template cast(),q1); - eigen2_Quaternion q1d = q1.template cast(); - VERIFY_IS_APPROX(q1d.template cast(),q1); - - eigen2_AngleAxis aa1f = aa1.template cast(); - VERIFY_IS_APPROX(aa1f.template cast(),aa1); - eigen2_AngleAxis aa1d = aa1.template cast(); - VERIFY_IS_APPROX(aa1d.template cast(),aa1); - - eigen2_Rotation2D r2d1(ei_random()); - eigen2_Rotation2D r2d1f = r2d1.template cast(); - VERIFY_IS_APPROX(r2d1f.template cast(),r2d1); - eigen2_Rotation2D r2d1d = r2d1.template cast(); - VERIFY_IS_APPROX(r2d1d.template cast(),r2d1); - - m = q1; -// m.col(1) = Vector3(0,ei_random(),ei_random()).normalized(); -// m.col(0) = Vector3(-1,0,0).normalized(); -// m.col(2) = m.col(0).cross(m.col(1)); - #define VERIFY_EULER(I,J,K, X,Y,Z) { \ - Vector3 ea = m.eulerAngles(I,J,K); \ - Matrix3 m1 = Matrix3(AngleAxisx(ea[0], Vector3::Unit##X()) * AngleAxisx(ea[1], Vector3::Unit##Y()) * AngleAxisx(ea[2], Vector3::Unit##Z())); \ - VERIFY_IS_APPROX(m, m1); \ - VERIFY_IS_APPROX(m, Matrix3(AngleAxisx(ea[0], Vector3::Unit##X()) * AngleAxisx(ea[1], Vector3::Unit##Y()) * AngleAxisx(ea[2], Vector3::Unit##Z()))); \ - } - VERIFY_EULER(0,1,2, X,Y,Z); - VERIFY_EULER(0,1,0, X,Y,X); - VERIFY_EULER(0,2,1, X,Z,Y); - VERIFY_EULER(0,2,0, X,Z,X); - - VERIFY_EULER(1,2,0, Y,Z,X); - VERIFY_EULER(1,2,1, Y,Z,Y); - VERIFY_EULER(1,0,2, Y,X,Z); - VERIFY_EULER(1,0,1, Y,X,Y); - - VERIFY_EULER(2,0,1, Z,X,Y); - VERIFY_EULER(2,0,2, Z,X,Z); - VERIFY_EULER(2,1,0, Z,Y,X); - VERIFY_EULER(2,1,2, Z,Y,Z); - - // colwise/rowwise cross product - mat3.setRandom(); - Vector3 vec3 = Vector3::Random(); - Matrix3 mcross; - int i = ei_random(0,2); - mcross = mat3.colwise().cross(vec3); - VERIFY_IS_APPROX(mcross.col(i), mat3.col(i).cross(vec3)); - mcross = mat3.rowwise().cross(vec3); - VERIFY_IS_APPROX(mcross.row(i), mat3.row(i).cross(vec3)); - - -} - -void test_eigen2_geometry_with_eigen2_prefix() -{ - std::cout << "eigen2 support: " << EIGEN2_SUPPORT_STAGE << std::endl; - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( geometry() ); - CALL_SUBTEST_2( geometry() ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_hyperplane.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_hyperplane.cpp deleted file mode 100644 index f3f85e14..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_hyperplane.cpp +++ /dev/null @@ -1,126 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include -#include -#include - -template void hyperplane(const HyperplaneType& _plane) -{ - /* this test covers the following files: - Hyperplane.h - */ - - const int dim = _plane.dim(); - typedef typename HyperplaneType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix VectorType; - typedef Matrix MatrixType; - - VectorType p0 = VectorType::Random(dim); - VectorType p1 = VectorType::Random(dim); - - VectorType n0 = VectorType::Random(dim).normalized(); - VectorType n1 = VectorType::Random(dim).normalized(); - - HyperplaneType pl0(n0, p0); - HyperplaneType pl1(n1, p1); - HyperplaneType pl2 = pl1; - - Scalar s0 = ei_random(); - Scalar s1 = ei_random(); - - VERIFY_IS_APPROX( n1.eigen2_dot(n1), Scalar(1) ); - - VERIFY_IS_MUCH_SMALLER_THAN( pl0.absDistance(p0), Scalar(1) ); - VERIFY_IS_APPROX( pl1.signedDistance(p1 + n1 * s0), s0 ); - VERIFY_IS_MUCH_SMALLER_THAN( pl1.signedDistance(pl1.projection(p0)), Scalar(1) ); - VERIFY_IS_MUCH_SMALLER_THAN( pl1.absDistance(p1 + pl1.normal().unitOrthogonal() * s1), Scalar(1) ); - - // transform - if (!NumTraits::IsComplex) - { - MatrixType rot = MatrixType::Random(dim,dim).qr().matrixQ(); - Scaling scaling(VectorType::Random()); - Translation translation(VectorType::Random()); - - pl2 = pl1; - VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot).absDistance(rot * p1), Scalar(1) ); - pl2 = pl1; - VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot,Isometry).absDistance(rot * p1), Scalar(1) ); - pl2 = pl1; - VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot*scaling).absDistance((rot*scaling) * p1), Scalar(1) ); - pl2 = pl1; - VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot*scaling*translation) - .absDistance((rot*scaling*translation) * p1), Scalar(1) ); - pl2 = pl1; - VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot*translation,Isometry) - .absDistance((rot*translation) * p1), Scalar(1) ); - } - - // casting - const int Dim = HyperplaneType::AmbientDimAtCompileTime; - typedef typename GetDifferentType::type OtherScalar; - Hyperplane hp1f = pl1.template cast(); - VERIFY_IS_APPROX(hp1f.template cast(),pl1); - Hyperplane hp1d = pl1.template cast(); - VERIFY_IS_APPROX(hp1d.template cast(),pl1); -} - -template void lines() -{ - typedef Hyperplane HLine; - typedef ParametrizedLine PLine; - typedef Matrix Vector; - typedef Matrix CoeffsType; - - for(int i = 0; i < 10; i++) - { - Vector center = Vector::Random(); - Vector u = Vector::Random(); - Vector v = Vector::Random(); - Scalar a = ei_random(); - while (ei_abs(a-1) < 1e-4) a = ei_random(); - while (u.norm() < 1e-4) u = Vector::Random(); - while (v.norm() < 1e-4) v = Vector::Random(); - - HLine line_u = HLine::Through(center + u, center + a*u); - HLine line_v = HLine::Through(center + v, center + a*v); - - // the line equations should be normalized so that a^2+b^2=1 - VERIFY_IS_APPROX(line_u.normal().norm(), Scalar(1)); - VERIFY_IS_APPROX(line_v.normal().norm(), Scalar(1)); - - Vector result = line_u.intersection(line_v); - - // the lines should intersect at the point we called "center" - VERIFY_IS_APPROX(result, center); - - // check conversions between two types of lines - PLine pl(line_u); // gcc 3.3 will commit suicide if we don't name this variable - CoeffsType converted_coeffs(HLine(pl).coeffs()); - converted_coeffs *= line_u.coeffs()(0)/converted_coeffs(0); - VERIFY(line_u.coeffs().isApprox(converted_coeffs)); - } -} - -void test_eigen2_hyperplane() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( hyperplane(Hyperplane()) ); - CALL_SUBTEST_2( hyperplane(Hyperplane()) ); - CALL_SUBTEST_3( hyperplane(Hyperplane()) ); - CALL_SUBTEST_4( hyperplane(Hyperplane,5>()) ); - CALL_SUBTEST_5( lines() ); - CALL_SUBTEST_6( lines() ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_inverse.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_inverse.cpp deleted file mode 100644 index ccd24a19..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_inverse.cpp +++ /dev/null @@ -1,62 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include - -template void inverse(const MatrixType& m) -{ - /* this test covers the following files: - Inverse.h - */ - int rows = m.rows(); - int cols = m.cols(); - - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix VectorType; - - MatrixType m1 = MatrixType::Random(rows, cols), - m2(rows, cols), - identity = MatrixType::Identity(rows, rows); - - while(ei_abs(m1.determinant()) < RealScalar(0.1) && rows <= 8) - { - m1 = MatrixType::Random(rows, cols); - } - - m2 = m1.inverse(); - VERIFY_IS_APPROX(m1, m2.inverse() ); - - m1.computeInverse(&m2); - VERIFY_IS_APPROX(m1, m2.inverse() ); - - VERIFY_IS_APPROX((Scalar(2)*m2).inverse(), m2.inverse()*Scalar(0.5)); - - VERIFY_IS_APPROX(identity, m1.inverse() * m1 ); - VERIFY_IS_APPROX(identity, m1 * m1.inverse() ); - - VERIFY_IS_APPROX(m1, m1.inverse().inverse() ); - - // since for the general case we implement separately row-major and col-major, test that - VERIFY_IS_APPROX(m1.transpose().inverse(), m1.inverse().transpose()); -} - -void test_eigen2_inverse() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( inverse(Matrix()) ); - CALL_SUBTEST_2( inverse(Matrix2d()) ); - CALL_SUBTEST_3( inverse(Matrix3f()) ); - CALL_SUBTEST_4( inverse(Matrix4f()) ); - CALL_SUBTEST_5( inverse(MatrixXf(8,8)) ); - CALL_SUBTEST_6( inverse(MatrixXcd(7,7)) ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_linearstructure.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_linearstructure.cpp deleted file mode 100644 index 488f4c48..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_linearstructure.cpp +++ /dev/null @@ -1,83 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template void linearStructure(const MatrixType& m) -{ - /* this test covers the following files: - Sum.h Difference.h Opposite.h ScalarMultiple.h - */ - - typedef typename MatrixType::Scalar Scalar; - typedef Matrix VectorType; - - int rows = m.rows(); - int cols = m.cols(); - - // this test relies a lot on Random.h, and there's not much more that we can do - // to test it, hence I consider that we will have tested Random.h - MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols), - m3(rows, cols); - - Scalar s1 = ei_random(); - while (ei_abs(s1)<1e-3) s1 = ei_random(); - - int r = ei_random(0, rows-1), - c = ei_random(0, cols-1); - - VERIFY_IS_APPROX(-(-m1), m1); - VERIFY_IS_APPROX(m1+m1, 2*m1); - VERIFY_IS_APPROX(m1+m2-m1, m2); - VERIFY_IS_APPROX(-m2+m1+m2, m1); - VERIFY_IS_APPROX(m1*s1, s1*m1); - VERIFY_IS_APPROX((m1+m2)*s1, s1*m1+s1*m2); - VERIFY_IS_APPROX((-m1+m2)*s1, -s1*m1+s1*m2); - m3 = m2; m3 += m1; - VERIFY_IS_APPROX(m3, m1+m2); - m3 = m2; m3 -= m1; - VERIFY_IS_APPROX(m3, m2-m1); - m3 = m2; m3 *= s1; - VERIFY_IS_APPROX(m3, s1*m2); - if(NumTraits::HasFloatingPoint) - { - m3 = m2; m3 /= s1; - VERIFY_IS_APPROX(m3, m2/s1); - } - - // again, test operator() to check const-qualification - VERIFY_IS_APPROX((-m1)(r,c), -(m1(r,c))); - VERIFY_IS_APPROX((m1-m2)(r,c), (m1(r,c))-(m2(r,c))); - VERIFY_IS_APPROX((m1+m2)(r,c), (m1(r,c))+(m2(r,c))); - VERIFY_IS_APPROX((s1*m1)(r,c), s1*(m1(r,c))); - VERIFY_IS_APPROX((m1*s1)(r,c), (m1(r,c))*s1); - if(NumTraits::HasFloatingPoint) - VERIFY_IS_APPROX((m1/s1)(r,c), (m1(r,c))/s1); - - // use .block to disable vectorization and compare to the vectorized version - VERIFY_IS_APPROX(m1+m1.block(0,0,rows,cols), m1+m1); - VERIFY_IS_APPROX(m1.cwise() * m1.block(0,0,rows,cols), m1.cwise() * m1); - VERIFY_IS_APPROX(m1 - m1.block(0,0,rows,cols), m1 - m1); - VERIFY_IS_APPROX(m1.block(0,0,rows,cols) * s1, m1 * s1); -} - -void test_eigen2_linearstructure() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( linearStructure(Matrix()) ); - CALL_SUBTEST_2( linearStructure(Matrix2f()) ); - CALL_SUBTEST_3( linearStructure(Vector3d()) ); - CALL_SUBTEST_4( linearStructure(Matrix4d()) ); - CALL_SUBTEST_5( linearStructure(MatrixXcf(3, 3)) ); - CALL_SUBTEST_6( linearStructure(MatrixXf(8, 12)) ); - CALL_SUBTEST_7( linearStructure(MatrixXi(8, 12)) ); - CALL_SUBTEST_8( linearStructure(MatrixXcd(20, 20)) ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_lu.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_lu.cpp deleted file mode 100644 index e993b1c7..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_lu.cpp +++ /dev/null @@ -1,122 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include - -template -void doSomeRankPreservingOperations(Eigen::MatrixBase& m) -{ - typedef typename Derived::RealScalar RealScalar; - for(int a = 0; a < 3*(m.rows()+m.cols()); a++) - { - RealScalar d = Eigen::ei_random(-1,1); - int i = Eigen::ei_random(0,m.rows()-1); // i is a random row number - int j; - do { - j = Eigen::ei_random(0,m.rows()-1); - } while (i==j); // j is another one (must be different) - m.row(i) += d * m.row(j); - - i = Eigen::ei_random(0,m.cols()-1); // i is a random column number - do { - j = Eigen::ei_random(0,m.cols()-1); - } while (i==j); // j is another one (must be different) - m.col(i) += d * m.col(j); - } -} - -template void lu_non_invertible() -{ - /* this test covers the following files: - LU.h - */ - // NOTE there seems to be a problem with too small sizes -- could easily lie in the doSomeRankPreservingOperations function - int rows = ei_random(20,200), cols = ei_random(20,200), cols2 = ei_random(20,200); - int rank = ei_random(1, std::min(rows, cols)-1); - - MatrixType m1(rows, cols), m2(cols, cols2), m3(rows, cols2), k(1,1); - m1 = MatrixType::Random(rows,cols); - if(rows <= cols) - for(int i = rank; i < rows; i++) m1.row(i).setZero(); - else - for(int i = rank; i < cols; i++) m1.col(i).setZero(); - doSomeRankPreservingOperations(m1); - - LU lu(m1); - typename LU::KernelResultType m1kernel = lu.kernel(); - typename LU::ImageResultType m1image = lu.image(); - - VERIFY(rank == lu.rank()); - VERIFY(cols - lu.rank() == lu.dimensionOfKernel()); - VERIFY(!lu.isInjective()); - VERIFY(!lu.isInvertible()); - VERIFY(lu.isSurjective() == (lu.rank() == rows)); - VERIFY((m1 * m1kernel).isMuchSmallerThan(m1)); - VERIFY(m1image.lu().rank() == rank); - MatrixType sidebyside(m1.rows(), m1.cols() + m1image.cols()); - sidebyside << m1, m1image; - VERIFY(sidebyside.lu().rank() == rank); - m2 = MatrixType::Random(cols,cols2); - m3 = m1*m2; - m2 = MatrixType::Random(cols,cols2); - lu.solve(m3, &m2); - VERIFY_IS_APPROX(m3, m1*m2); - /* solve now always returns true - m3 = MatrixType::Random(rows,cols2); - VERIFY(!lu.solve(m3, &m2)); - */ -} - -template void lu_invertible() -{ - /* this test covers the following files: - LU.h - */ - typedef typename NumTraits::Real RealScalar; - int size = ei_random(10,200); - - MatrixType m1(size, size), m2(size, size), m3(size, size); - m1 = MatrixType::Random(size,size); - - if (ei_is_same_type::ret) - { - // let's build a matrix more stable to inverse - MatrixType a = MatrixType::Random(size,size*2); - m1 += a * a.adjoint(); - } - - LU lu(m1); - VERIFY(0 == lu.dimensionOfKernel()); - VERIFY(size == lu.rank()); - VERIFY(lu.isInjective()); - VERIFY(lu.isSurjective()); - VERIFY(lu.isInvertible()); - VERIFY(lu.image().lu().isInvertible()); - m3 = MatrixType::Random(size,size); - lu.solve(m3, &m2); - VERIFY_IS_APPROX(m3, m1*m2); - VERIFY_IS_APPROX(m2, lu.inverse()*m3); - m3 = MatrixType::Random(size,size); - VERIFY(lu.solve(m3, &m2)); -} - -void test_eigen2_lu() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( lu_non_invertible() ); - CALL_SUBTEST_2( lu_non_invertible() ); - CALL_SUBTEST_3( lu_non_invertible() ); - CALL_SUBTEST_4( lu_non_invertible() ); - CALL_SUBTEST_1( lu_invertible() ); - CALL_SUBTEST_2( lu_invertible() ); - CALL_SUBTEST_3( lu_invertible() ); - CALL_SUBTEST_4( lu_invertible() ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_map.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_map.cpp deleted file mode 100644 index 4a1c4e11..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_map.cpp +++ /dev/null @@ -1,114 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2007-2010 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template void map_class_vector(const VectorType& m) -{ - typedef typename VectorType::Scalar Scalar; - - int size = m.size(); - - // test Map.h - Scalar* array1 = ei_aligned_new(size); - Scalar* array2 = ei_aligned_new(size); - Scalar* array3 = new Scalar[size+1]; - Scalar* array3unaligned = std::size_t(array3)%16 == 0 ? array3+1 : array3; - - Map(array1, size) = VectorType::Random(size); - Map(array2, size) = Map(array1, size); - Map(array3unaligned, size) = Map((const Scalar*)array1, size); // test non-const-correctness support in eigen2 - VectorType ma1 = Map(array1, size); - VectorType ma2 = Map(array2, size); - VectorType ma3 = Map(array3unaligned, size); - VERIFY_IS_APPROX(ma1, ma2); - VERIFY_IS_APPROX(ma1, ma3); - - ei_aligned_delete(array1, size); - ei_aligned_delete(array2, size); - delete[] array3; -} - -template void map_class_matrix(const MatrixType& m) -{ - typedef typename MatrixType::Scalar Scalar; - - int rows = m.rows(), cols = m.cols(), size = rows*cols; - - // test Map.h - Scalar* array1 = ei_aligned_new(size); - for(int i = 0; i < size; i++) array1[i] = Scalar(1); - Scalar* array2 = ei_aligned_new(size); - for(int i = 0; i < size; i++) array2[i] = Scalar(1); - Scalar* array3 = new Scalar[size+1]; - for(int i = 0; i < size+1; i++) array3[i] = Scalar(1); - Scalar* array3unaligned = std::size_t(array3)%16 == 0 ? array3+1 : array3; - Map(array1, rows, cols) = MatrixType::Ones(rows,cols); - Map(array2, rows, cols) = Map((const Scalar*)array1, rows, cols); // test non-const-correctness support in eigen2 - Map(array3unaligned, rows, cols) = Map(array1, rows, cols); - MatrixType ma1 = Map(array1, rows, cols); - MatrixType ma2 = Map(array2, rows, cols); - VERIFY_IS_APPROX(ma1, ma2); - MatrixType ma3 = Map(array3unaligned, rows, cols); - VERIFY_IS_APPROX(ma1, ma3); - - ei_aligned_delete(array1, size); - ei_aligned_delete(array2, size); - delete[] array3; -} - -template void map_static_methods(const VectorType& m) -{ - typedef typename VectorType::Scalar Scalar; - - int size = m.size(); - - // test Map.h - Scalar* array1 = ei_aligned_new(size); - Scalar* array2 = ei_aligned_new(size); - Scalar* array3 = new Scalar[size+1]; - Scalar* array3unaligned = std::size_t(array3)%16 == 0 ? array3+1 : array3; - - VectorType::MapAligned(array1, size) = VectorType::Random(size); - VectorType::Map(array2, size) = VectorType::Map(array1, size); - VectorType::Map(array3unaligned, size) = VectorType::Map(array1, size); - VectorType ma1 = VectorType::Map(array1, size); - VectorType ma2 = VectorType::MapAligned(array2, size); - VectorType ma3 = VectorType::Map(array3unaligned, size); - VERIFY_IS_APPROX(ma1, ma2); - VERIFY_IS_APPROX(ma1, ma3); - - ei_aligned_delete(array1, size); - ei_aligned_delete(array2, size); - delete[] array3; -} - - -void test_eigen2_map() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( map_class_vector(Matrix()) ); - CALL_SUBTEST_2( map_class_vector(Vector4d()) ); - CALL_SUBTEST_3( map_class_vector(RowVector4f()) ); - CALL_SUBTEST_4( map_class_vector(VectorXcf(8)) ); - CALL_SUBTEST_5( map_class_vector(VectorXi(12)) ); - - CALL_SUBTEST_1( map_class_matrix(Matrix()) ); - CALL_SUBTEST_2( map_class_matrix(Matrix4d()) ); - CALL_SUBTEST_6( map_class_matrix(Matrix()) ); - CALL_SUBTEST_4( map_class_matrix(MatrixXcf(ei_random(1,10),ei_random(1,10))) ); - CALL_SUBTEST_5( map_class_matrix(MatrixXi(ei_random(1,10),ei_random(1,10))) ); - - CALL_SUBTEST_1( map_static_methods(Matrix()) ); - CALL_SUBTEST_2( map_static_methods(Vector3f()) ); - CALL_SUBTEST_7( map_static_methods(RowVector3d()) ); - CALL_SUBTEST_4( map_static_methods(VectorXcd(8)) ); - CALL_SUBTEST_5( map_static_methods(VectorXf(12)) ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_meta.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_meta.cpp deleted file mode 100644 index 1d01bd84..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_meta.cpp +++ /dev/null @@ -1,60 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -void test_eigen2_meta() -{ - typedef float & FloatRef; - typedef const float & ConstFloatRef; - - VERIFY((ei_meta_if<(3<4),ei_meta_true, ei_meta_false>::ret::ret)); - VERIFY(( ei_is_same_type::ret)); - VERIFY((!ei_is_same_type::ret)); - VERIFY((!ei_is_same_type::ret)); - VERIFY((!ei_is_same_type::ret)); - - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - - VERIFY(ei_meta_sqrt<1>::ret == 1); - #define VERIFY_META_SQRT(X) VERIFY(ei_meta_sqrt::ret == int(ei_sqrt(double(X)))) - VERIFY_META_SQRT(2); - VERIFY_META_SQRT(3); - VERIFY_META_SQRT(4); - VERIFY_META_SQRT(5); - VERIFY_META_SQRT(6); - VERIFY_META_SQRT(8); - VERIFY_META_SQRT(9); - VERIFY_META_SQRT(15); - VERIFY_META_SQRT(16); - VERIFY_META_SQRT(17); - VERIFY_META_SQRT(255); - VERIFY_META_SQRT(256); - VERIFY_META_SQRT(257); - VERIFY_META_SQRT(1023); - VERIFY_META_SQRT(1024); - VERIFY_META_SQRT(1025); -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_miscmatrices.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_miscmatrices.cpp deleted file mode 100644 index 8bbb20cc..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_miscmatrices.cpp +++ /dev/null @@ -1,48 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template void miscMatrices(const MatrixType& m) -{ - /* this test covers the following files: - DiagonalMatrix.h Ones.h - */ - - typedef typename MatrixType::Scalar Scalar; - typedef Matrix VectorType; - typedef Matrix RowVectorType; - int rows = m.rows(); - int cols = m.cols(); - - int r = ei_random(0, rows-1), r2 = ei_random(0, rows-1), c = ei_random(0, cols-1); - VERIFY_IS_APPROX(MatrixType::Ones(rows,cols)(r,c), static_cast(1)); - MatrixType m1 = MatrixType::Ones(rows,cols); - VERIFY_IS_APPROX(m1(r,c), static_cast(1)); - VectorType v1 = VectorType::Random(rows); - v1[0]; - Matrix - square = v1.asDiagonal(); - if(r==r2) VERIFY_IS_APPROX(square(r,r2), v1[r]); - else VERIFY_IS_MUCH_SMALLER_THAN(square(r,r2), static_cast(1)); - square = MatrixType::Zero(rows, rows); - square.diagonal() = VectorType::Ones(rows); - VERIFY_IS_APPROX(square, MatrixType::Identity(rows, rows)); -} - -void test_eigen2_miscmatrices() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( miscMatrices(Matrix()) ); - CALL_SUBTEST_2( miscMatrices(Matrix4d()) ); - CALL_SUBTEST_3( miscMatrices(MatrixXcf(3, 3)) ); - CALL_SUBTEST_4( miscMatrices(MatrixXi(8, 12)) ); - CALL_SUBTEST_5( miscMatrices(MatrixXcd(20, 20)) ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_mixingtypes.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_mixingtypes.cpp deleted file mode 100644 index fb5ac5dd..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_mixingtypes.cpp +++ /dev/null @@ -1,77 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#ifndef EIGEN_NO_STATIC_ASSERT -#define EIGEN_NO_STATIC_ASSERT // turn static asserts into runtime asserts in order to check them -#endif - -#ifndef EIGEN_DONT_VECTORIZE -#define EIGEN_DONT_VECTORIZE // SSE intrinsics aren't designed to allow mixing types -#endif - -#include "main.h" - - -template void mixingtypes(int size = SizeAtCompileType) -{ - typedef Matrix Mat_f; - typedef Matrix Mat_d; - typedef Matrix, SizeAtCompileType, SizeAtCompileType> Mat_cf; - typedef Matrix, SizeAtCompileType, SizeAtCompileType> Mat_cd; - typedef Matrix Vec_f; - typedef Matrix Vec_d; - typedef Matrix, SizeAtCompileType, 1> Vec_cf; - typedef Matrix, SizeAtCompileType, 1> Vec_cd; - - Mat_f mf(size,size); - Mat_d md(size,size); - Mat_cf mcf(size,size); - Mat_cd mcd(size,size); - Vec_f vf(size,1); - Vec_d vd(size,1); - Vec_cf vcf(size,1); - Vec_cd vcd(size,1); - - mf+mf; - VERIFY_RAISES_ASSERT(mf+md); - VERIFY_RAISES_ASSERT(mf+mcf); - VERIFY_RAISES_ASSERT(vf=vd); - VERIFY_RAISES_ASSERT(vf+=vd); - VERIFY_RAISES_ASSERT(mcd=md); - - mf*mf; - md*mcd; - mcd*md; - mf*vcf; - mcf*vf; - mcf *= mf; - vcd = md*vcd; - vcf = mcf*vf; -#if 0 - // these are know generating hard build errors in eigen3 - VERIFY_RAISES_ASSERT(mf*md); - VERIFY_RAISES_ASSERT(mcf*mcd); - VERIFY_RAISES_ASSERT(mcf*vcd); - VERIFY_RAISES_ASSERT(vcf = mf*vf); - - vf.eigen2_dot(vf); - VERIFY_RAISES_ASSERT(vd.eigen2_dot(vf)); - VERIFY_RAISES_ASSERT(vcf.eigen2_dot(vf)); // yeah eventually we should allow this but i'm too lazy to make that change now in Dot.h - // especially as that might be rewritten as cwise product .sum() which would make that automatic. -#endif -} - -void test_eigen2_mixingtypes() -{ - // check that our operator new is indeed called: - CALL_SUBTEST_1(mixingtypes<3>()); - CALL_SUBTEST_2(mixingtypes<4>()); - CALL_SUBTEST_3(mixingtypes(20)); -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_nomalloc.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_nomalloc.cpp deleted file mode 100644 index d34a6999..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_nomalloc.cpp +++ /dev/null @@ -1,53 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -// this hack is needed to make this file compiles with -pedantic (gcc) -#ifdef __GNUC__ -#define throw(X) -#endif -// discard stack allocation as that too bypasses malloc -#define EIGEN_STACK_ALLOCATION_LIMIT 0 -// any heap allocation will raise an assert -#define EIGEN_NO_MALLOC - -#include "main.h" - -template void nomalloc(const MatrixType& m) -{ - /* this test check no dynamic memory allocation are issued with fixed-size matrices - */ - - typedef typename MatrixType::Scalar Scalar; - - int rows = m.rows(); - int cols = m.cols(); - - MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols); - - Scalar s1 = ei_random(); - - int r = ei_random(0, rows-1), - c = ei_random(0, cols-1); - - VERIFY_IS_APPROX((m1+m2)*s1, s1*m1+s1*m2); - VERIFY_IS_APPROX((m1+m2)(r,c), (m1(r,c))+(m2(r,c))); - VERIFY_IS_APPROX(m1.cwise() * m1.block(0,0,rows,cols), m1.cwise() * m1); - VERIFY_IS_APPROX((m1*m1.transpose())*m2, m1*(m1.transpose()*m2)); -} - -void test_eigen2_nomalloc() -{ - // check that our operator new is indeed called: - VERIFY_RAISES_ASSERT(MatrixXd dummy = MatrixXd::Random(3,3)); - CALL_SUBTEST_1( nomalloc(Matrix()) ); - CALL_SUBTEST_2( nomalloc(Matrix4d()) ); - CALL_SUBTEST_3( nomalloc(Matrix()) ); -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_packetmath.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_packetmath.cpp deleted file mode 100644 index b1f325fe..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_packetmath.cpp +++ /dev/null @@ -1,132 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -// using namespace Eigen; - -template bool areApprox(const Scalar* a, const Scalar* b, int size) -{ - for (int i=0; i const complex& min(const complex& a, const complex& b) -{ return a.real() < b.real() ? a : b; } - -template<> const complex& max(const complex& a, const complex& b) -{ return a.real() < b.real() ? b : a; } - -} - -template void packetmath() -{ - typedef typename ei_packet_traits::type Packet; - const int PacketSize = ei_packet_traits::size; - - const int size = PacketSize*4; - EIGEN_ALIGN_128 Scalar data1[ei_packet_traits::size*4]; - EIGEN_ALIGN_128 Scalar data2[ei_packet_traits::size*4]; - EIGEN_ALIGN_128 Packet packets[PacketSize*2]; - EIGEN_ALIGN_128 Scalar ref[ei_packet_traits::size*4]; - for (int i=0; i(); - data2[i] = ei_random(); - } - - ei_pstore(data2, ei_pload(data1)); - VERIFY(areApprox(data1, data2, PacketSize) && "aligned load/store"); - - for (int offset=0; offset(packets[0], packets[1]); - else if (offset==1) ei_palign<1>(packets[0], packets[1]); - else if (offset==2) ei_palign<2>(packets[0], packets[1]); - else if (offset==3) ei_palign<3>(packets[0], packets[1]); - ei_pstore(data2, packets[0]); - - for (int i=0; i Vector; - VERIFY(areApprox(ref, data2, PacketSize) && "ei_palign"); - } - - CHECK_CWISE(REF_ADD, ei_padd); - CHECK_CWISE(REF_SUB, ei_psub); - CHECK_CWISE(REF_MUL, ei_pmul); - #ifndef EIGEN_VECTORIZE_ALTIVEC - if (!ei_is_same_type::ret) - CHECK_CWISE(REF_DIV, ei_pdiv); - #endif - CHECK_CWISE(std::min, ei_pmin); - CHECK_CWISE(std::max, ei_pmax); - - for (int i=0; i() ); - CALL_SUBTEST_2( packetmath() ); - CALL_SUBTEST_3( packetmath() ); - CALL_SUBTEST_4( packetmath >() ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_parametrizedline.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_parametrizedline.cpp deleted file mode 100644 index 81472887..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_parametrizedline.cpp +++ /dev/null @@ -1,62 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include -#include -#include - -template void parametrizedline(const LineType& _line) -{ - /* this test covers the following files: - ParametrizedLine.h - */ - - const int dim = _line.dim(); - typedef typename LineType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix VectorType; - typedef Matrix MatrixType; - - VectorType p0 = VectorType::Random(dim); - VectorType p1 = VectorType::Random(dim); - - VectorType d0 = VectorType::Random(dim).normalized(); - - LineType l0(p0, d0); - - Scalar s0 = ei_random(); - Scalar s1 = ei_abs(ei_random()); - - VERIFY_IS_MUCH_SMALLER_THAN( l0.distance(p0), RealScalar(1) ); - VERIFY_IS_MUCH_SMALLER_THAN( l0.distance(p0+s0*d0), RealScalar(1) ); - VERIFY_IS_APPROX( (l0.projection(p1)-p1).norm(), l0.distance(p1) ); - VERIFY_IS_MUCH_SMALLER_THAN( l0.distance(l0.projection(p1)), RealScalar(1) ); - VERIFY_IS_APPROX( Scalar(l0.distance((p0+s0*d0) + d0.unitOrthogonal() * s1)), s1 ); - - // casting - const int Dim = LineType::AmbientDimAtCompileTime; - typedef typename GetDifferentType::type OtherScalar; - ParametrizedLine hp1f = l0.template cast(); - VERIFY_IS_APPROX(hp1f.template cast(),l0); - ParametrizedLine hp1d = l0.template cast(); - VERIFY_IS_APPROX(hp1d.template cast(),l0); -} - -void test_eigen2_parametrizedline() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( parametrizedline(ParametrizedLine()) ); - CALL_SUBTEST_2( parametrizedline(ParametrizedLine()) ); - CALL_SUBTEST_3( parametrizedline(ParametrizedLine()) ); - CALL_SUBTEST_4( parametrizedline(ParametrizedLine,5>()) ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_prec_inverse_4x4.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_prec_inverse_4x4.cpp deleted file mode 100644 index 8bfa5569..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_prec_inverse_4x4.cpp +++ /dev/null @@ -1,84 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2009 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include -#include - -template std::string type_name() { return "other"; } -template<> std::string type_name() { return "float"; } -template<> std::string type_name() { return "double"; } -template<> std::string type_name() { return "int"; } -template<> std::string type_name >() { return "complex"; } -template<> std::string type_name >() { return "complex"; } -template<> std::string type_name >() { return "complex"; } - -#define EIGEN_DEBUG_VAR(x) std::cerr << #x << " = " << x << std::endl; - -template inline typename NumTraits::Real epsilon() -{ - return std::numeric_limits::Real>::epsilon(); -} - -template void inverse_permutation_4x4() -{ - typedef typename MatrixType::Scalar Scalar; - typedef typename MatrixType::RealScalar RealScalar; - Vector4i indices(0,1,2,3); - for(int i = 0; i < 24; ++i) - { - MatrixType m = MatrixType::Zero(); - m(indices(0),0) = 1; - m(indices(1),1) = 1; - m(indices(2),2) = 1; - m(indices(3),3) = 1; - MatrixType inv = m.inverse(); - double error = double( (m*inv-MatrixType::Identity()).norm() / epsilon() ); - VERIFY(error == 0.0); - std::next_permutation(indices.data(),indices.data()+4); - } -} - -template void inverse_general_4x4(int repeat) -{ - typedef typename MatrixType::Scalar Scalar; - typedef typename MatrixType::RealScalar RealScalar; - double error_sum = 0., error_max = 0.; - for(int i = 0; i < repeat; ++i) - { - MatrixType m; - RealScalar absdet; - do { - m = MatrixType::Random(); - absdet = ei_abs(m.determinant()); - } while(absdet < 10 * epsilon()); - MatrixType inv = m.inverse(); - double error = double( (m*inv-MatrixType::Identity()).norm() * absdet / epsilon() ); - error_sum += error; - error_max = std::max(error_max, error); - } - std::cerr << "inverse_general_4x4, Scalar = " << type_name() << std::endl; - double error_avg = error_sum / repeat; - EIGEN_DEBUG_VAR(error_avg); - EIGEN_DEBUG_VAR(error_max); - VERIFY(error_avg < (NumTraits::IsComplex ? 8.0 : 1.25)); - VERIFY(error_max < (NumTraits::IsComplex ? 64.0 : 20.0)); -} - -void test_eigen2_prec_inverse_4x4() -{ - CALL_SUBTEST_1((inverse_permutation_4x4())); - CALL_SUBTEST_1(( inverse_general_4x4(200000 * g_repeat) )); - - CALL_SUBTEST_2((inverse_permutation_4x4 >())); - CALL_SUBTEST_2(( inverse_general_4x4 >(200000 * g_repeat) )); - - CALL_SUBTEST_3((inverse_permutation_4x4())); - CALL_SUBTEST_3((inverse_general_4x4(50000 * g_repeat))); -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_product_large.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_product_large.cpp deleted file mode 100644 index 5149ef74..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_product_large.cpp +++ /dev/null @@ -1,45 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "product.h" - -void test_eigen2_product_large() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( product(MatrixXf(ei_random(1,320), ei_random(1,320))) ); - CALL_SUBTEST_2( product(MatrixXd(ei_random(1,320), ei_random(1,320))) ); - CALL_SUBTEST_3( product(MatrixXi(ei_random(1,320), ei_random(1,320))) ); - CALL_SUBTEST_4( product(MatrixXcf(ei_random(1,50), ei_random(1,50))) ); - CALL_SUBTEST_5( product(Matrix(ei_random(1,320), ei_random(1,320))) ); - } - -#ifdef EIGEN_TEST_PART_6 - { - // test a specific issue in DiagonalProduct - int N = 1000000; - VectorXf v = VectorXf::Ones(N); - MatrixXf m = MatrixXf::Ones(N,3); - m = (v+v).asDiagonal() * m; - VERIFY_IS_APPROX(m, MatrixXf::Constant(N,3,2)); - } - - { - // test deferred resizing in Matrix::operator= - MatrixXf a = MatrixXf::Random(10,4), b = MatrixXf::Random(4,10), c = a; - VERIFY_IS_APPROX((a = a * b), (c * b).eval()); - } - - { - MatrixXf mat1(10,10); mat1.setRandom(); - MatrixXf mat2(32,10); mat2.setRandom(); - MatrixXf result = mat1.row(2)*mat2.transpose(); - VERIFY_IS_APPROX(result, (mat1.row(2)*mat2.transpose()).eval()); - } -#endif -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_product_small.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_product_small.cpp deleted file mode 100644 index 4cd8c102..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_product_small.cpp +++ /dev/null @@ -1,22 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#define EIGEN_NO_STATIC_ASSERT -#include "product.h" - -void test_eigen2_product_small() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( product(Matrix()) ); - CALL_SUBTEST_2( product(Matrix()) ); - CALL_SUBTEST_3( product(Matrix3d()) ); - CALL_SUBTEST_4( product(Matrix4d()) ); - CALL_SUBTEST_5( product(Matrix4f()) ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_qr.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_qr.cpp deleted file mode 100644 index 76977e4c..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_qr.cpp +++ /dev/null @@ -1,69 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include - -template void qr(const MatrixType& m) -{ - /* this test covers the following files: - QR.h - */ - int rows = m.rows(); - int cols = m.cols(); - - typedef typename MatrixType::Scalar Scalar; - typedef Matrix SquareMatrixType; - typedef Matrix VectorType; - - MatrixType a = MatrixType::Random(rows,cols); - QR qrOfA(a); - VERIFY_IS_APPROX(a, qrOfA.matrixQ() * qrOfA.matrixR()); - VERIFY_IS_NOT_APPROX(a+MatrixType::Identity(rows, cols), qrOfA.matrixQ() * qrOfA.matrixR()); - - #if 0 // eigenvalues module not yet ready - SquareMatrixType b = a.adjoint() * a; - - // check tridiagonalization - Tridiagonalization tridiag(b); - VERIFY_IS_APPROX(b, tridiag.matrixQ() * tridiag.matrixT() * tridiag.matrixQ().adjoint()); - - // check hessenberg decomposition - HessenbergDecomposition hess(b); - VERIFY_IS_APPROX(b, hess.matrixQ() * hess.matrixH() * hess.matrixQ().adjoint()); - VERIFY_IS_APPROX(tridiag.matrixT(), hess.matrixH()); - b = SquareMatrixType::Random(cols,cols); - hess.compute(b); - VERIFY_IS_APPROX(b, hess.matrixQ() * hess.matrixH() * hess.matrixQ().adjoint()); - #endif -} - -void test_eigen2_qr() -{ - for(int i = 0; i < 1; i++) { - CALL_SUBTEST_1( qr(Matrix2f()) ); - CALL_SUBTEST_2( qr(Matrix4d()) ); - CALL_SUBTEST_3( qr(MatrixXf(12,8)) ); - CALL_SUBTEST_4( qr(MatrixXcd(5,5)) ); - CALL_SUBTEST_4( qr(MatrixXcd(7,3)) ); - } - -#ifdef EIGEN_TEST_PART_5 - // small isFullRank test - { - Matrix3d mat; - mat << 1, 45, 1, 2, 2, 2, 1, 2, 3; - VERIFY(mat.qr().isFullRank()); - mat << 1, 1, 1, 2, 2, 2, 1, 2, 3; - //always returns true in eigen2support - //VERIFY(!mat.qr().isFullRank()); - } - -#endif -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_qtvector.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_qtvector.cpp deleted file mode 100644 index 6cfb58a2..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_qtvector.cpp +++ /dev/null @@ -1,158 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#define EIGEN_WORK_AROUND_QT_BUG_CALLING_WRONG_OPERATOR_NEW_FIXED_IN_QT_4_5 - -#include "main.h" - -#include -#include - -#include - -template -void check_qtvector_matrix(const MatrixType& m) -{ - int rows = m.rows(); - int cols = m.cols(); - MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols); - QVector v(10, MatrixType(rows,cols)), w(20, y); - for(int i = 0; i < 20; i++) - { - VERIFY_IS_APPROX(w[i], y); - } - v[5] = x; - w[6] = v[5]; - VERIFY_IS_APPROX(w[6], v[5]); - v = w; - for(int i = 0; i < 20; i++) - { - VERIFY_IS_APPROX(w[i], v[i]); - } - - v.resize(21); - v[20] = x; - VERIFY_IS_APPROX(v[20], x); - v.fill(y,22); - VERIFY_IS_APPROX(v[21], y); - v.push_back(x); - VERIFY_IS_APPROX(v[22], x); - VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(MatrixType)); - - // do a lot of push_back such that the vector gets internally resized - // (with memory reallocation) - MatrixType* ref = &w[0]; - for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i) - v.push_back(w[i%w.size()]); - for(int i=23; i -void check_qtvector_transform(const TransformType&) -{ - typedef typename TransformType::MatrixType MatrixType; - TransformType x(MatrixType::Random()), y(MatrixType::Random()); - QVector v(10), w(20, y); - v[5] = x; - w[6] = v[5]; - VERIFY_IS_APPROX(w[6], v[5]); - v = w; - for(int i = 0; i < 20; i++) - { - VERIFY_IS_APPROX(w[i], v[i]); - } - - v.resize(21); - v[20] = x; - VERIFY_IS_APPROX(v[20], x); - v.fill(y,22); - VERIFY_IS_APPROX(v[21], y); - v.push_back(x); - VERIFY_IS_APPROX(v[22], x); - VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(TransformType)); - - // do a lot of push_back such that the vector gets internally resized - // (with memory reallocation) - TransformType* ref = &w[0]; - for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i) - v.push_back(w[i%w.size()]); - for(unsigned int i=23; int(i) -void check_qtvector_quaternion(const QuaternionType&) -{ - typedef typename QuaternionType::Coefficients Coefficients; - QuaternionType x(Coefficients::Random()), y(Coefficients::Random()); - QVector v(10), w(20, y); - v[5] = x; - w[6] = v[5]; - VERIFY_IS_APPROX(w[6], v[5]); - v = w; - for(int i = 0; i < 20; i++) - { - VERIFY_IS_APPROX(w[i], v[i]); - } - - v.resize(21); - v[20] = x; - VERIFY_IS_APPROX(v[20], x); - v.fill(y,22); - VERIFY_IS_APPROX(v[21], y); - v.push_back(x); - VERIFY_IS_APPROX(v[22], x); - VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(QuaternionType)); - - // do a lot of push_back such that the vector gets internally resized - // (with memory reallocation) - QuaternionType* ref = &w[0]; - for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i) - v.push_back(w[i%w.size()]); - for(unsigned int i=23; int(i) -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include - -template -void makeNoisyCohyperplanarPoints(int numPoints, - VectorType **points, - HyperplaneType *hyperplane, - typename VectorType::Scalar noiseAmplitude) -{ - typedef typename VectorType::Scalar Scalar; - const int size = points[0]->size(); - // pick a random hyperplane, store the coefficients of its equation - hyperplane->coeffs().resize(size + 1); - for(int j = 0; j < size + 1; j++) - { - do { - hyperplane->coeffs().coeffRef(j) = ei_random(); - } while(ei_abs(hyperplane->coeffs().coeff(j)) < 0.5); - } - - // now pick numPoints random points on this hyperplane - for(int i = 0; i < numPoints; i++) - { - VectorType& cur_point = *(points[i]); - do - { - cur_point = VectorType::Random(size)/*.normalized()*/; - // project cur_point onto the hyperplane - Scalar x = - (hyperplane->coeffs().start(size).cwise()*cur_point).sum(); - cur_point *= hyperplane->coeffs().coeff(size) / x; - } while( cur_point.norm() < 0.5 - || cur_point.norm() > 2.0 ); - } - - // add some noise to these points - for(int i = 0; i < numPoints; i++ ) - *(points[i]) += noiseAmplitude * VectorType::Random(size); -} - -template -void check_linearRegression(int numPoints, - VectorType **points, - const VectorType& original, - typename VectorType::Scalar tolerance) -{ - int size = points[0]->size(); - assert(size==2); - VectorType result(size); - linearRegression(numPoints, points, &result, 1); - typename VectorType::Scalar error = (result - original).norm() / original.norm(); - VERIFY(ei_abs(error) < ei_abs(tolerance)); -} - -template -void check_fitHyperplane(int numPoints, - VectorType **points, - const HyperplaneType& original, - typename VectorType::Scalar tolerance) -{ - int size = points[0]->size(); - HyperplaneType result(size); - fitHyperplane(numPoints, points, &result); - result.coeffs() *= original.coeffs().coeff(size)/result.coeffs().coeff(size); - typename VectorType::Scalar error = (result.coeffs() - original.coeffs()).norm() / original.coeffs().norm(); - std::cout << ei_abs(error) << " xxx " << ei_abs(tolerance) << std::endl; - VERIFY(ei_abs(error) < ei_abs(tolerance)); -} - -void test_eigen2_regression() -{ - for(int i = 0; i < g_repeat; i++) - { -#ifdef EIGEN_TEST_PART_1 - { - Vector2f points2f [1000]; - Vector2f *points2f_ptrs [1000]; - for(int i = 0; i < 1000; i++) points2f_ptrs[i] = &(points2f[i]); - Vector2f coeffs2f; - Hyperplane coeffs3f; - makeNoisyCohyperplanarPoints(1000, points2f_ptrs, &coeffs3f, 0.01f); - coeffs2f[0] = -coeffs3f.coeffs()[0]/coeffs3f.coeffs()[1]; - coeffs2f[1] = -coeffs3f.coeffs()[2]/coeffs3f.coeffs()[1]; - CALL_SUBTEST(check_linearRegression(10, points2f_ptrs, coeffs2f, 0.05f)); - CALL_SUBTEST(check_linearRegression(100, points2f_ptrs, coeffs2f, 0.01f)); - CALL_SUBTEST(check_linearRegression(1000, points2f_ptrs, coeffs2f, 0.002f)); - } -#endif -#ifdef EIGEN_TEST_PART_2 - { - Vector2f points2f [1000]; - Vector2f *points2f_ptrs [1000]; - for(int i = 0; i < 1000; i++) points2f_ptrs[i] = &(points2f[i]); - Hyperplane coeffs3f; - makeNoisyCohyperplanarPoints(1000, points2f_ptrs, &coeffs3f, 0.01f); - CALL_SUBTEST(check_fitHyperplane(10, points2f_ptrs, coeffs3f, 0.05f)); - CALL_SUBTEST(check_fitHyperplane(100, points2f_ptrs, coeffs3f, 0.01f)); - CALL_SUBTEST(check_fitHyperplane(1000, points2f_ptrs, coeffs3f, 0.002f)); - } -#endif -#ifdef EIGEN_TEST_PART_3 - { - Vector4d points4d [1000]; - Vector4d *points4d_ptrs [1000]; - for(int i = 0; i < 1000; i++) points4d_ptrs[i] = &(points4d[i]); - Hyperplane coeffs5d; - makeNoisyCohyperplanarPoints(1000, points4d_ptrs, &coeffs5d, 0.01); - CALL_SUBTEST(check_fitHyperplane(10, points4d_ptrs, coeffs5d, 0.05)); - CALL_SUBTEST(check_fitHyperplane(100, points4d_ptrs, coeffs5d, 0.01)); - CALL_SUBTEST(check_fitHyperplane(1000, points4d_ptrs, coeffs5d, 0.002)); - } -#endif -#ifdef EIGEN_TEST_PART_4 - { - VectorXcd *points11cd_ptrs[1000]; - for(int i = 0; i < 1000; i++) points11cd_ptrs[i] = new VectorXcd(11); - Hyperplane,Dynamic> *coeffs12cd = new Hyperplane,Dynamic>(11); - makeNoisyCohyperplanarPoints(1000, points11cd_ptrs, coeffs12cd, 0.01); - CALL_SUBTEST(check_fitHyperplane(100, points11cd_ptrs, *coeffs12cd, 0.025)); - CALL_SUBTEST(check_fitHyperplane(1000, points11cd_ptrs, *coeffs12cd, 0.006)); - delete coeffs12cd; - for(int i = 0; i < 1000; i++) delete points11cd_ptrs[i]; - } -#endif - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_sizeof.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_sizeof.cpp deleted file mode 100644 index ec1af5a0..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_sizeof.cpp +++ /dev/null @@ -1,31 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template void verifySizeOf(const MatrixType&) -{ - typedef typename MatrixType::Scalar Scalar; - if (MatrixType::RowsAtCompileTime!=Dynamic && MatrixType::ColsAtCompileTime!=Dynamic) - VERIFY(sizeof(MatrixType)==sizeof(Scalar)*MatrixType::SizeAtCompileTime); - else - VERIFY(sizeof(MatrixType)==sizeof(Scalar*) + 2 * sizeof(typename MatrixType::Index)); -} - -void test_eigen2_sizeof() -{ - CALL_SUBTEST( verifySizeOf(Matrix()) ); - CALL_SUBTEST( verifySizeOf(Matrix4d()) ); - CALL_SUBTEST( verifySizeOf(Matrix()) ); - CALL_SUBTEST( verifySizeOf(Matrix()) ); - CALL_SUBTEST( verifySizeOf(MatrixXcf(3, 3)) ); - CALL_SUBTEST( verifySizeOf(MatrixXi(8, 12)) ); - CALL_SUBTEST( verifySizeOf(MatrixXcd(20, 20)) ); - CALL_SUBTEST( verifySizeOf(Matrix()) ); -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_smallvectors.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_smallvectors.cpp deleted file mode 100644 index 03962b17..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_smallvectors.cpp +++ /dev/null @@ -1,42 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template void smallVectors() -{ - typedef Matrix V2; - typedef Matrix V3; - typedef Matrix V4; - Scalar x1 = ei_random(), - x2 = ei_random(), - x3 = ei_random(), - x4 = ei_random(); - V2 v2(x1, x2); - V3 v3(x1, x2, x3); - V4 v4(x1, x2, x3, x4); - VERIFY_IS_APPROX(x1, v2.x()); - VERIFY_IS_APPROX(x1, v3.x()); - VERIFY_IS_APPROX(x1, v4.x()); - VERIFY_IS_APPROX(x2, v2.y()); - VERIFY_IS_APPROX(x2, v3.y()); - VERIFY_IS_APPROX(x2, v4.y()); - VERIFY_IS_APPROX(x3, v3.z()); - VERIFY_IS_APPROX(x3, v4.z()); - VERIFY_IS_APPROX(x4, v4.w()); -} - -void test_eigen2_smallvectors() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST( smallVectors() ); - CALL_SUBTEST( smallVectors() ); - CALL_SUBTEST( smallVectors() ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_sparse_basic.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_sparse_basic.cpp deleted file mode 100644 index 04907767..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_sparse_basic.cpp +++ /dev/null @@ -1,317 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Daniel Gomez Ferro -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "sparse.h" - -template -bool test_random_setter(SparseMatrix& sm, const DenseType& ref, const std::vector& nonzeroCoords) -{ - typedef SparseMatrix SparseType; - { - sm.setZero(); - SetterType w(sm); - std::vector remaining = nonzeroCoords; - while(!remaining.empty()) - { - int i = ei_random(0,remaining.size()-1); - w(remaining[i].x(),remaining[i].y()) = ref.coeff(remaining[i].x(),remaining[i].y()); - remaining[i] = remaining.back(); - remaining.pop_back(); - } - } - return sm.isApprox(ref); -} - -template -bool test_random_setter(DynamicSparseMatrix& sm, const DenseType& ref, const std::vector& nonzeroCoords) -{ - sm.setZero(); - std::vector remaining = nonzeroCoords; - while(!remaining.empty()) - { - int i = ei_random(0,remaining.size()-1); - sm.coeffRef(remaining[i].x(),remaining[i].y()) = ref.coeff(remaining[i].x(),remaining[i].y()); - remaining[i] = remaining.back(); - remaining.pop_back(); - } - return sm.isApprox(ref); -} - -template void sparse_basic(const SparseMatrixType& ref) -{ - const int rows = ref.rows(); - const int cols = ref.cols(); - typedef typename SparseMatrixType::Scalar Scalar; - enum { Flags = SparseMatrixType::Flags }; - - double density = std::max(8./(rows*cols), 0.01); - typedef Matrix DenseMatrix; - typedef Matrix DenseVector; - Scalar eps = 1e-6; - - SparseMatrixType m(rows, cols); - DenseMatrix refMat = DenseMatrix::Zero(rows, cols); - DenseVector vec1 = DenseVector::Random(rows); - Scalar s1 = ei_random(); - - std::vector zeroCoords; - std::vector nonzeroCoords; - initSparse(density, refMat, m, 0, &zeroCoords, &nonzeroCoords); - - if (zeroCoords.size()==0 || nonzeroCoords.size()==0) - return; - - // test coeff and coeffRef - for (int i=0; i<(int)zeroCoords.size(); ++i) - { - VERIFY_IS_MUCH_SMALLER_THAN( m.coeff(zeroCoords[i].x(),zeroCoords[i].y()), eps ); - if(ei_is_same_type >::ret) - VERIFY_RAISES_ASSERT( m.coeffRef(zeroCoords[0].x(),zeroCoords[0].y()) = 5 ); - } - VERIFY_IS_APPROX(m, refMat); - - m.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5); - refMat.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5); - - VERIFY_IS_APPROX(m, refMat); - /* - // test InnerIterators and Block expressions - for (int t=0; t<10; ++t) - { - int j = ei_random(0,cols-1); - int i = ei_random(0,rows-1); - int w = ei_random(1,cols-j-1); - int h = ei_random(1,rows-i-1); - -// VERIFY_IS_APPROX(m.block(i,j,h,w), refMat.block(i,j,h,w)); - for(int c=0; c w(m); -// for (int i=0; icoeffRef(nonzeroCoords[i].x(),nonzeroCoords[i].y()) = refMat.coeff(nonzeroCoords[i].x(),nonzeroCoords[i].y()); -// } -// } -// VERIFY_IS_APPROX(m, refMat); - - // random setter -// { -// m.setZero(); -// VERIFY_IS_NOT_APPROX(m, refMat); -// SparseSetter w(m); -// std::vector remaining = nonzeroCoords; -// while(!remaining.empty()) -// { -// int i = ei_random(0,remaining.size()-1); -// w->coeffRef(remaining[i].x(),remaining[i].y()) = refMat.coeff(remaining[i].x(),remaining[i].y()); -// remaining[i] = remaining.back(); -// remaining.pop_back(); -// } -// } -// VERIFY_IS_APPROX(m, refMat); - - VERIFY(( test_random_setter >(m,refMat,nonzeroCoords) )); - #ifdef EIGEN_UNORDERED_MAP_SUPPORT - VERIFY(( test_random_setter >(m,refMat,nonzeroCoords) )); - #endif - #ifdef _DENSE_HASH_MAP_H_ - VERIFY(( test_random_setter >(m,refMat,nonzeroCoords) )); - #endif - #ifdef _SPARSE_HASH_MAP_H_ - VERIFY(( test_random_setter >(m,refMat,nonzeroCoords) )); - #endif - - // test fillrand - { - DenseMatrix m1(rows,cols); - m1.setZero(); - SparseMatrixType m2(rows,cols); - m2.startFill(); - for (int j=0; j(0,rows-1); - if (m1.coeff(i,j)==Scalar(0)) - m2.fillrand(i,j) = m1(i,j) = ei_random(); - } - } - m2.endFill(); - VERIFY_IS_APPROX(m2,m1); - } - - // test RandomSetter - /*{ - SparseMatrixType m1(rows,cols), m2(rows,cols); - DenseMatrix refM1 = DenseMatrix::Zero(rows, rows); - initSparse(density, refM1, m1); - { - Eigen::RandomSetter setter(m2); - for (int j=0; j(density, refM1, m1); - initSparse(density, refM2, m2); - initSparse(density, refM3, m3); - initSparse(density, refM4, m4); - - VERIFY_IS_APPROX(m1+m2, refM1+refM2); - VERIFY_IS_APPROX(m1+m2+m3, refM1+refM2+refM3); - VERIFY_IS_APPROX(m3.cwise()*(m1+m2), refM3.cwise()*(refM1+refM2)); - VERIFY_IS_APPROX(m1*s1-m2, refM1*s1-refM2); - - VERIFY_IS_APPROX(m1*=s1, refM1*=s1); - VERIFY_IS_APPROX(m1/=s1, refM1/=s1); - - VERIFY_IS_APPROX(m1+=m2, refM1+=refM2); - VERIFY_IS_APPROX(m1-=m2, refM1-=refM2); - - VERIFY_IS_APPROX(m1.col(0).eigen2_dot(refM2.row(0)), refM1.col(0).eigen2_dot(refM2.row(0))); - - refM4.setRandom(); - // sparse cwise* dense - VERIFY_IS_APPROX(m3.cwise()*refM4, refM3.cwise()*refM4); -// VERIFY_IS_APPROX(m3.cwise()/refM4, refM3.cwise()/refM4); - } - - // test innerVector() - { - DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows); - SparseMatrixType m2(rows, rows); - initSparse(density, refMat2, m2); - int j0 = ei_random(0,rows-1); - int j1 = ei_random(0,rows-1); - VERIFY_IS_APPROX(m2.innerVector(j0), refMat2.col(j0)); - VERIFY_IS_APPROX(m2.innerVector(j0)+m2.innerVector(j1), refMat2.col(j0)+refMat2.col(j1)); - //m2.innerVector(j0) = 2*m2.innerVector(j1); - //refMat2.col(j0) = 2*refMat2.col(j1); - //VERIFY_IS_APPROX(m2, refMat2); - } - - // test innerVectors() - { - DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows); - SparseMatrixType m2(rows, rows); - initSparse(density, refMat2, m2); - int j0 = ei_random(0,rows-2); - int j1 = ei_random(0,rows-2); - int n0 = ei_random(1,rows-std::max(j0,j1)); - VERIFY_IS_APPROX(m2.innerVectors(j0,n0), refMat2.block(0,j0,rows,n0)); - VERIFY_IS_APPROX(m2.innerVectors(j0,n0)+m2.innerVectors(j1,n0), - refMat2.block(0,j0,rows,n0)+refMat2.block(0,j1,rows,n0)); - //m2.innerVectors(j0,n0) = m2.innerVectors(j0,n0) + m2.innerVectors(j1,n0); - //refMat2.block(0,j0,rows,n0) = refMat2.block(0,j0,rows,n0) + refMat2.block(0,j1,rows,n0); - } - - // test transpose - { - DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows); - SparseMatrixType m2(rows, rows); - initSparse(density, refMat2, m2); - VERIFY_IS_APPROX(m2.transpose().eval(), refMat2.transpose().eval()); - VERIFY_IS_APPROX(m2.transpose(), refMat2.transpose()); - } - - // test prune - { - SparseMatrixType m2(rows, rows); - DenseMatrix refM2(rows, rows); - refM2.setZero(); - int countFalseNonZero = 0; - int countTrueNonZero = 0; - m2.startFill(); - for (int j=0; j(0,1); - if (x<0.1) - { - // do nothing - } - else if (x<0.5) - { - countFalseNonZero++; - m2.fill(i,j) = Scalar(0); - } - else - { - countTrueNonZero++; - m2.fill(i,j) = refM2(i,j) = Scalar(1); - } - } - m2.endFill(); - VERIFY(countFalseNonZero+countTrueNonZero == m2.nonZeros()); - VERIFY_IS_APPROX(m2, refM2); - m2.prune(1); - VERIFY(countTrueNonZero==m2.nonZeros()); - VERIFY_IS_APPROX(m2, refM2); - } -} - -void test_eigen2_sparse_basic() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( sparse_basic(SparseMatrix(8, 8)) ); - CALL_SUBTEST_2( sparse_basic(SparseMatrix >(16, 16)) ); - CALL_SUBTEST_1( sparse_basic(SparseMatrix(33, 33)) ); - - CALL_SUBTEST_3( sparse_basic(DynamicSparseMatrix(8, 8)) ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_sparse_product.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_sparse_product.cpp deleted file mode 100644 index d28e76df..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_sparse_product.cpp +++ /dev/null @@ -1,115 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Daniel Gomez Ferro -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "sparse.h" - -template void sparse_product(const SparseMatrixType& ref) -{ - const int rows = ref.rows(); - const int cols = ref.cols(); - typedef typename SparseMatrixType::Scalar Scalar; - enum { Flags = SparseMatrixType::Flags }; - - double density = std::max(8./(rows*cols), 0.01); - typedef Matrix DenseMatrix; - typedef Matrix DenseVector; - - // test matrix-matrix product - { - DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows); - DenseMatrix refMat3 = DenseMatrix::Zero(rows, rows); - DenseMatrix refMat4 = DenseMatrix::Zero(rows, rows); - DenseMatrix dm4 = DenseMatrix::Zero(rows, rows); - SparseMatrixType m2(rows, rows); - SparseMatrixType m3(rows, rows); - SparseMatrixType m4(rows, rows); - initSparse(density, refMat2, m2); - initSparse(density, refMat3, m3); - initSparse(density, refMat4, m4); - VERIFY_IS_APPROX(m4=m2*m3, refMat4=refMat2*refMat3); - VERIFY_IS_APPROX(m4=m2.transpose()*m3, refMat4=refMat2.transpose()*refMat3); - VERIFY_IS_APPROX(m4=m2.transpose()*m3.transpose(), refMat4=refMat2.transpose()*refMat3.transpose()); - VERIFY_IS_APPROX(m4=m2*m3.transpose(), refMat4=refMat2*refMat3.transpose()); - - // sparse * dense - VERIFY_IS_APPROX(dm4=m2*refMat3, refMat4=refMat2*refMat3); - VERIFY_IS_APPROX(dm4=m2*refMat3.transpose(), refMat4=refMat2*refMat3.transpose()); - VERIFY_IS_APPROX(dm4=m2.transpose()*refMat3, refMat4=refMat2.transpose()*refMat3); - VERIFY_IS_APPROX(dm4=m2.transpose()*refMat3.transpose(), refMat4=refMat2.transpose()*refMat3.transpose()); - - // dense * sparse - VERIFY_IS_APPROX(dm4=refMat2*m3, refMat4=refMat2*refMat3); - VERIFY_IS_APPROX(dm4=refMat2*m3.transpose(), refMat4=refMat2*refMat3.transpose()); - VERIFY_IS_APPROX(dm4=refMat2.transpose()*m3, refMat4=refMat2.transpose()*refMat3); - VERIFY_IS_APPROX(dm4=refMat2.transpose()*m3.transpose(), refMat4=refMat2.transpose()*refMat3.transpose()); - - VERIFY_IS_APPROX(m3=m3*m3, refMat3=refMat3*refMat3); - } - - // test matrix - diagonal product - if(false) // it compiles, but the precision is terrible. probably doesn't matter in this branch.... - { - DenseMatrix refM2 = DenseMatrix::Zero(rows, rows); - DenseMatrix refM3 = DenseMatrix::Zero(rows, rows); - DiagonalMatrix d1(DenseVector::Random(rows)); - SparseMatrixType m2(rows, rows); - SparseMatrixType m3(rows, rows); - initSparse(density, refM2, m2); - initSparse(density, refM3, m3); - VERIFY_IS_APPROX(m3=m2*d1, refM3=refM2*d1); - VERIFY_IS_APPROX(m3=m2.transpose()*d1, refM3=refM2.transpose()*d1); - VERIFY_IS_APPROX(m3=d1*m2, refM3=d1*refM2); - VERIFY_IS_APPROX(m3=d1*m2.transpose(), refM3=d1 * refM2.transpose()); - } - - // test self adjoint products - { - DenseMatrix b = DenseMatrix::Random(rows, rows); - DenseMatrix x = DenseMatrix::Random(rows, rows); - DenseMatrix refX = DenseMatrix::Random(rows, rows); - DenseMatrix refUp = DenseMatrix::Zero(rows, rows); - DenseMatrix refLo = DenseMatrix::Zero(rows, rows); - DenseMatrix refS = DenseMatrix::Zero(rows, rows); - SparseMatrixType mUp(rows, rows); - SparseMatrixType mLo(rows, rows); - SparseMatrixType mS(rows, rows); - do { - initSparse(density, refUp, mUp, ForceRealDiag|/*ForceNonZeroDiag|*/MakeUpperTriangular); - } while (refUp.isZero()); - refLo = refUp.transpose().conjugate(); - mLo = mUp.transpose().conjugate(); - refS = refUp + refLo; - refS.diagonal() *= 0.5; - mS = mUp + mLo; - for (int k=0; k()*b, refX=refS*b); - VERIFY_IS_APPROX(x=mLo.template marked()*b, refX=refS*b); - VERIFY_IS_APPROX(x=mS.template marked()*b, refX=refS*b); - } - -} - -void test_eigen2_sparse_product() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( sparse_product(SparseMatrix(8, 8)) ); - CALL_SUBTEST_2( sparse_product(SparseMatrix >(16, 16)) ); - CALL_SUBTEST_1( sparse_product(SparseMatrix(33, 33)) ); - - CALL_SUBTEST_3( sparse_product(DynamicSparseMatrix(8, 8)) ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_sparse_solvers.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_sparse_solvers.cpp deleted file mode 100644 index 3aef27ab..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_sparse_solvers.cpp +++ /dev/null @@ -1,200 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Daniel Gomez Ferro -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "sparse.h" - -template void -initSPD(double density, - Matrix& refMat, - SparseMatrix& sparseMat) -{ - Matrix aux(refMat.rows(),refMat.cols()); - initSparse(density,refMat,sparseMat); - refMat = refMat * refMat.adjoint(); - for (int k=0; k<2; ++k) - { - initSparse(density,aux,sparseMat,ForceNonZeroDiag); - refMat += aux * aux.adjoint(); - } - sparseMat.startFill(); - for (int j=0 ; j void sparse_solvers(int rows, int cols) -{ - double density = std::max(8./(rows*cols), 0.01); - typedef Matrix DenseMatrix; - typedef Matrix DenseVector; - // Scalar eps = 1e-6; - - DenseVector vec1 = DenseVector::Random(rows); - - std::vector zeroCoords; - std::vector nonzeroCoords; - - // test triangular solver - { - DenseVector vec2 = vec1, vec3 = vec1; - SparseMatrix m2(rows, cols); - DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols); - - // lower - initSparse(density, refMat2, m2, ForceNonZeroDiag|MakeLowerTriangular, &zeroCoords, &nonzeroCoords); - VERIFY_IS_APPROX(refMat2.template marked().solveTriangular(vec2), - m2.template marked().solveTriangular(vec3)); - - // lower - transpose - initSparse(density, refMat2, m2, ForceNonZeroDiag|MakeLowerTriangular, &zeroCoords, &nonzeroCoords); - VERIFY_IS_APPROX(refMat2.template marked().transpose().solveTriangular(vec2), - m2.template marked().transpose().solveTriangular(vec3)); - - // upper - initSparse(density, refMat2, m2, ForceNonZeroDiag|MakeUpperTriangular, &zeroCoords, &nonzeroCoords); - VERIFY_IS_APPROX(refMat2.template marked().solveTriangular(vec2), - m2.template marked().solveTriangular(vec3)); - - // upper - transpose - initSparse(density, refMat2, m2, ForceNonZeroDiag|MakeUpperTriangular, &zeroCoords, &nonzeroCoords); - VERIFY_IS_APPROX(refMat2.template marked().transpose().solveTriangular(vec2), - m2.template marked().transpose().solveTriangular(vec3)); - } - - // test LLT - { - // TODO fix the issue with complex (see SparseLLT::solveInPlace) - SparseMatrix m2(rows, cols); - DenseMatrix refMat2(rows, cols); - - DenseVector b = DenseVector::Random(cols); - DenseVector refX(cols), x(cols); - - initSPD(density, refMat2, m2); - - refMat2.llt().solve(b, &refX); - typedef SparseMatrix SparseSelfAdjointMatrix; - if (!NumTraits::IsComplex) - { - x = b; - SparseLLT (m2).solveInPlace(x); - VERIFY(refX.isApprox(x,test_precision()) && "LLT: default"); - } - #ifdef EIGEN_CHOLMOD_SUPPORT - x = b; - SparseLLT(m2).solveInPlace(x); - VERIFY(refX.isApprox(x,test_precision()) && "LLT: cholmod"); - #endif - if (!NumTraits::IsComplex) - { - #ifdef EIGEN_TAUCS_SUPPORT - x = b; - SparseLLT(m2,IncompleteFactorization).solveInPlace(x); - VERIFY(refX.isApprox(x,test_precision()) && "LLT: taucs (IncompleteFactorization)"); - x = b; - SparseLLT(m2,SupernodalMultifrontal).solveInPlace(x); - VERIFY(refX.isApprox(x,test_precision()) && "LLT: taucs (SupernodalMultifrontal)"); - x = b; - SparseLLT(m2,SupernodalLeftLooking).solveInPlace(x); - VERIFY(refX.isApprox(x,test_precision()) && "LLT: taucs (SupernodalLeftLooking)"); - #endif - } - } - - // test LDLT - if (!NumTraits::IsComplex) - { - // TODO fix the issue with complex (see SparseLDLT::solveInPlace) - SparseMatrix m2(rows, cols); - DenseMatrix refMat2(rows, cols); - - DenseVector b = DenseVector::Random(cols); - DenseVector refX(cols), x(cols); - - //initSPD(density, refMat2, m2); - initSparse(density, refMat2, m2, ForceNonZeroDiag|MakeUpperTriangular, 0, 0); - refMat2 += refMat2.adjoint(); - refMat2.diagonal() *= 0.5; - - refMat2.ldlt().solve(b, &refX); - typedef SparseMatrix SparseSelfAdjointMatrix; - x = b; - SparseLDLT ldlt(m2); - if (ldlt.succeeded()) - ldlt.solveInPlace(x); - VERIFY(refX.isApprox(x,test_precision()) && "LDLT: default"); - } - - // test LU - { - static int count = 0; - SparseMatrix m2(rows, cols); - DenseMatrix refMat2(rows, cols); - - DenseVector b = DenseVector::Random(cols); - DenseVector refX(cols), x(cols); - - initSparse(density, refMat2, m2, ForceNonZeroDiag, &zeroCoords, &nonzeroCoords); - - LU refLu(refMat2); - refLu.solve(b, &refX); - #if defined(EIGEN_SUPERLU_SUPPORT) || defined(EIGEN_UMFPACK_SUPPORT) - Scalar refDet = refLu.determinant(); - #endif - x.setZero(); - // // SparseLU > (m2).solve(b,&x); - // // VERIFY(refX.isApprox(x,test_precision()) && "LU: default"); - #ifdef EIGEN_SUPERLU_SUPPORT - { - x.setZero(); - SparseLU,SuperLU> slu(m2); - if (slu.succeeded()) - { - if (slu.solve(b,&x)) { - VERIFY(refX.isApprox(x,test_precision()) && "LU: SuperLU"); - } - // std::cerr << refDet << " == " << slu.determinant() << "\n"; - if (count==0) { - VERIFY_IS_APPROX(refDet,slu.determinant()); // FIXME det is not very stable for complex - } - } - } - #endif - #ifdef EIGEN_UMFPACK_SUPPORT - { - // check solve - x.setZero(); - SparseLU,UmfPack> slu(m2); - if (slu.succeeded()) { - if (slu.solve(b,&x)) { - if (count==0) { - VERIFY(refX.isApprox(x,test_precision()) && "LU: umfpack"); // FIXME solve is not very stable for complex - } - } - VERIFY_IS_APPROX(refDet,slu.determinant()); - // TODO check the extracted data - //std::cerr << slu.matrixL() << "\n"; - } - } - #endif - count++; - } - -} - -void test_eigen2_sparse_solvers() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( sparse_solvers(8, 8) ); - CALL_SUBTEST_2( sparse_solvers >(16, 16) ); - CALL_SUBTEST_1( sparse_solvers(101, 101) ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_sparse_vector.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_sparse_vector.cpp deleted file mode 100644 index e6d2d77a..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_sparse_vector.cpp +++ /dev/null @@ -1,84 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Daniel Gomez Ferro -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "sparse.h" - -template void sparse_vector(int rows, int cols) -{ - double densityMat = std::max(8./(rows*cols), 0.01); - double densityVec = std::max(8./float(rows), 0.1); - typedef Matrix DenseMatrix; - typedef Matrix DenseVector; - typedef SparseVector SparseVectorType; - typedef SparseMatrix SparseMatrixType; - Scalar eps = 1e-6; - - SparseMatrixType m1(rows,cols); - SparseVectorType v1(rows), v2(rows), v3(rows); - DenseMatrix refM1 = DenseMatrix::Zero(rows, cols); - DenseVector refV1 = DenseVector::Random(rows), - refV2 = DenseVector::Random(rows), - refV3 = DenseVector::Random(rows); - - std::vector zerocoords, nonzerocoords; - initSparse(densityVec, refV1, v1, &zerocoords, &nonzerocoords); - initSparse(densityMat, refM1, m1); - - initSparse(densityVec, refV2, v2); - initSparse(densityVec, refV3, v3); - - Scalar s1 = ei_random(); - - // test coeff and coeffRef - for (unsigned int i=0; i(8, 8) ); - CALL_SUBTEST_2( sparse_vector >(16, 16) ); - CALL_SUBTEST_1( sparse_vector(299, 535) ); - } -} - diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_stdvector.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_stdvector.cpp deleted file mode 100644 index 6ab05c20..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_stdvector.cpp +++ /dev/null @@ -1,148 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include -#include "main.h" -#include - -template -void check_stdvector_matrix(const MatrixType& m) -{ - int rows = m.rows(); - int cols = m.cols(); - MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols); - std::vector > v(10, MatrixType(rows,cols)), w(20, y); - v[5] = x; - w[6] = v[5]; - VERIFY_IS_APPROX(w[6], v[5]); - v = w; - for(int i = 0; i < 20; i++) - { - VERIFY_IS_APPROX(w[i], v[i]); - } - - v.resize(21); - v[20] = x; - VERIFY_IS_APPROX(v[20], x); - v.resize(22,y); - VERIFY_IS_APPROX(v[21], y); - v.push_back(x); - VERIFY_IS_APPROX(v[22], x); - VERIFY((std::size_t)&(v[22]) == (std::size_t)&(v[21]) + sizeof(MatrixType)); - - // do a lot of push_back such that the vector gets internally resized - // (with memory reallocation) - MatrixType* ref = &w[0]; - for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i) - v.push_back(w[i%w.size()]); - for(unsigned int i=23; i -void check_stdvector_transform(const TransformType&) -{ - typedef typename TransformType::MatrixType MatrixType; - TransformType x(MatrixType::Random()), y(MatrixType::Random()); - std::vector > v(10), w(20, y); - v[5] = x; - w[6] = v[5]; - VERIFY_IS_APPROX(w[6], v[5]); - v = w; - for(int i = 0; i < 20; i++) - { - VERIFY_IS_APPROX(w[i], v[i]); - } - - v.resize(21); - v[20] = x; - VERIFY_IS_APPROX(v[20], x); - v.resize(22,y); - VERIFY_IS_APPROX(v[21], y); - v.push_back(x); - VERIFY_IS_APPROX(v[22], x); - VERIFY((std::size_t)&(v[22]) == (std::size_t)&(v[21]) + sizeof(TransformType)); - - // do a lot of push_back such that the vector gets internally resized - // (with memory reallocation) - TransformType* ref = &w[0]; - for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i) - v.push_back(w[i%w.size()]); - for(unsigned int i=23; i -void check_stdvector_quaternion(const QuaternionType&) -{ - typedef typename QuaternionType::Coefficients Coefficients; - QuaternionType x(Coefficients::Random()), y(Coefficients::Random()); - std::vector > v(10), w(20, y); - v[5] = x; - w[6] = v[5]; - VERIFY_IS_APPROX(w[6], v[5]); - v = w; - for(int i = 0; i < 20; i++) - { - VERIFY_IS_APPROX(w[i], v[i]); - } - - v.resize(21); - v[20] = x; - VERIFY_IS_APPROX(v[20], x); - v.resize(22,y); - VERIFY_IS_APPROX(v[21], y); - v.push_back(x); - VERIFY_IS_APPROX(v[22], x); - VERIFY((std::size_t)&(v[22]) == (std::size_t)&(v[21]) + sizeof(QuaternionType)); - - // do a lot of push_back such that the vector gets internally resized - // (with memory reallocation) - QuaternionType* ref = &w[0]; - for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i) - v.push_back(w[i%w.size()]); - for(unsigned int i=23; i -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -// check minor separately in order to avoid the possible creation of a zero-sized -// array. Comes from a compilation error with gcc-3.4 or gcc-4 with -ansi -pedantic. -// Another solution would be to declare the array like this: T m_data[Size==0?1:Size]; in ei_matrix_storage -// but this is probably not bad to raise such an error at compile time... -template struct CheckMinor -{ - typedef Matrix MatrixType; - CheckMinor(MatrixType& m1, int r1, int c1) - { - int rows = m1.rows(); - int cols = m1.cols(); - - Matrix mi = m1.minor(0,0).eval(); - VERIFY_IS_APPROX(mi, m1.block(1,1,rows-1,cols-1)); - mi = m1.minor(r1,c1); - VERIFY_IS_APPROX(mi.transpose(), m1.transpose().minor(c1,r1)); - //check operator(), both constant and non-constant, on minor() - m1.minor(r1,c1)(0,0) = m1.minor(0,0)(0,0); - } -}; - -template struct CheckMinor -{ - typedef Matrix MatrixType; - CheckMinor(MatrixType&, int, int) {} -}; - -template void submatrices(const MatrixType& m) -{ - /* this test covers the following files: - Row.h Column.h Block.h Minor.h DiagonalCoeffs.h - */ - typedef typename MatrixType::Scalar Scalar; - typedef typename MatrixType::RealScalar RealScalar; - typedef Matrix VectorType; - typedef Matrix RowVectorType; - int rows = m.rows(); - int cols = m.cols(); - - MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols), - m3(rows, cols), - ones = MatrixType::Ones(rows, cols), - square = Matrix - ::Random(rows, rows); - VectorType v1 = VectorType::Random(rows); - - Scalar s1 = ei_random(); - - int r1 = ei_random(0,rows-1); - int r2 = ei_random(r1,rows-1); - int c1 = ei_random(0,cols-1); - int c2 = ei_random(c1,cols-1); - - //check row() and col() - VERIFY_IS_APPROX(m1.col(c1).transpose(), m1.transpose().row(c1)); - VERIFY_IS_APPROX(square.row(r1).eigen2_dot(m1.col(c1)), (square.lazy() * m1.conjugate())(r1,c1)); - //check operator(), both constant and non-constant, on row() and col() - m1.row(r1) += s1 * m1.row(r2); - m1.col(c1) += s1 * m1.col(c2); - - //check block() - Matrix b1(1,1); b1(0,0) = m1(r1,c1); - RowVectorType br1(m1.block(r1,0,1,cols)); - VectorType bc1(m1.block(0,c1,rows,1)); - VERIFY_IS_APPROX(b1, m1.block(r1,c1,1,1)); - VERIFY_IS_APPROX(m1.row(r1), br1); - VERIFY_IS_APPROX(m1.col(c1), bc1); - //check operator(), both constant and non-constant, on block() - m1.block(r1,c1,r2-r1+1,c2-c1+1) = s1 * m2.block(0, 0, r2-r1+1,c2-c1+1); - m1.block(r1,c1,r2-r1+1,c2-c1+1)(r2-r1,c2-c1) = m2.block(0, 0, r2-r1+1,c2-c1+1)(0,0); - - //check minor() - CheckMinor checkminor(m1,r1,c1); - - //check diagonal() - VERIFY_IS_APPROX(m1.diagonal(), m1.transpose().diagonal()); - m2.diagonal() = 2 * m1.diagonal(); - m2.diagonal()[0] *= 3; - VERIFY_IS_APPROX(m2.diagonal()[0], static_cast(6) * m1.diagonal()[0]); - - enum { - BlockRows = EIGEN_SIZE_MIN_PREFER_FIXED(MatrixType::RowsAtCompileTime,2), - BlockCols = EIGEN_SIZE_MIN_PREFER_FIXED(MatrixType::ColsAtCompileTime,5) - }; - if (rows>=5 && cols>=8) - { - // test fixed block() as lvalue - m1.template block(1,1) *= s1; - // test operator() on fixed block() both as constant and non-constant - m1.template block(1,1)(0, 3) = m1.template block<2,5>(1,1)(1,2); - // check that fixed block() and block() agree - Matrix b = m1.template block(3,3); - VERIFY_IS_APPROX(b, m1.block(3,3,BlockRows,BlockCols)); - } - - if (rows>2) - { - // test sub vectors - VERIFY_IS_APPROX(v1.template start<2>(), v1.block(0,0,2,1)); - VERIFY_IS_APPROX(v1.template start<2>(), v1.start(2)); - VERIFY_IS_APPROX(v1.template start<2>(), v1.segment(0,2)); - VERIFY_IS_APPROX(v1.template start<2>(), v1.template segment<2>(0)); - int i = rows-2; - VERIFY_IS_APPROX(v1.template end<2>(), v1.block(i,0,2,1)); - VERIFY_IS_APPROX(v1.template end<2>(), v1.end(2)); - VERIFY_IS_APPROX(v1.template end<2>(), v1.segment(i,2)); - VERIFY_IS_APPROX(v1.template end<2>(), v1.template segment<2>(i)); - i = ei_random(0,rows-2); - VERIFY_IS_APPROX(v1.segment(i,2), v1.template segment<2>(i)); - } - - // stress some basic stuffs with block matrices - VERIFY(ei_real(ones.col(c1).sum()) == RealScalar(rows)); - VERIFY(ei_real(ones.row(r1).sum()) == RealScalar(cols)); - - VERIFY(ei_real(ones.col(c1).eigen2_dot(ones.col(c2))) == RealScalar(rows)); - VERIFY(ei_real(ones.row(r1).eigen2_dot(ones.row(r2))) == RealScalar(cols)); -} - -void test_eigen2_submatrices() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( submatrices(Matrix()) ); - CALL_SUBTEST_2( submatrices(Matrix4d()) ); - CALL_SUBTEST_3( submatrices(MatrixXcf(3, 3)) ); - CALL_SUBTEST_4( submatrices(MatrixXi(8, 12)) ); - CALL_SUBTEST_5( submatrices(MatrixXcd(20, 20)) ); - CALL_SUBTEST_6( submatrices(MatrixXf(20, 20)) ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_sum.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_sum.cpp deleted file mode 100644 index b47057ca..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_sum.cpp +++ /dev/null @@ -1,71 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template void matrixSum(const MatrixType& m) -{ - typedef typename MatrixType::Scalar Scalar; - - int rows = m.rows(); - int cols = m.cols(); - - MatrixType m1 = MatrixType::Random(rows, cols); - - VERIFY_IS_MUCH_SMALLER_THAN(MatrixType::Zero(rows, cols).sum(), Scalar(1)); - VERIFY_IS_APPROX(MatrixType::Ones(rows, cols).sum(), Scalar(float(rows*cols))); // the float() here to shut up excessive MSVC warning about int->complex conversion being lossy - Scalar x = Scalar(0); - for(int i = 0; i < rows; i++) for(int j = 0; j < cols; j++) x += m1(i,j); - VERIFY_IS_APPROX(m1.sum(), x); -} - -template void vectorSum(const VectorType& w) -{ - typedef typename VectorType::Scalar Scalar; - int size = w.size(); - - VectorType v = VectorType::Random(size); - for(int i = 1; i < size; i++) - { - Scalar s = Scalar(0); - for(int j = 0; j < i; j++) s += v[j]; - VERIFY_IS_APPROX(s, v.start(i).sum()); - } - - for(int i = 0; i < size-1; i++) - { - Scalar s = Scalar(0); - for(int j = i; j < size; j++) s += v[j]; - VERIFY_IS_APPROX(s, v.end(size-i).sum()); - } - - for(int i = 0; i < size/2; i++) - { - Scalar s = Scalar(0); - for(int j = i; j < size-i; j++) s += v[j]; - VERIFY_IS_APPROX(s, v.segment(i, size-2*i).sum()); - } -} - -void test_eigen2_sum() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( matrixSum(Matrix()) ); - CALL_SUBTEST_2( matrixSum(Matrix2f()) ); - CALL_SUBTEST_3( matrixSum(Matrix4d()) ); - CALL_SUBTEST_4( matrixSum(MatrixXcf(3, 3)) ); - CALL_SUBTEST_5( matrixSum(MatrixXf(8, 12)) ); - CALL_SUBTEST_6( matrixSum(MatrixXi(8, 12)) ); - } - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_5( vectorSum(VectorXf(5)) ); - CALL_SUBTEST_7( vectorSum(VectorXd(10)) ); - CALL_SUBTEST_5( vectorSum(VectorXf(33)) ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_svd.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_svd.cpp deleted file mode 100644 index d4689a56..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_svd.cpp +++ /dev/null @@ -1,87 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include - -template void svd(const MatrixType& m) -{ - /* this test covers the following files: - SVD.h - */ - int rows = m.rows(); - int cols = m.cols(); - - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - MatrixType a = MatrixType::Random(rows,cols); - Matrix b = - Matrix::Random(rows,1); - Matrix x(cols,1), x2(cols,1); - - RealScalar largerEps = test_precision(); - if (ei_is_same_type::ret) - largerEps = 1e-3f; - - { - SVD svd(a); - MatrixType sigma = MatrixType::Zero(rows,cols); - MatrixType matU = MatrixType::Zero(rows,rows); - sigma.block(0,0,cols,cols) = svd.singularValues().asDiagonal(); - matU.block(0,0,rows,cols) = svd.matrixU(); - VERIFY_IS_APPROX(a, matU * sigma * svd.matrixV().transpose()); - } - - - if (rows==cols) - { - if (ei_is_same_type::ret) - { - MatrixType a1 = MatrixType::Random(rows,cols); - a += a * a.adjoint() + a1 * a1.adjoint(); - } - SVD svd(a); - svd.solve(b, &x); - VERIFY_IS_APPROX(a * x,b); - } - - - if(rows==cols) - { - SVD svd(a); - MatrixType unitary, positive; - svd.computeUnitaryPositive(&unitary, &positive); - VERIFY_IS_APPROX(unitary * unitary.adjoint(), MatrixType::Identity(unitary.rows(),unitary.rows())); - VERIFY_IS_APPROX(positive, positive.adjoint()); - for(int i = 0; i < rows; i++) VERIFY(positive.diagonal()[i] >= 0); // cheap necessary (not sufficient) condition for positivity - VERIFY_IS_APPROX(unitary*positive, a); - - svd.computePositiveUnitary(&positive, &unitary); - VERIFY_IS_APPROX(unitary * unitary.adjoint(), MatrixType::Identity(unitary.rows(),unitary.rows())); - VERIFY_IS_APPROX(positive, positive.adjoint()); - for(int i = 0; i < rows; i++) VERIFY(positive.diagonal()[i] >= 0); // cheap necessary (not sufficient) condition for positivity - VERIFY_IS_APPROX(positive*unitary, a); - } -} - -void test_eigen2_svd() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( svd(Matrix3f()) ); - CALL_SUBTEST_2( svd(Matrix4d()) ); - CALL_SUBTEST_3( svd(MatrixXf(7,7)) ); - CALL_SUBTEST_4( svd(MatrixXd(14,7)) ); - // complex are not implemented yet -// CALL_SUBTEST( svd(MatrixXcd(6,6)) ); -// CALL_SUBTEST( svd(MatrixXcf(3,3)) ); - SVD s; - MatrixXf m = MatrixXf::Random(10,1); - s.compute(m); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_swap.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_swap.cpp deleted file mode 100644 index f3a8846d..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_swap.cpp +++ /dev/null @@ -1,83 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2009 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#define EIGEN_NO_STATIC_ASSERT -#include "main.h" - -template -struct other_matrix_type -{ - typedef int type; -}; - -template -struct other_matrix_type > -{ - typedef Matrix<_Scalar, _Rows, _Cols, _Options^RowMajor, _MaxRows, _MaxCols> type; -}; - -template void swap(const MatrixType& m) -{ - typedef typename other_matrix_type::type OtherMatrixType; - typedef typename MatrixType::Scalar Scalar; - - ei_assert((!ei_is_same_type::ret)); - int rows = m.rows(); - int cols = m.cols(); - - // construct 3 matrix guaranteed to be distinct - MatrixType m1 = MatrixType::Random(rows,cols); - MatrixType m2 = MatrixType::Random(rows,cols) + Scalar(100) * MatrixType::Identity(rows,cols); - OtherMatrixType m3 = OtherMatrixType::Random(rows,cols) + Scalar(200) * OtherMatrixType::Identity(rows,cols); - - MatrixType m1_copy = m1; - MatrixType m2_copy = m2; - OtherMatrixType m3_copy = m3; - - // test swapping 2 matrices of same type - m1.swap(m2); - VERIFY_IS_APPROX(m1,m2_copy); - VERIFY_IS_APPROX(m2,m1_copy); - m1 = m1_copy; - m2 = m2_copy; - - // test swapping 2 matrices of different types - m1.swap(m3); - VERIFY_IS_APPROX(m1,m3_copy); - VERIFY_IS_APPROX(m3,m1_copy); - m1 = m1_copy; - m3 = m3_copy; - - // test swapping matrix with expression - m1.swap(m2.block(0,0,rows,cols)); - VERIFY_IS_APPROX(m1,m2_copy); - VERIFY_IS_APPROX(m2,m1_copy); - m1 = m1_copy; - m2 = m2_copy; - - // test swapping two expressions of different types - m1.transpose().swap(m3.transpose()); - VERIFY_IS_APPROX(m1,m3_copy); - VERIFY_IS_APPROX(m3,m1_copy); - m1 = m1_copy; - m3 = m3_copy; - - // test assertion on mismatching size -- matrix case - VERIFY_RAISES_ASSERT(m1.swap(m1.row(0))); - // test assertion on mismatching size -- xpr case - VERIFY_RAISES_ASSERT(m1.row(0).swap(m1)); -} - -void test_eigen2_swap() -{ - CALL_SUBTEST_1( swap(Matrix3f()) ); // fixed size, no vectorization - CALL_SUBTEST_1( swap(Matrix4d()) ); // fixed size, possible vectorization - CALL_SUBTEST_1( swap(MatrixXd(3,3)) ); // dyn size, no vectorization - CALL_SUBTEST_1( swap(MatrixXf(30,30)) ); // dyn size, possible vectorization -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_triangular.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_triangular.cpp deleted file mode 100644 index 6f17b7df..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_triangular.cpp +++ /dev/null @@ -1,148 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template void triangular(const MatrixType& m) -{ - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - - RealScalar largerEps = 10*test_precision(); - - int rows = m.rows(); - int cols = m.cols(); - - MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols), - m3(rows, cols), - m4(rows, cols), - r1(rows, cols), - r2(rows, cols); - - MatrixType m1up = m1.template part(); - MatrixType m2up = m2.template part(); - - if (rows*cols>1) - { - VERIFY(m1up.isUpperTriangular()); - VERIFY(m2up.transpose().isLowerTriangular()); - VERIFY(!m2.isLowerTriangular()); - } - -// VERIFY_IS_APPROX(m1up.transpose() * m2, m1.upper().transpose().lower() * m2); - - // test overloaded operator+= - r1.setZero(); - r2.setZero(); - r1.template part() += m1; - r2 += m1up; - VERIFY_IS_APPROX(r1,r2); - - // test overloaded operator= - m1.setZero(); - m1.template part() = (m2.transpose() * m2).lazy(); - m3 = m2.transpose() * m2; - VERIFY_IS_APPROX(m3.template part().transpose(), m1); - - // test overloaded operator= - m1.setZero(); - m1.template part() = (m2.transpose() * m2).lazy(); - VERIFY_IS_APPROX(m3.template part(), m1); - - VERIFY_IS_APPROX(m3.template part(), m3.diagonal().asDiagonal()); - - m1 = MatrixType::Random(rows, cols); - for (int i=0; i(); - - Transpose trm4(m4); - // test back and forward subsitution - m3 = m1.template part(); - VERIFY(m3.template marked().solveTriangular(m3).cwise().abs().isIdentity(test_precision())); - VERIFY(m3.transpose().template marked() - .solveTriangular(m3.transpose()).cwise().abs().isIdentity(test_precision())); - // check M * inv(L) using in place API - m4 = m3; - m3.transpose().template marked().solveTriangularInPlace(trm4); - VERIFY(m4.cwise().abs().isIdentity(test_precision())); - - m3 = m1.template part(); - VERIFY(m3.template marked().solveTriangular(m3).cwise().abs().isIdentity(test_precision())); - VERIFY(m3.transpose().template marked() - .solveTriangular(m3.transpose()).cwise().abs().isIdentity(test_precision())); - // check M * inv(U) using in place API - m4 = m3; - m3.transpose().template marked().solveTriangularInPlace(trm4); - VERIFY(m4.cwise().abs().isIdentity(test_precision())); - - m3 = m1.template part(); - VERIFY(m2.isApprox(m3 * (m3.template marked().solveTriangular(m2)), largerEps)); - m3 = m1.template part(); - VERIFY(m2.isApprox(m3 * (m3.template marked().solveTriangular(m2)), largerEps)); - - VERIFY((m1.template part() * m2.template part()).isUpperTriangular()); - - // test swap - m1.setOnes(); - m2.setZero(); - m2.template part().swap(m1); - m3.setZero(); - m3.template part().setOnes(); - VERIFY_IS_APPROX(m2,m3); - -} - -void selfadjoint() -{ - Matrix2i m; - m << 1, 2, - 3, 4; - - Matrix2i m1 = Matrix2i::Zero(); - m1.part() = m; - Matrix2i ref1; - ref1 << 1, 2, - 2, 4; - VERIFY(m1 == ref1); - - Matrix2i m2 = Matrix2i::Zero(); - m2.part() = m.part(); - Matrix2i ref2; - ref2 << 1, 2, - 2, 4; - VERIFY(m2 == ref2); - - Matrix2i m3 = Matrix2i::Zero(); - m3.part() = m.part(); - Matrix2i ref3; - ref3 << 1, 0, - 0, 4; - VERIFY(m3 == ref3); - - // example inspired from bug 159 - int array[] = {1, 2, 3, 4}; - Matrix2i::Map(array).part() = Matrix2i::Random().part(); - - std::cout << "hello\n" << array << std::endl; -} - -void test_eigen2_triangular() -{ - CALL_SUBTEST_8( selfadjoint() ); - for(int i = 0; i < g_repeat ; i++) { - CALL_SUBTEST_1( triangular(Matrix()) ); - CALL_SUBTEST_2( triangular(Matrix()) ); - CALL_SUBTEST_3( triangular(Matrix3d()) ); - CALL_SUBTEST_4( triangular(MatrixXcf(4, 4)) ); - CALL_SUBTEST_5( triangular(Matrix,8, 8>()) ); - CALL_SUBTEST_6( triangular(MatrixXd(17,17)) ); - CALL_SUBTEST_7( triangular(Matrix(5, 5)) ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_unalignedassert.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_unalignedassert.cpp deleted file mode 100644 index d10b6f53..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_unalignedassert.cpp +++ /dev/null @@ -1,116 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -struct Good1 -{ - MatrixXd m; // good: m will allocate its own array, taking care of alignment. - Good1() : m(20,20) {} -}; - -struct Good2 -{ - Matrix3d m; // good: m's size isn't a multiple of 16 bytes, so m doesn't have to be aligned -}; - -struct Good3 -{ - Vector2f m; // good: same reason -}; - -struct Bad4 -{ - Vector2d m; // bad: sizeof(m)%16==0 so alignment is required -}; - -struct Bad5 -{ - Matrix m; // bad: same reason -}; - -struct Bad6 -{ - Matrix m; // bad: same reason -}; - -struct Good7 -{ - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - Vector2d m; - float f; // make the struct have sizeof%16!=0 to make it a little more tricky when we allow an array of 2 such objects -}; - -struct Good8 -{ - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - float f; // try the f at first -- the EIGEN_ALIGN_128 attribute of m should make that still work - Matrix4f m; -}; - -struct Good9 -{ - Matrix m; // good: no alignment requested - float f; -}; - -template struct Depends -{ - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(Align) - Vector2d m; - float f; -}; - -template -void check_unalignedassert_good() -{ - T *x, *y; - x = new T; - delete x; - y = new T[2]; - delete[] y; -} - -#if EIGEN_ARCH_WANTS_ALIGNMENT -template -void check_unalignedassert_bad() -{ - float buf[sizeof(T)+16]; - float *unaligned = buf; - while((reinterpret_cast(unaligned)&0xf)==0) ++unaligned; // make sure unaligned is really unaligned - T *x = ::new(static_cast(unaligned)) T; - x->~T(); -} -#endif - -void unalignedassert() -{ - check_unalignedassert_good(); - check_unalignedassert_good(); - check_unalignedassert_good(); -#if EIGEN_ARCH_WANTS_ALIGNMENT - VERIFY_RAISES_ASSERT(check_unalignedassert_bad()); - VERIFY_RAISES_ASSERT(check_unalignedassert_bad()); - VERIFY_RAISES_ASSERT(check_unalignedassert_bad()); -#endif - - check_unalignedassert_good(); - check_unalignedassert_good(); - check_unalignedassert_good(); - check_unalignedassert_good >(); - -#if EIGEN_ARCH_WANTS_ALIGNMENT - VERIFY_RAISES_ASSERT(check_unalignedassert_bad >()); -#endif -} - -void test_eigen2_unalignedassert() -{ - CALL_SUBTEST(unalignedassert()); -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_visitor.cpp b/testbed/nanogui/ext/eigen/test/eigen2/eigen2_visitor.cpp deleted file mode 100644 index 4781991d..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_visitor.cpp +++ /dev/null @@ -1,116 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template void matrixVisitor(const MatrixType& p) -{ - typedef typename MatrixType::Scalar Scalar; - - int rows = p.rows(); - int cols = p.cols(); - - // construct a random matrix where all coefficients are different - MatrixType m; - m = MatrixType::Random(rows, cols); - for(int i = 0; i < m.size(); i++) - for(int i2 = 0; i2 < i; i2++) - while(m(i) == m(i2)) // yes, == - m(i) = ei_random(); - - Scalar minc = Scalar(1000), maxc = Scalar(-1000); - int minrow=0,mincol=0,maxrow=0,maxcol=0; - for(int j = 0; j < cols; j++) - for(int i = 0; i < rows; i++) - { - if(m(i,j) < minc) - { - minc = m(i,j); - minrow = i; - mincol = j; - } - if(m(i,j) > maxc) - { - maxc = m(i,j); - maxrow = i; - maxcol = j; - } - } - int eigen_minrow, eigen_mincol, eigen_maxrow, eigen_maxcol; - Scalar eigen_minc, eigen_maxc; - eigen_minc = m.minCoeff(&eigen_minrow,&eigen_mincol); - eigen_maxc = m.maxCoeff(&eigen_maxrow,&eigen_maxcol); - VERIFY(minrow == eigen_minrow); - VERIFY(maxrow == eigen_maxrow); - VERIFY(mincol == eigen_mincol); - VERIFY(maxcol == eigen_maxcol); - VERIFY_IS_APPROX(minc, eigen_minc); - VERIFY_IS_APPROX(maxc, eigen_maxc); - VERIFY_IS_APPROX(minc, m.minCoeff()); - VERIFY_IS_APPROX(maxc, m.maxCoeff()); -} - -template void vectorVisitor(const VectorType& w) -{ - typedef typename VectorType::Scalar Scalar; - - int size = w.size(); - - // construct a random vector where all coefficients are different - VectorType v; - v = VectorType::Random(size); - for(int i = 0; i < size; i++) - for(int i2 = 0; i2 < i; i2++) - while(v(i) == v(i2)) // yes, == - v(i) = ei_random(); - - Scalar minc = Scalar(1000), maxc = Scalar(-1000); - int minidx=0,maxidx=0; - for(int i = 0; i < size; i++) - { - if(v(i) < minc) - { - minc = v(i); - minidx = i; - } - if(v(i) > maxc) - { - maxc = v(i); - maxidx = i; - } - } - int eigen_minidx, eigen_maxidx; - Scalar eigen_minc, eigen_maxc; - eigen_minc = v.minCoeff(&eigen_minidx); - eigen_maxc = v.maxCoeff(&eigen_maxidx); - VERIFY(minidx == eigen_minidx); - VERIFY(maxidx == eigen_maxidx); - VERIFY_IS_APPROX(minc, eigen_minc); - VERIFY_IS_APPROX(maxc, eigen_maxc); - VERIFY_IS_APPROX(minc, v.minCoeff()); - VERIFY_IS_APPROX(maxc, v.maxCoeff()); -} - -void test_eigen2_visitor() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( matrixVisitor(Matrix()) ); - CALL_SUBTEST_2( matrixVisitor(Matrix2f()) ); - CALL_SUBTEST_3( matrixVisitor(Matrix4d()) ); - CALL_SUBTEST_4( matrixVisitor(MatrixXd(8, 12)) ); - CALL_SUBTEST_5( matrixVisitor(Matrix(20, 20)) ); - CALL_SUBTEST_6( matrixVisitor(MatrixXi(8, 12)) ); - } - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_7( vectorVisitor(Vector4f()) ); - CALL_SUBTEST_4( vectorVisitor(VectorXd(10)) ); - CALL_SUBTEST_4( vectorVisitor(RowVectorXd(10)) ); - CALL_SUBTEST_8( vectorVisitor(VectorXf(33)) ); - } -} diff --git a/testbed/nanogui/ext/eigen/test/eigen2/gsl_helper.h b/testbed/nanogui/ext/eigen/test/eigen2/gsl_helper.h deleted file mode 100644 index d1d85453..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/gsl_helper.h +++ /dev/null @@ -1,175 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#ifndef EIGEN_GSL_HELPER -#define EIGEN_GSL_HELPER - -#include - -#include -#include -#include -#include -#include -#include - -namespace Eigen { - -template::IsComplex> struct GslTraits -{ - typedef gsl_matrix* Matrix; - typedef gsl_vector* Vector; - static Matrix createMatrix(int rows, int cols) { return gsl_matrix_alloc(rows,cols); } - static Vector createVector(int size) { return gsl_vector_alloc(size); } - static void free(Matrix& m) { gsl_matrix_free(m); m=0; } - static void free(Vector& m) { gsl_vector_free(m); m=0; } - static void prod(const Matrix& m, const Vector& v, Vector& x) { gsl_blas_dgemv(CblasNoTrans,1,m,v,0,x); } - static void cholesky(Matrix& m) { gsl_linalg_cholesky_decomp(m); } - static void cholesky_solve(const Matrix& m, const Vector& b, Vector& x) { gsl_linalg_cholesky_solve(m,b,x); } - static void eigen_symm(const Matrix& m, Vector& eval, Matrix& evec) - { - gsl_eigen_symmv_workspace * w = gsl_eigen_symmv_alloc(m->size1); - Matrix a = createMatrix(m->size1, m->size2); - gsl_matrix_memcpy(a, m); - gsl_eigen_symmv(a,eval,evec,w); - gsl_eigen_symmv_sort(eval, evec, GSL_EIGEN_SORT_VAL_ASC); - gsl_eigen_symmv_free(w); - free(a); - } - static void eigen_symm_gen(const Matrix& m, const Matrix& _b, Vector& eval, Matrix& evec) - { - gsl_eigen_gensymmv_workspace * w = gsl_eigen_gensymmv_alloc(m->size1); - Matrix a = createMatrix(m->size1, m->size2); - Matrix b = createMatrix(_b->size1, _b->size2); - gsl_matrix_memcpy(a, m); - gsl_matrix_memcpy(b, _b); - gsl_eigen_gensymmv(a,b,eval,evec,w); - gsl_eigen_symmv_sort(eval, evec, GSL_EIGEN_SORT_VAL_ASC); - gsl_eigen_gensymmv_free(w); - free(a); - } -}; - -template struct GslTraits -{ - typedef gsl_matrix_complex* Matrix; - typedef gsl_vector_complex* Vector; - static Matrix createMatrix(int rows, int cols) { return gsl_matrix_complex_alloc(rows,cols); } - static Vector createVector(int size) { return gsl_vector_complex_alloc(size); } - static void free(Matrix& m) { gsl_matrix_complex_free(m); m=0; } - static void free(Vector& m) { gsl_vector_complex_free(m); m=0; } - static void cholesky(Matrix& m) { gsl_linalg_complex_cholesky_decomp(m); } - static void cholesky_solve(const Matrix& m, const Vector& b, Vector& x) { gsl_linalg_complex_cholesky_solve(m,b,x); } - static void prod(const Matrix& m, const Vector& v, Vector& x) - { gsl_blas_zgemv(CblasNoTrans,gsl_complex_rect(1,0),m,v,gsl_complex_rect(0,0),x); } - static void eigen_symm(const Matrix& m, gsl_vector* &eval, Matrix& evec) - { - gsl_eigen_hermv_workspace * w = gsl_eigen_hermv_alloc(m->size1); - Matrix a = createMatrix(m->size1, m->size2); - gsl_matrix_complex_memcpy(a, m); - gsl_eigen_hermv(a,eval,evec,w); - gsl_eigen_hermv_sort(eval, evec, GSL_EIGEN_SORT_VAL_ASC); - gsl_eigen_hermv_free(w); - free(a); - } - static void eigen_symm_gen(const Matrix& m, const Matrix& _b, gsl_vector* &eval, Matrix& evec) - { - gsl_eigen_genhermv_workspace * w = gsl_eigen_genhermv_alloc(m->size1); - Matrix a = createMatrix(m->size1, m->size2); - Matrix b = createMatrix(_b->size1, _b->size2); - gsl_matrix_complex_memcpy(a, m); - gsl_matrix_complex_memcpy(b, _b); - gsl_eigen_genhermv(a,b,eval,evec,w); - gsl_eigen_hermv_sort(eval, evec, GSL_EIGEN_SORT_VAL_ASC); - gsl_eigen_genhermv_free(w); - free(a); - } -}; - -template -void convert(const MatrixType& m, gsl_matrix* &res) -{ -// if (res) -// gsl_matrix_free(res); - res = gsl_matrix_alloc(m.rows(), m.cols()); - for (int i=0 ; i -void convert(const gsl_matrix* m, MatrixType& res) -{ - res.resize(int(m->size1), int(m->size2)); - for (int i=0 ; i -void convert(const VectorType& m, gsl_vector* &res) -{ - if (res) gsl_vector_free(res); - res = gsl_vector_alloc(m.size()); - for (int i=0 ; i -void convert(const gsl_vector* m, VectorType& res) -{ - res.resize (m->size); - for (int i=0 ; i -void convert(const MatrixType& m, gsl_matrix_complex* &res) -{ - res = gsl_matrix_complex_alloc(m.rows(), m.cols()); - for (int i=0 ; i -void convert(const gsl_matrix_complex* m, MatrixType& res) -{ - res.resize(int(m->size1), int(m->size2)); - for (int i=0 ; i -void convert(const VectorType& m, gsl_vector_complex* &res) -{ - res = gsl_vector_complex_alloc(m.size()); - for (int i=0 ; i -void convert(const gsl_vector_complex* m, VectorType& res) -{ - res.resize(m->size); - for (int i=0 ; i -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include -#include -#include -#include -#include - -#ifndef EIGEN_TEST_FUNC -#error EIGEN_TEST_FUNC must be defined -#endif - -#define DEFAULT_REPEAT 10 - -namespace Eigen -{ - static std::vector g_test_stack; - static int g_repeat; -} - -#define EI_PP_MAKE_STRING2(S) #S -#define EI_PP_MAKE_STRING(S) EI_PP_MAKE_STRING2(S) - -#define EI_PP_CAT2(a,b) a ## b -#define EI_PP_CAT(a,b) EI_PP_CAT2(a,b) - -#ifndef EIGEN_NO_ASSERTION_CHECKING - - namespace Eigen - { - static const bool should_raise_an_assert = false; - - // Used to avoid to raise two exceptions at a time in which - // case the exception is not properly caught. - // This may happen when a second exceptions is raise in a destructor. - static bool no_more_assert = false; - - struct eigen_assert_exception - { - eigen_assert_exception(void) {} - ~eigen_assert_exception() { Eigen::no_more_assert = false; } - }; - } - - // If EIGEN_DEBUG_ASSERTS is defined and if no assertion is raised while - // one should have been, then the list of excecuted assertions is printed out. - // - // EIGEN_DEBUG_ASSERTS is not enabled by default as it - // significantly increases the compilation time - // and might even introduce side effects that would hide - // some memory errors. - #ifdef EIGEN_DEBUG_ASSERTS - - namespace Eigen - { - static bool ei_push_assert = false; - static std::vector eigen_assert_list; - } - - #define eigen_assert(a) \ - if( (!(a)) && (!no_more_assert) ) \ - { \ - Eigen::no_more_assert = true; \ - throw Eigen::eigen_assert_exception(); \ - } \ - else if (Eigen::ei_push_assert) \ - { \ - eigen_assert_list.push_back(std::string(EI_PP_MAKE_STRING(__FILE__)" ("EI_PP_MAKE_STRING(__LINE__)") : "#a) ); \ - } - - #define VERIFY_RAISES_ASSERT(a) \ - { \ - Eigen::no_more_assert = false; \ - try { \ - Eigen::eigen_assert_list.clear(); \ - Eigen::ei_push_assert = true; \ - a; \ - Eigen::ei_push_assert = false; \ - std::cerr << "One of the following asserts should have been raised:\n"; \ - for (uint ai=0 ; ai - - -#define VERIFY(a) do { if (!(a)) { \ - std::cerr << "Test " << g_test_stack.back() << " failed in "EI_PP_MAKE_STRING(__FILE__) << " (" << EI_PP_MAKE_STRING(__LINE__) << ")" \ - << std::endl << " " << EI_PP_MAKE_STRING(a) << std::endl << std::endl; \ - abort(); \ - } } while (0) - -#define VERIFY_IS_APPROX(a, b) VERIFY(test_ei_isApprox(a, b)) -#define VERIFY_IS_NOT_APPROX(a, b) VERIFY(!test_ei_isApprox(a, b)) -#define VERIFY_IS_MUCH_SMALLER_THAN(a, b) VERIFY(test_ei_isMuchSmallerThan(a, b)) -#define VERIFY_IS_NOT_MUCH_SMALLER_THAN(a, b) VERIFY(!test_ei_isMuchSmallerThan(a, b)) -#define VERIFY_IS_APPROX_OR_LESS_THAN(a, b) VERIFY(test_ei_isApproxOrLessThan(a, b)) -#define VERIFY_IS_NOT_APPROX_OR_LESS_THAN(a, b) VERIFY(!test_ei_isApproxOrLessThan(a, b)) - -#define CALL_SUBTEST(FUNC) do { \ - g_test_stack.push_back(EI_PP_MAKE_STRING(FUNC)); \ - FUNC; \ - g_test_stack.pop_back(); \ - } while (0) - -namespace Eigen { - -template inline typename NumTraits::Real test_precision(); -template<> inline int test_precision() { return 0; } -template<> inline float test_precision() { return 1e-3f; } -template<> inline double test_precision() { return 1e-6; } -template<> inline float test_precision >() { return test_precision(); } -template<> inline double test_precision >() { return test_precision(); } -template<> inline long double test_precision() { return 1e-6; } - -inline bool test_ei_isApprox(const int& a, const int& b) -{ return ei_isApprox(a, b, test_precision()); } -inline bool test_ei_isMuchSmallerThan(const int& a, const int& b) -{ return ei_isMuchSmallerThan(a, b, test_precision()); } -inline bool test_ei_isApproxOrLessThan(const int& a, const int& b) -{ return ei_isApproxOrLessThan(a, b, test_precision()); } - -inline bool test_ei_isApprox(const float& a, const float& b) -{ return ei_isApprox(a, b, test_precision()); } -inline bool test_ei_isMuchSmallerThan(const float& a, const float& b) -{ return ei_isMuchSmallerThan(a, b, test_precision()); } -inline bool test_ei_isApproxOrLessThan(const float& a, const float& b) -{ return ei_isApproxOrLessThan(a, b, test_precision()); } - -inline bool test_ei_isApprox(const double& a, const double& b) -{ return ei_isApprox(a, b, test_precision()); } -inline bool test_ei_isMuchSmallerThan(const double& a, const double& b) -{ return ei_isMuchSmallerThan(a, b, test_precision()); } -inline bool test_ei_isApproxOrLessThan(const double& a, const double& b) -{ return ei_isApproxOrLessThan(a, b, test_precision()); } - -inline bool test_ei_isApprox(const std::complex& a, const std::complex& b) -{ return ei_isApprox(a, b, test_precision >()); } -inline bool test_ei_isMuchSmallerThan(const std::complex& a, const std::complex& b) -{ return ei_isMuchSmallerThan(a, b, test_precision >()); } - -inline bool test_ei_isApprox(const std::complex& a, const std::complex& b) -{ return ei_isApprox(a, b, test_precision >()); } -inline bool test_ei_isMuchSmallerThan(const std::complex& a, const std::complex& b) -{ return ei_isMuchSmallerThan(a, b, test_precision >()); } - -inline bool test_ei_isApprox(const long double& a, const long double& b) -{ return ei_isApprox(a, b, test_precision()); } -inline bool test_ei_isMuchSmallerThan(const long double& a, const long double& b) -{ return ei_isMuchSmallerThan(a, b, test_precision()); } -inline bool test_ei_isApproxOrLessThan(const long double& a, const long double& b) -{ return ei_isApproxOrLessThan(a, b, test_precision()); } - -template -inline bool test_ei_isApprox(const Type1& a, const Type2& b) -{ - return a.isApprox(b, test_precision()); -} - -template -inline bool test_ei_isMuchSmallerThan(const MatrixBase& m1, - const MatrixBase& m2) -{ - return m1.isMuchSmallerThan(m2, test_precision::Scalar>()); -} - -template -inline bool test_ei_isMuchSmallerThan(const MatrixBase& m, - const typename NumTraits::Scalar>::Real& s) -{ - return m.isMuchSmallerThan(s, test_precision::Scalar>()); -} - -} // end namespace Eigen - -template struct GetDifferentType; - -template<> struct GetDifferentType { typedef double type; }; -template<> struct GetDifferentType { typedef float type; }; -template struct GetDifferentType > -{ typedef std::complex::type> type; }; - -// forward declaration of the main test function -void EI_PP_CAT(test_,EIGEN_TEST_FUNC)(); - -using namespace Eigen; - -#ifdef EIGEN_TEST_PART_1 -#define CALL_SUBTEST_1(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_1(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_2 -#define CALL_SUBTEST_2(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_2(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_3 -#define CALL_SUBTEST_3(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_3(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_4 -#define CALL_SUBTEST_4(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_4(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_5 -#define CALL_SUBTEST_5(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_5(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_6 -#define CALL_SUBTEST_6(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_6(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_7 -#define CALL_SUBTEST_7(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_7(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_8 -#define CALL_SUBTEST_8(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_8(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_9 -#define CALL_SUBTEST_9(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_9(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_10 -#define CALL_SUBTEST_10(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_10(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_11 -#define CALL_SUBTEST_11(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_11(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_12 -#define CALL_SUBTEST_12(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_12(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_13 -#define CALL_SUBTEST_13(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_13(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_14 -#define CALL_SUBTEST_14(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_14(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_15 -#define CALL_SUBTEST_15(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_15(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_16 -#define CALL_SUBTEST_16(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_16(FUNC) -#endif - - - -int main(int argc, char *argv[]) -{ - bool has_set_repeat = false; - bool has_set_seed = false; - bool need_help = false; - unsigned int seed = 0; - int repeat = DEFAULT_REPEAT; - - for(int i = 1; i < argc; i++) - { - if(argv[i][0] == 'r') - { - if(has_set_repeat) - { - std::cout << "Argument " << argv[i] << " conflicting with a former argument" << std::endl; - return 1; - } - repeat = std::atoi(argv[i]+1); - has_set_repeat = true; - if(repeat <= 0) - { - std::cout << "Invalid \'repeat\' value " << argv[i]+1 << std::endl; - return 1; - } - } - else if(argv[i][0] == 's') - { - if(has_set_seed) - { - std::cout << "Argument " << argv[i] << " conflicting with a former argument" << std::endl; - return 1; - } - seed = int(std::strtoul(argv[i]+1, 0, 10)); - has_set_seed = true; - bool ok = seed!=0; - if(!ok) - { - std::cout << "Invalid \'seed\' value " << argv[i]+1 << std::endl; - return 1; - } - } - else - { - need_help = true; - } - } - - if(need_help) - { - std::cout << "This test application takes the following optional arguments:" << std::endl; - std::cout << " rN Repeat each test N times (default: " << DEFAULT_REPEAT << ")" << std::endl; - std::cout << " sN Use N as seed for random numbers (default: based on current time)" << std::endl; - return 1; - } - - if(!has_set_seed) seed = (unsigned int) std::time(NULL); - if(!has_set_repeat) repeat = DEFAULT_REPEAT; - - std::cout << "Initializing random number generator with seed " << seed << std::endl; - std::srand(seed); - std::cout << "Repeating each test " << repeat << " times" << std::endl; - - Eigen::g_repeat = repeat; - Eigen::g_test_stack.push_back(EI_PP_MAKE_STRING(EIGEN_TEST_FUNC)); - - EI_PP_CAT(test_,EIGEN_TEST_FUNC)(); - return 0; -} - - - diff --git a/testbed/nanogui/ext/eigen/test/eigen2/product.h b/testbed/nanogui/ext/eigen/test/eigen2/product.h deleted file mode 100644 index ae1b4bae..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/product.h +++ /dev/null @@ -1,129 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include -#include - -template -bool areNotApprox(const MatrixBase& m1, const MatrixBase& m2, typename Derived1::RealScalar epsilon = precision()) -{ - return !((m1-m2).cwise().abs2().maxCoeff() < epsilon * epsilon - * std::max(m1.cwise().abs2().maxCoeff(), m2.cwise().abs2().maxCoeff())); -} - -template void product(const MatrixType& m) -{ - /* this test covers the following files: - Identity.h Product.h - */ - - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::FloatingPoint FloatingPoint; - typedef Matrix RowVectorType; - typedef Matrix ColVectorType; - typedef Matrix RowSquareMatrixType; - typedef Matrix ColSquareMatrixType; - typedef Matrix OtherMajorMatrixType; - - int rows = m.rows(); - int cols = m.cols(); - - // this test relies a lot on Random.h, and there's not much more that we can do - // to test it, hence I consider that we will have tested Random.h - MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols), - m3(rows, cols); - RowSquareMatrixType - identity = RowSquareMatrixType::Identity(rows, rows), - square = RowSquareMatrixType::Random(rows, rows), - res = RowSquareMatrixType::Random(rows, rows); - ColSquareMatrixType - square2 = ColSquareMatrixType::Random(cols, cols), - res2 = ColSquareMatrixType::Random(cols, cols); - RowVectorType v1 = RowVectorType::Random(rows); - ColVectorType vc2 = ColVectorType::Random(cols), vcres(cols); - OtherMajorMatrixType tm1 = m1; - - Scalar s1 = ei_random(); - - int r = ei_random(0, rows-1), - c = ei_random(0, cols-1); - - // begin testing Product.h: only associativity for now - // (we use Transpose.h but this doesn't count as a test for it) - - VERIFY_IS_APPROX((m1*m1.transpose())*m2, m1*(m1.transpose()*m2)); - m3 = m1; - m3 *= m1.transpose() * m2; - VERIFY_IS_APPROX(m3, m1 * (m1.transpose()*m2)); - VERIFY_IS_APPROX(m3, m1.lazy() * (m1.transpose()*m2)); - - // continue testing Product.h: distributivity - VERIFY_IS_APPROX(square*(m1 + m2), square*m1+square*m2); - VERIFY_IS_APPROX(square*(m1 - m2), square*m1-square*m2); - - // continue testing Product.h: compatibility with ScalarMultiple.h - VERIFY_IS_APPROX(s1*(square*m1), (s1*square)*m1); - VERIFY_IS_APPROX(s1*(square*m1), square*(m1*s1)); - - // again, test operator() to check const-qualification - s1 += (square.lazy() * m1)(r,c); - - // test Product.h together with Identity.h - VERIFY_IS_APPROX(v1, identity*v1); - VERIFY_IS_APPROX(v1.transpose(), v1.transpose() * identity); - // again, test operator() to check const-qualification - VERIFY_IS_APPROX(MatrixType::Identity(rows, cols)(r,c), static_cast(r==c)); - - if (rows!=cols) - VERIFY_RAISES_ASSERT(m3 = m1*m1); - - // test the previous tests were not screwed up because operator* returns 0 - // (we use the more accurate default epsilon) - if (NumTraits::HasFloatingPoint && std::min(rows,cols)>1) - { - VERIFY(areNotApprox(m1.transpose()*m2,m2.transpose()*m1)); - } - - // test optimized operator+= path - res = square; - res += (m1 * m2.transpose()).lazy(); - VERIFY_IS_APPROX(res, square + m1 * m2.transpose()); - if (NumTraits::HasFloatingPoint && std::min(rows,cols)>1) - { - VERIFY(areNotApprox(res,square + m2 * m1.transpose())); - } - vcres = vc2; - vcres += (m1.transpose() * v1).lazy(); - VERIFY_IS_APPROX(vcres, vc2 + m1.transpose() * v1); - tm1 = m1; - VERIFY_IS_APPROX(tm1.transpose() * v1, m1.transpose() * v1); - VERIFY_IS_APPROX(v1.transpose() * tm1, v1.transpose() * m1); - - // test submatrix and matrix/vector product - for (int i=0; i::HasFloatingPoint && std::min(rows,cols)>1) - { - VERIFY(areNotApprox(res2,square2 + m2.transpose() * m1)); - } -} - diff --git a/testbed/nanogui/ext/eigen/test/eigen2/runtest.sh b/testbed/nanogui/ext/eigen/test/eigen2/runtest.sh deleted file mode 100755 index bc693af1..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/runtest.sh +++ /dev/null @@ -1,28 +0,0 @@ -#!/bin/bash - -black='\E[30m' -red='\E[31m' -green='\E[32m' -yellow='\E[33m' -blue='\E[34m' -magenta='\E[35m' -cyan='\E[36m' -white='\E[37m' - -if make test_$1 > /dev/null 2> .runtest.log ; then - if ! ./test_$1 r20 > /dev/null 2> .runtest.log ; then - echo -e $red Test $1 failed: $black - echo -e $blue - cat .runtest.log - echo -e $black - exit 1 - else - echo -e $green Test $1 passed$black - fi -else - echo -e $red Build of target $1 failed: $black - echo -e $blue - cat .runtest.log - echo -e $black - exit 1 -fi diff --git a/testbed/nanogui/ext/eigen/test/eigen2/sparse.h b/testbed/nanogui/ext/eigen/test/eigen2/sparse.h deleted file mode 100644 index e12f8999..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/sparse.h +++ /dev/null @@ -1,154 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Daniel Gomez Ferro -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#ifndef EIGEN_TESTSPARSE_H - -#include "main.h" - -#if EIGEN_GNUC_AT_LEAST(4,0) && !defined __ICC -#include -#define EIGEN_UNORDERED_MAP_SUPPORT -namespace std { - using std::tr1::unordered_map; -} -#endif - -#ifdef EIGEN_GOOGLEHASH_SUPPORT - #include -#endif - -#include -#include -#include - -enum { - ForceNonZeroDiag = 1, - MakeLowerTriangular = 2, - MakeUpperTriangular = 4, - ForceRealDiag = 8 -}; - -/* Initializes both a sparse and dense matrix with same random values, - * and a ratio of \a density non zero entries. - * \param flags is a union of ForceNonZeroDiag, MakeLowerTriangular and MakeUpperTriangular - * allowing to control the shape of the matrix. - * \param zeroCoords and nonzeroCoords allows to get the coordinate lists of the non zero, - * and zero coefficients respectively. - */ -template void -initSparse(double density, - Matrix& refMat, - SparseMatrix& sparseMat, - int flags = 0, - std::vector* zeroCoords = 0, - std::vector* nonzeroCoords = 0) -{ - sparseMat.startFill(int(refMat.rows()*refMat.cols()*density)); - for(int j=0; j(0,1) < density) ? ei_random() : Scalar(0); - if ((flags&ForceNonZeroDiag) && (i==j)) - { - v = ei_random()*Scalar(3.); - v = v*v + Scalar(5.); - } - if ((flags & MakeLowerTriangular) && j>i) - v = Scalar(0); - else if ((flags & MakeUpperTriangular) && jpush_back(Vector2i(i,j)); - } - else if (zeroCoords) - { - zeroCoords->push_back(Vector2i(i,j)); - } - refMat(i,j) = v; - } - } - sparseMat.endFill(); -} - -template void -initSparse(double density, - Matrix& refMat, - DynamicSparseMatrix& sparseMat, - int flags = 0, - std::vector* zeroCoords = 0, - std::vector* nonzeroCoords = 0) -{ - sparseMat.startFill(int(refMat.rows()*refMat.cols()*density)); - for(int j=0; j(0,1) < density) ? ei_random() : Scalar(0); - if ((flags&ForceNonZeroDiag) && (i==j)) - { - v = ei_random()*Scalar(3.); - v = v*v + Scalar(5.); - } - if ((flags & MakeLowerTriangular) && j>i) - v = Scalar(0); - else if ((flags & MakeUpperTriangular) && jpush_back(Vector2i(i,j)); - } - else if (zeroCoords) - { - zeroCoords->push_back(Vector2i(i,j)); - } - refMat(i,j) = v; - } - } - sparseMat.endFill(); -} - -template void -initSparse(double density, - Matrix& refVec, - SparseVector& sparseVec, - std::vector* zeroCoords = 0, - std::vector* nonzeroCoords = 0) -{ - sparseVec.reserve(int(refVec.size()*density)); - sparseVec.setZero(); - for(int i=0; i(0,1) < density) ? ei_random() : Scalar(0); - if (v!=Scalar(0)) - { - sparseVec.fill(i) = v; - if (nonzeroCoords) - nonzeroCoords->push_back(i); - } - else if (zeroCoords) - zeroCoords->push_back(i); - refVec[i] = v; - } -} - -#endif // EIGEN_TESTSPARSE_H diff --git a/testbed/nanogui/ext/eigen/test/eigen2/testsuite.cmake b/testbed/nanogui/ext/eigen/test/eigen2/testsuite.cmake deleted file mode 100644 index 12b6bfa2..00000000 --- a/testbed/nanogui/ext/eigen/test/eigen2/testsuite.cmake +++ /dev/null @@ -1,197 +0,0 @@ - -#################################################################### -# -# Usage: -# - create a new folder, let's call it cdash -# - in that folder, do: -# ctest -S path/to/eigen2/test/testsuite.cmake[,option1=value1[,option2=value2]] -# -# Options: -# - EIGEN_CXX: compiler, eg.: g++-4.2 -# default: default c++ compiler -# - EIGEN_SITE: eg, INRIA-Bdx_pc-gael, or the name of the contributor, etc. -# default: hostname -# - EIGEN_BUILD_STRING: a string which identify the system/compiler. It should be formed like that: -# --- -# with: -# = opensuse, debian, osx, windows, cygwin, freebsd, solaris, etc. -# = 11.1, XP, vista, leopard, etc. -# = i386, x86_64, ia64, powerpc, etc. -# = gcc-4.3.2, icc-11.0, MSVC-2008, etc. -# - EIGEN_EXPLICIT_VECTORIZATION: novec, SSE2, Altivec -# default: SSE2 for x86_64 systems, novec otherwise -# Its value is automatically appended to EIGEN_BUILD_STRING -# - EIGEN_CMAKE_DIR: path to cmake executable -# - EIGEN_MODE: dashboard model, can be Experimental, Nightly, or Continuous -# default: Nightly -# - EIGEN_WORK_DIR: directory used to download the source files and make the builds -# default: folder which contains this script -# - EIGEN_CMAKE_ARGS: additional arguments passed to cmake -# - CTEST_SOURCE_DIRECTORY: path to eigen's src (use a new and empty folder, not the one you are working on) -# default: /src -# - CTEST_BINARY_DIRECTORY: build directory -# default: /nightly- -# -# Here is an example running several compilers on a linux system: -# #!/bin/bash -# ARCH=`uname -m` -# SITE=`hostname` -# VERSION=opensuse-11.1 -# WORK_DIR=/home/gael/Coding/eigen2/cdash -# # get the last version of the script -# wget http://bitbucket.org/eigen/eigen/raw/tip/test/testsuite.cmake -o $WORK_DIR/testsuite.cmake -# COMMON="ctest -S $WORK_DIR/testsuite.cmake,EIGEN_WORK_DIR=$WORK_DIR,EIGEN_SITE=$SITE,EIGEN_MODE=$1,EIGEN_BUILD_STRING=$OS_VERSION-$ARCH" -# $COMMON-gcc-3.4.6,EIGEN_CXX=g++-3.4 -# $COMMON-gcc-4.0.1,EIGEN_CXX=g++-4.0.1 -# $COMMON-gcc-4.3.2,EIGEN_CXX=g++-4.3,EIGEN_EXPLICIT_VECTORIZATION=novec -# $COMMON-gcc-4.3.2,EIGEN_CXX=g++-4.3,EIGEN_EXPLICIT_VECTORIZATION=SSE2 -# $COMMON-icc-11.0,EIGEN_CXX=icpc -# -#################################################################### - -# process the arguments - -set(ARGLIST ${CTEST_SCRIPT_ARG}) -while(${ARGLIST} MATCHES ".+.*") - - # pick first - string(REGEX MATCH "([^,]*)(,.*)?" DUMMY ${ARGLIST}) - SET(TOP ${CMAKE_MATCH_1}) - - # remove first - string(REGEX MATCHALL "[^,]*,(.*)" DUMMY ${ARGLIST}) - SET(ARGLIST ${CMAKE_MATCH_1}) - - # decompose as a pair key=value - string(REGEX MATCH "([^=]*)(=.*)?" DUMMY ${TOP}) - SET(KEY ${CMAKE_MATCH_1}) - - string(REGEX MATCH "[^=]*=(.*)" DUMMY ${TOP}) - SET(VALUE ${CMAKE_MATCH_1}) - - # set the variable to the specified value - if(VALUE) - SET(${KEY} ${VALUE}) - else(VALUE) - SET(${KEY} ON) - endif(VALUE) - -endwhile(${ARGLIST} MATCHES ".+.*") - -#################################################################### -# Automatically set some user variables if they have not been defined manually -#################################################################### -cmake_minimum_required(VERSION 2.6 FATAL_ERROR) - -if(NOT EIGEN_SITE) - site_name(EIGEN_SITE) -endif(NOT EIGEN_SITE) - -if(NOT EIGEN_CMAKE_DIR) - SET(EIGEN_CMAKE_DIR "") -endif(NOT EIGEN_CMAKE_DIR) - -if(NOT EIGEN_BUILD_STRING) - - # let's try to find all information we need to make the build string ourself - - # OS - build_name(EIGEN_OS_VERSION) - - # arch - set(EIGEN_ARCH ${CMAKE_SYSTEM_PROCESSOR}) - if(WIN32) - set(EIGEN_ARCH $ENV{PROCESSOR_ARCHITECTURE}) - else(WIN32) - execute_process(COMMAND uname -m OUTPUT_VARIABLE EIGEN_ARCH OUTPUT_STRIP_TRAILING_WHITESPACE) - endif(WIN32) - - set(EIGEN_BUILD_STRING ${EIGEN_OS_VERSION}${EIGEN_ARCH}-${EIGEN_CXX}) - -endif(NOT EIGEN_BUILD_STRING) - -if(DEFINED EIGEN_EXPLICIT_VECTORIZATION) - set(EIGEN_BUILD_STRING ${EIGEN_BUILD_STRING}-${EIGEN_EXPLICIT_VECTORIZATION}) -endif(DEFINED EIGEN_EXPLICIT_VECTORIZATION) - -if(NOT EIGEN_WORK_DIR) - set(EIGEN_WORK_DIR ${CTEST_SCRIPT_DIRECTORY}) -endif(NOT EIGEN_WORK_DIR) - -if(NOT CTEST_SOURCE_DIRECTORY) - SET (CTEST_SOURCE_DIRECTORY "${EIGEN_WORK_DIR}/src") -endif(NOT CTEST_SOURCE_DIRECTORY) - -if(NOT CTEST_BINARY_DIRECTORY) - SET (CTEST_BINARY_DIRECTORY "${EIGEN_WORK_DIR}/nightly_${EIGEN_CXX}") -endif(NOT CTEST_BINARY_DIRECTORY) - -if(NOT EIGEN_MODE) - set(EIGEN_MODE Nightly) -endif(NOT EIGEN_MODE) - -## mandatory variables (the default should be ok in most cases): - -SET (CTEST_CVS_COMMAND "hg") -SET (CTEST_CVS_CHECKOUT "${CTEST_CVS_COMMAND} clone -r 2.0 http://bitbucket.org/eigen/eigen \"${CTEST_SOURCE_DIRECTORY}\"") - -# which ctest command to use for running the dashboard -SET (CTEST_COMMAND "${EIGEN_CMAKE_DIR}ctest -D ${EIGEN_MODE}") - -# what cmake command to use for configuring this dashboard -SET (CTEST_CMAKE_COMMAND "${EIGEN_CMAKE_DIR}cmake -DEIGEN_BUILD_TESTS=on ") - -#################################################################### -# The values in this section are optional you can either -# have them or leave them commented out -#################################################################### - -# this make sure we get consistent outputs -SET($ENV{LC_MESSAGES} "en_EN") - -# should ctest wipe the binary tree before running -SET(CTEST_START_WITH_EMPTY_BINARY_DIRECTORY TRUE) -SET(CTEST_BACKUP_AND_RESTORE TRUE) - -# this is the initial cache to use for the binary tree, be careful to escape -# any quotes inside of this string if you use it -if(WIN32 AND NOT UNIX) - #message(SEND_ERROR "win32") - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -G \"NMake Makefiles\" -DCMAKE_MAKE_PROGRAM=nmake") - SET (CTEST_INITIAL_CACHE " - MAKECOMMAND:STRING=nmake -i - CMAKE_MAKE_PROGRAM:FILEPATH=nmake - CMAKE_GENERATOR:INTERNAL=NMake Makefiles - BUILDNAME:STRING=${EIGEN_BUILD_STRING} - SITE:STRING=${EIGEN_SITE} - ") -else(WIN32 AND NOT UNIX) - SET (CTEST_INITIAL_CACHE " - BUILDNAME:STRING=${EIGEN_BUILD_STRING} - SITE:STRING=${EIGEN_SITE} - ") -endif(WIN32 AND NOT UNIX) - -# set any extra environment variables to use during the execution of the script here: - -if(EIGEN_CXX) - set(CTEST_ENVIRONMENT "CXX=${EIGEN_CXX}") -endif(EIGEN_CXX) - -if(DEFINED EIGEN_EXPLICIT_VECTORIZATION) - if(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSE2) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_SSE2=ON") - elseif(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSE3) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_SSE2=ON -DEIGEN_TEST_SSE3=ON") - elseif(EIGEN_EXPLICIT_VECTORIZATION MATCHES Altivec) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_ALTIVEC=ON") - elseif(EIGEN_EXPLICIT_VECTORIZATION MATCHES novec) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_NO_EXPLICIT_VECTORIZATION=ON") - else(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSE2) - message(FATAL_ERROR "Invalid value for EIGEN_EXPLICIT_VECTORIZATION (${EIGEN_EXPLICIT_VECTORIZATION}), must be: novec, SSE2, SSE3, Altivec") - endif(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSE2) -endif(DEFINED EIGEN_EXPLICIT_VECTORIZATION) - -if(DEFINED EIGEN_CMAKE_ARGS) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} ${EIGEN_CMAKE_ARGS}") -endif(DEFINED EIGEN_CMAKE_ARGS) diff --git a/testbed/nanogui/ext/eigen/test/eigen2support.cpp b/testbed/nanogui/ext/eigen/test/eigen2support.cpp index 1fa49a8c..ad1d9809 100644 --- a/testbed/nanogui/ext/eigen/test/eigen2support.cpp +++ b/testbed/nanogui/ext/eigen/test/eigen2support.cpp @@ -8,7 +8,6 @@ // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. #define EIGEN2_SUPPORT -#define EIGEN_NO_EIGEN2_DEPRECATED_WARNING #include "main.h" diff --git a/testbed/nanogui/ext/eigen/test/eigensolver_complex.cpp b/testbed/nanogui/ext/eigen/test/eigensolver_complex.cpp index c9d8c087..293b1b26 100644 --- a/testbed/nanogui/ext/eigen/test/eigensolver_complex.cpp +++ b/testbed/nanogui/ext/eigen/test/eigensolver_complex.cpp @@ -13,20 +13,59 @@ #include #include -/* Check that two column vectors are approximately equal upto permutations, - by checking that the k-th power sums are equal for k = 1, ..., vec1.rows() */ +template bool find_pivot(typename MatrixType::Scalar tol, MatrixType &diffs, Index col=0) +{ + bool match = diffs.diagonal().sum() <= tol; + if(match || col==diffs.cols()) + { + return match; + } + else + { + Index n = diffs.cols(); + std::vector > transpositions; + for(Index i=col; i tol) + break; + + best_index += col; + + diffs.row(col).swap(diffs.row(best_index)); + if(find_pivot(tol,diffs,col+1)) return true; + diffs.row(col).swap(diffs.row(best_index)); + + // move current pivot to the end + diffs.row(n-(i-col)-1).swap(diffs.row(best_index)); + transpositions.push_back(std::pair(n-(i-col)-1,best_index)); + } + // restore + for(Index k=transpositions.size()-1; k>=0; --k) + diffs.row(transpositions[k].first).swap(diffs.row(transpositions[k].second)); + } + return false; +} + +/* Check that two column vectors are approximately equal upto permutations. + * Initially, this method checked that the k-th power sums are equal for all k = 1, ..., vec1.rows(), + * however this strategy is numerically inacurate because of numerical cancellation issues. + */ template void verify_is_approx_upto_permutation(const VectorType& vec1, const VectorType& vec2) { - typedef typename NumTraits::Real RealScalar; + typedef typename VectorType::Scalar Scalar; + typedef typename NumTraits::Real RealScalar; VERIFY(vec1.cols() == 1); VERIFY(vec2.cols() == 1); VERIFY(vec1.rows() == vec2.rows()); - for (int k = 1; k <= vec1.rows(); ++k) - { - VERIFY_IS_APPROX(vec1.array().pow(RealScalar(k)).sum(), vec2.array().pow(RealScalar(k)).sum()); - } + + Index n = vec1.rows(); + RealScalar tol = test_precision()*test_precision()*numext::maxi(vec1.squaredNorm(),vec2.squaredNorm()); + Matrix diffs = (vec1.rowwise().replicate(n) - vec2.rowwise().replicate(n).transpose()).cwiseAbs2(); + + VERIFY( find_pivot(tol, diffs) ); } @@ -79,13 +118,28 @@ template void eigensolver(const MatrixType& m) MatrixType id = MatrixType::Identity(rows, cols); VERIFY_IS_APPROX(id.operatorNorm(), RealScalar(1)); - if (rows > 1) + if (rows > 1 && rows < 20) { // Test matrix with NaN a(0,0) = std::numeric_limits::quiet_NaN(); ComplexEigenSolver eiNaN(a); VERIFY_IS_EQUAL(eiNaN.info(), NoConvergence); } + + // regression test for bug 1098 + { + ComplexEigenSolver eig(a.adjoint() * a); + eig.compute(a.adjoint() * a); + } + + // regression test for bug 478 + { + a.setZero(); + ComplexEigenSolver ei3(a); + VERIFY_IS_EQUAL(ei3.info(), Success); + VERIFY_IS_MUCH_SMALLER_THAN(ei3.eigenvalues().norm(),RealScalar(1)); + VERIFY((ei3.eigenvectors().transpose()*ei3.eigenvectors().transpose()).eval().isIdentity()); + } } template void eigensolver_verify_assert(const MatrixType& m) @@ -108,6 +162,7 @@ void test_eigensolver_complex() CALL_SUBTEST_2( eigensolver(MatrixXcd(s,s)) ); CALL_SUBTEST_3( eigensolver(Matrix, 1, 1>()) ); CALL_SUBTEST_4( eigensolver(Matrix3f()) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) } CALL_SUBTEST_1( eigensolver_verify_assert(Matrix4cf()) ); s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); diff --git a/testbed/nanogui/ext/eigen/test/eigensolver_generalized_real.cpp b/testbed/nanogui/ext/eigen/test/eigensolver_generalized_real.cpp index 566a4bdc..9c0838ba 100644 --- a/testbed/nanogui/ext/eigen/test/eigensolver_generalized_real.cpp +++ b/testbed/nanogui/ext/eigen/test/eigensolver_generalized_real.cpp @@ -1,15 +1,17 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2012 Gael Guennebaud +// Copyright (C) 2012-2016 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +#define EIGEN_RUNTIME_NO_MALLOC #include "main.h" #include #include +#include template void generalized_eigensolver_real(const MatrixType& m) { @@ -21,6 +23,7 @@ template void generalized_eigensolver_real(const MatrixType Index cols = m.cols(); typedef typename MatrixType::Scalar Scalar; + typedef std::complex ComplexScalar; typedef Matrix VectorType; MatrixType a = MatrixType::Random(rows,cols); @@ -31,14 +34,49 @@ template void generalized_eigensolver_real(const MatrixType MatrixType spdB = b.adjoint() * b + b1.adjoint() * b1; // lets compare to GeneralizedSelfAdjointEigenSolver - GeneralizedSelfAdjointEigenSolver symmEig(spdA, spdB); - GeneralizedEigenSolver eig(spdA, spdB); + { + GeneralizedSelfAdjointEigenSolver symmEig(spdA, spdB); + GeneralizedEigenSolver eig(spdA, spdB); - VERIFY_IS_EQUAL(eig.eigenvalues().imag().cwiseAbs().maxCoeff(), 0); + VERIFY_IS_EQUAL(eig.eigenvalues().imag().cwiseAbs().maxCoeff(), 0); - VectorType realEigenvalues = eig.eigenvalues().real(); - std::sort(realEigenvalues.data(), realEigenvalues.data()+realEigenvalues.size()); - VERIFY_IS_APPROX(realEigenvalues, symmEig.eigenvalues()); + VectorType realEigenvalues = eig.eigenvalues().real(); + std::sort(realEigenvalues.data(), realEigenvalues.data()+realEigenvalues.size()); + VERIFY_IS_APPROX(realEigenvalues, symmEig.eigenvalues()); + + // check eigenvectors + typename GeneralizedEigenSolver::EigenvectorsType D = eig.eigenvalues().asDiagonal(); + typename GeneralizedEigenSolver::EigenvectorsType V = eig.eigenvectors(); + VERIFY_IS_APPROX(spdA*V, spdB*V*D); + } + + // non symmetric case: + { + GeneralizedEigenSolver eig(rows); + // TODO enable full-prealocation of required memory, this probably requires an in-place mode for HessenbergDecomposition + //Eigen::internal::set_is_malloc_allowed(false); + eig.compute(a,b); + //Eigen::internal::set_is_malloc_allowed(true); + for(Index k=0; k tmp = (eig.betas()(k)*a).template cast() - eig.alphas()(k)*b; + if(tmp.size()>1 && tmp.norm()>(std::numeric_limits::min)()) + tmp /= tmp.norm(); + VERIFY_IS_MUCH_SMALLER_THAN( std::abs(tmp.determinant()), Scalar(1) ); + } + // check eigenvectors + typename GeneralizedEigenSolver::EigenvectorsType D = eig.eigenvalues().asDiagonal(); + typename GeneralizedEigenSolver::EigenvectorsType V = eig.eigenvectors(); + VERIFY_IS_APPROX(a*V, b*V*D); + } + + // regression test for bug 1098 + { + GeneralizedSelfAdjointEigenSolver eig1(a.adjoint() * a,b.adjoint() * b); + eig1.compute(a.adjoint() * a,b.adjoint() * b); + GeneralizedEigenSolver eig2(a.adjoint() * a,b.adjoint() * b); + eig2.compute(a.adjoint() * a,b.adjoint() * b); + } } void test_eigensolver_generalized_real() @@ -49,7 +87,7 @@ void test_eigensolver_generalized_real() s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); CALL_SUBTEST_2( generalized_eigensolver_real(MatrixXd(s,s)) ); - // some trivial but implementation-wise tricky cases + // some trivial but implementation-wise special cases CALL_SUBTEST_2( generalized_eigensolver_real(MatrixXd(1,1)) ); CALL_SUBTEST_2( generalized_eigensolver_real(MatrixXd(2,2)) ); CALL_SUBTEST_3( generalized_eigensolver_real(Matrix()) ); diff --git a/testbed/nanogui/ext/eigen/test/eigensolver_generic.cpp b/testbed/nanogui/ext/eigen/test/eigensolver_generic.cpp index 005af81e..d0e644d4 100644 --- a/testbed/nanogui/ext/eigen/test/eigensolver_generic.cpp +++ b/testbed/nanogui/ext/eigen/test/eigensolver_generic.cpp @@ -63,13 +63,28 @@ template void eigensolver(const MatrixType& m) MatrixType id = MatrixType::Identity(rows, cols); VERIFY_IS_APPROX(id.operatorNorm(), RealScalar(1)); - if (rows > 2) + if (rows > 2 && rows < 20) { // Test matrix with NaN a(0,0) = std::numeric_limits::quiet_NaN(); EigenSolver eiNaN(a); VERIFY_IS_EQUAL(eiNaN.info(), NoConvergence); } + + // regression test for bug 1098 + { + EigenSolver eig(a.adjoint() * a); + eig.compute(a.adjoint() * a); + } + + // regression test for bug 478 + { + a.setZero(); + EigenSolver ei3(a); + VERIFY_IS_EQUAL(ei3.info(), Success); + VERIFY_IS_MUCH_SMALLER_THAN(ei3.eigenvalues().norm(),RealScalar(1)); + VERIFY((ei3.eigenvectors().transpose()*ei3.eigenvectors().transpose()).eval().isIdentity()); + } } template void eigensolver_verify_assert(const MatrixType& m) @@ -93,6 +108,7 @@ void test_eigensolver_generic() CALL_SUBTEST_1( eigensolver(Matrix4f()) ); s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); CALL_SUBTEST_2( eigensolver(MatrixXd(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) // some trivial but implementation-wise tricky cases CALL_SUBTEST_2( eigensolver(MatrixXd(1,1)) ); @@ -114,12 +130,37 @@ void test_eigensolver_generic() CALL_SUBTEST_2( { MatrixXd A(1,1); - A(0,0) = std::sqrt(-1.); + A(0,0) = std::sqrt(-1.); // is Not-a-Number Eigen::EigenSolver solver(A); - MatrixXd V(1, 1); - V(0,0) = solver.eigenvectors()(0,0).real(); + VERIFY_IS_EQUAL(solver.info(), NumericalIssue); } ); +#ifdef EIGEN_TEST_PART_2 + { + // regression test for bug 793 + MatrixXd a(3,3); + a << 0, 0, 1, + 1, 1, 1, + 1, 1e+200, 1; + Eigen::EigenSolver eig(a); + double scale = 1e-200; // scale to avoid overflow during the comparisons + VERIFY_IS_APPROX(a * eig.pseudoEigenvectors()*scale, eig.pseudoEigenvectors() * eig.pseudoEigenvalueMatrix()*scale); + VERIFY_IS_APPROX(a * eig.eigenvectors()*scale, eig.eigenvectors() * eig.eigenvalues().asDiagonal()*scale); + } + { + // check a case where all eigenvalues are null. + MatrixXd a(2,2); + a << 1, 1, + -1, -1; + Eigen::EigenSolver eig(a); + VERIFY_IS_APPROX(eig.pseudoEigenvectors().squaredNorm(), 2.); + VERIFY_IS_APPROX((a * eig.pseudoEigenvectors()).norm()+1., 1.); + VERIFY_IS_APPROX((eig.pseudoEigenvectors() * eig.pseudoEigenvalueMatrix()).norm()+1., 1.); + VERIFY_IS_APPROX((a * eig.eigenvectors()).norm()+1., 1.); + VERIFY_IS_APPROX((eig.eigenvectors() * eig.eigenvalues().asDiagonal()).norm()+1., 1.); + } +#endif + TEST_SET_BUT_UNUSED_VARIABLE(s) } diff --git a/testbed/nanogui/ext/eigen/test/eigensolver_selfadjoint.cpp b/testbed/nanogui/ext/eigen/test/eigensolver_selfadjoint.cpp index 38689cfb..39ad4130 100644 --- a/testbed/nanogui/ext/eigen/test/eigensolver_selfadjoint.cpp +++ b/testbed/nanogui/ext/eigen/test/eigensolver_selfadjoint.cpp @@ -9,8 +9,62 @@ // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. #include "main.h" +#include "svd_fill.h" #include #include +#include + + +template void selfadjointeigensolver_essential_check(const MatrixType& m) +{ + typedef typename MatrixType::Scalar Scalar; + typedef typename NumTraits::Real RealScalar; + RealScalar eival_eps = numext::mini(test_precision(), NumTraits::dummy_precision()*20000); + + SelfAdjointEigenSolver eiSymm(m); + VERIFY_IS_EQUAL(eiSymm.info(), Success); + + RealScalar scaling = m.cwiseAbs().maxCoeff(); + + if(scaling<(std::numeric_limits::min)()) + { + VERIFY(eiSymm.eigenvalues().cwiseAbs().maxCoeff() <= (std::numeric_limits::min)()); + } + else + { + VERIFY_IS_APPROX((m.template selfadjointView() * eiSymm.eigenvectors())/scaling, + (eiSymm.eigenvectors() * eiSymm.eigenvalues().asDiagonal())/scaling); + } + VERIFY_IS_APPROX(m.template selfadjointView().eigenvalues(), eiSymm.eigenvalues()); + VERIFY_IS_UNITARY(eiSymm.eigenvectors()); + + if(m.cols()<=4) + { + SelfAdjointEigenSolver eiDirect; + eiDirect.computeDirect(m); + VERIFY_IS_EQUAL(eiDirect.info(), Success); + if(! eiSymm.eigenvalues().isApprox(eiDirect.eigenvalues(), eival_eps) ) + { + std::cerr << "reference eigenvalues: " << eiSymm.eigenvalues().transpose() << "\n" + << "obtained eigenvalues: " << eiDirect.eigenvalues().transpose() << "\n" + << "diff: " << (eiSymm.eigenvalues()-eiDirect.eigenvalues()).transpose() << "\n" + << "error (eps): " << (eiSymm.eigenvalues()-eiDirect.eigenvalues()).norm() / eiSymm.eigenvalues().norm() << " (" << eival_eps << ")\n"; + } + if(scaling<(std::numeric_limits::min)()) + { + VERIFY(eiDirect.eigenvalues().cwiseAbs().maxCoeff() <= (std::numeric_limits::min)()); + } + else + { + VERIFY_IS_APPROX(eiSymm.eigenvalues()/scaling, eiDirect.eigenvalues()/scaling); + VERIFY_IS_APPROX((m.template selfadjointView() * eiDirect.eigenvectors())/scaling, + (eiDirect.eigenvectors() * eiDirect.eigenvalues().asDiagonal())/scaling); + VERIFY_IS_APPROX(m.template selfadjointView().eigenvalues()/scaling, eiDirect.eigenvalues()/scaling); + } + + VERIFY_IS_UNITARY(eiDirect.eigenvectors()); + } +} template void selfadjointeigensolver(const MatrixType& m) { @@ -31,17 +85,8 @@ template void selfadjointeigensolver(const MatrixType& m) MatrixType symmA = a.adjoint() * a + a1.adjoint() * a1; MatrixType symmC = symmA; - // randomly nullify some rows/columns - { - Index count = 1;//internal::random(-cols,cols); - for(Index k=0; k(0,cols-1); - symmA.row(i).setZero(); - symmA.col(i).setZero(); - } - } - + svd_fill_random(symmA,Symmetric); + symmA.template triangularView().setZero(); symmC.template triangularView().setZero(); @@ -49,23 +94,13 @@ template void selfadjointeigensolver(const MatrixType& m) MatrixType b1 = MatrixType::Random(rows,cols); MatrixType symmB = b.adjoint() * b + b1.adjoint() * b1; symmB.template triangularView().setZero(); + + CALL_SUBTEST( selfadjointeigensolver_essential_check(symmA) ); SelfAdjointEigenSolver eiSymm(symmA); - SelfAdjointEigenSolver eiDirect; - eiDirect.computeDirect(symmA); // generalized eigen pb GeneralizedSelfAdjointEigenSolver eiSymmGen(symmC, symmB); - VERIFY_IS_EQUAL(eiSymm.info(), Success); - VERIFY((symmA.template selfadjointView() * eiSymm.eigenvectors()).isApprox( - eiSymm.eigenvectors() * eiSymm.eigenvalues().asDiagonal(), largerEps)); - VERIFY_IS_APPROX(symmA.template selfadjointView().eigenvalues(), eiSymm.eigenvalues()); - - VERIFY_IS_EQUAL(eiDirect.info(), Success); - VERIFY((symmA.template selfadjointView() * eiDirect.eigenvectors()).isApprox( - eiDirect.eigenvectors() * eiDirect.eigenvalues().asDiagonal(), largerEps)); - VERIFY_IS_APPROX(symmA.template selfadjointView().eigenvalues(), eiDirect.eigenvalues()); - SelfAdjointEigenSolver eiSymmNoEivecs(symmA, false); VERIFY_IS_EQUAL(eiSymmNoEivecs.info(), Success); VERIFY_IS_APPROX(eiSymm.eigenvalues(), eiSymmNoEivecs.eigenvalues()); @@ -111,37 +146,111 @@ template void selfadjointeigensolver(const MatrixType& m) // test Tridiagonalization's methods Tridiagonalization tridiag(symmC); - // FIXME tridiag.matrixQ().adjoint() does not work + VERIFY_IS_APPROX(tridiag.diagonal(), tridiag.matrixT().diagonal()); + VERIFY_IS_APPROX(tridiag.subDiagonal(), tridiag.matrixT().template diagonal<-1>()); + Matrix T = tridiag.matrixT(); + if(rows>1 && cols>1) { + // FIXME check that upper and lower part are 0: + //VERIFY(T.topRightCorner(rows-2, cols-2).template triangularView().isZero()); + } + VERIFY_IS_APPROX(tridiag.diagonal(), T.diagonal()); + VERIFY_IS_APPROX(tridiag.subDiagonal(), T.template diagonal<1>()); VERIFY_IS_APPROX(MatrixType(symmC.template selfadjointView()), tridiag.matrixQ() * tridiag.matrixT().eval() * MatrixType(tridiag.matrixQ()).adjoint()); + VERIFY_IS_APPROX(MatrixType(symmC.template selfadjointView()), tridiag.matrixQ() * tridiag.matrixT() * tridiag.matrixQ().adjoint()); - if (rows > 1) + // Test computation of eigenvalues from tridiagonal matrix + if(rows > 1) + { + SelfAdjointEigenSolver eiSymmTridiag; + eiSymmTridiag.computeFromTridiagonal(tridiag.matrixT().diagonal(), tridiag.matrixT().diagonal(-1), ComputeEigenvectors); + VERIFY_IS_APPROX(eiSymm.eigenvalues(), eiSymmTridiag.eigenvalues()); + VERIFY_IS_APPROX(tridiag.matrixT(), eiSymmTridiag.eigenvectors().real() * eiSymmTridiag.eigenvalues().asDiagonal() * eiSymmTridiag.eigenvectors().real().transpose()); + } + + if (rows > 1 && rows < 20) { // Test matrix with NaN symmC(0,0) = std::numeric_limits::quiet_NaN(); SelfAdjointEigenSolver eiSymmNaN(symmC); VERIFY_IS_EQUAL(eiSymmNaN.info(), NoConvergence); } + + // regression test for bug 1098 + { + SelfAdjointEigenSolver eig(a.adjoint() * a); + eig.compute(a.adjoint() * a); + } + + // regression test for bug 478 + { + a.setZero(); + SelfAdjointEigenSolver ei3(a); + VERIFY_IS_EQUAL(ei3.info(), Success); + VERIFY_IS_MUCH_SMALLER_THAN(ei3.eigenvalues().norm(),RealScalar(1)); + VERIFY((ei3.eigenvectors().transpose()*ei3.eigenvectors().transpose()).eval().isIdentity()); + } +} + +template +void bug_854() +{ + Matrix3d m; + m << 850.961, 51.966, 0, + 51.966, 254.841, 0, + 0, 0, 0; + selfadjointeigensolver_essential_check(m); +} + +template +void bug_1014() +{ + Matrix3d m; + m << 0.11111111111111114658, 0, 0, + 0, 0.11111111111111109107, 0, + 0, 0, 0.11111111111111107719; + selfadjointeigensolver_essential_check(m); +} + +template +void bug_1225() +{ + Matrix3d m1, m2; + m1.setRandom(); + m1 = m1*m1.transpose(); + m2 = m1.triangularView(); + SelfAdjointEigenSolver eig1(m1); + SelfAdjointEigenSolver eig2(m2.selfadjointView()); + VERIFY_IS_APPROX(eig1.eigenvalues(), eig2.eigenvalues()); +} + +template +void bug_1204() +{ + SparseMatrix A(2,2); + A.setIdentity(); + SelfAdjointEigenSolver > eig(A); } void test_eigensolver_selfadjoint() { int s = 0; for(int i = 0; i < g_repeat; i++) { + // trivial test for 1x1 matrices: + CALL_SUBTEST_1( selfadjointeigensolver(Matrix())); + CALL_SUBTEST_1( selfadjointeigensolver(Matrix())); // very important to test 3x3 and 2x2 matrices since we provide special paths for them - CALL_SUBTEST_1( selfadjointeigensolver(Matrix2f()) ); - CALL_SUBTEST_1( selfadjointeigensolver(Matrix2d()) ); - CALL_SUBTEST_1( selfadjointeigensolver(Matrix3f()) ); - CALL_SUBTEST_1( selfadjointeigensolver(Matrix3d()) ); + CALL_SUBTEST_12( selfadjointeigensolver(Matrix2f()) ); + CALL_SUBTEST_12( selfadjointeigensolver(Matrix2d()) ); + CALL_SUBTEST_13( selfadjointeigensolver(Matrix3f()) ); + CALL_SUBTEST_13( selfadjointeigensolver(Matrix3d()) ); CALL_SUBTEST_2( selfadjointeigensolver(Matrix4d()) ); - s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); - CALL_SUBTEST_3( selfadjointeigensolver(MatrixXf(s,s)) ); - s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); - CALL_SUBTEST_4( selfadjointeigensolver(MatrixXd(s,s)) ); - s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); - CALL_SUBTEST_5( selfadjointeigensolver(MatrixXcd(s,s)) ); s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); + CALL_SUBTEST_3( selfadjointeigensolver(MatrixXf(s,s)) ); + CALL_SUBTEST_4( selfadjointeigensolver(MatrixXd(s,s)) ); + CALL_SUBTEST_5( selfadjointeigensolver(MatrixXcd(s,s)) ); CALL_SUBTEST_9( selfadjointeigensolver(Matrix,Dynamic,Dynamic,RowMajor>(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) // some trivial but implementation-wise tricky cases CALL_SUBTEST_4( selfadjointeigensolver(MatrixXd(1,1)) ); @@ -149,6 +258,11 @@ void test_eigensolver_selfadjoint() CALL_SUBTEST_6( selfadjointeigensolver(Matrix()) ); CALL_SUBTEST_7( selfadjointeigensolver(Matrix()) ); } + + CALL_SUBTEST_13( bug_854<0>() ); + CALL_SUBTEST_13( bug_1014<0>() ); + CALL_SUBTEST_13( bug_1204<0>() ); + CALL_SUBTEST_13( bug_1225<0>() ); // Test problem size constructors s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); diff --git a/testbed/nanogui/ext/eigen/test/evaluator_common.h b/testbed/nanogui/ext/eigen/test/evaluator_common.h new file mode 100644 index 00000000..e69de29b diff --git a/testbed/nanogui/ext/eigen/test/evaluators.cpp b/testbed/nanogui/ext/eigen/test/evaluators.cpp new file mode 100644 index 00000000..aed5a05a --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/evaluators.cpp @@ -0,0 +1,499 @@ + +#include "main.h" + +namespace Eigen { + + template + const Product + prod(const Lhs& lhs, const Rhs& rhs) + { + return Product(lhs,rhs); + } + + template + const Product + lazyprod(const Lhs& lhs, const Rhs& rhs) + { + return Product(lhs,rhs); + } + + template + EIGEN_STRONG_INLINE + DstXprType& copy_using_evaluator(const EigenBase &dst, const SrcXprType &src) + { + call_assignment(dst.const_cast_derived(), src.derived(), internal::assign_op()); + return dst.const_cast_derived(); + } + + template class StorageBase, typename SrcXprType> + EIGEN_STRONG_INLINE + const DstXprType& copy_using_evaluator(const NoAlias& dst, const SrcXprType &src) + { + call_assignment(dst, src.derived(), internal::assign_op()); + return dst.expression(); + } + + template + EIGEN_STRONG_INLINE + DstXprType& copy_using_evaluator(const PlainObjectBase &dst, const SrcXprType &src) + { + #ifdef EIGEN_NO_AUTOMATIC_RESIZING + eigen_assert((dst.size()==0 || (IsVectorAtCompileTime ? (dst.size() == src.size()) + : (dst.rows() == src.rows() && dst.cols() == src.cols()))) + && "Size mismatch. Automatic resizing is disabled because EIGEN_NO_AUTOMATIC_RESIZING is defined"); + #else + dst.const_cast_derived().resizeLike(src.derived()); + #endif + + call_assignment(dst.const_cast_derived(), src.derived(), internal::assign_op()); + return dst.const_cast_derived(); + } + + template + void add_assign_using_evaluator(const DstXprType& dst, const SrcXprType& src) + { + typedef typename DstXprType::Scalar Scalar; + call_assignment(const_cast(dst), src.derived(), internal::add_assign_op()); + } + + template + void subtract_assign_using_evaluator(const DstXprType& dst, const SrcXprType& src) + { + typedef typename DstXprType::Scalar Scalar; + call_assignment(const_cast(dst), src.derived(), internal::sub_assign_op()); + } + + template + void multiply_assign_using_evaluator(const DstXprType& dst, const SrcXprType& src) + { + typedef typename DstXprType::Scalar Scalar; + call_assignment(dst.const_cast_derived(), src.derived(), internal::mul_assign_op()); + } + + template + void divide_assign_using_evaluator(const DstXprType& dst, const SrcXprType& src) + { + typedef typename DstXprType::Scalar Scalar; + call_assignment(dst.const_cast_derived(), src.derived(), internal::div_assign_op()); + } + + template + void swap_using_evaluator(const DstXprType& dst, const SrcXprType& src) + { + typedef typename DstXprType::Scalar Scalar; + call_assignment(dst.const_cast_derived(), src.const_cast_derived(), internal::swap_assign_op()); + } + + namespace internal { + template class StorageBase, typename Src, typename Func> + EIGEN_DEVICE_FUNC void call_assignment(const NoAlias& dst, const Src& src, const Func& func) + { + call_assignment_no_alias(dst.expression(), src, func); + } + } + +} + +template long get_cost(const XprType& ) { return Eigen::internal::evaluator::CoeffReadCost; } + +using namespace std; + +#define VERIFY_IS_APPROX_EVALUATOR(DEST,EXPR) VERIFY_IS_APPROX(copy_using_evaluator(DEST,(EXPR)), (EXPR).eval()); +#define VERIFY_IS_APPROX_EVALUATOR2(DEST,EXPR,REF) VERIFY_IS_APPROX(copy_using_evaluator(DEST,(EXPR)), (REF).eval()); + +void test_evaluators() +{ + // Testing Matrix evaluator and Transpose + Vector2d v = Vector2d::Random(); + const Vector2d v_const(v); + Vector2d v2; + RowVector2d w; + + VERIFY_IS_APPROX_EVALUATOR(v2, v); + VERIFY_IS_APPROX_EVALUATOR(v2, v_const); + + // Testing Transpose + VERIFY_IS_APPROX_EVALUATOR(w, v.transpose()); // Transpose as rvalue + VERIFY_IS_APPROX_EVALUATOR(w, v_const.transpose()); + + copy_using_evaluator(w.transpose(), v); // Transpose as lvalue + VERIFY_IS_APPROX(w,v.transpose().eval()); + + copy_using_evaluator(w.transpose(), v_const); + VERIFY_IS_APPROX(w,v_const.transpose().eval()); + + // Testing Array evaluator + { + ArrayXXf a(2,3); + ArrayXXf b(3,2); + a << 1,2,3, 4,5,6; + const ArrayXXf a_const(a); + + VERIFY_IS_APPROX_EVALUATOR(b, a.transpose()); + + VERIFY_IS_APPROX_EVALUATOR(b, a_const.transpose()); + + // Testing CwiseNullaryOp evaluator + copy_using_evaluator(w, RowVector2d::Random()); + VERIFY((w.array() >= -1).all() && (w.array() <= 1).all()); // not easy to test ... + + VERIFY_IS_APPROX_EVALUATOR(w, RowVector2d::Zero()); + + VERIFY_IS_APPROX_EVALUATOR(w, RowVector2d::Constant(3)); + + // mix CwiseNullaryOp and transpose + VERIFY_IS_APPROX_EVALUATOR(w, Vector2d::Zero().transpose()); + } + + { + // test product expressions + int s = internal::random(1,100); + MatrixXf a(s,s), b(s,s), c(s,s), d(s,s); + a.setRandom(); + b.setRandom(); + c.setRandom(); + d.setRandom(); + VERIFY_IS_APPROX_EVALUATOR(d, (a + b)); + VERIFY_IS_APPROX_EVALUATOR(d, (a + b).transpose()); + VERIFY_IS_APPROX_EVALUATOR2(d, prod(a,b), a*b); + VERIFY_IS_APPROX_EVALUATOR2(d.noalias(), prod(a,b), a*b); + VERIFY_IS_APPROX_EVALUATOR2(d, prod(a,b) + c, a*b + c); + VERIFY_IS_APPROX_EVALUATOR2(d, s * prod(a,b), s * a*b); + VERIFY_IS_APPROX_EVALUATOR2(d, prod(a,b).transpose(), (a*b).transpose()); + VERIFY_IS_APPROX_EVALUATOR2(d, prod(a,b) + prod(b,c), a*b + b*c); + + // check that prod works even with aliasing present + c = a*a; + copy_using_evaluator(a, prod(a,a)); + VERIFY_IS_APPROX(a,c); + + // check compound assignment of products + d = c; + add_assign_using_evaluator(c.noalias(), prod(a,b)); + d.noalias() += a*b; + VERIFY_IS_APPROX(c, d); + + d = c; + subtract_assign_using_evaluator(c.noalias(), prod(a,b)); + d.noalias() -= a*b; + VERIFY_IS_APPROX(c, d); + } + + { + // test product with all possible sizes + int s = internal::random(1,100); + Matrix m11, res11; m11.setRandom(1,1); + Matrix m14, res14; m14.setRandom(1,4); + Matrix m1X, res1X; m1X.setRandom(1,s); + Matrix m41, res41; m41.setRandom(4,1); + Matrix m44, res44; m44.setRandom(4,4); + Matrix m4X, res4X; m4X.setRandom(4,s); + Matrix mX1, resX1; mX1.setRandom(s,1); + Matrix mX4, resX4; mX4.setRandom(s,4); + Matrix mXX, resXX; mXX.setRandom(s,s); + + VERIFY_IS_APPROX_EVALUATOR2(res11, prod(m11,m11), m11*m11); + VERIFY_IS_APPROX_EVALUATOR2(res11, prod(m14,m41), m14*m41); + VERIFY_IS_APPROX_EVALUATOR2(res11, prod(m1X,mX1), m1X*mX1); + VERIFY_IS_APPROX_EVALUATOR2(res14, prod(m11,m14), m11*m14); + VERIFY_IS_APPROX_EVALUATOR2(res14, prod(m14,m44), m14*m44); + VERIFY_IS_APPROX_EVALUATOR2(res14, prod(m1X,mX4), m1X*mX4); + VERIFY_IS_APPROX_EVALUATOR2(res1X, prod(m11,m1X), m11*m1X); + VERIFY_IS_APPROX_EVALUATOR2(res1X, prod(m14,m4X), m14*m4X); + VERIFY_IS_APPROX_EVALUATOR2(res1X, prod(m1X,mXX), m1X*mXX); + VERIFY_IS_APPROX_EVALUATOR2(res41, prod(m41,m11), m41*m11); + VERIFY_IS_APPROX_EVALUATOR2(res41, prod(m44,m41), m44*m41); + VERIFY_IS_APPROX_EVALUATOR2(res41, prod(m4X,mX1), m4X*mX1); + VERIFY_IS_APPROX_EVALUATOR2(res44, prod(m41,m14), m41*m14); + VERIFY_IS_APPROX_EVALUATOR2(res44, prod(m44,m44), m44*m44); + VERIFY_IS_APPROX_EVALUATOR2(res44, prod(m4X,mX4), m4X*mX4); + VERIFY_IS_APPROX_EVALUATOR2(res4X, prod(m41,m1X), m41*m1X); + VERIFY_IS_APPROX_EVALUATOR2(res4X, prod(m44,m4X), m44*m4X); + VERIFY_IS_APPROX_EVALUATOR2(res4X, prod(m4X,mXX), m4X*mXX); + VERIFY_IS_APPROX_EVALUATOR2(resX1, prod(mX1,m11), mX1*m11); + VERIFY_IS_APPROX_EVALUATOR2(resX1, prod(mX4,m41), mX4*m41); + VERIFY_IS_APPROX_EVALUATOR2(resX1, prod(mXX,mX1), mXX*mX1); + VERIFY_IS_APPROX_EVALUATOR2(resX4, prod(mX1,m14), mX1*m14); + VERIFY_IS_APPROX_EVALUATOR2(resX4, prod(mX4,m44), mX4*m44); + VERIFY_IS_APPROX_EVALUATOR2(resX4, prod(mXX,mX4), mXX*mX4); + VERIFY_IS_APPROX_EVALUATOR2(resXX, prod(mX1,m1X), mX1*m1X); + VERIFY_IS_APPROX_EVALUATOR2(resXX, prod(mX4,m4X), mX4*m4X); + VERIFY_IS_APPROX_EVALUATOR2(resXX, prod(mXX,mXX), mXX*mXX); + } + + { + ArrayXXf a(2,3); + ArrayXXf b(3,2); + a << 1,2,3, 4,5,6; + const ArrayXXf a_const(a); + + // this does not work because Random is eval-before-nested: + // copy_using_evaluator(w, Vector2d::Random().transpose()); + + // test CwiseUnaryOp + VERIFY_IS_APPROX_EVALUATOR(v2, 3 * v); + VERIFY_IS_APPROX_EVALUATOR(w, (3 * v).transpose()); + VERIFY_IS_APPROX_EVALUATOR(b, (a + 3).transpose()); + VERIFY_IS_APPROX_EVALUATOR(b, (2 * a_const + 3).transpose()); + + // test CwiseBinaryOp + VERIFY_IS_APPROX_EVALUATOR(v2, v + Vector2d::Ones()); + VERIFY_IS_APPROX_EVALUATOR(w, (v + Vector2d::Ones()).transpose().cwiseProduct(RowVector2d::Constant(3))); + + // dynamic matrices and arrays + MatrixXd mat1(6,6), mat2(6,6); + VERIFY_IS_APPROX_EVALUATOR(mat1, MatrixXd::Identity(6,6)); + VERIFY_IS_APPROX_EVALUATOR(mat2, mat1); + copy_using_evaluator(mat2.transpose(), mat1); + VERIFY_IS_APPROX(mat2.transpose(), mat1); + + ArrayXXd arr1(6,6), arr2(6,6); + VERIFY_IS_APPROX_EVALUATOR(arr1, ArrayXXd::Constant(6,6, 3.0)); + VERIFY_IS_APPROX_EVALUATOR(arr2, arr1); + + // test automatic resizing + mat2.resize(3,3); + VERIFY_IS_APPROX_EVALUATOR(mat2, mat1); + arr2.resize(9,9); + VERIFY_IS_APPROX_EVALUATOR(arr2, arr1); + + // test direct traversal + Matrix3f m3; + Array33f a3; + VERIFY_IS_APPROX_EVALUATOR(m3, Matrix3f::Identity()); // matrix, nullary + // TODO: find a way to test direct traversal with array + VERIFY_IS_APPROX_EVALUATOR(m3.transpose(), Matrix3f::Identity().transpose()); // transpose + VERIFY_IS_APPROX_EVALUATOR(m3, 2 * Matrix3f::Identity()); // unary + VERIFY_IS_APPROX_EVALUATOR(m3, Matrix3f::Identity() + Matrix3f::Zero()); // binary + VERIFY_IS_APPROX_EVALUATOR(m3.block(0,0,2,2), Matrix3f::Identity().block(1,1,2,2)); // block + + // test linear traversal + VERIFY_IS_APPROX_EVALUATOR(m3, Matrix3f::Zero()); // matrix, nullary + VERIFY_IS_APPROX_EVALUATOR(a3, Array33f::Zero()); // array + VERIFY_IS_APPROX_EVALUATOR(m3.transpose(), Matrix3f::Zero().transpose()); // transpose + VERIFY_IS_APPROX_EVALUATOR(m3, 2 * Matrix3f::Zero()); // unary + VERIFY_IS_APPROX_EVALUATOR(m3, Matrix3f::Zero() + m3); // binary + + // test inner vectorization + Matrix4f m4, m4src = Matrix4f::Random(); + Array44f a4, a4src = Matrix4f::Random(); + VERIFY_IS_APPROX_EVALUATOR(m4, m4src); // matrix + VERIFY_IS_APPROX_EVALUATOR(a4, a4src); // array + VERIFY_IS_APPROX_EVALUATOR(m4.transpose(), m4src.transpose()); // transpose + // TODO: find out why Matrix4f::Zero() does not allow inner vectorization + VERIFY_IS_APPROX_EVALUATOR(m4, 2 * m4src); // unary + VERIFY_IS_APPROX_EVALUATOR(m4, m4src + m4src); // binary + + // test linear vectorization + MatrixXf mX(6,6), mXsrc = MatrixXf::Random(6,6); + ArrayXXf aX(6,6), aXsrc = ArrayXXf::Random(6,6); + VERIFY_IS_APPROX_EVALUATOR(mX, mXsrc); // matrix + VERIFY_IS_APPROX_EVALUATOR(aX, aXsrc); // array + VERIFY_IS_APPROX_EVALUATOR(mX.transpose(), mXsrc.transpose()); // transpose + VERIFY_IS_APPROX_EVALUATOR(mX, MatrixXf::Zero(6,6)); // nullary + VERIFY_IS_APPROX_EVALUATOR(mX, 2 * mXsrc); // unary + VERIFY_IS_APPROX_EVALUATOR(mX, mXsrc + mXsrc); // binary + + // test blocks and slice vectorization + VERIFY_IS_APPROX_EVALUATOR(m4, (mXsrc.block<4,4>(1,0))); + VERIFY_IS_APPROX_EVALUATOR(aX, ArrayXXf::Constant(10, 10, 3.0).block(2, 3, 6, 6)); + + Matrix4f m4ref = m4; + copy_using_evaluator(m4.block(1, 1, 2, 3), m3.bottomRows(2)); + m4ref.block(1, 1, 2, 3) = m3.bottomRows(2); + VERIFY_IS_APPROX(m4, m4ref); + + mX.setIdentity(20,20); + MatrixXf mXref = MatrixXf::Identity(20,20); + mXsrc = MatrixXf::Random(9,12); + copy_using_evaluator(mX.block(4, 4, 9, 12), mXsrc); + mXref.block(4, 4, 9, 12) = mXsrc; + VERIFY_IS_APPROX(mX, mXref); + + // test Map + const float raw[3] = {1,2,3}; + float buffer[3] = {0,0,0}; + Vector3f v3; + Array3f a3f; + VERIFY_IS_APPROX_EVALUATOR(v3, Map(raw)); + VERIFY_IS_APPROX_EVALUATOR(a3f, Map(raw)); + Vector3f::Map(buffer) = 2*v3; + VERIFY(buffer[0] == 2); + VERIFY(buffer[1] == 4); + VERIFY(buffer[2] == 6); + + // test CwiseUnaryView + mat1.setRandom(); + mat2.setIdentity(); + MatrixXcd matXcd(6,6), matXcd_ref(6,6); + copy_using_evaluator(matXcd.real(), mat1); + copy_using_evaluator(matXcd.imag(), mat2); + matXcd_ref.real() = mat1; + matXcd_ref.imag() = mat2; + VERIFY_IS_APPROX(matXcd, matXcd_ref); + + // test Select + VERIFY_IS_APPROX_EVALUATOR(aX, (aXsrc > 0).select(aXsrc, -aXsrc)); + + // test Replicate + mXsrc = MatrixXf::Random(6, 6); + VectorXf vX = VectorXf::Random(6); + mX.resize(6, 6); + VERIFY_IS_APPROX_EVALUATOR(mX, mXsrc.colwise() + vX); + matXcd.resize(12, 12); + VERIFY_IS_APPROX_EVALUATOR(matXcd, matXcd_ref.replicate(2,2)); + VERIFY_IS_APPROX_EVALUATOR(matXcd, (matXcd_ref.replicate<2,2>())); + + // test partial reductions + VectorXd vec1(6); + VERIFY_IS_APPROX_EVALUATOR(vec1, mat1.rowwise().sum()); + VERIFY_IS_APPROX_EVALUATOR(vec1, mat1.colwise().sum().transpose()); + + // test MatrixWrapper and ArrayWrapper + mat1.setRandom(6,6); + arr1.setRandom(6,6); + VERIFY_IS_APPROX_EVALUATOR(mat2, arr1.matrix()); + VERIFY_IS_APPROX_EVALUATOR(arr2, mat1.array()); + VERIFY_IS_APPROX_EVALUATOR(mat2, (arr1 + 2).matrix()); + VERIFY_IS_APPROX_EVALUATOR(arr2, mat1.array() + 2); + mat2.array() = arr1 * arr1; + VERIFY_IS_APPROX(mat2, (arr1 * arr1).matrix()); + arr2.matrix() = MatrixXd::Identity(6,6); + VERIFY_IS_APPROX(arr2, MatrixXd::Identity(6,6).array()); + + // test Reverse + VERIFY_IS_APPROX_EVALUATOR(arr2, arr1.reverse()); + VERIFY_IS_APPROX_EVALUATOR(arr2, arr1.colwise().reverse()); + VERIFY_IS_APPROX_EVALUATOR(arr2, arr1.rowwise().reverse()); + arr2.reverse() = arr1; + VERIFY_IS_APPROX(arr2, arr1.reverse()); + mat2.array() = mat1.array().reverse(); + VERIFY_IS_APPROX(mat2.array(), mat1.array().reverse()); + + // test Diagonal + VERIFY_IS_APPROX_EVALUATOR(vec1, mat1.diagonal()); + vec1.resize(5); + VERIFY_IS_APPROX_EVALUATOR(vec1, mat1.diagonal(1)); + VERIFY_IS_APPROX_EVALUATOR(vec1, mat1.diagonal<-1>()); + vec1.setRandom(); + + mat2 = mat1; + copy_using_evaluator(mat1.diagonal(1), vec1); + mat2.diagonal(1) = vec1; + VERIFY_IS_APPROX(mat1, mat2); + + copy_using_evaluator(mat1.diagonal<-1>(), mat1.diagonal(1)); + mat2.diagonal<-1>() = mat2.diagonal(1); + VERIFY_IS_APPROX(mat1, mat2); + } + + { + // test swapping + MatrixXd mat1, mat2, mat1ref, mat2ref; + mat1ref = mat1 = MatrixXd::Random(6, 6); + mat2ref = mat2 = 2 * mat1 + MatrixXd::Identity(6, 6); + swap_using_evaluator(mat1, mat2); + mat1ref.swap(mat2ref); + VERIFY_IS_APPROX(mat1, mat1ref); + VERIFY_IS_APPROX(mat2, mat2ref); + + swap_using_evaluator(mat1.block(0, 0, 3, 3), mat2.block(3, 3, 3, 3)); + mat1ref.block(0, 0, 3, 3).swap(mat2ref.block(3, 3, 3, 3)); + VERIFY_IS_APPROX(mat1, mat1ref); + VERIFY_IS_APPROX(mat2, mat2ref); + + swap_using_evaluator(mat1.row(2), mat2.col(3).transpose()); + mat1.row(2).swap(mat2.col(3).transpose()); + VERIFY_IS_APPROX(mat1, mat1ref); + VERIFY_IS_APPROX(mat2, mat2ref); + } + + { + // test compound assignment + const Matrix4d mat_const = Matrix4d::Random(); + Matrix4d mat, mat_ref; + mat = mat_ref = Matrix4d::Identity(); + add_assign_using_evaluator(mat, mat_const); + mat_ref += mat_const; + VERIFY_IS_APPROX(mat, mat_ref); + + subtract_assign_using_evaluator(mat.row(1), 2*mat.row(2)); + mat_ref.row(1) -= 2*mat_ref.row(2); + VERIFY_IS_APPROX(mat, mat_ref); + + const ArrayXXf arr_const = ArrayXXf::Random(5,3); + ArrayXXf arr, arr_ref; + arr = arr_ref = ArrayXXf::Constant(5, 3, 0.5); + multiply_assign_using_evaluator(arr, arr_const); + arr_ref *= arr_const; + VERIFY_IS_APPROX(arr, arr_ref); + + divide_assign_using_evaluator(arr.row(1), arr.row(2) + 1); + arr_ref.row(1) /= (arr_ref.row(2) + 1); + VERIFY_IS_APPROX(arr, arr_ref); + } + + { + // test triangular shapes + MatrixXd A = MatrixXd::Random(6,6), B(6,6), C(6,6), D(6,6); + A.setRandom();B.setRandom(); + VERIFY_IS_APPROX_EVALUATOR2(B, A.triangularView(), MatrixXd(A.triangularView())); + + A.setRandom();B.setRandom(); + VERIFY_IS_APPROX_EVALUATOR2(B, A.triangularView(), MatrixXd(A.triangularView())); + + A.setRandom();B.setRandom(); + VERIFY_IS_APPROX_EVALUATOR2(B, A.triangularView(), MatrixXd(A.triangularView())); + + A.setRandom();B.setRandom(); + C = B; C.triangularView() = A; + copy_using_evaluator(B.triangularView(), A); + VERIFY(B.isApprox(C) && "copy_using_evaluator(B.triangularView(), A)"); + + A.setRandom();B.setRandom(); + C = B; C.triangularView() = A.triangularView(); + copy_using_evaluator(B.triangularView(), A.triangularView()); + VERIFY(B.isApprox(C) && "copy_using_evaluator(B.triangularView(), A.triangularView())"); + + + A.setRandom();B.setRandom(); + C = B; C.triangularView() = A.triangularView().transpose(); + copy_using_evaluator(B.triangularView(), A.triangularView().transpose()); + VERIFY(B.isApprox(C) && "copy_using_evaluator(B.triangularView(), A.triangularView().transpose())"); + + + A.setRandom();B.setRandom(); C = B; D = A; + C.triangularView().swap(D.triangularView()); + swap_using_evaluator(B.triangularView(), A.triangularView()); + VERIFY(B.isApprox(C) && "swap_using_evaluator(B.triangularView(), A.triangularView())"); + + + VERIFY_IS_APPROX_EVALUATOR2(B, prod(A.triangularView(),A), MatrixXd(A.triangularView()*A)); + + VERIFY_IS_APPROX_EVALUATOR2(B, prod(A.selfadjointView(),A), MatrixXd(A.selfadjointView()*A)); + } + + { + // test diagonal shapes + VectorXd d = VectorXd::Random(6); + MatrixXd A = MatrixXd::Random(6,6), B(6,6); + A.setRandom();B.setRandom(); + + VERIFY_IS_APPROX_EVALUATOR2(B, lazyprod(d.asDiagonal(),A), MatrixXd(d.asDiagonal()*A)); + VERIFY_IS_APPROX_EVALUATOR2(B, lazyprod(A,d.asDiagonal()), MatrixXd(A*d.asDiagonal())); + } + + { + // test CoeffReadCost + Matrix4d a, b; + VERIFY_IS_EQUAL( get_cost(a), 1 ); + VERIFY_IS_EQUAL( get_cost(a+b), 3); + VERIFY_IS_EQUAL( get_cost(2*a+b), 4); + VERIFY_IS_EQUAL( get_cost(a*b), 1); + VERIFY_IS_EQUAL( get_cost(a.lazyProduct(b)), 15); + VERIFY_IS_EQUAL( get_cost(a*(a*b)), 1); + VERIFY_IS_EQUAL( get_cost(a.lazyProduct(a*b)), 15); + VERIFY_IS_EQUAL( get_cost(a*(a+b)), 1); + VERIFY_IS_EQUAL( get_cost(a.lazyProduct(a+b)), 15); + } +} diff --git a/testbed/nanogui/ext/eigen/test/fastmath.cpp b/testbed/nanogui/ext/eigen/test/fastmath.cpp new file mode 100644 index 00000000..cc5db074 --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/fastmath.cpp @@ -0,0 +1,99 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "main.h" + +void check(bool b, bool ref) +{ + std::cout << b; + if(b==ref) + std::cout << " OK "; + else + std::cout << " BAD "; +} + +#if EIGEN_COMP_MSVC && EIGEN_COMP_MSVC < 1800 +namespace std { + template bool (isfinite)(T x) { return _finite(x); } + template bool (isnan)(T x) { return _isnan(x); } + template bool (isinf)(T x) { return _fpclass(x)==_FPCLASS_NINF || _fpclass(x)==_FPCLASS_PINF; } +} +#endif + +template +void check_inf_nan(bool dryrun) { + Matrix m(10); + m.setRandom(); + m(3) = std::numeric_limits::quiet_NaN(); + + if(dryrun) + { + std::cout << "std::isfinite(" << m(3) << ") = "; check((std::isfinite)(m(3)),false); std::cout << " ; numext::isfinite = "; check((numext::isfinite)(m(3)), false); std::cout << "\n"; + std::cout << "std::isinf(" << m(3) << ") = "; check((std::isinf)(m(3)),false); std::cout << " ; numext::isinf = "; check((numext::isinf)(m(3)), false); std::cout << "\n"; + std::cout << "std::isnan(" << m(3) << ") = "; check((std::isnan)(m(3)),true); std::cout << " ; numext::isnan = "; check((numext::isnan)(m(3)), true); std::cout << "\n"; + std::cout << "allFinite: "; check(m.allFinite(), 0); std::cout << "\n"; + std::cout << "hasNaN: "; check(m.hasNaN(), 1); std::cout << "\n"; + std::cout << "\n"; + } + else + { + VERIFY( !(numext::isfinite)(m(3)) ); + VERIFY( !(numext::isinf)(m(3)) ); + VERIFY( (numext::isnan)(m(3)) ); + VERIFY( !m.allFinite() ); + VERIFY( m.hasNaN() ); + } + T hidden_zero = (std::numeric_limits::min)()*(std::numeric_limits::min)(); + m(4) /= hidden_zero; + if(dryrun) + { + std::cout << "std::isfinite(" << m(4) << ") = "; check((std::isfinite)(m(4)),false); std::cout << " ; numext::isfinite = "; check((numext::isfinite)(m(4)), false); std::cout << "\n"; + std::cout << "std::isinf(" << m(4) << ") = "; check((std::isinf)(m(4)),true); std::cout << " ; numext::isinf = "; check((numext::isinf)(m(4)), true); std::cout << "\n"; + std::cout << "std::isnan(" << m(4) << ") = "; check((std::isnan)(m(4)),false); std::cout << " ; numext::isnan = "; check((numext::isnan)(m(4)), false); std::cout << "\n"; + std::cout << "allFinite: "; check(m.allFinite(), 0); std::cout << "\n"; + std::cout << "hasNaN: "; check(m.hasNaN(), 1); std::cout << "\n"; + std::cout << "\n"; + } + else + { + VERIFY( !(numext::isfinite)(m(4)) ); + VERIFY( (numext::isinf)(m(4)) ); + VERIFY( !(numext::isnan)(m(4)) ); + VERIFY( !m.allFinite() ); + VERIFY( m.hasNaN() ); + } + m(3) = 0; + if(dryrun) + { + std::cout << "std::isfinite(" << m(3) << ") = "; check((std::isfinite)(m(3)),true); std::cout << " ; numext::isfinite = "; check((numext::isfinite)(m(3)), true); std::cout << "\n"; + std::cout << "std::isinf(" << m(3) << ") = "; check((std::isinf)(m(3)),false); std::cout << " ; numext::isinf = "; check((numext::isinf)(m(3)), false); std::cout << "\n"; + std::cout << "std::isnan(" << m(3) << ") = "; check((std::isnan)(m(3)),false); std::cout << " ; numext::isnan = "; check((numext::isnan)(m(3)), false); std::cout << "\n"; + std::cout << "allFinite: "; check(m.allFinite(), 0); std::cout << "\n"; + std::cout << "hasNaN: "; check(m.hasNaN(), 0); std::cout << "\n"; + std::cout << "\n\n"; + } + else + { + VERIFY( (numext::isfinite)(m(3)) ); + VERIFY( !(numext::isinf)(m(3)) ); + VERIFY( !(numext::isnan)(m(3)) ); + VERIFY( !m.allFinite() ); + VERIFY( !m.hasNaN() ); + } +} + +void test_fastmath() { + std::cout << "*** float *** \n\n"; check_inf_nan(true); + std::cout << "*** double ***\n\n"; check_inf_nan(true); + std::cout << "*** long double *** \n\n"; check_inf_nan(true); + + check_inf_nan(false); + check_inf_nan(false); + check_inf_nan(false); +} diff --git a/testbed/nanogui/ext/eigen/test/first_aligned.cpp b/testbed/nanogui/ext/eigen/test/first_aligned.cpp index 467f9451..ae2d4bc4 100644 --- a/testbed/nanogui/ext/eigen/test/first_aligned.cpp +++ b/testbed/nanogui/ext/eigen/test/first_aligned.cpp @@ -13,7 +13,7 @@ template void test_first_aligned_helper(Scalar *array, int size) { const int packet_size = sizeof(Scalar) * internal::packet_traits::size; - VERIFY(((size_t(array) + sizeof(Scalar) * internal::first_aligned(array, size)) % packet_size) == 0); + VERIFY(((size_t(array) + sizeof(Scalar) * internal::first_default_aligned(array, size)) % packet_size) == 0); } template @@ -21,7 +21,7 @@ void test_none_aligned_helper(Scalar *array, int size) { EIGEN_UNUSED_VARIABLE(array); EIGEN_UNUSED_VARIABLE(size); - VERIFY(internal::packet_traits::size == 1 || internal::first_aligned(array, size) == size); + VERIFY(internal::packet_traits::size == 1 || internal::first_default_aligned(array, size) == size); } struct some_non_vectorizable_type { float x; }; @@ -41,7 +41,7 @@ void test_first_aligned() test_first_aligned_helper(array_double+1, 50); test_first_aligned_helper(array_double+2, 50); - double *array_double_plus_4_bytes = (double*)(size_t(array_double)+4); + double *array_double_plus_4_bytes = (double*)(internal::UIntPtr(array_double)+4); test_none_aligned_helper(array_double_plus_4_bytes, 50); test_none_aligned_helper(array_double_plus_4_bytes+1, 50); diff --git a/testbed/nanogui/ext/eigen/test/geo_alignedbox.cpp b/testbed/nanogui/ext/eigen/test/geo_alignedbox.cpp index 8e36adbe..223ff5ee 100644 --- a/testbed/nanogui/ext/eigen/test/geo_alignedbox.cpp +++ b/testbed/nanogui/ext/eigen/test/geo_alignedbox.cpp @@ -15,8 +15,17 @@ #include using namespace std; +// NOTE the following workaround was needed on some 32 bits builds to kill extra precision of x87 registers. +// It seems that it os not needed anymore, but let's keep it here, just in case... + template EIGEN_DONT_INLINE -void kill_extra_precision(T& x) { eigen_assert(&x != 0); } +void kill_extra_precision(T& /* x */) { + // This one worked but triggered a warning: + /* eigen_assert((void*)(&x) != (void*)0); */ + // An alternative could be: + /* volatile T tmp = x; */ + /* x = tmp; */ +} template void alignedbox(const BoxType& _box) @@ -48,12 +57,21 @@ template void alignedbox(const BoxType& _box) b0.extend(p0); b0.extend(p1); VERIFY(b0.contains(p0*s1+(Scalar(1)-s1)*p1)); + VERIFY(b0.contains(b0.center())); + VERIFY_IS_APPROX(b0.center(),(p0+p1)/Scalar(2)); (b2 = b0).extend(b1); VERIFY(b2.contains(b0)); VERIFY(b2.contains(b1)); VERIFY_IS_APPROX(b2.clamp(b0), b0); + // intersection + BoxType box1(VectorType::Random(dim)); + box1.extend(VectorType::Random(dim)); + BoxType box2(VectorType::Random(dim)); + box2.extend(VectorType::Random(dim)); + + VERIFY(box1.intersects(box2) == !box1.intersection(box2).isEmpty()); // alignment -- make sure there is no memory alignment assertion BoxType *bp0 = new BoxType(dim); @@ -172,6 +190,8 @@ void test_geo_alignedbox() CALL_SUBTEST_9( alignedbox(AlignedBox1i()) ); CALL_SUBTEST_10( alignedbox(AlignedBox2i()) ); CALL_SUBTEST_11( alignedbox(AlignedBox3i()) ); + + CALL_SUBTEST_14( alignedbox(AlignedBox(4)) ); } CALL_SUBTEST_12( specificTest1() ); CALL_SUBTEST_13( specificTest2() ); diff --git a/testbed/nanogui/ext/eigen/test/geo_eulerangles.cpp b/testbed/nanogui/ext/eigen/test/geo_eulerangles.cpp index b4830bd4..932ebe77 100644 --- a/testbed/nanogui/ext/eigen/test/geo_eulerangles.cpp +++ b/testbed/nanogui/ext/eigen/test/geo_eulerangles.cpp @@ -26,16 +26,16 @@ void verify_euler(const Matrix& ea, int i, int j, int k) VERIFY_IS_APPROX(m, mbis); /* If I==K, and ea[1]==0, then there no unique solution. */ /* The remark apply in the case where I!=K, and |ea[1]| is close to pi/2. */ - if( (i!=k || ea[1]!=0) && (i==k || !internal::isApprox(abs(ea[1]),Scalar(M_PI/2),test_precision())) ) + if( (i!=k || ea[1]!=0) && (i==k || !internal::isApprox(abs(ea[1]),Scalar(EIGEN_PI/2),test_precision())) ) VERIFY((ea-eabis).norm() <= test_precision()); // approx_or_less_than does not work for 0 VERIFY(0 < eabis[0] || test_isMuchSmallerThan(eabis[0], Scalar(1))); - VERIFY_IS_APPROX_OR_LESS_THAN(eabis[0], Scalar(M_PI)); - VERIFY_IS_APPROX_OR_LESS_THAN(-Scalar(M_PI), eabis[1]); - VERIFY_IS_APPROX_OR_LESS_THAN(eabis[1], Scalar(M_PI)); - VERIFY_IS_APPROX_OR_LESS_THAN(-Scalar(M_PI), eabis[2]); - VERIFY_IS_APPROX_OR_LESS_THAN(eabis[2], Scalar(M_PI)); + VERIFY_IS_APPROX_OR_LESS_THAN(eabis[0], Scalar(EIGEN_PI)); + VERIFY_IS_APPROX_OR_LESS_THAN(-Scalar(EIGEN_PI), eabis[1]); + VERIFY_IS_APPROX_OR_LESS_THAN(eabis[1], Scalar(EIGEN_PI)); + VERIFY_IS_APPROX_OR_LESS_THAN(-Scalar(EIGEN_PI), eabis[2]); + VERIFY_IS_APPROX_OR_LESS_THAN(eabis[2], Scalar(EIGEN_PI)); } template void check_all_var(const Matrix& ea) @@ -64,7 +64,7 @@ template void eulerangles() typedef Quaternion Quaternionx; typedef AngleAxis AngleAxisx; - Scalar a = internal::random(-Scalar(M_PI), Scalar(M_PI)); + Scalar a = internal::random(-Scalar(EIGEN_PI), Scalar(EIGEN_PI)); Quaternionx q1; q1 = AngleAxisx(a, Vector3::Random().normalized()); Matrix3 m; @@ -84,13 +84,13 @@ template void eulerangles() check_all_var(ea); // Check with random angles in range [0:pi]x[-pi:pi]x[-pi:pi]. - ea = (Array3::Random() + Array3(1,0,0))*Scalar(M_PI)*Array3(0.5,1,1); + ea = (Array3::Random() + Array3(1,0,0))*Scalar(EIGEN_PI)*Array3(0.5,1,1); check_all_var(ea); - ea[2] = ea[0] = internal::random(0,Scalar(M_PI)); + ea[2] = ea[0] = internal::random(0,Scalar(EIGEN_PI)); check_all_var(ea); - ea[0] = ea[1] = internal::random(0,Scalar(M_PI)); + ea[0] = ea[1] = internal::random(0,Scalar(EIGEN_PI)); check_all_var(ea); ea[1] = 0; diff --git a/testbed/nanogui/ext/eigen/test/geo_homogeneous.cpp b/testbed/nanogui/ext/eigen/test/geo_homogeneous.cpp index c91bde81..2187c7bf 100644 --- a/testbed/nanogui/ext/eigen/test/geo_homogeneous.cpp +++ b/testbed/nanogui/ext/eigen/test/geo_homogeneous.cpp @@ -38,6 +38,10 @@ template void homogeneous(void) hv0 << v0, 1; VERIFY_IS_APPROX(v0.homogeneous(), hv0); VERIFY_IS_APPROX(v0, hv0.hnormalized()); + + VERIFY_IS_APPROX(v0.homogeneous().sum(), hv0.sum()); + VERIFY_IS_APPROX(v0.homogeneous().minCoeff(), hv0.minCoeff()); + VERIFY_IS_APPROX(v0.homogeneous().maxCoeff(), hv0.maxCoeff()); hm0 << m0, ones.transpose(); VERIFY_IS_APPROX(m0.colwise().homogeneous(), hm0); @@ -54,10 +58,11 @@ template void homogeneous(void) T2MatrixType t2 = T2MatrixType::Random(); VERIFY_IS_APPROX(t2 * (v0.homogeneous().eval()), t2 * v0.homogeneous()); VERIFY_IS_APPROX(t2 * (m0.colwise().homogeneous().eval()), t2 * m0.colwise().homogeneous()); + VERIFY_IS_APPROX(t2 * (v0.homogeneous().asDiagonal()), t2 * hv0.asDiagonal()); + VERIFY_IS_APPROX((v0.homogeneous().asDiagonal()) * t2, hv0.asDiagonal() * t2); VERIFY_IS_APPROX((v0.transpose().rowwise().homogeneous().eval()) * t2, v0.transpose().rowwise().homogeneous() * t2); - m0.transpose().rowwise().homogeneous().eval(); VERIFY_IS_APPROX((m0.transpose().rowwise().homogeneous().eval()) * t2, m0.transpose().rowwise().homogeneous() * t2); @@ -82,7 +87,7 @@ template void homogeneous(void) VERIFY_IS_APPROX(aff * pts.colwise().homogeneous(), (aff * pts1).colwise().hnormalized()); VERIFY_IS_APPROX(caff * pts.colwise().homogeneous(), (caff * pts1).colwise().hnormalized()); VERIFY_IS_APPROX(proj * pts.colwise().homogeneous(), (proj * pts1)); - + VERIFY_IS_APPROX((aff * pts1).colwise().hnormalized(), aff * pts); VERIFY_IS_APPROX((caff * pts1).colwise().hnormalized(), caff * pts); @@ -91,6 +96,23 @@ template void homogeneous(void) VERIFY_IS_APPROX((aff * pts2).colwise().hnormalized(), aff * pts2.colwise().hnormalized()); VERIFY_IS_APPROX((caff * pts2).colwise().hnormalized(), caff * pts2.colwise().hnormalized()); VERIFY_IS_APPROX((proj * pts2).colwise().hnormalized(), (proj * pts2.colwise().hnormalized().colwise().homogeneous()).colwise().hnormalized()); + + // Test combination of homogeneous + + VERIFY_IS_APPROX( (t2 * v0.homogeneous()).hnormalized(), + (t2.template topLeftCorner() * v0 + t2.template topRightCorner()) + / ((t2.template bottomLeftCorner<1,Size>()*v0).value() + t2(Size,Size)) ); + + VERIFY_IS_APPROX( (t2 * pts.colwise().homogeneous()).colwise().hnormalized(), + (Matrix(t2 * pts1).colwise().hnormalized()) ); + + VERIFY_IS_APPROX( (t2 .lazyProduct( v0.homogeneous() )).hnormalized(), (t2 * v0.homogeneous()).hnormalized() ); + VERIFY_IS_APPROX( (t2 .lazyProduct ( pts.colwise().homogeneous() )).colwise().hnormalized(), (t2 * pts1).colwise().hnormalized() ); + + VERIFY_IS_APPROX( (v0.transpose().homogeneous() .lazyProduct( t2 )).hnormalized(), (v0.transpose().homogeneous()*t2).hnormalized() ); + VERIFY_IS_APPROX( (pts.transpose().rowwise().homogeneous() .lazyProduct( t2 )).rowwise().hnormalized(), (pts1.transpose()*t2).rowwise().hnormalized() ); + + VERIFY_IS_APPROX( (t2.template triangularView() * v0.homogeneous()).eval(), (t2.template triangularView()*hv0) ); } void test_geo_homogeneous() diff --git a/testbed/nanogui/ext/eigen/test/geo_hyperplane.cpp b/testbed/nanogui/ext/eigen/test/geo_hyperplane.cpp index 32753780..27892850 100644 --- a/testbed/nanogui/ext/eigen/test/geo_hyperplane.cpp +++ b/testbed/nanogui/ext/eigen/test/geo_hyperplane.cpp @@ -18,10 +18,12 @@ template void hyperplane(const HyperplaneType& _plane) /* this test covers the following files: Hyperplane.h */ + using std::abs; typedef typename HyperplaneType::Index Index; const Index dim = _plane.dim(); enum { Options = HyperplaneType::Options }; typedef typename HyperplaneType::Scalar Scalar; + typedef typename HyperplaneType::RealScalar RealScalar; typedef Matrix VectorType; typedef Matrix MatrixType; @@ -42,7 +44,10 @@ template void hyperplane(const HyperplaneType& _plane) VERIFY_IS_APPROX( n1.dot(n1), Scalar(1) ); VERIFY_IS_MUCH_SMALLER_THAN( pl0.absDistance(p0), Scalar(1) ); - VERIFY_IS_APPROX( pl1.signedDistance(p1 + n1 * s0), s0 ); + if(numext::abs2(s0)>RealScalar(1e-6)) + VERIFY_IS_APPROX( pl1.signedDistance(p1 + n1 * s0), s0); + else + VERIFY_IS_MUCH_SMALLER_THAN( abs(pl1.signedDistance(p1 + n1 * s0) - s0), Scalar(1) ); VERIFY_IS_MUCH_SMALLER_THAN( pl1.signedDistance(pl1.projection(p0)), Scalar(1) ); VERIFY_IS_MUCH_SMALLER_THAN( pl1.absDistance(p1 + pl1.normal().unitOrthogonal() * s1), Scalar(1) ); @@ -52,6 +57,8 @@ template void hyperplane(const HyperplaneType& _plane) MatrixType rot = MatrixType::Random(dim,dim).householderQr().householderQ(); DiagonalMatrix scaling(VectorType::Random()); Translation translation(VectorType::Random()); + + while(scaling.diagonal().cwiseAbs().minCoeff() void hyperplane(const HyperplaneType& _plane) VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot,Isometry).absDistance(rot * p1), Scalar(1) ); pl2 = pl1; VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot*scaling).absDistance((rot*scaling) * p1), Scalar(1) ); + VERIFY_IS_APPROX( pl2.normal().norm(), RealScalar(1) ); pl2 = pl1; VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot*scaling*translation) - .absDistance((rot*scaling*translation) * p1), Scalar(1) ); + .absDistance((rot*scaling*translation) * p1), Scalar(1) ); + VERIFY_IS_APPROX( pl2.normal().norm(), RealScalar(1) ); pl2 = pl1; VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot*translation,Isometry) .absDistance((rot*translation) * p1), Scalar(1) ); + VERIFY_IS_APPROX( pl2.normal().norm(), RealScalar(1) ); } // casting @@ -90,9 +100,9 @@ template void lines() Vector u = Vector::Random(); Vector v = Vector::Random(); Scalar a = internal::random(); - while (abs(a-1) < 1e-4) a = internal::random(); - while (u.norm() < 1e-4) u = Vector::Random(); - while (v.norm() < 1e-4) v = Vector::Random(); + while (abs(a-1) < Scalar(1e-4)) a = internal::random(); + while (u.norm() < Scalar(1e-4)) u = Vector::Random(); + while (v.norm() < Scalar(1e-4)) v = Vector::Random(); HLine line_u = HLine::Through(center + u, center + a*u); HLine line_v = HLine::Through(center + v, center + a*v); @@ -104,12 +114,15 @@ template void lines() Vector result = line_u.intersection(line_v); // the lines should intersect at the point we called "center" - VERIFY_IS_APPROX(result, center); + if(abs(a-1) > Scalar(1e-2) && abs(v.normalized().dot(u.normalized())) void hyperplane_alignment() typedef Hyperplane Plane3a; typedef Hyperplane Plane3u; - EIGEN_ALIGN16 Scalar array1[4]; - EIGEN_ALIGN16 Scalar array2[4]; - EIGEN_ALIGN16 Scalar array3[4+1]; + EIGEN_ALIGN_MAX Scalar array1[4]; + EIGEN_ALIGN_MAX Scalar array2[4]; + EIGEN_ALIGN_MAX Scalar array3[4+1]; Scalar* array3u = array3+1; Plane3a *p1 = ::new(reinterpret_cast(array1)) Plane3a; @@ -161,8 +174,8 @@ template void hyperplane_alignment() VERIFY_IS_APPROX(p1->coeffs(), p2->coeffs()); VERIFY_IS_APPROX(p1->coeffs(), p3->coeffs()); - #if defined(EIGEN_VECTORIZE) && EIGEN_ALIGN_STATICALLY - if(internal::packet_traits::Vectorizable) + #if defined(EIGEN_VECTORIZE) && EIGEN_MAX_STATIC_ALIGN_BYTES > 0 + if(internal::packet_traits::Vectorizable && internal::packet_traits::size<=4) VERIFY_RAISES_ASSERT((::new(reinterpret_cast(array3u)) Plane3a)); #endif } diff --git a/testbed/nanogui/ext/eigen/test/geo_orthomethods.cpp b/testbed/nanogui/ext/eigen/test/geo_orthomethods.cpp index c836dae4..e178df25 100644 --- a/testbed/nanogui/ext/eigen/test/geo_orthomethods.cpp +++ b/testbed/nanogui/ext/eigen/test/geo_orthomethods.cpp @@ -33,12 +33,16 @@ template void orthomethods_3() VERIFY_IS_MUCH_SMALLER_THAN(v1.dot(v1.cross(v2)), Scalar(1)); VERIFY_IS_MUCH_SMALLER_THAN(v1.cross(v2).dot(v2), Scalar(1)); VERIFY_IS_MUCH_SMALLER_THAN(v2.dot(v1.cross(v2)), Scalar(1)); + VERIFY_IS_MUCH_SMALLER_THAN(v1.cross(Vector3::Random()).dot(v1), Scalar(1)); Matrix3 mat3; mat3 << v0.normalized(), (v0.cross(v1)).normalized(), (v0.cross(v1).cross(v0)).normalized(); VERIFY(mat3.isUnitary()); - + + mat3.setRandom(); + VERIFY_IS_APPROX(v0.cross(mat3*v1), -(mat3*v1).cross(v0)); + VERIFY_IS_APPROX(v0.cross(mat3.lazyProduct(v1)), -(mat3.lazyProduct(v1)).cross(v0)); // colwise/rowwise cross product mat3.setRandom(); @@ -47,6 +51,13 @@ template void orthomethods_3() int i = internal::random(0,2); mcross = mat3.colwise().cross(vec3); VERIFY_IS_APPROX(mcross.col(i), mat3.col(i).cross(vec3)); + + VERIFY_IS_MUCH_SMALLER_THAN((mat3.adjoint() * mat3.colwise().cross(vec3)).diagonal().cwiseAbs().sum(), Scalar(1)); + VERIFY_IS_MUCH_SMALLER_THAN((mat3.adjoint() * mat3.colwise().cross(Vector3::Random())).diagonal().cwiseAbs().sum(), Scalar(1)); + + VERIFY_IS_MUCH_SMALLER_THAN((vec3.adjoint() * mat3.colwise().cross(vec3)).cwiseAbs().sum(), Scalar(1)); + VERIFY_IS_MUCH_SMALLER_THAN((vec3.adjoint() * Matrix3::Random().colwise().cross(vec3)).cwiseAbs().sum(), Scalar(1)); + mcross = mat3.rowwise().cross(vec3); VERIFY_IS_APPROX(mcross.row(i), mat3.row(i).cross(vec3)); @@ -57,6 +68,7 @@ template void orthomethods_3() v40.w() = v41.w() = v42.w() = 0; v42.template head<3>() = v40.template head<3>().cross(v41.template head<3>()); VERIFY_IS_APPROX(v40.cross3(v41), v42); + VERIFY_IS_MUCH_SMALLER_THAN(v40.cross3(Vector4::Random()).dot(v40), Scalar(1)); // check mixed product typedef Matrix RealVector3; diff --git a/testbed/nanogui/ext/eigen/test/geo_parametrizedline.cpp b/testbed/nanogui/ext/eigen/test/geo_parametrizedline.cpp index f0462d40..29c1b105 100644 --- a/testbed/nanogui/ext/eigen/test/geo_parametrizedline.cpp +++ b/testbed/nanogui/ext/eigen/test/geo_parametrizedline.cpp @@ -25,6 +25,8 @@ template void parametrizedline(const LineType& _line) typedef typename NumTraits::Real RealScalar; typedef Matrix VectorType; typedef Hyperplane HyperplaneType; + typedef Matrix MatrixType; VectorType p0 = VectorType::Random(dim); VectorType p1 = VectorType::Random(dim); @@ -59,6 +61,31 @@ template void parametrizedline(const LineType& _line) VERIFY_IS_MUCH_SMALLER_THAN(hp.signedDistance(pi), RealScalar(1)); VERIFY_IS_MUCH_SMALLER_THAN(l0.distance(pi), RealScalar(1)); VERIFY_IS_APPROX(l0.intersectionPoint(hp), pi); + + // transform + if (!NumTraits::IsComplex) + { + MatrixType rot = MatrixType::Random(dim,dim).householderQr().householderQ(); + DiagonalMatrix scaling(VectorType::Random()); + Translation translation(VectorType::Random()); + + while(scaling.diagonal().cwiseAbs().minCoeff() void parametrizedline_alignment() @@ -66,9 +93,9 @@ template void parametrizedline_alignment() typedef ParametrizedLine Line4a; typedef ParametrizedLine Line4u; - EIGEN_ALIGN16 Scalar array1[8]; - EIGEN_ALIGN16 Scalar array2[8]; - EIGEN_ALIGN16 Scalar array3[8+1]; + EIGEN_ALIGN_MAX Scalar array1[16]; + EIGEN_ALIGN_MAX Scalar array2[16]; + EIGEN_ALIGN_MAX Scalar array3[16+1]; Scalar* array3u = array3+1; Line4a *p1 = ::new(reinterpret_cast(array1)) Line4a; @@ -85,8 +112,8 @@ template void parametrizedline_alignment() VERIFY_IS_APPROX(p1->direction(), p2->direction()); VERIFY_IS_APPROX(p1->direction(), p3->direction()); - #if defined(EIGEN_VECTORIZE) && EIGEN_ALIGN_STATICALLY - if(internal::packet_traits::Vectorizable) + #if defined(EIGEN_VECTORIZE) && EIGEN_MAX_STATIC_ALIGN_BYTES>0 + if(internal::packet_traits::Vectorizable && internal::packet_traits::size<=4) VERIFY_RAISES_ASSERT((::new(reinterpret_cast(array3u)) Line4a)); #endif } diff --git a/testbed/nanogui/ext/eigen/test/geo_quaternion.cpp b/testbed/nanogui/ext/eigen/test/geo_quaternion.cpp index 1694b32c..96889e72 100644 --- a/testbed/nanogui/ext/eigen/test/geo_quaternion.cpp +++ b/testbed/nanogui/ext/eigen/test/geo_quaternion.cpp @@ -30,8 +30,8 @@ template void check_slerp(const QuatType& q0, const QuatType& Scalar largeEps = test_precision(); Scalar theta_tot = AA(q1*q0.inverse()).angle(); - if(theta_tot>M_PI) - theta_tot = Scalar(2.*M_PI)-theta_tot; + if(theta_tot>Scalar(EIGEN_PI)) + theta_tot = Scalar(2.)*Scalar(EIGEN_PI)-theta_tot; for(Scalar t=0; t<=Scalar(1.001); t+=Scalar(0.1)) { QuatType q = q0.slerp(t,q1); @@ -49,13 +49,13 @@ template void quaternion(void) */ using std::abs; typedef Matrix Vector3; - typedef Matrix Vector4; + typedef Matrix Matrix3; typedef Quaternion Quaternionx; typedef AngleAxis AngleAxisx; Scalar largeEps = test_precision(); if (internal::is_same::value) - largeEps = 1e-3f; + largeEps = Scalar(1e-3); Scalar eps = internal::random() * Scalar(1e-2); @@ -64,8 +64,8 @@ template void quaternion(void) v2 = Vector3::Random(), v3 = Vector3::Random(); - Scalar a = internal::random(-Scalar(M_PI), Scalar(M_PI)), - b = internal::random(-Scalar(M_PI), Scalar(M_PI)); + Scalar a = internal::random(-Scalar(EIGEN_PI), Scalar(EIGEN_PI)), + b = internal::random(-Scalar(EIGEN_PI), Scalar(EIGEN_PI)); // Quaternion: Identity(), setIdentity(); Quaternionx q1, q2; @@ -82,8 +82,8 @@ template void quaternion(void) // angular distance Scalar refangle = abs(AngleAxisx(q1.inverse()*q2).angle()); - if (refangle>Scalar(M_PI)) - refangle = Scalar(2)*Scalar(M_PI) - refangle; + if (refangle>Scalar(EIGEN_PI)) + refangle = Scalar(2)*Scalar(EIGEN_PI) - refangle; if((q1.coeffs()-q2.coeffs()).norm() > 10*largeEps) { @@ -101,6 +101,11 @@ template void quaternion(void) q2 = q1.toRotationMatrix(); VERIFY_IS_APPROX(q1*v1,q2*v1); + Matrix3 rot1(q1); + VERIFY_IS_APPROX(q1*v1,rot1*v1); + Quaternionx q3(rot1.transpose()*rot1); + VERIFY_IS_APPROX(q3*v1,v1); + // angle-axis conversion AngleAxisx aa = AngleAxisx(q1); @@ -109,8 +114,8 @@ template void quaternion(void) // Do not execute the test if the rotation angle is almost zero, or // the rotation axis and v1 are almost parallel. if (abs(aa.angle()) > 5*test_precision() - && (aa.axis() - v1.normalized()).norm() < 1.99 - && (aa.axis() + v1.normalized()).norm() < 1.99) + && (aa.axis() - v1.normalized()).norm() < Scalar(1.99) + && (aa.axis() + v1.normalized()).norm() < Scalar(1.99)) { VERIFY_IS_NOT_APPROX(q1 * v1, Quaternionx(AngleAxisx(aa.angle()*2,aa.axis())) * v1); } @@ -151,19 +156,19 @@ template void quaternion(void) Quaternionx *q = new Quaternionx; delete q; - q1 = AngleAxisx(a, v0.normalized()); - q2 = AngleAxisx(b, v1.normalized()); + q1 = Quaternionx::UnitRandom(); + q2 = Quaternionx::UnitRandom(); check_slerp(q1,q2); q1 = AngleAxisx(b, v1.normalized()); - q2 = AngleAxisx(b+Scalar(M_PI), v1.normalized()); + q2 = AngleAxisx(b+Scalar(EIGEN_PI), v1.normalized()); check_slerp(q1,q2); q1 = AngleAxisx(b, v1.normalized()); q2 = AngleAxisx(-b, -v1.normalized()); check_slerp(q1,q2); - q1.coeffs() = Vector4::Random().normalized(); + q1 = Quaternionx::UnitRandom(); q2.coeffs() = -q1.coeffs(); check_slerp(q1,q2); } @@ -179,11 +184,11 @@ template void mapQuaternion(void){ Vector3 v0 = Vector3::Random(), v1 = Vector3::Random(); - Scalar a = internal::random(-Scalar(M_PI), Scalar(M_PI)); + Scalar a = internal::random(-Scalar(EIGEN_PI), Scalar(EIGEN_PI)); - EIGEN_ALIGN16 Scalar array1[4]; - EIGEN_ALIGN16 Scalar array2[4]; - EIGEN_ALIGN16 Scalar array3[4+1]; + EIGEN_ALIGN_MAX Scalar array1[4]; + EIGEN_ALIGN_MAX Scalar array2[4]; + EIGEN_ALIGN_MAX Scalar array3[4+1]; Scalar* array3unaligned = array3+1; MQuaternionA mq1(array1); @@ -232,9 +237,9 @@ template void quaternionAlignment(void){ typedef Quaternion QuaternionA; typedef Quaternion QuaternionUA; - EIGEN_ALIGN16 Scalar array1[4]; - EIGEN_ALIGN16 Scalar array2[4]; - EIGEN_ALIGN16 Scalar array3[4+1]; + EIGEN_ALIGN_MAX Scalar array1[4]; + EIGEN_ALIGN_MAX Scalar array2[4]; + EIGEN_ALIGN_MAX Scalar array3[4+1]; Scalar* arrayunaligned = array3+1; QuaternionA *q1 = ::new(reinterpret_cast(array1)) QuaternionA; @@ -247,8 +252,8 @@ template void quaternionAlignment(void){ VERIFY_IS_APPROX(q1->coeffs(), q2->coeffs()); VERIFY_IS_APPROX(q1->coeffs(), q3->coeffs()); - #if defined(EIGEN_VECTORIZE) && EIGEN_ALIGN_STATICALLY - if(internal::packet_traits::Vectorizable) + #if defined(EIGEN_VECTORIZE) && EIGEN_MAX_STATIC_ALIGN_BYTES>0 + if(internal::packet_traits::Vectorizable && internal::packet_traits::size<=4) VERIFY_RAISES_ASSERT((::new(reinterpret_cast(arrayunaligned)) QuaternionA)); #endif } diff --git a/testbed/nanogui/ext/eigen/test/geo_transformations.cpp b/testbed/nanogui/ext/eigen/test/geo_transformations.cpp index 54776571..278e527c 100644 --- a/testbed/nanogui/ext/eigen/test/geo_transformations.cpp +++ b/testbed/nanogui/ext/eigen/test/geo_transformations.cpp @@ -12,6 +12,17 @@ #include #include +template +Matrix angleToVec(T a) +{ + return Matrix(std::cos(a), std::sin(a)); +} + +// This permits to workaround a bug in clang/llvm code generation. +template +EIGEN_DONT_INLINE +void dont_over_optimize(T& x) { volatile typename T::Scalar tmp = x(0); x(0) = tmp; } + template void non_projective_only() { /* this test covers the following files: @@ -29,7 +40,7 @@ template void non_projective_only() Transform3 t0, t1, t2; - Scalar a = internal::random(-Scalar(M_PI), Scalar(M_PI)); + Scalar a = internal::random(-Scalar(EIGEN_PI), Scalar(EIGEN_PI)); Quaternionx q1, q2; @@ -97,16 +108,14 @@ template void transformations() v1 = Vector3::Random(); Matrix3 matrot1, m; - Scalar a = internal::random(-Scalar(M_PI), Scalar(M_PI)); - Scalar s0 = internal::random(), - s1 = internal::random(); + Scalar a = internal::random(-Scalar(EIGEN_PI), Scalar(EIGEN_PI)); + Scalar s0 = internal::random(), s1 = internal::random(); while(v0.norm() < test_precision()) v0 = Vector3::Random(); while(v1.norm() < test_precision()) v1 = Vector3::Random(); - VERIFY_IS_APPROX(v0, AngleAxisx(a, v0.normalized()) * v0); - VERIFY_IS_APPROX(-v0, AngleAxisx(Scalar(M_PI), v0.unitOrthogonal()) * v0); + VERIFY_IS_APPROX(-v0, AngleAxisx(Scalar(EIGEN_PI), v0.unitOrthogonal()) * v0); if(abs(cos(a)) > test_precision()) { VERIFY_IS_APPROX(cos(a)*v0.squaredNorm(), v0.dot(AngleAxisx(a, v0.unitOrthogonal()) * v0)); @@ -132,14 +141,16 @@ template void transformations() AngleAxisx aa = AngleAxisx(q1); VERIFY_IS_APPROX(q1 * v1, Quaternionx(aa) * v1); - if(abs(aa.angle()) > NumTraits::dummy_precision()) + // The following test is stable only if 2*angle != angle and v1 is not colinear with axis + if( (abs(aa.angle()) > test_precision()) && (abs(aa.axis().dot(v1.normalized()))<(Scalar(1)-Scalar(4)*test_precision())) ) { VERIFY( !(q1 * v1).isApprox(Quaternionx(AngleAxisx(aa.angle()*2,aa.axis())) * v1) ); } aa.fromRotationMatrix(aa.toRotationMatrix()); VERIFY_IS_APPROX(q1 * v1, Quaternionx(aa) * v1); - if(abs(aa.angle()) > NumTraits::dummy_precision()) + // The following test is stable only if 2*angle != angle and v1 is not colinear with axis + if( (abs(aa.angle()) > test_precision()) && (abs(aa.axis().dot(v1.normalized()))<(Scalar(1)-Scalar(4)*test_precision())) ) { VERIFY( !(q1 * v1).isApprox(Quaternionx(AngleAxisx(aa.angle()*2,aa.axis())) * v1) ); } @@ -158,7 +169,7 @@ template void transformations() // TODO complete the tests ! a = 0; while (abs(a)(-Scalar(0.4)*Scalar(M_PI), Scalar(0.4)*Scalar(M_PI)); + a = internal::random(-Scalar(0.4)*Scalar(EIGEN_PI), Scalar(0.4)*Scalar(EIGEN_PI)); q1 = AngleAxisx(a, v0.normalized()); Transform3 t0, t1, t2; @@ -204,7 +215,7 @@ template void transformations() tmat4.matrix()(3,3) = Scalar(1); VERIFY_IS_APPROX(tmat3.matrix(), tmat4.matrix()); - Scalar a3 = internal::random(-Scalar(M_PI), Scalar(M_PI)); + Scalar a3 = internal::random(-Scalar(EIGEN_PI), Scalar(EIGEN_PI)); Vector3 v3 = Vector3::Random().normalized(); AngleAxisx aa3(a3, v3); Transform3 t3(aa3); @@ -216,12 +227,15 @@ template void transformations() t4 *= aa3; VERIFY_IS_APPROX(t3.matrix(), t4.matrix()); - v3 = Vector3::Random(); + do { + v3 = Vector3::Random(); + dont_over_optimize(v3); + } while (v3.cwiseAbs().minCoeff()::epsilon()); Translation3 tv3(v3); Transform3 t5(tv3); t4 = tv3; VERIFY_IS_APPROX(t5.matrix(), t4.matrix()); - t4.translate(-v3); + t4.translate((-v3).eval()); VERIFY_IS_APPROX(t4.matrix(), MatrixType::Identity()); t4 *= tv3; VERIFY_IS_APPROX(t5.matrix(), t4.matrix()); @@ -320,6 +334,9 @@ template void transformations() t0.scale(v0); t1 *= AlignedScaling3(v0); VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); + t1 = AlignedScaling3(v0) * (Translation3(v0) * Transform3(q1)); + t1 = t1 * v0.asDiagonal(); + VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); // transformation * translation t0.translate(v0); t1 = t1 * Translation3(v0); @@ -410,12 +427,28 @@ template void transformations() VERIFY_IS_APPROX(r2d1f.template cast(),r2d1); Rotation2D r2d1d = r2d1.template cast(); VERIFY_IS_APPROX(r2d1d.template cast(),r2d1); - - t20 = Translation2(v20) * (Rotation2D(s0) * Eigen::Scaling(s0)); - t21 = Translation2(v20) * Rotation2D(s0) * Eigen::Scaling(s0); - VERIFY_IS_APPROX(t20,t21); + for(int k=0; k<100; ++k) + { + Scalar angle = internal::random(-100,100); + Rotation2D rot2(angle); + VERIFY( rot2.smallestPositiveAngle() >= 0 ); + VERIFY( rot2.smallestPositiveAngle() <= Scalar(2)*Scalar(EIGEN_PI) ); + VERIFY_IS_APPROX( angleToVec(rot2.smallestPositiveAngle()), angleToVec(rot2.angle()) ); + + VERIFY( rot2.smallestAngle() >= -Scalar(EIGEN_PI) ); + VERIFY( rot2.smallestAngle() <= Scalar(EIGEN_PI) ); + VERIFY_IS_APPROX( angleToVec(rot2.smallestAngle()), angleToVec(rot2.angle()) ); + + Matrix rot2_as_mat(rot2); + Rotation2D rot3(rot2_as_mat); + VERIFY_IS_APPROX( angleToVec(rot2.smallestAngle()), angleToVec(rot3.angle()) ); + } + + s0 = internal::random(-100,100); + s1 = internal::random(-100,100); Rotation2D R0(s0), R1(s1); + t20 = Translation2(v20) * (R0 * Eigen::Scaling(s0)); t21 = Translation2(v20) * R0 * Eigen::Scaling(s0); VERIFY_IS_APPROX(t20,t21); @@ -425,9 +458,24 @@ template void transformations() VERIFY_IS_APPROX(t20,t21); VERIFY_IS_APPROX(s0, (R0.slerp(0, R1)).angle()); - VERIFY_IS_APPROX(s1, (R0.slerp(1, R1)).angle()); - VERIFY_IS_APPROX(s0, (R0.slerp(0.5, R0)).angle()); - VERIFY_IS_APPROX(Scalar(0), (R0.slerp(0.5, R0.inverse())).angle()); + VERIFY_IS_APPROX( angleToVec(R1.smallestPositiveAngle()), angleToVec((R0.slerp(1, R1)).smallestPositiveAngle()) ); + VERIFY_IS_APPROX(R0.smallestPositiveAngle(), (R0.slerp(0.5, R0)).smallestPositiveAngle()); + + if(std::cos(s0)>0) + VERIFY_IS_MUCH_SMALLER_THAN((R0.slerp(0.5, R0.inverse())).smallestAngle(), Scalar(1)); + else + VERIFY_IS_APPROX(Scalar(EIGEN_PI), (R0.slerp(0.5, R0.inverse())).smallestPositiveAngle()); + + // Check path length + Scalar l = 0; + int path_steps = 100; + for(int k=0; k::epsilon()*Scalar(path_steps/2))); // check basic features { @@ -437,6 +485,79 @@ template void transformations() Rotation2D r2(r1); // copy ctor VERIFY_IS_APPROX(r2.angle(),s0); } + + { + Transform3 t32(Matrix4::Random()), t33, t34; + t34 = t33 = t32; + t32.scale(v0); + t33*=AlignedScaling3(v0); + VERIFY_IS_APPROX(t32.matrix(), t33.matrix()); + t33 = t34 * AlignedScaling3(v0); + VERIFY_IS_APPROX(t32.matrix(), t33.matrix()); + } + +} + +template +void transform_associativity_left(const A1& a1, const A2& a2, const P& p, const Q& q, const V& v, const H& h) +{ + VERIFY_IS_APPROX( q*(a1*v), (q*a1)*v ); + VERIFY_IS_APPROX( q*(a2*v), (q*a2)*v ); + VERIFY_IS_APPROX( q*(p*h).hnormalized(), ((q*p)*h).hnormalized() ); +} + +template +void transform_associativity2(const A1& a1, const A2& a2, const P& p, const Q& q, const V& v, const H& h) +{ + VERIFY_IS_APPROX( a1*(q*v), (a1*q)*v ); + VERIFY_IS_APPROX( a2*(q*v), (a2*q)*v ); + VERIFY_IS_APPROX( p *(q*v).homogeneous(), (p *q)*v.homogeneous() ); + + transform_associativity_left(a1, a2,p, q, v, h); +} + +template +void transform_associativity(const RotationType& R) +{ + typedef Matrix VectorType; + typedef Matrix HVectorType; + typedef Matrix LinearType; + typedef Matrix MatrixType; + typedef Transform AffineCompactType; + typedef Transform AffineType; + typedef Transform ProjectiveType; + typedef DiagonalMatrix ScalingType; + typedef Translation TranslationType; + + AffineCompactType A1c; A1c.matrix().setRandom(); + AffineCompactType A2c; A2c.matrix().setRandom(); + AffineType A1(A1c); + AffineType A2(A2c); + ProjectiveType P1; P1.matrix().setRandom(); + VectorType v1 = VectorType::Random(); + VectorType v2 = VectorType::Random(); + HVectorType h1 = HVectorType::Random(); + Scalar s1 = internal::random(); + LinearType L = LinearType::Random(); + MatrixType M = MatrixType::Random(); + + CALL_SUBTEST( transform_associativity2(A1c, A1, P1, A2, v2, h1) ); + CALL_SUBTEST( transform_associativity2(A1c, A1, P1, A2c, v2, h1) ); + CALL_SUBTEST( transform_associativity2(A1c, A1, P1, v1.asDiagonal(), v2, h1) ); + CALL_SUBTEST( transform_associativity2(A1c, A1, P1, ScalingType(v1), v2, h1) ); + CALL_SUBTEST( transform_associativity2(A1c, A1, P1, Scaling(v1), v2, h1) ); + CALL_SUBTEST( transform_associativity2(A1c, A1, P1, Scaling(s1), v2, h1) ); + CALL_SUBTEST( transform_associativity2(A1c, A1, P1, TranslationType(v1), v2, h1) ); + CALL_SUBTEST( transform_associativity_left(A1c, A1, P1, L, v2, h1) ); + CALL_SUBTEST( transform_associativity2(A1c, A1, P1, R, v2, h1) ); + + VERIFY_IS_APPROX( A1*(M*h1), (A1*M)*h1 ); + VERIFY_IS_APPROX( A1c*(M*h1), (A1c*M)*h1 ); + VERIFY_IS_APPROX( P1*(M*h1), (P1*M)*h1 ); + + VERIFY_IS_APPROX( M*(A1*h1), (M*A1)*h1 ); + VERIFY_IS_APPROX( M*(A1c*h1), (M*A1c)*h1 ); + VERIFY_IS_APPROX( M*(P1*h1), ((M*P1)*h1) ); } template void transform_alignment() @@ -444,9 +565,9 @@ template void transform_alignment() typedef Transform Projective3a; typedef Transform Projective3u; - EIGEN_ALIGN16 Scalar array1[16]; - EIGEN_ALIGN16 Scalar array2[16]; - EIGEN_ALIGN16 Scalar array3[16+1]; + EIGEN_ALIGN_MAX Scalar array1[16]; + EIGEN_ALIGN_MAX Scalar array2[16]; + EIGEN_ALIGN_MAX Scalar array3[16+1]; Scalar* array3u = array3+1; Projective3a *p1 = ::new(reinterpret_cast(array1)) Projective3a; @@ -462,7 +583,7 @@ template void transform_alignment() VERIFY_IS_APPROX( (*p1) * (*p1), (*p2)*(*p3)); - #if defined(EIGEN_VECTORIZE) && EIGEN_ALIGN_STATICALLY + #if defined(EIGEN_VECTORIZE) && EIGEN_MAX_STATIC_ALIGN_BYTES>0 if(internal::packet_traits::Vectorizable) VERIFY_RAISES_ASSERT((::new(reinterpret_cast(array3u)) Projective3a)); #endif @@ -517,5 +638,8 @@ void test_geo_transformations() CALL_SUBTEST_7(( transform_products() )); CALL_SUBTEST_7(( transform_products() )); + + CALL_SUBTEST_8(( transform_associativity(Rotation2D(internal::random()*double(EIGEN_PI))) )); + CALL_SUBTEST_8(( transform_associativity(Quaterniond::UnitRandom()) )); } } diff --git a/testbed/nanogui/ext/eigen/test/half_float.cpp b/testbed/nanogui/ext/eigen/test/half_float.cpp new file mode 100644 index 00000000..6f319685 --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/half_float.cpp @@ -0,0 +1,257 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include + +#include "main.h" + +#include + +// Make sure it's possible to forward declare Eigen::half +namespace Eigen { +struct half; +} + +using Eigen::half; + +void test_conversion() +{ + using Eigen::half_impl::__half; + + // Conversion from float. + VERIFY_IS_EQUAL(half(1.0f).x, 0x3c00); + VERIFY_IS_EQUAL(half(0.5f).x, 0x3800); + VERIFY_IS_EQUAL(half(0.33333f).x, 0x3555); + VERIFY_IS_EQUAL(half(0.0f).x, 0x0000); + VERIFY_IS_EQUAL(half(-0.0f).x, 0x8000); + VERIFY_IS_EQUAL(half(65504.0f).x, 0x7bff); + VERIFY_IS_EQUAL(half(65536.0f).x, 0x7c00); // Becomes infinity. + + // Denormals. + VERIFY_IS_EQUAL(half(-5.96046e-08f).x, 0x8001); + VERIFY_IS_EQUAL(half(5.96046e-08f).x, 0x0001); + VERIFY_IS_EQUAL(half(1.19209e-07f).x, 0x0002); + + // Verify round-to-nearest-even behavior. + float val1 = float(half(__half(0x3c00))); + float val2 = float(half(__half(0x3c01))); + float val3 = float(half(__half(0x3c02))); + VERIFY_IS_EQUAL(half(0.5f * (val1 + val2)).x, 0x3c00); + VERIFY_IS_EQUAL(half(0.5f * (val2 + val3)).x, 0x3c02); + + // Conversion from int. + VERIFY_IS_EQUAL(half(-1).x, 0xbc00); + VERIFY_IS_EQUAL(half(0).x, 0x0000); + VERIFY_IS_EQUAL(half(1).x, 0x3c00); + VERIFY_IS_EQUAL(half(2).x, 0x4000); + VERIFY_IS_EQUAL(half(3).x, 0x4200); + + // Conversion from bool. + VERIFY_IS_EQUAL(half(false).x, 0x0000); + VERIFY_IS_EQUAL(half(true).x, 0x3c00); + + // Conversion to float. + VERIFY_IS_EQUAL(float(half(__half(0x0000))), 0.0f); + VERIFY_IS_EQUAL(float(half(__half(0x3c00))), 1.0f); + + // Denormals. + VERIFY_IS_APPROX(float(half(__half(0x8001))), -5.96046e-08f); + VERIFY_IS_APPROX(float(half(__half(0x0001))), 5.96046e-08f); + VERIFY_IS_APPROX(float(half(__half(0x0002))), 1.19209e-07f); + + // NaNs and infinities. + VERIFY(!(numext::isinf)(float(half(65504.0f)))); // Largest finite number. + VERIFY(!(numext::isnan)(float(half(0.0f)))); + VERIFY((numext::isinf)(float(half(__half(0xfc00))))); + VERIFY((numext::isnan)(float(half(__half(0xfc01))))); + VERIFY((numext::isinf)(float(half(__half(0x7c00))))); + VERIFY((numext::isnan)(float(half(__half(0x7c01))))); + +#if !EIGEN_COMP_MSVC + // Visual Studio errors out on divisions by 0 + VERIFY((numext::isnan)(float(half(0.0 / 0.0)))); + VERIFY((numext::isinf)(float(half(1.0 / 0.0)))); + VERIFY((numext::isinf)(float(half(-1.0 / 0.0)))); +#endif + + // Exactly same checks as above, just directly on the half representation. + VERIFY(!(numext::isinf)(half(__half(0x7bff)))); + VERIFY(!(numext::isnan)(half(__half(0x0000)))); + VERIFY((numext::isinf)(half(__half(0xfc00)))); + VERIFY((numext::isnan)(half(__half(0xfc01)))); + VERIFY((numext::isinf)(half(__half(0x7c00)))); + VERIFY((numext::isnan)(half(__half(0x7c01)))); + +#if !EIGEN_COMP_MSVC + // Visual Studio errors out on divisions by 0 + VERIFY((numext::isnan)(half(0.0 / 0.0))); + VERIFY((numext::isinf)(half(1.0 / 0.0))); + VERIFY((numext::isinf)(half(-1.0 / 0.0))); +#endif +} + +void test_numtraits() +{ + std::cout << "epsilon = " << NumTraits::epsilon() << std::endl; + std::cout << "highest = " << NumTraits::highest() << std::endl; + std::cout << "lowest = " << NumTraits::lowest() << std::endl; + std::cout << "inifinty = " << NumTraits::infinity() << std::endl; + std::cout << "nan = " << NumTraits::quiet_NaN() << std::endl; + +} + +void test_arithmetic() +{ + VERIFY_IS_EQUAL(float(half(2) + half(2)), 4); + VERIFY_IS_EQUAL(float(half(2) + half(-2)), 0); + VERIFY_IS_APPROX(float(half(0.33333f) + half(0.66667f)), 1.0f); + VERIFY_IS_EQUAL(float(half(2.0f) * half(-5.5f)), -11.0f); + VERIFY_IS_APPROX(float(half(1.0f) / half(3.0f)), 0.33333f); + VERIFY_IS_EQUAL(float(-half(4096.0f)), -4096.0f); + VERIFY_IS_EQUAL(float(-half(-4096.0f)), 4096.0f); +} + +void test_comparison() +{ + VERIFY(half(1.0f) > half(0.5f)); + VERIFY(half(0.5f) < half(1.0f)); + VERIFY(!(half(1.0f) < half(0.5f))); + VERIFY(!(half(0.5f) > half(1.0f))); + + VERIFY(!(half(4.0f) > half(4.0f))); + VERIFY(!(half(4.0f) < half(4.0f))); + + VERIFY(!(half(0.0f) < half(-0.0f))); + VERIFY(!(half(-0.0f) < half(0.0f))); + VERIFY(!(half(0.0f) > half(-0.0f))); + VERIFY(!(half(-0.0f) > half(0.0f))); + + VERIFY(half(0.2f) > half(-1.0f)); + VERIFY(half(-1.0f) < half(0.2f)); + VERIFY(half(-16.0f) < half(-15.0f)); + + VERIFY(half(1.0f) == half(1.0f)); + VERIFY(half(1.0f) != half(2.0f)); + + // Comparisons with NaNs and infinities. +#if !EIGEN_COMP_MSVC + // Visual Studio errors out on divisions by 0 + VERIFY(!(half(0.0 / 0.0) == half(0.0 / 0.0))); + VERIFY(half(0.0 / 0.0) != half(0.0 / 0.0)); + + VERIFY(!(half(1.0) == half(0.0 / 0.0))); + VERIFY(!(half(1.0) < half(0.0 / 0.0))); + VERIFY(!(half(1.0) > half(0.0 / 0.0))); + VERIFY(half(1.0) != half(0.0 / 0.0)); + + VERIFY(half(1.0) < half(1.0 / 0.0)); + VERIFY(half(1.0) > half(-1.0 / 0.0)); +#endif +} + +void test_basic_functions() +{ + VERIFY_IS_EQUAL(float(numext::abs(half(3.5f))), 3.5f); + VERIFY_IS_EQUAL(float(abs(half(3.5f))), 3.5f); + VERIFY_IS_EQUAL(float(numext::abs(half(-3.5f))), 3.5f); + VERIFY_IS_EQUAL(float(abs(half(-3.5f))), 3.5f); + + VERIFY_IS_EQUAL(float(numext::floor(half(3.5f))), 3.0f); + VERIFY_IS_EQUAL(float(floor(half(3.5f))), 3.0f); + VERIFY_IS_EQUAL(float(numext::floor(half(-3.5f))), -4.0f); + VERIFY_IS_EQUAL(float(floor(half(-3.5f))), -4.0f); + + VERIFY_IS_EQUAL(float(numext::ceil(half(3.5f))), 4.0f); + VERIFY_IS_EQUAL(float(ceil(half(3.5f))), 4.0f); + VERIFY_IS_EQUAL(float(numext::ceil(half(-3.5f))), -3.0f); + VERIFY_IS_EQUAL(float(ceil(half(-3.5f))), -3.0f); + + VERIFY_IS_APPROX(float(numext::sqrt(half(0.0f))), 0.0f); + VERIFY_IS_APPROX(float(sqrt(half(0.0f))), 0.0f); + VERIFY_IS_APPROX(float(numext::sqrt(half(4.0f))), 2.0f); + VERIFY_IS_APPROX(float(sqrt(half(4.0f))), 2.0f); + + VERIFY_IS_APPROX(float(numext::pow(half(0.0f), half(1.0f))), 0.0f); + VERIFY_IS_APPROX(float(pow(half(0.0f), half(1.0f))), 0.0f); + VERIFY_IS_APPROX(float(numext::pow(half(2.0f), half(2.0f))), 4.0f); + VERIFY_IS_APPROX(float(pow(half(2.0f), half(2.0f))), 4.0f); + + VERIFY_IS_EQUAL(float(numext::exp(half(0.0f))), 1.0f); + VERIFY_IS_EQUAL(float(exp(half(0.0f))), 1.0f); + VERIFY_IS_APPROX(float(numext::exp(half(EIGEN_PI))), 20.f + float(EIGEN_PI)); + VERIFY_IS_APPROX(float(exp(half(EIGEN_PI))), 20.f + float(EIGEN_PI)); + + VERIFY_IS_EQUAL(float(numext::expm1(half(0.0f))), 0.0f); + VERIFY_IS_EQUAL(float(expm1(half(0.0f))), 0.0f); + VERIFY_IS_APPROX(float(numext::expm1(half(2.0f))), 6.3890561f); + VERIFY_IS_APPROX(float(expm1(half(2.0f))), 6.3890561f); + + VERIFY_IS_EQUAL(float(numext::log(half(1.0f))), 0.0f); + VERIFY_IS_EQUAL(float(log(half(1.0f))), 0.0f); + VERIFY_IS_APPROX(float(numext::log(half(10.0f))), 2.30273f); + VERIFY_IS_APPROX(float(log(half(10.0f))), 2.30273f); + + VERIFY_IS_EQUAL(float(numext::log1p(half(0.0f))), 0.0f); + VERIFY_IS_EQUAL(float(log1p(half(0.0f))), 0.0f); + VERIFY_IS_APPROX(float(numext::log1p(half(10.0f))), 2.3978953f); + VERIFY_IS_APPROX(float(log1p(half(10.0f))), 2.3978953f); +} + +void test_trigonometric_functions() +{ + VERIFY_IS_APPROX(numext::cos(half(0.0f)), half(cosf(0.0f))); + VERIFY_IS_APPROX(cos(half(0.0f)), half(cosf(0.0f))); + VERIFY_IS_APPROX(numext::cos(half(EIGEN_PI)), half(cosf(EIGEN_PI))); + //VERIFY_IS_APPROX(numext::cos(half(EIGEN_PI/2)), half(cosf(EIGEN_PI/2))); + //VERIFY_IS_APPROX(numext::cos(half(3*EIGEN_PI/2)), half(cosf(3*EIGEN_PI/2))); + VERIFY_IS_APPROX(numext::cos(half(3.5f)), half(cosf(3.5f))); + + VERIFY_IS_APPROX(numext::sin(half(0.0f)), half(sinf(0.0f))); + VERIFY_IS_APPROX(sin(half(0.0f)), half(sinf(0.0f))); + // VERIFY_IS_APPROX(numext::sin(half(EIGEN_PI)), half(sinf(EIGEN_PI))); + VERIFY_IS_APPROX(numext::sin(half(EIGEN_PI/2)), half(sinf(EIGEN_PI/2))); + VERIFY_IS_APPROX(numext::sin(half(3*EIGEN_PI/2)), half(sinf(3*EIGEN_PI/2))); + VERIFY_IS_APPROX(numext::sin(half(3.5f)), half(sinf(3.5f))); + + VERIFY_IS_APPROX(numext::tan(half(0.0f)), half(tanf(0.0f))); + VERIFY_IS_APPROX(tan(half(0.0f)), half(tanf(0.0f))); + // VERIFY_IS_APPROX(numext::tan(half(EIGEN_PI)), half(tanf(EIGEN_PI))); + // VERIFY_IS_APPROX(numext::tan(half(EIGEN_PI/2)), half(tanf(EIGEN_PI/2))); + //VERIFY_IS_APPROX(numext::tan(half(3*EIGEN_PI/2)), half(tanf(3*EIGEN_PI/2))); + VERIFY_IS_APPROX(numext::tan(half(3.5f)), half(tanf(3.5f))); +} + +void test_array() +{ + typedef Array ArrayXh; + Index size = internal::random(1,10); + Index i = internal::random(0,size-1); + ArrayXh a1 = ArrayXh::Random(size), a2 = ArrayXh::Random(size); + VERIFY_IS_APPROX( a1+a1, half(2)*a1 ); + VERIFY( (a1.abs() >= half(0)).all() ); + VERIFY_IS_APPROX( (a1*a1).sqrt(), a1.abs() ); + + VERIFY( ((a1.min)(a2) <= (a1.max)(a2)).all() ); + a1(i) = half(-10.); + VERIFY_IS_EQUAL( a1.minCoeff(), half(-10.) ); + a1(i) = half(10.); + VERIFY_IS_EQUAL( a1.maxCoeff(), half(10.) ); + + std::stringstream ss; + ss << a1; +} + +void test_half_float() +{ + CALL_SUBTEST(test_conversion()); + CALL_SUBTEST(test_numtraits()); + CALL_SUBTEST(test_arithmetic()); + CALL_SUBTEST(test_comparison()); + CALL_SUBTEST(test_basic_functions()); + CALL_SUBTEST(test_trigonometric_functions()); + CALL_SUBTEST(test_array()); +} diff --git a/testbed/nanogui/ext/eigen/test/incomplete_cholesky.cpp b/testbed/nanogui/ext/eigen/test/incomplete_cholesky.cpp new file mode 100644 index 00000000..59ffe925 --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/incomplete_cholesky.cpp @@ -0,0 +1,65 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015-2016 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +// #define EIGEN_DONT_VECTORIZE +// #define EIGEN_MAX_ALIGN_BYTES 0 +#include "sparse_solver.h" +#include +#include + +template void test_incomplete_cholesky_T() +{ + typedef SparseMatrix SparseMatrixType; + ConjugateGradient > > cg_illt_lower_amd; + ConjugateGradient > > cg_illt_lower_nat; + ConjugateGradient > > cg_illt_upper_amd; + ConjugateGradient > > cg_illt_upper_nat; + ConjugateGradient > > cg_illt_uplo_amd; + + + CALL_SUBTEST( check_sparse_spd_solving(cg_illt_lower_amd) ); + CALL_SUBTEST( check_sparse_spd_solving(cg_illt_lower_nat) ); + CALL_SUBTEST( check_sparse_spd_solving(cg_illt_upper_amd) ); + CALL_SUBTEST( check_sparse_spd_solving(cg_illt_upper_nat) ); + CALL_SUBTEST( check_sparse_spd_solving(cg_illt_uplo_amd) ); +} + +void test_incomplete_cholesky() +{ + CALL_SUBTEST_1(( test_incomplete_cholesky_T() )); + CALL_SUBTEST_2(( test_incomplete_cholesky_T, int>() )); + CALL_SUBTEST_3(( test_incomplete_cholesky_T() )); + +#ifdef EIGEN_TEST_PART_1 + // regression for bug 1150 + for(int N = 1; N<20; ++N) + { + Eigen::MatrixXd b( N, N ); + b.setOnes(); + + Eigen::SparseMatrix m( N, N ); + m.reserve(Eigen::VectorXi::Constant(N,4)); + for( int i = 0; i < N; ++i ) + { + m.insert( i, i ) = 1; + m.coeffRef( i, i / 2 ) = 2; + m.coeffRef( i, i / 3 ) = 2; + m.coeffRef( i, i / 4 ) = 2; + } + + Eigen::SparseMatrix A; + A = m * m.transpose(); + + Eigen::ConjugateGradient, + Eigen::Lower | Eigen::Upper, + Eigen::IncompleteCholesky > solver( A ); + VERIFY(solver.preconditioner().info() == Eigen::Success); + VERIFY(solver.info() == Eigen::Success); + } +#endif +} diff --git a/testbed/nanogui/ext/eigen/test/indexed_view.cpp b/testbed/nanogui/ext/eigen/test/indexed_view.cpp new file mode 100644 index 00000000..7245cf37 --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/indexed_view.cpp @@ -0,0 +1,378 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2017 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifdef EIGEN_TEST_PART_2 +// Make sure we also check c++11 max implementation +#define EIGEN_MAX_CPP_VER 11 +#endif + +#ifdef EIGEN_TEST_PART_3 +// Make sure we also check c++98 max implementation +#define EIGEN_MAX_CPP_VER 03 +#endif + +#include +#include +#include "main.h" + +#if EIGEN_HAS_CXX11 +#include +#endif + +typedef std::pair IndexPair; + +int encode(Index i, Index j) { + return int(i*100 + j); +} + +IndexPair decode(Index ij) { + return IndexPair(ij / 100, ij % 100); +} + +template +bool match(const T& xpr, std::string ref, std::string str_xpr = "") { + EIGEN_UNUSED_VARIABLE(str_xpr); + std::stringstream str; + str << xpr; + if(!(str.str() == ref)) + std::cout << str_xpr << "\n" << xpr << "\n\n"; + return str.str() == ref; +} + +#define MATCH(X,R) match(X, R, #X) + +template +typename internal::enable_if::value,bool>::type +is_same_eq(const T1& a, const T2& b) +{ + return (a == b).all(); +} + +template +bool is_same_seq(const T1& a, const T2& b) +{ + bool ok = a.first()==b.first() && a.size() == b.size() && Index(a.incrObject())==Index(b.incrObject());; + if(!ok) + { + std::cerr << "seqN(" << a.first() << ", " << a.size() << ", " << Index(a.incrObject()) << ") != "; + std::cerr << "seqN(" << b.first() << ", " << b.size() << ", " << Index(b.incrObject()) << ")\n"; + } + return ok; +} + +template +typename internal::enable_if::value,bool>::type +is_same_seq_type(const T1& a, const T2& b) +{ + return is_same_seq(a,b); +} + + + +#define VERIFY_EQ_INT(A,B) VERIFY_IS_APPROX(int(A),int(B)) + +void check_indexed_view() +{ + using Eigen::placeholders::all; + using Eigen::placeholders::last; + using Eigen::placeholders::end; + + Index n = 10; + + ArrayXd a = ArrayXd::LinSpaced(n,0,n-1); + Array b = a.transpose(); + + ArrayXXi A = ArrayXXi::NullaryExpr(n,n, std::ptr_fun(encode)); + + for(Index i=0; i vali(4); Map(&vali[0],4) = eii; + std::vector veci(4); Map(veci.data(),4) = eii; + + VERIFY( MATCH( A(3, seq(9,3,-1)), + "309 308 307 306 305 304 303") + ); + + VERIFY( MATCH( A(seqN(2,5), seq(9,3,-1)), + "209 208 207 206 205 204 203\n" + "309 308 307 306 305 304 303\n" + "409 408 407 406 405 404 403\n" + "509 508 507 506 505 504 503\n" + "609 608 607 606 605 604 603") + ); + + VERIFY( MATCH( A(seqN(2,5), 5), + "205\n" + "305\n" + "405\n" + "505\n" + "605") + ); + + VERIFY( MATCH( A(seqN(last,5,-1), seq(2,last)), + "902 903 904 905 906 907 908 909\n" + "802 803 804 805 806 807 808 809\n" + "702 703 704 705 706 707 708 709\n" + "602 603 604 605 606 607 608 609\n" + "502 503 504 505 506 507 508 509") + ); + + VERIFY( MATCH( A(eii, veci), + "303 301 306 305\n" + "103 101 106 105\n" + "603 601 606 605\n" + "503 501 506 505") + ); + + VERIFY( MATCH( A(eii, all), + "300 301 302 303 304 305 306 307 308 309\n" + "100 101 102 103 104 105 106 107 108 109\n" + "600 601 602 603 604 605 606 607 608 609\n" + "500 501 502 503 504 505 506 507 508 509") + ); + + // takes the row numer 3, and repeat it 5 times + VERIFY( MATCH( A(seqN(3,5,0), all), + "300 301 302 303 304 305 306 307 308 309\n" + "300 301 302 303 304 305 306 307 308 309\n" + "300 301 302 303 304 305 306 307 308 309\n" + "300 301 302 303 304 305 306 307 308 309\n" + "300 301 302 303 304 305 306 307 308 309") + ); + + VERIFY( MATCH( a(seqN(3,3),0), "3\n4\n5" ) ); + VERIFY( MATCH( a(seq(3,5)), "3\n4\n5" ) ); + VERIFY( MATCH( a(seqN(3,3,1)), "3\n4\n5" ) ); + VERIFY( MATCH( a(seqN(5,3,-1)), "5\n4\n3" ) ); + + VERIFY( MATCH( b(0,seqN(3,3)), "3 4 5" ) ); + VERIFY( MATCH( b(seq(3,5)), "3 4 5" ) ); + VERIFY( MATCH( b(seqN(3,3,1)), "3 4 5" ) ); + VERIFY( MATCH( b(seqN(5,3,-1)), "5 4 3" ) ); + + VERIFY( MATCH( b(all), "0 1 2 3 4 5 6 7 8 9" ) ); + VERIFY( MATCH( b(eii), "3 1 6 5" ) ); + + Array44i B; + B.setRandom(); + VERIFY( (A(seqN(2,5), 5)).ColsAtCompileTime == 1); + VERIFY( (A(seqN(2,5), 5)).RowsAtCompileTime == Dynamic); + VERIFY_EQ_INT( (A(seqN(2,5), 5)).InnerStrideAtCompileTime , A.InnerStrideAtCompileTime); + VERIFY_EQ_INT( (A(seqN(2,5), 5)).OuterStrideAtCompileTime , A.col(5).OuterStrideAtCompileTime); + + VERIFY_EQ_INT( (A(5,seqN(2,5))).InnerStrideAtCompileTime , A.row(5).InnerStrideAtCompileTime); + VERIFY_EQ_INT( (A(5,seqN(2,5))).OuterStrideAtCompileTime , A.row(5).OuterStrideAtCompileTime); + VERIFY_EQ_INT( (B(1,seqN(1,2))).InnerStrideAtCompileTime , B.row(1).InnerStrideAtCompileTime); + VERIFY_EQ_INT( (B(1,seqN(1,2))).OuterStrideAtCompileTime , B.row(1).OuterStrideAtCompileTime); + + VERIFY_EQ_INT( (A(seqN(2,5), seq(1,3))).InnerStrideAtCompileTime , A.InnerStrideAtCompileTime); + VERIFY_EQ_INT( (A(seqN(2,5), seq(1,3))).OuterStrideAtCompileTime , A.OuterStrideAtCompileTime); + VERIFY_EQ_INT( (B(seqN(1,2), seq(1,3))).InnerStrideAtCompileTime , B.InnerStrideAtCompileTime); + VERIFY_EQ_INT( (B(seqN(1,2), seq(1,3))).OuterStrideAtCompileTime , B.OuterStrideAtCompileTime); + VERIFY_EQ_INT( (A(seqN(2,5,2), seq(1,3,2))).InnerStrideAtCompileTime , Dynamic); + VERIFY_EQ_INT( (A(seqN(2,5,2), seq(1,3,2))).OuterStrideAtCompileTime , Dynamic); + VERIFY_EQ_INT( (A(seqN(2,5,fix<2>), seq(1,3,fix<3>))).InnerStrideAtCompileTime , 2); + VERIFY_EQ_INT( (A(seqN(2,5,fix<2>), seq(1,3,fix<3>))).OuterStrideAtCompileTime , Dynamic); + VERIFY_EQ_INT( (B(seqN(1,2,fix<2>), seq(1,3,fix<3>))).InnerStrideAtCompileTime , 2); + VERIFY_EQ_INT( (B(seqN(1,2,fix<2>), seq(1,3,fix<3>))).OuterStrideAtCompileTime , 3*4); + + VERIFY_EQ_INT( (A(seqN(2,fix<5>), seqN(1,fix<3>))).RowsAtCompileTime, 5); + VERIFY_EQ_INT( (A(seqN(2,fix<5>), seqN(1,fix<3>))).ColsAtCompileTime, 3); + VERIFY_EQ_INT( (A(seqN(2,fix<5>(5)), seqN(1,fix<3>(3)))).RowsAtCompileTime, 5); + VERIFY_EQ_INT( (A(seqN(2,fix<5>(5)), seqN(1,fix<3>(3)))).ColsAtCompileTime, 3); + VERIFY_EQ_INT( (A(seqN(2,fix(5)), seqN(1,fix(3)))).RowsAtCompileTime, Dynamic); + VERIFY_EQ_INT( (A(seqN(2,fix(5)), seqN(1,fix(3)))).ColsAtCompileTime, Dynamic); + VERIFY_EQ_INT( (A(seqN(2,fix(5)), seqN(1,fix(3)))).rows(), 5); + VERIFY_EQ_INT( (A(seqN(2,fix(5)), seqN(1,fix(3)))).cols(), 3); + + VERIFY( is_same_seq_type( seqN(2,5,fix<-1>), seqN(2,5,fix<-1>(-1)) ) ); + VERIFY( is_same_seq_type( seqN(2,5), seqN(2,5,fix<1>(1)) ) ); + VERIFY( is_same_seq_type( seqN(2,5,3), seqN(2,5,fix(3)) ) ); + VERIFY( is_same_seq_type( seq(2,7,fix<3>), seqN(2,2,fix<3>) ) ); + VERIFY( is_same_seq_type( seqN(2,fix(5),3), seqN(2,5,fix(3)) ) ); + VERIFY( is_same_seq_type( seqN(2,fix<5>(5),fix<-2>), seqN(2,fix<5>,fix<-2>()) ) ); + + VERIFY( is_same_seq_type( seq(2,fix<5>), seqN(2,4) ) ); +#if EIGEN_HAS_CXX11 + VERIFY( is_same_seq_type( seq(fix<2>,fix<5>), seqN(fix<2>,fix<4>) ) ); + VERIFY( is_same_seq( seqN(2,std::integral_constant(),std::integral_constant()), seqN(2,fix<5>,fix<-2>()) ) ); + VERIFY( is_same_seq( seq(std::integral_constant(),std::integral_constant(),std::integral_constant()), + seq(fix<1>,fix<5>,fix<2>()) ) ); + VERIFY( is_same_seq_type( seqN(2,std::integral_constant(),std::integral_constant()), seqN(2,fix<5>,fix<-2>()) ) ); + VERIFY( is_same_seq_type( seq(std::integral_constant(),std::integral_constant(),std::integral_constant()), + seq(fix<1>,fix<5>,fix<2>()) ) ); + + VERIFY( is_same_seq_type( seqN(2,std::integral_constant()), seqN(2,fix<5>) ) ); + VERIFY( is_same_seq_type( seq(std::integral_constant(),std::integral_constant()), seq(fix<1>,fix<5>) ) ); +#else + // sorry, no compile-time size recovery in c++98/03 + VERIFY( is_same_seq( seq(fix<2>,fix<5>), seqN(fix<2>,fix<4>) ) ); +#endif + + VERIFY( (A(seqN(2,fix<5>), 5)).RowsAtCompileTime == 5); + VERIFY( (A(4, all)).ColsAtCompileTime == Dynamic); + VERIFY( (A(4, all)).RowsAtCompileTime == 1); + VERIFY( (B(1, all)).ColsAtCompileTime == 4); + VERIFY( (B(1, all)).RowsAtCompileTime == 1); + VERIFY( (B(all,1)).ColsAtCompileTime == 1); + VERIFY( (B(all,1)).RowsAtCompileTime == 4); + + VERIFY(int( (A(all, eii)).ColsAtCompileTime) == int(eii.SizeAtCompileTime)); + VERIFY_EQ_INT( (A(eii, eii)).Flags&DirectAccessBit, (unsigned int)(0)); + VERIFY_EQ_INT( (A(eii, eii)).InnerStrideAtCompileTime, 0); + VERIFY_EQ_INT( (A(eii, eii)).OuterStrideAtCompileTime, 0); + + VERIFY_IS_APPROX( A(seq(n-1,2,-2), seqN(n-1-6,3,-1)), A(seq(last,2,fix<-2>), seqN(last-6,3,fix<-1>)) ); + + VERIFY_IS_APPROX( A(seq(n-1,2,-2), seqN(n-1-6,4)), A(seq(last,2,-2), seqN(last-6,4)) ); + VERIFY_IS_APPROX( A(seq(n-1-6,n-1-2), seqN(n-1-6,4)), A(seq(last-6,last-2), seqN(6+last-6-6,4)) ); + VERIFY_IS_APPROX( A(seq((n-1)/2,(n)/2+3), seqN(2,4)), A(seq(last/2,(last+1)/2+3), seqN(last+2-last,4)) ); + VERIFY_IS_APPROX( A(seq(n-2,2,-2), seqN(n-8,4)), A(seq(end-2,2,-2), seqN(end-8,4)) ); + + // Check all combinations of seq: + VERIFY_IS_APPROX( A(seq(1,n-1-2,2), seq(1,n-1-2,2)), A(seq(1,last-2,2), seq(1,last-2,fix<2>)) ); + VERIFY_IS_APPROX( A(seq(n-1-5,n-1-2,2), seq(n-1-5,n-1-2,2)), A(seq(last-5,last-2,2), seq(last-5,last-2,fix<2>)) ); + VERIFY_IS_APPROX( A(seq(n-1-5,7,2), seq(n-1-5,7,2)), A(seq(last-5,7,2), seq(last-5,7,fix<2>)) ); + VERIFY_IS_APPROX( A(seq(1,n-1-2), seq(n-1-5,7)), A(seq(1,last-2), seq(last-5,7)) ); + VERIFY_IS_APPROX( A(seq(n-1-5,n-1-2), seq(n-1-5,n-1-2)), A(seq(last-5,last-2), seq(last-5,last-2)) ); + + VERIFY_IS_APPROX( A.col(A.cols()-1), A(all,last) ); + VERIFY_IS_APPROX( A(A.rows()-2, A.cols()/2), A(last-1, end/2) ); + VERIFY_IS_APPROX( a(a.size()-2), a(last-1) ); + VERIFY_IS_APPROX( a(a.size()/2), a((last+1)/2) ); + + // Check fall-back to Block + { + VERIFY( is_same_eq(A.col(0), A(all,0)) ); + VERIFY( is_same_eq(A.row(0), A(0,all)) ); + VERIFY( is_same_eq(A.block(0,0,2,2), A(seqN(0,2),seq(0,1))) ); + VERIFY( is_same_eq(A.middleRows(2,4), A(seqN(2,4),all)) ); + VERIFY( is_same_eq(A.middleCols(2,4), A(all,seqN(2,4))) ); + + VERIFY( is_same_eq(A.col(A.cols()-1), A(all,last)) ); + + const ArrayXXi& cA(A); + VERIFY( is_same_eq(cA.col(0), cA(all,0)) ); + VERIFY( is_same_eq(cA.row(0), cA(0,all)) ); + VERIFY( is_same_eq(cA.block(0,0,2,2), cA(seqN(0,2),seq(0,1))) ); + VERIFY( is_same_eq(cA.middleRows(2,4), cA(seqN(2,4),all)) ); + VERIFY( is_same_eq(cA.middleCols(2,4), cA(all,seqN(2,4))) ); + + VERIFY( is_same_eq(a.head(4), a(seq(0,3))) ); + VERIFY( is_same_eq(a.tail(4), a(seqN(last-3,4))) ); + VERIFY( is_same_eq(a.tail(4), a(seq(end-4,last))) ); + VERIFY( is_same_eq(a.segment<4>(3), a(seqN(3,fix<4>))) ); + } + + ArrayXXi A1=A, A2 = ArrayXXi::Random(4,4); + ArrayXi range25(4); range25 << 3,2,4,5; + A1(seqN(3,4),seq(2,5)) = A2; + VERIFY_IS_APPROX( A1.block(3,2,4,4), A2 ); + A1 = A; + A2.setOnes(); + A1(seq(6,3,-1),range25) = A2; + VERIFY_IS_APPROX( A1.block(3,2,4,4), A2 ); + + // check reverse + { + VERIFY( is_same_seq_type( seq(3,7).reverse(), seqN(7,5,fix<-1>) ) ); + VERIFY( is_same_seq_type( seq(7,3,fix<-2>).reverse(), seqN(3,3,fix<2>) ) ); + VERIFY_IS_APPROX( a(seqN(2,last/2).reverse()), a(seqN(2+(last/2-1)*1,last/2,fix<-1>)) ); + VERIFY_IS_APPROX( a(seqN(last/2,fix<4>).reverse()),a(seqN(last/2,fix<4>)).reverse() ); + VERIFY_IS_APPROX( A(seq(last-5,last-1,2).reverse(), seqN(last-3,3,fix<-2>).reverse()), + A(seq(last-5,last-1,2), seqN(last-3,3,fix<-2>)).reverse() ); + } + +#if EIGEN_HAS_CXX11 + VERIFY( (A(all, std::array{{1,3,2,4}})).ColsAtCompileTime == 4); + + VERIFY_IS_APPROX( (A(std::array{{1,3,5}}, std::array{{9,6,3,0}})), A(seqN(1,3,2), seqN(9,4,-3)) ); + +#if EIGEN_HAS_STATIC_ARRAY_TEMPLATE + VERIFY_IS_APPROX( A({3, 1, 6, 5}, all), A(std::array{{3, 1, 6, 5}}, all) ); + VERIFY_IS_APPROX( A(all,{3, 1, 6, 5}), A(all,std::array{{3, 1, 6, 5}}) ); + VERIFY_IS_APPROX( A({1,3,5},{3, 1, 6, 5}), A(std::array{{1,3,5}},std::array{{3, 1, 6, 5}}) ); + + VERIFY_IS_EQUAL( A({1,3,5},{3, 1, 6, 5}).RowsAtCompileTime, 3 ); + VERIFY_IS_EQUAL( A({1,3,5},{3, 1, 6, 5}).ColsAtCompileTime, 4 ); + + VERIFY_IS_APPROX( a({3, 1, 6, 5}), a(std::array{{3, 1, 6, 5}}) ); + VERIFY_IS_EQUAL( a({1,3,5}).SizeAtCompileTime, 3 ); + + VERIFY_IS_APPROX( b({3, 1, 6, 5}), b(std::array{{3, 1, 6, 5}}) ); + VERIFY_IS_EQUAL( b({1,3,5}).SizeAtCompileTime, 3 ); +#endif + +#endif + + // check mat(i,j) with weird types for i and j + { + VERIFY_IS_APPROX( A(B.RowsAtCompileTime-1, 1), A(3,1) ); + VERIFY_IS_APPROX( A(B.RowsAtCompileTime, 1), A(4,1) ); + VERIFY_IS_APPROX( A(B.RowsAtCompileTime-1, B.ColsAtCompileTime-1), A(3,3) ); + VERIFY_IS_APPROX( A(B.RowsAtCompileTime, B.ColsAtCompileTime), A(4,4) ); + const Index I = 3, J = 4; + VERIFY_IS_APPROX( A(I,J), A(3,4) ); + } + + // check extended block API + { + VERIFY( is_same_eq( A.block<3,4>(1,1), A.block(1,1,fix<3>,fix<4>)) ); + VERIFY( is_same_eq( A.block<3,4>(1,1,3,4), A.block(1,1,fix<3>(),fix<4>(4))) ); + VERIFY( is_same_eq( A.block<3,Dynamic>(1,1,3,4), A.block(1,1,fix<3>,4)) ); + VERIFY( is_same_eq( A.block(1,1,3,4), A.block(1,1,fix(3),fix<4>)) ); + VERIFY( is_same_eq( A.block(1,1,3,4), A.block(1,1,fix(3),fix(4))) ); + + VERIFY( is_same_eq( A.topLeftCorner<3,4>(), A.topLeftCorner(fix<3>,fix<4>)) ); + VERIFY( is_same_eq( A.bottomLeftCorner<3,4>(), A.bottomLeftCorner(fix<3>,fix<4>)) ); + VERIFY( is_same_eq( A.bottomRightCorner<3,4>(), A.bottomRightCorner(fix<3>,fix<4>)) ); + VERIFY( is_same_eq( A.topRightCorner<3,4>(), A.topRightCorner(fix<3>,fix<4>)) ); + + VERIFY( is_same_eq( A.leftCols<3>(), A.leftCols(fix<3>)) ); + VERIFY( is_same_eq( A.rightCols<3>(), A.rightCols(fix<3>)) ); + VERIFY( is_same_eq( A.middleCols<3>(1), A.middleCols(1,fix<3>)) ); + + VERIFY( is_same_eq( A.topRows<3>(), A.topRows(fix<3>)) ); + VERIFY( is_same_eq( A.bottomRows<3>(), A.bottomRows(fix<3>)) ); + VERIFY( is_same_eq( A.middleRows<3>(1), A.middleRows(1,fix<3>)) ); + + VERIFY( is_same_eq( a.segment<3>(1), a.segment(1,fix<3>)) ); + VERIFY( is_same_eq( a.head<3>(), a.head(fix<3>)) ); + VERIFY( is_same_eq( a.tail<3>(), a.tail(fix<3>)) ); + + const ArrayXXi& cA(A); + VERIFY( is_same_eq( cA.block(1,1,3,4), cA.block(1,1,fix(3),fix<4>)) ); + + VERIFY( is_same_eq( cA.topLeftCorner<3,4>(), cA.topLeftCorner(fix<3>,fix<4>)) ); + VERIFY( is_same_eq( cA.bottomLeftCorner<3,4>(), cA.bottomLeftCorner(fix<3>,fix<4>)) ); + VERIFY( is_same_eq( cA.bottomRightCorner<3,4>(), cA.bottomRightCorner(fix<3>,fix<4>)) ); + VERIFY( is_same_eq( cA.topRightCorner<3,4>(), cA.topRightCorner(fix<3>,fix<4>)) ); + + VERIFY( is_same_eq( cA.leftCols<3>(), cA.leftCols(fix<3>)) ); + VERIFY( is_same_eq( cA.rightCols<3>(), cA.rightCols(fix<3>)) ); + VERIFY( is_same_eq( cA.middleCols<3>(1), cA.middleCols(1,fix<3>)) ); + + VERIFY( is_same_eq( cA.topRows<3>(), cA.topRows(fix<3>)) ); + VERIFY( is_same_eq( cA.bottomRows<3>(), cA.bottomRows(fix<3>)) ); + VERIFY( is_same_eq( cA.middleRows<3>(1), cA.middleRows(1,fix<3>)) ); + } + +} + +void test_indexed_view() +{ +// for(int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_1( check_indexed_view() ); + CALL_SUBTEST_2( check_indexed_view() ); + CALL_SUBTEST_3( check_indexed_view() ); +// } +} diff --git a/testbed/nanogui/ext/eigen/test/inplace_decomposition.cpp b/testbed/nanogui/ext/eigen/test/inplace_decomposition.cpp new file mode 100644 index 00000000..92d0d91b --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/inplace_decomposition.cpp @@ -0,0 +1,110 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2016 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "main.h" +#include +#include +#include + +// This file test inplace decomposition through Ref<>, as supported by Cholesky, LU, and QR decompositions. + +template void inplace(bool square = false, bool SPD = false) +{ + typedef typename MatrixType::Scalar Scalar; + typedef Matrix RhsType; + typedef Matrix ResType; + + Index rows = MatrixType::RowsAtCompileTime==Dynamic ? internal::random(2,EIGEN_TEST_MAX_SIZE/2) : Index(MatrixType::RowsAtCompileTime); + Index cols = MatrixType::ColsAtCompileTime==Dynamic ? (square?rows:internal::random(2,rows)) : Index(MatrixType::ColsAtCompileTime); + + MatrixType A = MatrixType::Random(rows,cols); + RhsType b = RhsType::Random(rows); + ResType x(cols); + + if(SPD) + { + assert(square); + A.topRows(cols) = A.topRows(cols).adjoint() * A.topRows(cols); + A.diagonal().array() += 1e-3; + } + + MatrixType A0 = A; + MatrixType A1 = A; + + DecType dec(A); + + // Check that the content of A has been modified + VERIFY_IS_NOT_APPROX( A, A0 ); + + // Check that the decomposition is correct: + if(rows==cols) + { + VERIFY_IS_APPROX( A0 * (x = dec.solve(b)), b ); + } + else + { + VERIFY_IS_APPROX( A0.transpose() * A0 * (x = dec.solve(b)), A0.transpose() * b ); + } + + // Check that modifying A breaks the current dec: + A.setRandom(); + if(rows==cols) + { + VERIFY_IS_NOT_APPROX( A0 * (x = dec.solve(b)), b ); + } + else + { + VERIFY_IS_NOT_APPROX( A0.transpose() * A0 * (x = dec.solve(b)), A0.transpose() * b ); + } + + // Check that calling compute(A1) does not modify A1: + A = A0; + dec.compute(A1); + VERIFY_IS_EQUAL(A0,A1); + VERIFY_IS_NOT_APPROX( A, A0 ); + if(rows==cols) + { + VERIFY_IS_APPROX( A0 * (x = dec.solve(b)), b ); + } + else + { + VERIFY_IS_APPROX( A0.transpose() * A0 * (x = dec.solve(b)), A0.transpose() * b ); + } +} + + +void test_inplace_decomposition() +{ + EIGEN_UNUSED typedef Matrix Matrix43d; + for(int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_1(( inplace >, MatrixXd>(true,true) )); + CALL_SUBTEST_1(( inplace >, Matrix4d>(true,true) )); + + CALL_SUBTEST_2(( inplace >, MatrixXd>(true,true) )); + CALL_SUBTEST_2(( inplace >, Matrix4d>(true,true) )); + + CALL_SUBTEST_3(( inplace >, MatrixXd>(true,false) )); + CALL_SUBTEST_3(( inplace >, Matrix4d>(true,false) )); + + CALL_SUBTEST_4(( inplace >, MatrixXd>(true,false) )); + CALL_SUBTEST_4(( inplace >, Matrix4d>(true,false) )); + + CALL_SUBTEST_5(( inplace >, MatrixXd>(false,false) )); + CALL_SUBTEST_5(( inplace >, Matrix43d>(false,false) )); + + CALL_SUBTEST_6(( inplace >, MatrixXd>(false,false) )); + CALL_SUBTEST_6(( inplace >, Matrix43d>(false,false) )); + + CALL_SUBTEST_7(( inplace >, MatrixXd>(false,false) )); + CALL_SUBTEST_7(( inplace >, Matrix43d>(false,false) )); + + CALL_SUBTEST_8(( inplace >, MatrixXd>(false,false) )); + CALL_SUBTEST_8(( inplace >, Matrix43d>(false,false) )); + } +} diff --git a/testbed/nanogui/ext/eigen/test/integer_types.cpp b/testbed/nanogui/ext/eigen/test/integer_types.cpp index 950f8e9b..a21f73a8 100644 --- a/testbed/nanogui/ext/eigen/test/integer_types.cpp +++ b/testbed/nanogui/ext/eigen/test/integer_types.cpp @@ -158,4 +158,12 @@ void test_integer_types() CALL_SUBTEST_8( integer_type_tests(Matrix(1, 5)) ); } +#ifdef EIGEN_TEST_PART_9 + VERIFY_IS_EQUAL(internal::scalar_div_cost::value, 8); + VERIFY_IS_EQUAL(internal::scalar_div_cost::value, 8); + if(sizeof(long)>sizeof(int)) { + VERIFY(internal::scalar_div_cost::value > internal::scalar_div_cost::value); + VERIFY(internal::scalar_div_cost::value > internal::scalar_div_cost::value); + } +#endif } diff --git a/testbed/nanogui/ext/eigen/test/inverse.cpp b/testbed/nanogui/ext/eigen/test/inverse.cpp index 8187b088..5c6777a1 100644 --- a/testbed/nanogui/ext/eigen/test/inverse.cpp +++ b/testbed/nanogui/ext/eigen/test/inverse.cpp @@ -68,6 +68,15 @@ template void inverse(const MatrixType& m) VERIFY_IS_MUCH_SMALLER_THAN(abs(det-m3.determinant()), RealScalar(1)); m3.computeInverseWithCheck(m4, invertible); VERIFY( rows==1 ? invertible : !invertible ); + + // check with submatrices + { + Matrix m5; + m5.setRandom(); + m5.topLeftCorner(rows,rows) = m1; + m2 = m5.template topLeftCorner().inverse(); + VERIFY_IS_APPROX( (m5.template topLeftCorner()), m2.inverse() ); + } #endif // check in-place inversion @@ -93,12 +102,16 @@ void test_inverse() CALL_SUBTEST_3( inverse(Matrix3f()) ); CALL_SUBTEST_4( inverse(Matrix4f()) ); CALL_SUBTEST_4( inverse(Matrix()) ); + s = internal::random(50,320); CALL_SUBTEST_5( inverse(MatrixXf(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) + s = internal::random(25,100); CALL_SUBTEST_6( inverse(MatrixXcd(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) + CALL_SUBTEST_7( inverse(Matrix4d()) ); CALL_SUBTEST_7( inverse(Matrix()) ); } - TEST_SET_BUT_UNUSED_VARIABLE(s) } diff --git a/testbed/nanogui/ext/eigen/test/is_same_dense.cpp b/testbed/nanogui/ext/eigen/test/is_same_dense.cpp new file mode 100644 index 00000000..2c7838ce --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/is_same_dense.cpp @@ -0,0 +1,33 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "main.h" + +using internal::is_same_dense; + +void test_is_same_dense() +{ + typedef Matrix ColMatrixXd; + ColMatrixXd m1(10,10); + Ref ref_m1(m1); + Ref const_ref_m1(m1); + VERIFY(is_same_dense(m1,m1)); + VERIFY(is_same_dense(m1,ref_m1)); + VERIFY(is_same_dense(const_ref_m1,m1)); + VERIFY(is_same_dense(const_ref_m1,ref_m1)); + + VERIFY(is_same_dense(m1.block(0,0,m1.rows(),m1.cols()),m1)); + VERIFY(!is_same_dense(m1.row(0),m1.col(0))); + + Ref const_ref_m1_row(m1.row(1)); + VERIFY(!is_same_dense(m1.row(1),const_ref_m1_row)); + + Ref const_ref_m1_col(m1.col(1)); + VERIFY(is_same_dense(m1.col(1),const_ref_m1_col)); +} diff --git a/testbed/nanogui/ext/eigen/test/jacobisvd.cpp b/testbed/nanogui/ext/eigen/test/jacobisvd.cpp index 12c556e5..7f5f7156 100644 --- a/testbed/nanogui/ext/eigen/test/jacobisvd.cpp +++ b/testbed/nanogui/ext/eigen/test/jacobisvd.cpp @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2008 Gael Guennebaud +// Copyright (C) 2008-2014 Gael Guennebaud // Copyright (C) 2009 Benoit Jacob // // This Source Code Form is subject to the terms of the Mozilla @@ -14,279 +14,47 @@ #include "main.h" #include -template -void jacobisvd_check_full(const MatrixType& m, const JacobiSVD& svd) -{ - typedef typename MatrixType::Index Index; - Index rows = m.rows(); - Index cols = m.cols(); - - enum { - RowsAtCompileTime = MatrixType::RowsAtCompileTime, - ColsAtCompileTime = MatrixType::ColsAtCompileTime - }; - - typedef typename MatrixType::Scalar Scalar; - typedef Matrix MatrixUType; - typedef Matrix MatrixVType; - - MatrixType sigma = MatrixType::Zero(rows,cols); - sigma.diagonal() = svd.singularValues().template cast(); - MatrixUType u = svd.matrixU(); - MatrixVType v = svd.matrixV(); - - VERIFY_IS_APPROX(m, u * sigma * v.adjoint()); - VERIFY_IS_UNITARY(u); - VERIFY_IS_UNITARY(v); -} - -template -void jacobisvd_compare_to_full(const MatrixType& m, - unsigned int computationOptions, - const JacobiSVD& referenceSvd) -{ - typedef typename MatrixType::Index Index; - Index rows = m.rows(); - Index cols = m.cols(); - Index diagSize = (std::min)(rows, cols); - - JacobiSVD svd(m, computationOptions); - - VERIFY_IS_APPROX(svd.singularValues(), referenceSvd.singularValues()); - if(computationOptions & ComputeFullU) - VERIFY_IS_APPROX(svd.matrixU(), referenceSvd.matrixU()); - if(computationOptions & ComputeThinU) - VERIFY_IS_APPROX(svd.matrixU(), referenceSvd.matrixU().leftCols(diagSize)); - if(computationOptions & ComputeFullV) - VERIFY_IS_APPROX(svd.matrixV(), referenceSvd.matrixV()); - if(computationOptions & ComputeThinV) - VERIFY_IS_APPROX(svd.matrixV(), referenceSvd.matrixV().leftCols(diagSize)); -} - -template -void jacobisvd_solve(const MatrixType& m, unsigned int computationOptions) -{ - typedef typename MatrixType::Scalar Scalar; - typedef typename MatrixType::RealScalar RealScalar; - typedef typename MatrixType::Index Index; - Index rows = m.rows(); - Index cols = m.cols(); - - enum { - RowsAtCompileTime = MatrixType::RowsAtCompileTime, - ColsAtCompileTime = MatrixType::ColsAtCompileTime - }; - - typedef Matrix RhsType; - typedef Matrix SolutionType; - - RhsType rhs = RhsType::Random(rows, internal::random(1, cols)); - JacobiSVD svd(m, computationOptions); - - if(internal::is_same::value) svd.setThreshold(1e-8); - else if(internal::is_same::value) svd.setThreshold(1e-4); - - SolutionType x = svd.solve(rhs); - - RealScalar residual = (m*x-rhs).norm(); - // Check that there is no significantly better solution in the neighborhood of x - if(!test_isMuchSmallerThan(residual,rhs.norm())) - { - // If the residual is very small, then we have an exact solution, so we are already good. - for(int k=0;k::epsilon(); - RealScalar residual_y = (m*y-rhs).norm(); - VERIFY( test_isApprox(residual_y,residual) || residual < residual_y ); - - y.row(k) = x.row(k).array() - 2*NumTraits::epsilon(); - residual_y = (m*y-rhs).norm(); - VERIFY( test_isApprox(residual_y,residual) || residual < residual_y ); - } - } - - // evaluate normal equation which works also for least-squares solutions - if(internal::is_same::value) - { - // This test is not stable with single precision. - // This is probably because squaring m signicantly affects the precision. - VERIFY_IS_APPROX(m.adjoint()*m*x,m.adjoint()*rhs); - } - - // check minimal norm solutions - { - // generate a full-rank m x n problem with m MatrixType2; - typedef Matrix RhsType2; - typedef Matrix MatrixType2T; - Index rank = RankAtCompileTime2==Dynamic ? internal::random(1,cols) : Index(RankAtCompileTime2); - MatrixType2 m2(rank,cols); - int guard = 0; - do { - m2.setRandom(); - } while(m2.jacobiSvd().setThreshold(test_precision()).rank()!=rank && (++guard)<10); - VERIFY(guard<10); - RhsType2 rhs2 = RhsType2::Random(rank); - // use QR to find a reference minimal norm solution - HouseholderQR qr(m2.adjoint()); - Matrix tmp = qr.matrixQR().topLeftCorner(rank,rank).template triangularView().adjoint().solve(rhs2); - tmp.conservativeResize(cols); - tmp.tail(cols-rank).setZero(); - SolutionType x21 = qr.householderQ() * tmp; - // now check with SVD - JacobiSVD svd2(m2, computationOptions); - SolutionType x22 = svd2.solve(rhs2); - VERIFY_IS_APPROX(m2*x21, rhs2); - VERIFY_IS_APPROX(m2*x22, rhs2); - VERIFY_IS_APPROX(x21, x22); - - // Now check with a rank deficient matrix - typedef Matrix MatrixType3; - typedef Matrix RhsType3; - Index rows3 = RowsAtCompileTime3==Dynamic ? internal::random(rank+1,2*cols) : Index(RowsAtCompileTime3); - Matrix C = Matrix::Random(rows3,rank); - MatrixType3 m3 = C * m2; - RhsType3 rhs3 = C * rhs2; - JacobiSVD svd3(m3, computationOptions); - SolutionType x3 = svd3.solve(rhs3); - if(svd3.rank()!=rank) { - std::cout << m3 << "\n\n"; - std::cout << svd3.singularValues().transpose() << "\n"; - std::cout << svd3.rank() << " == " << rank << "\n"; - std::cout << x21.norm() << " == " << x3.norm() << "\n"; - } -// VERIFY_IS_APPROX(m3*x3, rhs3); - VERIFY_IS_APPROX(m3*x21, rhs3); - VERIFY_IS_APPROX(m2*x3, rhs2); - - VERIFY_IS_APPROX(x21, x3); - } -} - -template -void jacobisvd_test_all_computation_options(const MatrixType& m) -{ - if (QRPreconditioner == NoQRPreconditioner && m.rows() != m.cols()) - return; - JacobiSVD fullSvd(m, ComputeFullU|ComputeFullV); - CALL_SUBTEST(( jacobisvd_check_full(m, fullSvd) )); - CALL_SUBTEST(( jacobisvd_solve(m, ComputeFullU | ComputeFullV) )); - - #if defined __INTEL_COMPILER - // remark #111: statement is unreachable - #pragma warning disable 111 - #endif - if(QRPreconditioner == FullPivHouseholderQRPreconditioner) - return; - - CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeFullU, fullSvd) )); - CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeFullV, fullSvd) )); - CALL_SUBTEST(( jacobisvd_compare_to_full(m, 0, fullSvd) )); - - if (MatrixType::ColsAtCompileTime == Dynamic) { - // thin U/V are only available with dynamic number of columns - CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeFullU|ComputeThinV, fullSvd) )); - CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeThinV, fullSvd) )); - CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeThinU|ComputeFullV, fullSvd) )); - CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeThinU , fullSvd) )); - CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeThinU|ComputeThinV, fullSvd) )); - CALL_SUBTEST(( jacobisvd_solve(m, ComputeFullU | ComputeThinV) )); - CALL_SUBTEST(( jacobisvd_solve(m, ComputeThinU | ComputeFullV) )); - CALL_SUBTEST(( jacobisvd_solve(m, ComputeThinU | ComputeThinV) )); - - // test reconstruction - typedef typename MatrixType::Index Index; - Index diagSize = (std::min)(m.rows(), m.cols()); - JacobiSVD svd(m, ComputeThinU | ComputeThinV); - VERIFY_IS_APPROX(m, svd.matrixU().leftCols(diagSize) * svd.singularValues().asDiagonal() * svd.matrixV().leftCols(diagSize).adjoint()); - } -} +#define SVD_DEFAULT(M) JacobiSVD +#define SVD_FOR_MIN_NORM(M) JacobiSVD +#include "svd_common.h" +// Check all variants of JacobiSVD template void jacobisvd(const MatrixType& a = MatrixType(), bool pickrandom = true) { MatrixType m = a; if(pickrandom) - { - typedef typename MatrixType::Scalar Scalar; - typedef typename MatrixType::RealScalar RealScalar; - typedef typename MatrixType::Index Index; - Index diagSize = (std::min)(a.rows(), a.cols()); - RealScalar s = std::numeric_limits::max_exponent10/4; - s = internal::random(1,s); - Matrix d = Matrix::Random(diagSize); - for(Index k=0; k(-s,s)); - m = Matrix::Random(a.rows(),diagSize) * d.asDiagonal() * Matrix::Random(diagSize,a.cols()); - // cancel some coeffs - Index n = internal::random(0,m.size()-1); - for(Index i=0; i(0,m.rows()-1), internal::random(0,m.cols()-1)) = Scalar(0); - } + svd_fill_random(m); - CALL_SUBTEST(( jacobisvd_test_all_computation_options(m) )); - CALL_SUBTEST(( jacobisvd_test_all_computation_options(m) )); - CALL_SUBTEST(( jacobisvd_test_all_computation_options(m) )); - CALL_SUBTEST(( jacobisvd_test_all_computation_options(m) )); + CALL_SUBTEST(( svd_test_all_computation_options >(m, true) )); // check full only + CALL_SUBTEST(( svd_test_all_computation_options >(m, false) )); + CALL_SUBTEST(( svd_test_all_computation_options >(m, false) )); + if(m.rows()==m.cols()) + CALL_SUBTEST(( svd_test_all_computation_options >(m, false) )); } template void jacobisvd_verify_assert(const MatrixType& m) { - typedef typename MatrixType::Scalar Scalar; + svd_verify_assert >(m); typedef typename MatrixType::Index Index; Index rows = m.rows(); Index cols = m.cols(); enum { - RowsAtCompileTime = MatrixType::RowsAtCompileTime, ColsAtCompileTime = MatrixType::ColsAtCompileTime }; - typedef Matrix RhsType; - - RhsType rhs(rows); - - JacobiSVD svd; - VERIFY_RAISES_ASSERT(svd.matrixU()) - VERIFY_RAISES_ASSERT(svd.singularValues()) - VERIFY_RAISES_ASSERT(svd.matrixV()) - VERIFY_RAISES_ASSERT(svd.solve(rhs)) MatrixType a = MatrixType::Zero(rows, cols); a.setZero(); - svd.compute(a, 0); - VERIFY_RAISES_ASSERT(svd.matrixU()) - VERIFY_RAISES_ASSERT(svd.matrixV()) - svd.singularValues(); - VERIFY_RAISES_ASSERT(svd.solve(rhs)) if (ColsAtCompileTime == Dynamic) { - svd.compute(a, ComputeThinU); - svd.matrixU(); - VERIFY_RAISES_ASSERT(svd.matrixV()) - VERIFY_RAISES_ASSERT(svd.solve(rhs)) - - svd.compute(a, ComputeThinV); - svd.matrixV(); - VERIFY_RAISES_ASSERT(svd.matrixU()) - VERIFY_RAISES_ASSERT(svd.solve(rhs)) - JacobiSVD svd_fullqr; VERIFY_RAISES_ASSERT(svd_fullqr.compute(a, ComputeFullU|ComputeThinV)) VERIFY_RAISES_ASSERT(svd_fullqr.compute(a, ComputeThinU|ComputeThinV)) VERIFY_RAISES_ASSERT(svd_fullqr.compute(a, ComputeThinU|ComputeFullV)) } - else - { - VERIFY_RAISES_ASSERT(svd.compute(a, ComputeThinU)) - VERIFY_RAISES_ASSERT(svd.compute(a, ComputeThinV)) - } } template @@ -302,126 +70,17 @@ void jacobisvd_method() VERIFY_IS_APPROX(m.jacobiSvd(ComputeFullU|ComputeFullV).solve(m), m); } -// work around stupid msvc error when constructing at compile time an expression that involves -// a division by zero, even if the numeric type has floating point -template -EIGEN_DONT_INLINE Scalar zero() { return Scalar(0); } - -// workaround aggressive optimization in ICC -template EIGEN_DONT_INLINE T sub(T a, T b) { return a - b; } - -template -void jacobisvd_inf_nan() -{ - // all this function does is verify we don't iterate infinitely on nan/inf values - - JacobiSVD svd; - typedef typename MatrixType::Scalar Scalar; - Scalar some_inf = Scalar(1) / zero(); - VERIFY(sub(some_inf, some_inf) != sub(some_inf, some_inf)); - svd.compute(MatrixType::Constant(10,10,some_inf), ComputeFullU | ComputeFullV); - - Scalar nan = std::numeric_limits::quiet_NaN(); - VERIFY(nan != nan); - svd.compute(MatrixType::Constant(10,10,nan), ComputeFullU | ComputeFullV); - - MatrixType m = MatrixType::Zero(10,10); - m(internal::random(0,9), internal::random(0,9)) = some_inf; - svd.compute(m, ComputeFullU | ComputeFullV); - - m = MatrixType::Zero(10,10); - m(internal::random(0,9), internal::random(0,9)) = nan; - svd.compute(m, ComputeFullU | ComputeFullV); - - // regression test for bug 791 - m.resize(3,3); - m << 0, 2*NumTraits::epsilon(), 0.5, - 0, -0.5, 0, - nan, 0, 0; - svd.compute(m, ComputeFullU | ComputeFullV); -} - -// Regression test for bug 286: JacobiSVD loops indefinitely with some -// matrices containing denormal numbers. -void jacobisvd_bug286() -{ -#if defined __INTEL_COMPILER -// shut up warning #239: floating point underflow -#pragma warning push -#pragma warning disable 239 -#endif - Matrix2d M; - M << -7.90884e-313, -4.94e-324, - 0, 5.60844e-313; -#if defined __INTEL_COMPILER -#pragma warning pop -#endif - JacobiSVD svd; - svd.compute(M); // just check we don't loop indefinitely -} - -void jacobisvd_preallocate() -{ - Vector3f v(3.f, 2.f, 1.f); - MatrixXf m = v.asDiagonal(); - - internal::set_is_malloc_allowed(false); - VERIFY_RAISES_ASSERT(VectorXf tmp(10);) - JacobiSVD svd; - internal::set_is_malloc_allowed(true); - svd.compute(m); - VERIFY_IS_APPROX(svd.singularValues(), v); - - JacobiSVD svd2(3,3); - internal::set_is_malloc_allowed(false); - svd2.compute(m); - internal::set_is_malloc_allowed(true); - VERIFY_IS_APPROX(svd2.singularValues(), v); - VERIFY_RAISES_ASSERT(svd2.matrixU()); - VERIFY_RAISES_ASSERT(svd2.matrixV()); - svd2.compute(m, ComputeFullU | ComputeFullV); - VERIFY_IS_APPROX(svd2.matrixU(), Matrix3f::Identity()); - VERIFY_IS_APPROX(svd2.matrixV(), Matrix3f::Identity()); - internal::set_is_malloc_allowed(false); - svd2.compute(m); - internal::set_is_malloc_allowed(true); - - JacobiSVD svd3(3,3,ComputeFullU|ComputeFullV); - internal::set_is_malloc_allowed(false); - svd2.compute(m); - internal::set_is_malloc_allowed(true); - VERIFY_IS_APPROX(svd2.singularValues(), v); - VERIFY_IS_APPROX(svd2.matrixU(), Matrix3f::Identity()); - VERIFY_IS_APPROX(svd2.matrixV(), Matrix3f::Identity()); - internal::set_is_malloc_allowed(false); - svd2.compute(m, ComputeFullU|ComputeFullV); - internal::set_is_malloc_allowed(true); -} - void test_jacobisvd() { CALL_SUBTEST_3(( jacobisvd_verify_assert(Matrix3f()) )); CALL_SUBTEST_4(( jacobisvd_verify_assert(Matrix4d()) )); CALL_SUBTEST_7(( jacobisvd_verify_assert(MatrixXf(10,12)) )); CALL_SUBTEST_8(( jacobisvd_verify_assert(MatrixXcd(7,5)) )); + + CALL_SUBTEST_11(svd_all_trivial_2x2(jacobisvd)); + CALL_SUBTEST_12(svd_all_trivial_2x2(jacobisvd)); for(int i = 0; i < g_repeat; i++) { - Matrix2cd m; - m << 0, 1, - 0, 1; - CALL_SUBTEST_1(( jacobisvd(m, false) )); - m << 1, 0, - 1, 0; - CALL_SUBTEST_1(( jacobisvd(m, false) )); - - Matrix2d n; - n << 0, 0, - 0, 0; - CALL_SUBTEST_2(( jacobisvd(n, false) )); - n << 0, 0, - 0, 1; - CALL_SUBTEST_2(( jacobisvd(n, false) )); - CALL_SUBTEST_3(( jacobisvd() )); CALL_SUBTEST_4(( jacobisvd() )); CALL_SUBTEST_5(( jacobisvd >() )); @@ -440,8 +99,14 @@ void test_jacobisvd() (void) c; // Test on inf/nan matrix - CALL_SUBTEST_7( jacobisvd_inf_nan() ); - CALL_SUBTEST_10( jacobisvd_inf_nan() ); + CALL_SUBTEST_7( (svd_inf_nan, MatrixXf>()) ); + CALL_SUBTEST_10( (svd_inf_nan, MatrixXd>()) ); + + // bug1395 test compile-time vectors as input + CALL_SUBTEST_13(( jacobisvd_verify_assert(Matrix()) )); + CALL_SUBTEST_13(( jacobisvd_verify_assert(Matrix()) )); + CALL_SUBTEST_13(( jacobisvd_verify_assert(Matrix(r)) )); + CALL_SUBTEST_13(( jacobisvd_verify_assert(Matrix(c)) )); } CALL_SUBTEST_7(( jacobisvd(MatrixXf(internal::random(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/2), internal::random(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/2))) )); @@ -455,8 +120,7 @@ void test_jacobisvd() CALL_SUBTEST_7( JacobiSVD(10,10) ); // Check that preallocation avoids subsequent mallocs - CALL_SUBTEST_9( jacobisvd_preallocate() ); + CALL_SUBTEST_9( svd_preallocate() ); - // Regression check for bug 286 - CALL_SUBTEST_2( jacobisvd_bug286() ); + CALL_SUBTEST_2( svd_underoverflow() ); } diff --git a/testbed/nanogui/ext/eigen/test/linearstructure.cpp b/testbed/nanogui/ext/eigen/test/linearstructure.cpp index 618984d5..17474af1 100644 --- a/testbed/nanogui/ext/eigen/test/linearstructure.cpp +++ b/testbed/nanogui/ext/eigen/test/linearstructure.cpp @@ -2,11 +2,15 @@ // for linear algebra. // // Copyright (C) 2006-2008 Benoit Jacob +// Copyright (C) 2014 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +static bool g_called; +#define EIGEN_SCALAR_BINARY_OP_PLUGIN { g_called |= (!internal::is_same::value); } + #include "main.h" template void linearStructure(const MatrixType& m) @@ -17,6 +21,7 @@ template void linearStructure(const MatrixType& m) */ typedef typename MatrixType::Index Index; typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; Index rows = m.rows(); Index cols = m.cols(); @@ -28,7 +33,7 @@ template void linearStructure(const MatrixType& m) m3(rows, cols); Scalar s1 = internal::random(); - while (abs(s1)<1e-3) s1 = internal::random(); + while (abs(s1)(); Index r = internal::random(0, rows-1), c = internal::random(0, cols-1); @@ -68,8 +73,48 @@ template void linearStructure(const MatrixType& m) VERIFY_IS_APPROX(m1.block(0,0,rows,cols) * s1, m1 * s1); } +// Make sure that complex * real and real * complex are properly optimized +template void real_complex(DenseIndex rows = MatrixType::RowsAtCompileTime, DenseIndex cols = MatrixType::ColsAtCompileTime) +{ + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + + RealScalar s = internal::random(); + MatrixType m1 = MatrixType::Random(rows, cols); + + g_called = false; + VERIFY_IS_APPROX(s*m1, Scalar(s)*m1); + VERIFY(g_called && "real * matrix not properly optimized"); + + g_called = false; + VERIFY_IS_APPROX(m1*s, m1*Scalar(s)); + VERIFY(g_called && "matrix * real not properly optimized"); + + g_called = false; + VERIFY_IS_APPROX(m1/s, m1/Scalar(s)); + VERIFY(g_called && "matrix / real not properly optimized"); + + g_called = false; + VERIFY_IS_APPROX(s+m1.array(), Scalar(s)+m1.array()); + VERIFY(g_called && "real + matrix not properly optimized"); + + g_called = false; + VERIFY_IS_APPROX(m1.array()+s, m1.array()+Scalar(s)); + VERIFY(g_called && "matrix + real not properly optimized"); + + g_called = false; + VERIFY_IS_APPROX(s-m1.array(), Scalar(s)-m1.array()); + VERIFY(g_called && "real - matrix not properly optimized"); + + g_called = false; + VERIFY_IS_APPROX(m1.array()-s, m1.array()-Scalar(s)); + VERIFY(g_called && "matrix - real not properly optimized"); +} + void test_linearstructure() { + g_called = true; + VERIFY(g_called); // avoid `unneeded-internal-declaration` warning. for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( linearStructure(Matrix()) ); CALL_SUBTEST_2( linearStructure(Matrix2f()) ); @@ -80,5 +125,25 @@ void test_linearstructure() CALL_SUBTEST_7( linearStructure(MatrixXi (internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); CALL_SUBTEST_8( linearStructure(MatrixXcd(internal::random(1,EIGEN_TEST_MAX_SIZE/2), internal::random(1,EIGEN_TEST_MAX_SIZE/2))) ); CALL_SUBTEST_9( linearStructure(ArrayXXf (internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_10( linearStructure(ArrayXXcf (internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + + CALL_SUBTEST_11( real_complex() ); + CALL_SUBTEST_11( real_complex(10,10) ); + CALL_SUBTEST_11( real_complex(10,10) ); } + +#ifdef EIGEN_TEST_PART_4 + { + // make sure that /=scalar and /scalar do not overflow + // rational: 1.0/4.94e-320 overflow, but m/4.94e-320 should not + Matrix4d m2, m3; + m3 = m2 = Matrix4d::Random()*1e-20; + m2 = m2 / 4.9e-320; + VERIFY_IS_APPROX(m2.cwiseQuotient(m2), Matrix4d::Ones()); + m3 /= 4.9e-320; + VERIFY_IS_APPROX(m3.cwiseQuotient(m3), Matrix4d::Ones()); + + + } +#endif } diff --git a/testbed/nanogui/ext/eigen/test/lscg.cpp b/testbed/nanogui/ext/eigen/test/lscg.cpp new file mode 100644 index 00000000..daa62a95 --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/lscg.cpp @@ -0,0 +1,29 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "sparse_solver.h" +#include + +template void test_lscg_T() +{ + LeastSquaresConjugateGradient > lscg_colmajor_diag; + LeastSquaresConjugateGradient, IdentityPreconditioner> lscg_colmajor_I; + + CALL_SUBTEST( check_sparse_square_solving(lscg_colmajor_diag) ); + CALL_SUBTEST( check_sparse_square_solving(lscg_colmajor_I) ); + + CALL_SUBTEST( check_sparse_leastsquare_solving(lscg_colmajor_diag) ); + CALL_SUBTEST( check_sparse_leastsquare_solving(lscg_colmajor_I) ); +} + +void test_lscg() +{ + CALL_SUBTEST_1(test_lscg_T()); + CALL_SUBTEST_2(test_lscg_T >()); +} diff --git a/testbed/nanogui/ext/eigen/test/lu.cpp b/testbed/nanogui/ext/eigen/test/lu.cpp index 25f86755..9787f4d8 100644 --- a/testbed/nanogui/ext/eigen/test/lu.cpp +++ b/testbed/nanogui/ext/eigen/test/lu.cpp @@ -11,6 +11,11 @@ #include using namespace std; +template +typename MatrixType::RealScalar matrix_l1_norm(const MatrixType& m) { + return m.cwiseAbs().colwise().sum().maxCoeff(); +} + template void lu_non_invertible() { typedef typename MatrixType::Index Index; @@ -92,6 +97,26 @@ template void lu_non_invertible() // test that the code, which does resize(), may be applied to an xpr m2.block(0,0,m2.rows(),m2.cols()) = lu.solve(m3); VERIFY_IS_APPROX(m3, m1*m2); + + // test solve with transposed + m3 = MatrixType::Random(rows,cols2); + m2 = m1.transpose()*m3; + m3 = MatrixType::Random(rows,cols2); + lu.template _solve_impl_transposed(m2, m3); + VERIFY_IS_APPROX(m2, m1.transpose()*m3); + m3 = MatrixType::Random(rows,cols2); + m3 = lu.transpose().solve(m2); + VERIFY_IS_APPROX(m2, m1.transpose()*m3); + + // test solve with conjugate transposed + m3 = MatrixType::Random(rows,cols2); + m2 = m1.adjoint()*m3; + m3 = MatrixType::Random(rows,cols2); + lu.template _solve_impl_transposed(m2, m3); + VERIFY_IS_APPROX(m2, m1.adjoint()*m3); + m3 = MatrixType::Random(rows,cols2); + m3 = lu.adjoint().solve(m2); + VERIFY_IS_APPROX(m2, m1.adjoint()*m3); } template void lu_invertible() @@ -100,7 +125,9 @@ template void lu_invertible() LU.h */ typedef typename NumTraits::Real RealScalar; - int size = internal::random(1,EIGEN_TEST_MAX_SIZE); + Index size = MatrixType::RowsAtCompileTime; + if( size==Dynamic) + size = internal::random(1,EIGEN_TEST_MAX_SIZE); MatrixType m1(size, size), m2(size, size), m3(size, size); FullPivLU lu; @@ -121,7 +148,32 @@ template void lu_invertible() m3 = MatrixType::Random(size,size); m2 = lu.solve(m3); VERIFY_IS_APPROX(m3, m1*m2); - VERIFY_IS_APPROX(m2, lu.inverse()*m3); + MatrixType m1_inverse = lu.inverse(); + VERIFY_IS_APPROX(m2, m1_inverse*m3); + + RealScalar rcond = (RealScalar(1) / matrix_l1_norm(m1)) / matrix_l1_norm(m1_inverse); + const RealScalar rcond_est = lu.rcond(); + // Verify that the estimated condition number is within a factor of 10 of the + // truth. + VERIFY(rcond_est > rcond / 10 && rcond_est < rcond * 10); + + // test solve with transposed + lu.template _solve_impl_transposed(m3, m2); + VERIFY_IS_APPROX(m3, m1.transpose()*m2); + m3 = MatrixType::Random(size,size); + m3 = lu.transpose().solve(m2); + VERIFY_IS_APPROX(m2, m1.transpose()*m3); + + // test solve with conjugate transposed + lu.template _solve_impl_transposed(m3, m2); + VERIFY_IS_APPROX(m3, m1.adjoint()*m2); + m3 = MatrixType::Random(size,size); + m3 = lu.adjoint().solve(m2); + VERIFY_IS_APPROX(m2, m1.adjoint()*m3); + + // Regression test for Bug 302 + MatrixType m4 = MatrixType::Random(size,size); + VERIFY_IS_APPROX(lu.solve(m3*m4), lu.solve(m3)*m4); } template void lu_partial_piv() @@ -130,14 +182,39 @@ template void lu_partial_piv() PartialPivLU.h */ typedef typename MatrixType::Index Index; - Index rows = internal::random(1,4); - Index cols = rows; + typedef typename NumTraits::Real RealScalar; + Index size = internal::random(1,4); - MatrixType m1(cols, rows); + MatrixType m1(size, size), m2(size, size), m3(size, size); m1.setRandom(); PartialPivLU plu(m1); VERIFY_IS_APPROX(m1, plu.reconstructedMatrix()); + + m3 = MatrixType::Random(size,size); + m2 = plu.solve(m3); + VERIFY_IS_APPROX(m3, m1*m2); + MatrixType m1_inverse = plu.inverse(); + VERIFY_IS_APPROX(m2, m1_inverse*m3); + + RealScalar rcond = (RealScalar(1) / matrix_l1_norm(m1)) / matrix_l1_norm(m1_inverse); + const RealScalar rcond_est = plu.rcond(); + // Verify that the estimate is within a factor of 10 of the truth. + VERIFY(rcond_est > rcond / 10 && rcond_est < rcond * 10); + + // test solve with transposed + plu.template _solve_impl_transposed(m3, m2); + VERIFY_IS_APPROX(m3, m1.transpose()*m2); + m3 = MatrixType::Random(size,size); + m3 = plu.transpose().solve(m2); + VERIFY_IS_APPROX(m2, m1.transpose()*m3); + + // test solve with conjugate transposed + plu.template _solve_impl_transposed(m3, m2); + VERIFY_IS_APPROX(m3, m1.adjoint()*m2); + m3 = MatrixType::Random(size,size); + m3 = plu.adjoint().solve(m2); + VERIFY_IS_APPROX(m2, m1.adjoint()*m3); } template void lu_verify_assert() @@ -171,6 +248,7 @@ void test_lu() { for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( lu_non_invertible() ); + CALL_SUBTEST_1( lu_invertible() ); CALL_SUBTEST_1( lu_verify_assert() ); CALL_SUBTEST_2( (lu_non_invertible >()) ); diff --git a/testbed/nanogui/ext/eigen/test/main.h b/testbed/nanogui/ext/eigen/test/main.h index 66420486..25d2dcf4 100644 --- a/testbed/nanogui/ext/eigen/test/main.h +++ b/testbed/nanogui/ext/eigen/test/main.h @@ -41,7 +41,14 @@ #include #include #include +#include #include +#if __cplusplus >= 201103L +#include +#ifdef EIGEN_USE_THREADS +#include +#endif +#endif // To test that all calls from Eigen code to std::min() and std::max() are // protected by parenthesis against macro expansion, the min()/max() macros @@ -49,14 +56,48 @@ // compiler error. #define min(A,B) please_protect_your_min_with_parentheses #define max(A,B) please_protect_your_max_with_parentheses +#define isnan(X) please_protect_your_isnan_with_parentheses +#define isinf(X) please_protect_your_isinf_with_parentheses +#define isfinite(X) please_protect_your_isfinite_with_parentheses +#ifdef M_PI +#undef M_PI +#endif +#define M_PI please_use_EIGEN_PI_instead_of_M_PI #define FORBIDDEN_IDENTIFIER (this_identifier_is_forbidden_to_avoid_clashes) this_identifier_is_forbidden_to_avoid_clashes // B0 is defined in POSIX header termios.h #define B0 FORBIDDEN_IDENTIFIER +// Unit tests calling Eigen's blas library must preserve the default blocking size +// to avoid troubles. +#ifndef EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS +#define EIGEN_DEBUG_SMALL_PRODUCT_BLOCKS +#endif // shuts down ICC's remark #593: variable "XXX" was set but never used -#define TEST_SET_BUT_UNUSED_VARIABLE(X) X = X + 0; +#define TEST_SET_BUT_UNUSED_VARIABLE(X) EIGEN_UNUSED_VARIABLE(X) + +#ifdef TEST_ENABLE_TEMPORARY_TRACKING + +static long int nb_temporaries; +static long int nb_temporaries_on_assert = -1; + +inline void on_temporary_creation(long int size) { + // here's a great place to set a breakpoint when debugging failures in this test! + if(size!=0) nb_temporaries++; + if(nb_temporaries_on_assert>0) assert(nb_temporaries g_test_stack; + // level == 0 <=> abort if test fail + // level >= 1 <=> warning message to std::cerr if test fail + static int g_test_level = 0; static int g_repeat; static unsigned int g_seed; static bool g_has_set_repeat, g_has_set_seed; } +#define TRACK std::cerr << __FILE__ << " " << __LINE__ << std::endl +// #define TRACK while() + #define EI_PP_MAKE_STRING2(S) #S #define EI_PP_MAKE_STRING(S) EI_PP_MAKE_STRING2(S) #define EIGEN_DEFAULT_IO_FORMAT IOFormat(4, 0, " ", "\n", "", "", "", "") +#if (defined(_CPPUNWIND) || defined(__EXCEPTIONS)) && !defined(__CUDA_ARCH__) + #define EIGEN_EXCEPTIONS +#endif + #ifndef EIGEN_NO_ASSERTION_CHECKING namespace Eigen @@ -135,33 +186,35 @@ namespace Eigen if(report_on_cerr_on_assert_failure) \ std::cerr << #a << " " __FILE__ << "(" << __LINE__ << ")\n"; \ Eigen::no_more_assert = true; \ - throw Eigen::eigen_assert_exception(); \ + EIGEN_THROW_X(Eigen::eigen_assert_exception()); \ } \ else if (Eigen::internal::push_assert) \ { \ eigen_assert_list.push_back(std::string(EI_PP_MAKE_STRING(__FILE__) " (" EI_PP_MAKE_STRING(__LINE__) ") : " #a) ); \ } + #ifdef EIGEN_EXCEPTIONS #define VERIFY_RAISES_ASSERT(a) \ { \ Eigen::no_more_assert = false; \ - Eigen::eigen_assert_list.clear(); \ - Eigen::internal::push_assert = true; \ + Eigen::eigen_assert_list.clear(); \ + Eigen::internal::push_assert = true; \ Eigen::report_on_cerr_on_assert_failure = false; \ try { \ a; \ std::cerr << "One of the following asserts should have been triggered:\n"; \ - for (uint ai=0 ; ai0) + std::cerr << "WARNING: "; std::cerr << "Test " << testname << " failed in " << file << " (" << line << ")" << std::endl << " " << condition_as_string << std::endl; std::cerr << "Stack:\n"; @@ -208,14 +271,20 @@ inline void verify_impl(bool condition, const char *testname, const char *file, for(int i=test_stack_size-1; i>=0; --i) std::cerr << " - " << Eigen::g_test_stack[i] << "\n"; std::cerr << "\n"; - abort(); + if(Eigen::g_test_level==0) + abort(); } } #define VERIFY(a) ::verify_impl(a, g_test_stack.back().c_str(), __FILE__, __LINE__, EI_PP_MAKE_STRING(a)) -#define VERIFY_IS_EQUAL(a, b) VERIFY(test_is_equal(a, b)) -#define VERIFY_IS_APPROX(a, b) VERIFY(test_isApprox(a, b)) +#define VERIFY_GE(a, b) ::verify_impl(a >= b, g_test_stack.back().c_str(), __FILE__, __LINE__, EI_PP_MAKE_STRING(a >= b)) +#define VERIFY_LE(a, b) ::verify_impl(a <= b, g_test_stack.back().c_str(), __FILE__, __LINE__, EI_PP_MAKE_STRING(a <= b)) + + +#define VERIFY_IS_EQUAL(a, b) VERIFY(test_is_equal(a, b, true)) +#define VERIFY_IS_NOT_EQUAL(a, b) VERIFY(test_is_equal(a, b, false)) +#define VERIFY_IS_APPROX(a, b) VERIFY(verifyIsApprox(a, b)) #define VERIFY_IS_NOT_APPROX(a, b) VERIFY(!test_isApprox(a, b)) #define VERIFY_IS_MUCH_SMALLER_THAN(a, b) VERIFY(test_isMuchSmallerThan(a, b)) #define VERIFY_IS_NOT_MUCH_SMALLER_THAN(a, b) VERIFY(!test_isMuchSmallerThan(a, b)) @@ -236,9 +305,10 @@ namespace Eigen { template inline typename NumTraits::Real test_precision() { return NumTraits::dummy_precision(); } template<> inline float test_precision() { return 1e-3f; } template<> inline double test_precision() { return 1e-6; } +template<> inline long double test_precision() { return 1e-6l; } template<> inline float test_precision >() { return test_precision(); } template<> inline double test_precision >() { return test_precision(); } -template<> inline long double test_precision() { return 1e-6; } +template<> inline long double test_precision >() { return test_precision(); } inline bool test_isApprox(const int& a, const int& b) { return internal::isApprox(a, b, test_precision()); } @@ -253,14 +323,15 @@ inline bool test_isMuchSmallerThan(const float& a, const float& b) { return internal::isMuchSmallerThan(a, b, test_precision()); } inline bool test_isApproxOrLessThan(const float& a, const float& b) { return internal::isApproxOrLessThan(a, b, test_precision()); } + inline bool test_isApprox(const double& a, const double& b) { return internal::isApprox(a, b, test_precision()); } - inline bool test_isMuchSmallerThan(const double& a, const double& b) { return internal::isMuchSmallerThan(a, b, test_precision()); } inline bool test_isApproxOrLessThan(const double& a, const double& b) { return internal::isApproxOrLessThan(a, b, test_precision()); } +#ifndef EIGEN_TEST_NO_COMPLEX inline bool test_isApprox(const std::complex& a, const std::complex& b) { return internal::isApprox(a, b, test_precision >()); } inline bool test_isMuchSmallerThan(const std::complex& a, const std::complex& b) @@ -271,6 +342,15 @@ inline bool test_isApprox(const std::complex& a, const std::complex& a, const std::complex& b) { return internal::isMuchSmallerThan(a, b, test_precision >()); } +#ifndef EIGEN_TEST_NO_LONGDOUBLE +inline bool test_isApprox(const std::complex& a, const std::complex& b) +{ return internal::isApprox(a, b, test_precision >()); } +inline bool test_isMuchSmallerThan(const std::complex& a, const std::complex& b) +{ return internal::isMuchSmallerThan(a, b, test_precision >()); } +#endif +#endif + +#ifndef EIGEN_TEST_NO_LONGDOUBLE inline bool test_isApprox(const long double& a, const long double& b) { bool ret = internal::isApprox(a, b, test_precision()); @@ -284,13 +364,127 @@ inline bool test_isMuchSmallerThan(const long double& a, const long double& b) { return internal::isMuchSmallerThan(a, b, test_precision()); } inline bool test_isApproxOrLessThan(const long double& a, const long double& b) { return internal::isApproxOrLessThan(a, b, test_precision()); } +#endif // EIGEN_TEST_NO_LONGDOUBLE + +inline bool test_isApprox(const half& a, const half& b) +{ return internal::isApprox(a, b, test_precision()); } +inline bool test_isMuchSmallerThan(const half& a, const half& b) +{ return internal::isMuchSmallerThan(a, b, test_precision()); } +inline bool test_isApproxOrLessThan(const half& a, const half& b) +{ return internal::isApproxOrLessThan(a, b, test_precision()); } + +// test_relative_error returns the relative difference between a and b as a real scalar as used in isApprox. +template +typename NumTraits::NonInteger test_relative_error(const EigenBase &a, const EigenBase &b) +{ + using std::sqrt; + typedef typename NumTraits::NonInteger RealScalar; + typename internal::nested_eval::type ea(a.derived()); + typename internal::nested_eval::type eb(b.derived()); + return sqrt(RealScalar((ea-eb).cwiseAbs2().sum()) / RealScalar((std::min)(eb.cwiseAbs2().sum(),ea.cwiseAbs2().sum()))); +} + +template +typename T1::RealScalar test_relative_error(const T1 &a, const T2 &b, const typename T1::Coefficients* = 0) +{ + return test_relative_error(a.coeffs(), b.coeffs()); +} + +template +typename T1::Scalar test_relative_error(const T1 &a, const T2 &b, const typename T1::MatrixType* = 0) +{ + return test_relative_error(a.matrix(), b.matrix()); +} + +template +S test_relative_error(const Translation &a, const Translation &b) +{ + return test_relative_error(a.vector(), b.vector()); +} + +template +S test_relative_error(const ParametrizedLine &a, const ParametrizedLine &b) +{ + return (std::max)(test_relative_error(a.origin(), b.origin()), test_relative_error(a.origin(), b.origin())); +} + +template +S test_relative_error(const AlignedBox &a, const AlignedBox &b) +{ + return (std::max)(test_relative_error((a.min)(), (b.min)()), test_relative_error((a.max)(), (b.max)())); +} + +template class SparseMatrixBase; +template +typename T1::RealScalar test_relative_error(const MatrixBase &a, const SparseMatrixBase &b) +{ + return test_relative_error(a,b.toDense()); +} + +template class SparseMatrixBase; +template +typename T1::RealScalar test_relative_error(const SparseMatrixBase &a, const MatrixBase &b) +{ + return test_relative_error(a.toDense(),b); +} + +template class SparseMatrixBase; +template +typename T1::RealScalar test_relative_error(const SparseMatrixBase &a, const SparseMatrixBase &b) +{ + return test_relative_error(a.toDense(),b.toDense()); +} + +template +typename NumTraits::Real>::NonInteger test_relative_error(const T1 &a, const T2 &b, typename internal::enable_if::Real>::value, T1>::type* = 0) +{ + typedef typename NumTraits::Real>::NonInteger RealScalar; + return numext::sqrt(RealScalar(numext::abs2(a-b))/RealScalar((numext::mini)(numext::abs2(a),numext::abs2(b)))); +} + +template +T test_relative_error(const Rotation2D &a, const Rotation2D &b) +{ + return test_relative_error(a.angle(), b.angle()); +} + +template +T test_relative_error(const AngleAxis &a, const AngleAxis &b) +{ + return (std::max)(test_relative_error(a.angle(), b.angle()), test_relative_error(a.axis(), b.axis())); +} template -inline bool test_isApprox(const Type1& a, const Type2& b) +inline bool test_isApprox(const Type1& a, const Type2& b, typename Type1::Scalar* = 0) // Enabled for Eigen's type only { return a.isApprox(b, test_precision()); } +// get_test_precision is a small wrapper to test_precision allowing to return the scalar precision for either scalars or expressions +template +typename NumTraits::Real get_test_precision(const T&, const typename T::Scalar* = 0) +{ + return test_precision::Real>(); +} + +template +typename NumTraits::Real get_test_precision(const T&,typename internal::enable_if::Real>::value, T>::type* = 0) +{ + return test_precision::Real>(); +} + +// verifyIsApprox is a wrapper to test_isApprox that outputs the relative difference magnitude if the test fails. +template +inline bool verifyIsApprox(const Type1& a, const Type2& b) +{ + bool ret = test_isApprox(a,b); + if(!ret) + { + std::cerr << "Difference too large wrt tolerance " << get_test_precision(a) << ", relative error is: " << test_relative_error(a,b) << std::endl; + } + return ret; +} + // The idea behind this function is to compare the two scalars a and b where // the scalar ref is a hint about the expected order of magnitude of a and b. // WARNING: the scalar a and b must be positive @@ -326,17 +520,17 @@ inline bool test_isUnitary(const MatrixBase& m) // Forward declaration to avoid ICC warning template -bool test_is_equal(const T& actual, const U& expected); +bool test_is_equal(const T& actual, const U& expected, bool expect_equal=true); template -bool test_is_equal(const T& actual, const U& expected) +bool test_is_equal(const T& actual, const U& expected, bool expect_equal) { - if (actual==expected) + if ((actual==expected) == expect_equal) return true; // false: std::cerr - << std::endl << " actual = " << actual - << std::endl << " expected = " << expected << std::endl << std::endl; + << "\n actual = " << actual + << "\n expected " << (expect_equal ? "= " : "!=") << expected << "\n\n"; return false; } @@ -347,11 +541,10 @@ bool test_is_equal(const T& actual, const U& expected) */ // Forward declaration to avoid ICC warning template -void createRandomPIMatrixOfRank(typename MatrixType::Index desired_rank, typename MatrixType::Index rows, typename MatrixType::Index cols, MatrixType& m); +void createRandomPIMatrixOfRank(Index desired_rank, Index rows, Index cols, MatrixType& m); template -void createRandomPIMatrixOfRank(typename MatrixType::Index desired_rank, typename MatrixType::Index rows, typename MatrixType::Index cols, MatrixType& m) +void createRandomPIMatrixOfRank(Index desired_rank, Index rows, Index cols, MatrixType& m) { - typedef typename internal::traits::Index Index; typedef typename internal::traits::Scalar Scalar; enum { Rows = MatrixType::RowsAtCompileTime, Cols = MatrixType::ColsAtCompileTime }; @@ -388,11 +581,10 @@ void createRandomPIMatrixOfRank(typename MatrixType::Index desired_rank, typenam // Forward declaration to avoid ICC warning template -void randomPermutationVector(PermutationVectorType& v, typename PermutationVectorType::Index size); +void randomPermutationVector(PermutationVectorType& v, Index size); template -void randomPermutationVector(PermutationVectorType& v, typename PermutationVectorType::Index size) +void randomPermutationVector(PermutationVectorType& v, Index size) { - typedef typename PermutationVectorType::Index Index; typedef typename PermutationVectorType::Scalar Scalar; v.resize(size); for(Index i = 0; i < size; ++i) v(i) = Scalar(i); @@ -411,12 +603,7 @@ template bool isNotNaN(const T& x) return x==x; } -template bool isNaN(const T& x) -{ - return x!=x; -} - -template bool isInf(const T& x) +template bool isPlusInf(const T& x) { return x > NumTraits::highest(); } @@ -437,13 +624,15 @@ template struct GetDifferentType > // Forward declaration to avoid ICC warning template std::string type_name(); -template std::string type_name() { return "other"; } -template<> std::string type_name() { return "float"; } -template<> std::string type_name() { return "double"; } -template<> std::string type_name() { return "int"; } -template<> std::string type_name >() { return "complex"; } -template<> std::string type_name >() { return "complex"; } -template<> std::string type_name >() { return "complex"; } +template std::string type_name() { return "other"; } +template<> std::string type_name() { return "float"; } +template<> std::string type_name() { return "double"; } +template<> std::string type_name() { return "long double"; } +template<> std::string type_name() { return "int"; } +template<> std::string type_name >() { return "complex"; } +template<> std::string type_name >() { return "complex"; } +template<> std::string type_name >() { return "complex"; } +template<> std::string type_name >() { return "complex"; } // forward declaration of the main test function void EIGEN_CAT(test_,EIGEN_TEST_FUNC)(); @@ -550,3 +739,8 @@ int main(int argc, char *argv[]) // remark #1572: floating-point equality and inequality comparisons are unreliable #pragma warning disable 279 383 1418 1572 #endif + +#ifdef _MSC_VER + // 4503 - decorated name length exceeded, name was truncated + #pragma warning( disable : 4503) +#endif diff --git a/testbed/nanogui/ext/eigen/test/mapped_matrix.cpp b/testbed/nanogui/ext/eigen/test/mapped_matrix.cpp index de9dbbde..6a84c589 100644 --- a/testbed/nanogui/ext/eigen/test/mapped_matrix.cpp +++ b/testbed/nanogui/ext/eigen/test/mapped_matrix.cpp @@ -13,6 +13,8 @@ #include "main.h" +#define EIGEN_TESTMAP_MAX_SIZE 256 + template void map_class_vector(const VectorType& m) { typedef typename VectorType::Index Index; @@ -20,23 +22,26 @@ template void map_class_vector(const VectorType& m) Index size = m.size(); - // test Map.h Scalar* array1 = internal::aligned_new(size); Scalar* array2 = internal::aligned_new(size); Scalar* array3 = new Scalar[size+1]; - Scalar* array3unaligned = size_t(array3)%16 == 0 ? array3+1 : array3; + Scalar* array3unaligned = (internal::UIntPtr(array3)%EIGEN_MAX_ALIGN_BYTES) == 0 ? array3+1 : array3; + Scalar array4[EIGEN_TESTMAP_MAX_SIZE]; - Map(array1, size) = VectorType::Random(size); - Map(array2, size) = Map(array1, size); + Map(array1, size) = VectorType::Random(size); + Map(array2, size) = Map(array1, size); Map(array3unaligned, size) = Map(array1, size); - VectorType ma1 = Map(array1, size); - VectorType ma2 = Map(array2, size); + Map(array4, size) = Map(array1, size); + VectorType ma1 = Map(array1, size); + VectorType ma2 = Map(array2, size); VectorType ma3 = Map(array3unaligned, size); + VectorType ma4 = Map(array4, size); VERIFY_IS_EQUAL(ma1, ma2); VERIFY_IS_EQUAL(ma1, ma3); + VERIFY_IS_EQUAL(ma1, ma4); #ifdef EIGEN_VECTORIZE - if(internal::packet_traits::Vectorizable) - VERIFY_RAISES_ASSERT((Map(array3unaligned, size))) + if(internal::packet_traits::Vectorizable && size>=AlignedMax) + VERIFY_RAISES_ASSERT((Map(array3unaligned, size))) #endif internal::aligned_delete(array1, size); @@ -50,23 +55,64 @@ template void map_class_matrix(const MatrixType& m) typedef typename MatrixType::Scalar Scalar; Index rows = m.rows(), cols = m.cols(), size = rows*cols; + Scalar s1 = internal::random(); - // test Map.h + // array1 and array2 -> aligned heap allocation Scalar* array1 = internal::aligned_new(size); for(int i = 0; i < size; i++) array1[i] = Scalar(1); Scalar* array2 = internal::aligned_new(size); for(int i = 0; i < size; i++) array2[i] = Scalar(1); + // array3unaligned -> unaligned pointer to heap Scalar* array3 = new Scalar[size+1]; for(int i = 0; i < size+1; i++) array3[i] = Scalar(1); - Scalar* array3unaligned = size_t(array3)%16 == 0 ? array3+1 : array3; - Map(array1, rows, cols) = MatrixType::Ones(rows,cols); - Map(array2, rows, cols) = Map(array1, rows, cols); - Map(array3unaligned, rows, cols) = Map(array1, rows, cols); - MatrixType ma1 = Map(array1, rows, cols); - MatrixType ma2 = Map(array2, rows, cols); + Scalar* array3unaligned = internal::UIntPtr(array3)%EIGEN_MAX_ALIGN_BYTES == 0 ? array3+1 : array3; + Scalar array4[256]; + if(size<=256) + for(int i = 0; i < size; i++) array4[i] = Scalar(1); + + Map map1(array1, rows, cols); + Map map2(array2, rows, cols); + Map map3(array3unaligned, rows, cols); + Map map4(array4, rows, cols); + + VERIFY_IS_EQUAL(map1, MatrixType::Ones(rows,cols)); + VERIFY_IS_EQUAL(map2, MatrixType::Ones(rows,cols)); + VERIFY_IS_EQUAL(map3, MatrixType::Ones(rows,cols)); + map1 = MatrixType::Random(rows,cols); + map2 = map1; + map3 = map1; + MatrixType ma1 = map1; + MatrixType ma2 = map2; + MatrixType ma3 = map3; + VERIFY_IS_EQUAL(map1, map2); + VERIFY_IS_EQUAL(map1, map3); VERIFY_IS_EQUAL(ma1, ma2); - MatrixType ma3 = Map(array3unaligned, rows, cols); VERIFY_IS_EQUAL(ma1, ma3); + VERIFY_IS_EQUAL(ma1, map3); + + VERIFY_IS_APPROX(s1*map1, s1*map2); + VERIFY_IS_APPROX(s1*ma1, s1*ma2); + VERIFY_IS_EQUAL(s1*ma1, s1*ma3); + VERIFY_IS_APPROX(s1*map1, s1*map3); + + map2 *= s1; + map3 *= s1; + VERIFY_IS_APPROX(s1*map1, map2); + VERIFY_IS_APPROX(s1*map1, map3); + + if(size<=256) + { + VERIFY_IS_EQUAL(map4, MatrixType::Ones(rows,cols)); + map4 = map1; + MatrixType ma4 = map4; + VERIFY_IS_EQUAL(map1, map4); + VERIFY_IS_EQUAL(ma1, map4); + VERIFY_IS_EQUAL(ma1, ma4); + VERIFY_IS_APPROX(s1*map1, s1*map4); + + map4 *= s1; + VERIFY_IS_APPROX(s1*map1, map4); + } internal::aligned_delete(array1, size); internal::aligned_delete(array2, size); @@ -80,11 +126,10 @@ template void map_static_methods(const VectorType& m) Index size = m.size(); - // test Map.h Scalar* array1 = internal::aligned_new(size); Scalar* array2 = internal::aligned_new(size); Scalar* array3 = new Scalar[size+1]; - Scalar* array3unaligned = size_t(array3)%16 == 0 ? array3+1 : array3; + Scalar* array3unaligned = internal::UIntPtr(array3)%EIGEN_MAX_ALIGN_BYTES == 0 ? array3+1 : array3; VectorType::MapAligned(array1, size) = VectorType::Random(size); VectorType::Map(array2, size) = VectorType::Map(array1, size); @@ -109,9 +154,31 @@ template void check_const_correctness(const PlainObjec // verify that map-to-const don't have LvalueBit typedef typename internal::add_const::type ConstPlainObjectType; VERIFY( !(internal::traits >::Flags & LvalueBit) ); - VERIFY( !(internal::traits >::Flags & LvalueBit) ); + VERIFY( !(internal::traits >::Flags & LvalueBit) ); VERIFY( !(Map::Flags & LvalueBit) ); - VERIFY( !(Map::Flags & LvalueBit) ); + VERIFY( !(Map::Flags & LvalueBit) ); +} + +template +void map_not_aligned_on_scalar() +{ + typedef Matrix MatrixType; + typedef typename MatrixType::Index Index; + Index size = 11; + Scalar* array1 = internal::aligned_new((size+1)*(size+1)+1); + Scalar* array2 = reinterpret_cast(sizeof(Scalar)/2+std::size_t(array1)); + Map > map2(array2, size, size, OuterStride<>(size+1)); + MatrixType m2 = MatrixType::Random(size,size); + map2 = m2; + VERIFY_IS_EQUAL(m2, map2); + + typedef Matrix VectorType; + Map map3(array2, size); + MatrixType v3 = VectorType::Random(size); + map3 = v3; + VERIFY_IS_EQUAL(v3, map3); + + internal::aligned_delete(array1, (size+1)*(size+1)+1); } void test_mapped_matrix() @@ -120,6 +187,7 @@ void test_mapped_matrix() CALL_SUBTEST_1( map_class_vector(Matrix()) ); CALL_SUBTEST_1( check_const_correctness(Matrix()) ); CALL_SUBTEST_2( map_class_vector(Vector4d()) ); + CALL_SUBTEST_2( map_class_vector(VectorXd(13)) ); CALL_SUBTEST_2( check_const_correctness(Matrix4d()) ); CALL_SUBTEST_3( map_class_vector(RowVector4f()) ); CALL_SUBTEST_4( map_class_vector(VectorXcf(8)) ); @@ -137,5 +205,7 @@ void test_mapped_matrix() CALL_SUBTEST_8( map_static_methods(RowVector3d()) ); CALL_SUBTEST_9( map_static_methods(VectorXcd(8)) ); CALL_SUBTEST_10( map_static_methods(VectorXf(12)) ); + + CALL_SUBTEST_11( map_not_aligned_on_scalar() ); } } diff --git a/testbed/nanogui/ext/eigen/test/mapstaticmethods.cpp b/testbed/nanogui/ext/eigen/test/mapstaticmethods.cpp index 5b512bde..06272d10 100644 --- a/testbed/nanogui/ext/eigen/test/mapstaticmethods.cpp +++ b/testbed/nanogui/ext/eigen/test/mapstaticmethods.cpp @@ -69,7 +69,8 @@ struct mapstaticmethods_impl { static void run(const PlainObjectType& m) { - int rows = m.rows(), cols = m.cols(); + typedef typename PlainObjectType::Index Index; + Index rows = m.rows(), cols = m.cols(); int i = internal::random(2,5), j = internal::random(2,5); @@ -115,7 +116,8 @@ struct mapstaticmethods_impl { static void run(const PlainObjectType& v) { - int size = v.size(); + typedef typename PlainObjectType::Index Index; + Index size = v.size(); int i = internal::random(2,5); diff --git a/testbed/nanogui/ext/eigen/test/mapstride.cpp b/testbed/nanogui/ext/eigen/test/mapstride.cpp index b1dc9de2..4858f8fe 100644 --- a/testbed/nanogui/ext/eigen/test/mapstride.cpp +++ b/testbed/nanogui/ext/eigen/test/mapstride.cpp @@ -23,7 +23,7 @@ template void map_class_vector(const VectorTy Scalar* a_array = internal::aligned_new(arraysize+1); Scalar* array = a_array; if(Alignment!=Aligned) - array = (Scalar*)(ptrdiff_t(a_array) + (internal::packet_traits::AlignedOnScalar?sizeof(Scalar):sizeof(typename NumTraits::Real))); + array = (Scalar*)(internal::IntPtr(a_array) + (internal::packet_traits::AlignedOnScalar?sizeof(Scalar):sizeof(typename NumTraits::Real))); { Map > map(array, size); @@ -56,16 +56,30 @@ template void map_class_matrix(const MatrixTy Index rows = _m.rows(), cols = _m.cols(); MatrixType m = MatrixType::Random(rows,cols); + Scalar s1 = internal::random(); Index arraysize = 2*(rows+4)*(cols+4); - Scalar* a_array = internal::aligned_new(arraysize+1); - Scalar* array = a_array; + Scalar* a_array1 = internal::aligned_new(arraysize+1); + Scalar* array1 = a_array1; if(Alignment!=Aligned) - array = (Scalar*)(ptrdiff_t(a_array) + (internal::packet_traits::AlignedOnScalar?sizeof(Scalar):sizeof(typename NumTraits::Real))); + array1 = (Scalar*)(internal::IntPtr(a_array1) + (internal::packet_traits::AlignedOnScalar?sizeof(Scalar):sizeof(typename NumTraits::Real))); + Scalar a_array2[256]; + Scalar* array2 = a_array2; + if(Alignment!=Aligned) + array2 = (Scalar*)(internal::IntPtr(a_array2) + (internal::packet_traits::AlignedOnScalar?sizeof(Scalar):sizeof(typename NumTraits::Real))); + else + array2 = (Scalar*)(((internal::UIntPtr(a_array2)+EIGEN_MAX_ALIGN_BYTES-1)/EIGEN_MAX_ALIGN_BYTES)*EIGEN_MAX_ALIGN_BYTES); + Index maxsize2 = a_array2 - array2 + 256; + // test no inner stride and some dynamic outer stride + for(int k=0; k<2; ++k) { + if(k==1 && (m.innerSize()+1)*m.outerSize() > maxsize2) + break; + Scalar* array = (k==0 ? array1 : array2); + Map > map(array, rows, cols, OuterStride(m.innerSize()+1)); map = m; VERIFY(map.outerStride() == map.innerSize()+1); @@ -75,11 +89,19 @@ template void map_class_matrix(const MatrixTy VERIFY(array[map.outerStride()*i+j] == m.coeffByOuterInner(i,j)); VERIFY(map.coeffByOuterInner(i,j) == m.coeffByOuterInner(i,j)); } + VERIFY_IS_APPROX(s1*map,s1*m); + map *= s1; + VERIFY_IS_APPROX(map,s1*m); } // test no inner stride and an outer stride of +4. This is quite important as for fixed-size matrices, // this allows to hit the special case where it's vectorizable. + for(int k=0; k<2; ++k) { + if(k==1 && (m.innerSize()+4)*m.outerSize() > maxsize2) + break; + Scalar* array = (k==0 ? array1 : array2); + enum { InnerSize = MatrixType::InnerSizeAtCompileTime, OuterStrideAtCompileTime = InnerSize==Dynamic ? Dynamic : InnerSize+4 @@ -94,10 +116,18 @@ template void map_class_matrix(const MatrixTy VERIFY(array[map.outerStride()*i+j] == m.coeffByOuterInner(i,j)); VERIFY(map.coeffByOuterInner(i,j) == m.coeffByOuterInner(i,j)); } + VERIFY_IS_APPROX(s1*map,s1*m); + map *= s1; + VERIFY_IS_APPROX(map,s1*m); } // test both inner stride and outer stride + for(int k=0; k<2; ++k) { + if(k==1 && (2*m.innerSize()+1)*(m.outerSize()*2) > maxsize2) + break; + Scalar* array = (k==0 ? array1 : array2); + Map > map(array, rows, cols, Stride(2*m.innerSize()+1, 2)); map = m; VERIFY(map.outerStride() == 2*map.innerSize()+1); @@ -108,9 +138,12 @@ template void map_class_matrix(const MatrixTy VERIFY(array[map.outerStride()*i+map.innerStride()*j] == m.coeffByOuterInner(i,j)); VERIFY(map.coeffByOuterInner(i,j) == m.coeffByOuterInner(i,j)); } + VERIFY_IS_APPROX(s1*map,s1*m); + map *= s1; + VERIFY_IS_APPROX(map,s1*m); } - internal::aligned_delete(a_array, arraysize+1); + internal::aligned_delete(a_array1, arraysize+1); } void test_mapstride() diff --git a/testbed/nanogui/ext/eigen/test/meta.cpp b/testbed/nanogui/ext/eigen/test/meta.cpp index 3302c588..b8dea68e 100644 --- a/testbed/nanogui/ext/eigen/test/meta.cpp +++ b/testbed/nanogui/ext/eigen/test/meta.cpp @@ -9,6 +9,12 @@ #include "main.h" +template +bool check_is_convertible(const From&, const To&) +{ + return internal::is_convertible::value; +} + void test_meta() { VERIFY((internal::conditional<(3<4),internal::true_type, internal::false_type>::type::value)); @@ -52,6 +58,24 @@ void test_meta() VERIFY(( internal::is_same::type >::value)); VERIFY(( internal::is_same::type >::value)); + VERIFY(( internal::is_convertible::value )); + VERIFY(( internal::is_convertible::value )); + VERIFY(( internal::is_convertible::value )); + VERIFY((!internal::is_convertible,double>::value )); + VERIFY(( internal::is_convertible::value )); +// VERIFY((!internal::is_convertible::value )); //does not work because the conversion is prevented by a static assertion + VERIFY((!internal::is_convertible::value )); + VERIFY((!internal::is_convertible::value )); + { + float f; + MatrixXf A, B; + VectorXf a, b; + VERIFY(( check_is_convertible(a.dot(b), f) )); + VERIFY(( check_is_convertible(a.transpose()*b, f) )); + VERIFY((!check_is_convertible(A*B, f) )); + VERIFY(( check_is_convertible(A*B, A) )); + } + VERIFY(internal::meta_sqrt<1>::ret == 1); #define VERIFY_META_SQRT(X) VERIFY(internal::meta_sqrt::ret == int(std::sqrt(double(X)))) VERIFY_META_SQRT(2); diff --git a/testbed/nanogui/ext/eigen/test/metis_support.cpp b/testbed/nanogui/ext/eigen/test/metis_support.cpp index 932b0407..d87c56a1 100644 --- a/testbed/nanogui/ext/eigen/test/metis_support.cpp +++ b/testbed/nanogui/ext/eigen/test/metis_support.cpp @@ -3,24 +3,10 @@ // // Copyright (C) 2012 Désiré Nuentsa-Wakam // -// Eigen is free software; you can redistribute it and/or -// modify it under the terms of the GNU Lesser General Public -// License as published by the Free Software Foundation; either -// version 3 of the License, or (at your option) any later version. -// -// Alternatively, you can redistribute it and/or -// modify it under the terms of the GNU General Public License as -// published by the Free Software Foundation; either version 2 of -// the License, or (at your option) any later version. -// -// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY -// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS -// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the -// GNU General Public License for more details. -// -// You should have received a copy of the GNU Lesser General Public -// License and a copy of the GNU General Public License along with -// Eigen. If not, see . +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #include "sparse_solver.h" #include #include diff --git a/testbed/nanogui/ext/eigen/test/mixingtypes.cpp b/testbed/nanogui/ext/eigen/test/mixingtypes.cpp index 6c2f7487..b796082c 100644 --- a/testbed/nanogui/ext/eigen/test/mixingtypes.cpp +++ b/testbed/nanogui/ext/eigen/test/mixingtypes.cpp @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2008 Gael Guennebaud +// Copyright (C) 2008-2015 Gael Guennebaud // Copyright (C) 2008 Benoit Jacob // // This Source Code Form is subject to the terms of the Mozilla @@ -15,14 +15,26 @@ #define EIGEN_NO_STATIC_ASSERT // turn static asserts into runtime asserts in order to check them #endif -// #ifndef EIGEN_DONT_VECTORIZE -// #define EIGEN_DONT_VECTORIZE // SSE intrinsics aren't designed to allow mixing types -// #endif +#if defined(EIGEN_TEST_PART_1) || defined(EIGEN_TEST_PART_2) || defined(EIGEN_TEST_PART_3) + +#ifndef EIGEN_DONT_VECTORIZE +#define EIGEN_DONT_VECTORIZE +#endif + +#endif + +static bool g_called; +#define EIGEN_SCALAR_BINARY_OP_PLUGIN { g_called |= (!internal::is_same::value); } #include "main.h" using namespace std; +#define VERIFY_MIX_SCALAR(XPR,REF) \ + g_called = false; \ + VERIFY_IS_APPROX(XPR,REF); \ + VERIFY( g_called && #XPR" not properly optimized"); + template void mixingtypes(int size = SizeAtCompileType) { typedef std::complex CF; @@ -38,8 +50,10 @@ template void mixingtypes(int size = SizeAtCompileType) Mat_f mf = Mat_f::Random(size,size); Mat_d md = mf.template cast(); + //Mat_d rd = md; Mat_cf mcf = Mat_cf::Random(size,size); Mat_cd mcd = mcf.template cast >(); + Mat_cd rcd = mcd; Vec_f vf = Vec_f::Random(size,1); Vec_d vd = vf.template cast(); Vec_cf vcf = Vec_cf::Random(size,1); @@ -49,19 +63,59 @@ template void mixingtypes(int size = SizeAtCompileType) complex scf = internal::random >(); complex scd = internal::random >(); - mf+mf; - VERIFY_RAISES_ASSERT(mf+md); - VERIFY_RAISES_ASSERT(mf+mcf); + + float epsf = std::sqrt(std::numeric_limits ::min EIGEN_EMPTY ()); + double epsd = std::sqrt(std::numeric_limits::min EIGEN_EMPTY ()); + + while(std::abs(sf )(); + while(std::abs(sd )(); + while(std::abs(scf)(); + while(std::abs(scd)(); + +// VERIFY_RAISES_ASSERT(mf+md); // does not even compile + +#ifdef EIGEN_DONT_VECTORIZE VERIFY_RAISES_ASSERT(vf=vd); VERIFY_RAISES_ASSERT(vf+=vd); - VERIFY_RAISES_ASSERT(mcd=md); - +#endif + // check scalar products - VERIFY_IS_APPROX(vcf * sf , vcf * complex(sf)); - VERIFY_IS_APPROX(sd * vcd, complex(sd) * vcd); - VERIFY_IS_APPROX(vf * scf , vf.template cast >() * scf); - VERIFY_IS_APPROX(scd * vd, scd * vd.template cast >()); + VERIFY_MIX_SCALAR(vcf * sf , vcf * complex(sf)); + VERIFY_MIX_SCALAR(sd * vcd , complex(sd) * vcd); + VERIFY_MIX_SCALAR(vf * scf , vf.template cast >() * scf); + VERIFY_MIX_SCALAR(scd * vd , scd * vd.template cast >()); + + VERIFY_MIX_SCALAR(vcf * 2 , vcf * complex(2)); + VERIFY_MIX_SCALAR(vcf * 2.1 , vcf * complex(2.1)); + VERIFY_MIX_SCALAR(2 * vcf, vcf * complex(2)); + VERIFY_MIX_SCALAR(2.1 * vcf , vcf * complex(2.1)); + + // check scalar quotients + VERIFY_MIX_SCALAR(vcf / sf , vcf / complex(sf)); + VERIFY_MIX_SCALAR(vf / scf , vf.template cast >() / scf); + VERIFY_MIX_SCALAR(vf.array() / scf, vf.template cast >().array() / scf); + VERIFY_MIX_SCALAR(scd / vd.array() , scd / vd.template cast >().array()); + + // check scalar increment + VERIFY_MIX_SCALAR(vcf.array() + sf , vcf.array() + complex(sf)); + VERIFY_MIX_SCALAR(sd + vcd.array(), complex(sd) + vcd.array()); + VERIFY_MIX_SCALAR(vf.array() + scf, vf.template cast >().array() + scf); + VERIFY_MIX_SCALAR(scd + vd.array() , scd + vd.template cast >().array()); + + // check scalar subtractions + VERIFY_MIX_SCALAR(vcf.array() - sf , vcf.array() - complex(sf)); + VERIFY_MIX_SCALAR(sd - vcd.array(), complex(sd) - vcd.array()); + VERIFY_MIX_SCALAR(vf.array() - scf, vf.template cast >().array() - scf); + VERIFY_MIX_SCALAR(scd - vd.array() , scd - vd.template cast >().array()); + + // check scalar powers + VERIFY_MIX_SCALAR( pow(vcf.array(), sf), Eigen::pow(vcf.array(), complex(sf)) ); + VERIFY_MIX_SCALAR( vcf.array().pow(sf) , Eigen::pow(vcf.array(), complex(sf)) ); + VERIFY_MIX_SCALAR( pow(sd, vcd.array()), Eigen::pow(complex(sd), vcd.array()) ); + VERIFY_MIX_SCALAR( Eigen::pow(vf.array(), scf), Eigen::pow(vf.template cast >().array(), scf) ); + VERIFY_MIX_SCALAR( vf.array().pow(scf) , Eigen::pow(vf.template cast >().array(), scf) ); + VERIFY_MIX_SCALAR( Eigen::pow(scd, vd.array()), Eigen::pow(scd, vd.template cast >().array()) ); // check dot product vf.dot(vf); @@ -75,6 +129,7 @@ template void mixingtypes(int size = SizeAtCompileType) VERIFY_IS_APPROX(vcd.asDiagonal() * md, vcd.asDiagonal() * md.template cast >()); VERIFY_IS_APPROX(mcf * vf.asDiagonal(), mcf * vf.template cast >().asDiagonal()); VERIFY_IS_APPROX(md * vcd.asDiagonal(), md.template cast >() * vcd.asDiagonal()); + // vd.asDiagonal() * mf; // does not even compile // vcd.asDiagonal() * mf; // does not even compile @@ -92,7 +147,6 @@ template void mixingtypes(int size = SizeAtCompileType) VERIFY_IS_APPROX(mcd.array() *= md.array(), mcd2.array() *= md.array().template cast >()); // check matrix-matrix products - VERIFY_IS_APPROX(sd*md*mcd, (sd*md).template cast().eval()*mcd); VERIFY_IS_APPROX(sd*mcd*md, sd*mcd*md.template cast()); VERIFY_IS_APPROX(scd*md*mcd, scd*md.template cast().eval()*mcd); @@ -103,6 +157,20 @@ template void mixingtypes(int size = SizeAtCompileType) VERIFY_IS_APPROX(scf*mf*mcf, scf*mf.template cast()*mcf); VERIFY_IS_APPROX(scf*mcf*mf, scf*mcf*mf.template cast()); + VERIFY_IS_APPROX(sd*md.adjoint()*mcd, (sd*md).template cast().eval().adjoint()*mcd); + VERIFY_IS_APPROX(sd*mcd.adjoint()*md, sd*mcd.adjoint()*md.template cast()); + VERIFY_IS_APPROX(sd*md.adjoint()*mcd.adjoint(), (sd*md).template cast().eval().adjoint()*mcd.adjoint()); + VERIFY_IS_APPROX(sd*mcd.adjoint()*md.adjoint(), sd*mcd.adjoint()*md.template cast().adjoint()); + VERIFY_IS_APPROX(sd*md*mcd.adjoint(), (sd*md).template cast().eval()*mcd.adjoint()); + VERIFY_IS_APPROX(sd*mcd*md.adjoint(), sd*mcd*md.template cast().adjoint()); + + VERIFY_IS_APPROX(sf*mf.adjoint()*mcf, (sf*mf).template cast().eval().adjoint()*mcf); + VERIFY_IS_APPROX(sf*mcf.adjoint()*mf, sf*mcf.adjoint()*mf.template cast()); + VERIFY_IS_APPROX(sf*mf.adjoint()*mcf.adjoint(), (sf*mf).template cast().eval().adjoint()*mcf.adjoint()); + VERIFY_IS_APPROX(sf*mcf.adjoint()*mf.adjoint(), sf*mcf.adjoint()*mf.template cast().adjoint()); + VERIFY_IS_APPROX(sf*mf*mcf.adjoint(), (sf*mf).template cast().eval()*mcf.adjoint()); + VERIFY_IS_APPROX(sf*mcf*mf.adjoint(), sf*mcf*mf.template cast().adjoint()); + VERIFY_IS_APPROX(sf*mf*vcf, (sf*mf).template cast().eval()*vcf); VERIFY_IS_APPROX(scf*mf*vcf,(scf*mf.template cast()).eval()*vcf); VERIFY_IS_APPROX(sf*mcf*vf, sf*mcf*vf.template cast()); @@ -122,11 +190,111 @@ template void mixingtypes(int size = SizeAtCompileType) VERIFY_IS_APPROX(scd*vcd.adjoint()*md, scd*vcd.adjoint()*md.template cast().eval()); VERIFY_IS_APPROX(sd*vd.adjoint()*mcd, sd*vd.adjoint().template cast().eval()*mcd); VERIFY_IS_APPROX(scd*vd.adjoint()*mcd, scd*vd.adjoint().template cast().eval()*mcd); + + VERIFY_IS_APPROX( sd*vcd.adjoint()*md.template triangularView(), sd*vcd.adjoint()*md.template cast().eval().template triangularView()); + VERIFY_IS_APPROX(scd*vcd.adjoint()*md.template triangularView(), scd*vcd.adjoint()*md.template cast().eval().template triangularView()); + VERIFY_IS_APPROX( sd*vcd.adjoint()*md.transpose().template triangularView(), sd*vcd.adjoint()*md.transpose().template cast().eval().template triangularView()); + VERIFY_IS_APPROX(scd*vcd.adjoint()*md.transpose().template triangularView(), scd*vcd.adjoint()*md.transpose().template cast().eval().template triangularView()); + VERIFY_IS_APPROX( sd*vd.adjoint()*mcd.template triangularView(), sd*vd.adjoint().template cast().eval()*mcd.template triangularView()); + VERIFY_IS_APPROX(scd*vd.adjoint()*mcd.template triangularView(), scd*vd.adjoint().template cast().eval()*mcd.template triangularView()); + VERIFY_IS_APPROX( sd*vd.adjoint()*mcd.transpose().template triangularView(), sd*vd.adjoint().template cast().eval()*mcd.transpose().template triangularView()); + VERIFY_IS_APPROX(scd*vd.adjoint()*mcd.transpose().template triangularView(), scd*vd.adjoint().template cast().eval()*mcd.transpose().template triangularView()); + + // Not supported yet: trmm +// VERIFY_IS_APPROX(sd*mcd*md.template triangularView(), sd*mcd*md.template cast().eval().template triangularView()); +// VERIFY_IS_APPROX(scd*mcd*md.template triangularView(), scd*mcd*md.template cast().eval().template triangularView()); +// VERIFY_IS_APPROX(sd*md*mcd.template triangularView(), sd*md.template cast().eval()*mcd.template triangularView()); +// VERIFY_IS_APPROX(scd*md*mcd.template triangularView(), scd*md.template cast().eval()*mcd.template triangularView()); + + // Not supported yet: symv +// VERIFY_IS_APPROX(sd*vcd.adjoint()*md.template selfadjointView(), sd*vcd.adjoint()*md.template cast().eval().template selfadjointView()); +// VERIFY_IS_APPROX(scd*vcd.adjoint()*md.template selfadjointView(), scd*vcd.adjoint()*md.template cast().eval().template selfadjointView()); +// VERIFY_IS_APPROX(sd*vd.adjoint()*mcd.template selfadjointView(), sd*vd.adjoint().template cast().eval()*mcd.template selfadjointView()); +// VERIFY_IS_APPROX(scd*vd.adjoint()*mcd.template selfadjointView(), scd*vd.adjoint().template cast().eval()*mcd.template selfadjointView()); + + // Not supported yet: symm +// VERIFY_IS_APPROX(sd*vcd.adjoint()*md.template selfadjointView(), sd*vcd.adjoint()*md.template cast().eval().template selfadjointView()); +// VERIFY_IS_APPROX(scd*vcd.adjoint()*md.template selfadjointView(), scd*vcd.adjoint()*md.template cast().eval().template selfadjointView()); +// VERIFY_IS_APPROX(sd*vd.adjoint()*mcd.template selfadjointView(), sd*vd.adjoint().template cast().eval()*mcd.template selfadjointView()); +// VERIFY_IS_APPROX(scd*vd.adjoint()*mcd.template selfadjointView(), scd*vd.adjoint().template cast().eval()*mcd.template selfadjointView()); + + rcd.setZero(); + VERIFY_IS_APPROX(Mat_cd(rcd.template triangularView() = sd * mcd * md), + Mat_cd((sd * mcd * md.template cast().eval()).template triangularView())); + VERIFY_IS_APPROX(Mat_cd(rcd.template triangularView() = sd * md * mcd), + Mat_cd((sd * md.template cast().eval() * mcd).template triangularView())); + VERIFY_IS_APPROX(Mat_cd(rcd.template triangularView() = scd * mcd * md), + Mat_cd((scd * mcd * md.template cast().eval()).template triangularView())); + VERIFY_IS_APPROX(Mat_cd(rcd.template triangularView() = scd * md * mcd), + Mat_cd((scd * md.template cast().eval() * mcd).template triangularView())); + + + VERIFY_IS_APPROX( md.array() * mcd.array(), md.template cast().eval().array() * mcd.array() ); + VERIFY_IS_APPROX( mcd.array() * md.array(), mcd.array() * md.template cast().eval().array() ); + + VERIFY_IS_APPROX( md.array() + mcd.array(), md.template cast().eval().array() + mcd.array() ); + VERIFY_IS_APPROX( mcd.array() + md.array(), mcd.array() + md.template cast().eval().array() ); + + VERIFY_IS_APPROX( md.array() - mcd.array(), md.template cast().eval().array() - mcd.array() ); + VERIFY_IS_APPROX( mcd.array() - md.array(), mcd.array() - md.template cast().eval().array() ); + + if(mcd.array().abs().minCoeff()>epsd) + { + VERIFY_IS_APPROX( md.array() / mcd.array(), md.template cast().eval().array() / mcd.array() ); + } + if(md.array().abs().minCoeff()>epsd) + { + VERIFY_IS_APPROX( mcd.array() / md.array(), mcd.array() / md.template cast().eval().array() ); + } + + if(md.array().abs().minCoeff()>epsd || mcd.array().abs().minCoeff()>epsd) + { + VERIFY_IS_APPROX( md.array().pow(mcd.array()), md.template cast().eval().array().pow(mcd.array()) ); + VERIFY_IS_APPROX( mcd.array().pow(md.array()), mcd.array().pow(md.template cast().eval().array()) ); + + VERIFY_IS_APPROX( pow(md.array(),mcd.array()), md.template cast().eval().array().pow(mcd.array()) ); + VERIFY_IS_APPROX( pow(mcd.array(),md.array()), mcd.array().pow(md.template cast().eval().array()) ); + } + + rcd = mcd; + VERIFY_IS_APPROX( rcd = md, md.template cast().eval() ); + rcd = mcd; + VERIFY_IS_APPROX( rcd += md, mcd + md.template cast().eval() ); + rcd = mcd; + VERIFY_IS_APPROX( rcd -= md, mcd - md.template cast().eval() ); + rcd = mcd; + VERIFY_IS_APPROX( rcd.array() *= md.array(), mcd.array() * md.template cast().eval().array() ); + rcd = mcd; + if(md.array().abs().minCoeff()>epsd) + { + VERIFY_IS_APPROX( rcd.array() /= md.array(), mcd.array() / md.template cast().eval().array() ); + } + + rcd = mcd; + VERIFY_IS_APPROX( rcd.noalias() += md + mcd*md, mcd + (md.template cast().eval()) + mcd*(md.template cast().eval())); + + VERIFY_IS_APPROX( rcd.noalias() = md*md, ((md*md).eval().template cast()) ); + rcd = mcd; + VERIFY_IS_APPROX( rcd.noalias() += md*md, mcd + ((md*md).eval().template cast()) ); + rcd = mcd; + VERIFY_IS_APPROX( rcd.noalias() -= md*md, mcd - ((md*md).eval().template cast()) ); + + VERIFY_IS_APPROX( rcd.noalias() = mcd + md*md, mcd + ((md*md).eval().template cast()) ); + rcd = mcd; + VERIFY_IS_APPROX( rcd.noalias() += mcd + md*md, mcd + mcd + ((md*md).eval().template cast()) ); + rcd = mcd; + VERIFY_IS_APPROX( rcd.noalias() -= mcd + md*md, - ((md*md).eval().template cast()) ); } void test_mixingtypes() { - CALL_SUBTEST_1(mixingtypes<3>()); - CALL_SUBTEST_2(mixingtypes<4>()); - CALL_SUBTEST_3(mixingtypes(internal::random(1,EIGEN_TEST_MAX_SIZE))); + for(int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_1(mixingtypes<3>()); + CALL_SUBTEST_2(mixingtypes<4>()); + CALL_SUBTEST_3(mixingtypes(internal::random(1,EIGEN_TEST_MAX_SIZE))); + + CALL_SUBTEST_4(mixingtypes<3>()); + CALL_SUBTEST_5(mixingtypes<4>()); + CALL_SUBTEST_6(mixingtypes(internal::random(1,EIGEN_TEST_MAX_SIZE))); + } } diff --git a/testbed/nanogui/ext/eigen/test/mpl2only.cpp b/testbed/nanogui/ext/eigen/test/mpl2only.cpp new file mode 100644 index 00000000..7d04d6bb --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/mpl2only.cpp @@ -0,0 +1,22 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#define EIGEN_MPL2_ONLY +#include +#include +#include +#include +#include +#include +#include + +int main() +{ + return 0; +} diff --git a/testbed/nanogui/ext/eigen/test/nesting_ops.cpp b/testbed/nanogui/ext/eigen/test/nesting_ops.cpp index 1e852328..a419b0e4 100644 --- a/testbed/nanogui/ext/eigen/test/nesting_ops.cpp +++ b/testbed/nanogui/ext/eigen/test/nesting_ops.cpp @@ -2,16 +2,37 @@ // for linear algebra. // // Copyright (C) 2010 Hauke Heibel +// Copyright (C) 2015 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +#define TEST_ENABLE_TEMPORARY_TRACKING + #include "main.h" -template void run_nesting_ops(const MatrixType& _m) +template +void use_n_times(const XprType &xpr) { - typename MatrixType::Nested m(_m); + typename internal::nested_eval::type mat(xpr); + typename XprType::PlainObject res(mat.rows(), mat.cols()); + nb_temporaries--; // remove res + res.setZero(); + for(int i=0; i +bool verify_eval_type(const XprType &, const ReferenceType&) +{ + typedef typename internal::nested_eval::type EvalType; + return internal::is_same::type, typename internal::remove_all::type>::value; +} + +template void run_nesting_ops_1(const MatrixType& _m) +{ + typename internal::nested_eval::type m(_m); // Make really sure that we are in debug mode! VERIFY_RAISES_ASSERT(eigen_assert(false)); @@ -24,10 +45,63 @@ template void run_nesting_ops(const MatrixType& _m) VERIFY_IS_APPROX( (m.transpose() * m).array().abs().sum(), (m.transpose() * m).array().abs().sum() ); } +template void run_nesting_ops_2(const MatrixType& _m) +{ + typedef typename MatrixType::Scalar Scalar; + Index rows = _m.rows(); + Index cols = _m.cols(); + MatrixType m1 = MatrixType::Random(rows,cols); + Matrix m2; + + if((MatrixType::SizeAtCompileTime==Dynamic)) + { + VERIFY_EVALUATION_COUNT( use_n_times<1>(m1 + m1*m1), 1 ); + VERIFY_EVALUATION_COUNT( use_n_times<10>(m1 + m1*m1), 1 ); + + VERIFY_EVALUATION_COUNT( use_n_times<1>(m1.template triangularView().solve(m1.col(0))), 1 ); + VERIFY_EVALUATION_COUNT( use_n_times<10>(m1.template triangularView().solve(m1.col(0))), 1 ); + + VERIFY_EVALUATION_COUNT( use_n_times<1>(Scalar(2)*m1.template triangularView().solve(m1.col(0))), 2 ); // FIXME could be one by applying the scaling in-place on the solve result + VERIFY_EVALUATION_COUNT( use_n_times<1>(m1.col(0)+m1.template triangularView().solve(m1.col(0))), 2 ); // FIXME could be one by adding m1.col() inplace + VERIFY_EVALUATION_COUNT( use_n_times<10>(m1.col(0)+m1.template triangularView().solve(m1.col(0))), 2 ); + } + + { + VERIFY( verify_eval_type<10>(m1, m1) ); + if(!NumTraits::IsComplex) + { + VERIFY( verify_eval_type<3>(2*m1, 2*m1) ); + VERIFY( verify_eval_type<4>(2*m1, m1) ); + } + else + { + VERIFY( verify_eval_type<2>(2*m1, 2*m1) ); + VERIFY( verify_eval_type<3>(2*m1, m1) ); + } + VERIFY( verify_eval_type<2>(m1+m1, m1+m1) ); + VERIFY( verify_eval_type<3>(m1+m1, m1) ); + VERIFY( verify_eval_type<1>(m1*m1.transpose(), m2) ); + VERIFY( verify_eval_type<1>(m1*(m1+m1).transpose(), m2) ); + VERIFY( verify_eval_type<2>(m1*m1.transpose(), m2) ); + VERIFY( verify_eval_type<1>(m1+m1*m1, m1) ); + + VERIFY( verify_eval_type<1>(m1.template triangularView().solve(m1), m1) ); + VERIFY( verify_eval_type<1>(m1+m1.template triangularView().solve(m1), m1) ); + } +} + + void test_nesting_ops() { - CALL_SUBTEST_1(run_nesting_ops(MatrixXf::Random(25,25))); - CALL_SUBTEST_2(run_nesting_ops(MatrixXd::Random(25,25))); - CALL_SUBTEST_3(run_nesting_ops(Matrix4f::Random())); - CALL_SUBTEST_4(run_nesting_ops(Matrix4d::Random())); + CALL_SUBTEST_1(run_nesting_ops_1(MatrixXf::Random(25,25))); + CALL_SUBTEST_2(run_nesting_ops_1(MatrixXcd::Random(25,25))); + CALL_SUBTEST_3(run_nesting_ops_1(Matrix4f::Random())); + CALL_SUBTEST_4(run_nesting_ops_1(Matrix2d::Random())); + + Index s = internal::random(1,EIGEN_TEST_MAX_SIZE); + CALL_SUBTEST_1( run_nesting_ops_2(MatrixXf(s,s)) ); + CALL_SUBTEST_2( run_nesting_ops_2(MatrixXcd(s,s)) ); + CALL_SUBTEST_3( run_nesting_ops_2(Matrix4f()) ); + CALL_SUBTEST_4( run_nesting_ops_2(Matrix2d()) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) } diff --git a/testbed/nanogui/ext/eigen/test/nomalloc.cpp b/testbed/nanogui/ext/eigen/test/nomalloc.cpp index 8e040235..50756c2f 100644 --- a/testbed/nanogui/ext/eigen/test/nomalloc.cpp +++ b/testbed/nanogui/ext/eigen/test/nomalloc.cpp @@ -8,20 +8,10 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. -// this hack is needed to make this file compiles with -pedantic (gcc) -#ifdef __GNUC__ -#define throw(X) -#endif - -#ifdef __INTEL_COMPILER - // disable "warning #76: argument to macro is empty" produced by the above hack - #pragma warning disable 76 -#endif - // discard stack allocation as that too bypasses malloc #define EIGEN_STACK_ALLOCATION_LIMIT 0 -// any heap allocation will raise an assert -#define EIGEN_NO_MALLOC +// heap allocation will raise an assert if enabled at runtime +#define EIGEN_RUNTIME_NO_MALLOC #include "main.h" #include @@ -88,14 +78,15 @@ template void nomalloc(const MatrixType& m) VERIFY_IS_APPROX(m2,m2); m2.template selfadjointView().rankUpdate(m1.col(0),-1); - m2.template selfadjointView().rankUpdate(m1.row(0),-1); + m2.template selfadjointView().rankUpdate(m1.row(0),-1); + m2.template selfadjointView().rankUpdate(m1.col(0), m1.col(0)); // rank-2 // The following fancy matrix-matrix products are not safe yet regarding static allocation -// m1 += m1.template triangularView() * m2.col(; -// m1.template selfadjointView().rankUpdate(m2); -// m1 += m1.template triangularView() * m2; -// m1 += m1.template selfadjointView() * m2; -// VERIFY_IS_APPROX(m1,m1); + m2.template selfadjointView().rankUpdate(m1); + m2 += m2.template triangularView() * m1; + m2.template triangularView() = m2 * m2; + m1 += m1.template selfadjointView() * m2; + VERIFY_IS_APPROX(m2,m2); } template @@ -171,7 +162,7 @@ void test_zerosized() { Eigen::VectorXd v; // explicit zero-sized: Eigen::ArrayXXd A0(0,0); - Eigen::ArrayXd v0(std::ptrdiff_t(0)); // FIXME ArrayXd(0) is ambiguous + Eigen::ArrayXd v0(0); // assigning empty objects to each other: A=A0; @@ -183,9 +174,11 @@ template void test_reference(const MatrixType& m) { enum { Flag = MatrixType::IsRowMajor ? Eigen::RowMajor : Eigen::ColMajor}; enum { TransposeFlag = !MatrixType::IsRowMajor ? Eigen::RowMajor : Eigen::ColMajor}; typename MatrixType::Index rows = m.rows(), cols=m.cols(); + typedef Eigen::Matrix MatrixX; + typedef Eigen::Matrix MatrixXT; // Dynamic reference: - typedef Eigen::Ref > Ref; - typedef Eigen::Ref > RefT; + typedef Eigen::Ref Ref; + typedef Eigen::Ref RefT; Ref r1(m); Ref r2(m.block(rows/3, cols/4, rows/2, cols/2)); @@ -195,10 +188,30 @@ template void test_reference(const MatrixType& m) { VERIFY_RAISES_ASSERT(RefT r5(m)); VERIFY_RAISES_ASSERT(Ref r6(m.transpose())); VERIFY_RAISES_ASSERT(Ref r7(Scalar(2) * m)); + + // Copy constructors shall also never malloc + Ref r8 = r1; + RefT r9 = r3; + + // Initializing from a compatible Ref shall also never malloc + Eigen::Ref > r10=r8, r11=m; + + // Initializing from an incompatible Ref will malloc: + typedef Eigen::Ref RefAligned; + VERIFY_RAISES_ASSERT(RefAligned r12=r10); + VERIFY_RAISES_ASSERT(Ref r13=r10); // r10 has more dynamic strides + } void test_nomalloc() { + // create some dynamic objects + Eigen::MatrixXd M1 = MatrixXd::Random(3,3); + Ref R1 = 2.0*M1; // Ref requires temporary + + // from here on prohibit malloc: + Eigen::internal::set_is_malloc_allowed(false); + // check that our operator new is indeed called: VERIFY_RAISES_ASSERT(MatrixXd dummy(MatrixXd::Random(3,3))); CALL_SUBTEST_1(nomalloc(Matrix()) ); @@ -207,6 +220,10 @@ void test_nomalloc() // Check decomposition modules with dynamic matrices that have a known compile-time max size (ctms) CALL_SUBTEST_4(ctms_decompositions()); + CALL_SUBTEST_5(test_zerosized()); + CALL_SUBTEST_6(test_reference(Matrix())); + CALL_SUBTEST_7(test_reference(R1)); + CALL_SUBTEST_8(Ref R2 = M1.topRows<2>(); test_reference(R2)); } diff --git a/testbed/nanogui/ext/eigen/test/nullary.cpp b/testbed/nanogui/ext/eigen/test/nullary.cpp index fbc721a1..acd55506 100644 --- a/testbed/nanogui/ext/eigen/test/nullary.cpp +++ b/testbed/nanogui/ext/eigen/test/nullary.cpp @@ -2,6 +2,7 @@ // for linear algebra. // // Copyright (C) 2010-2011 Jitse Niesen +// Copyright (C) 2016 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -12,7 +13,6 @@ template bool equalsIdentity(const MatrixType& A) { - typedef typename MatrixType::Index Index; typedef typename MatrixType::Scalar Scalar; Scalar zero = static_cast(0); @@ -30,13 +30,41 @@ bool equalsIdentity(const MatrixType& A) bool diagOK = (A.diagonal().array() == 1).all(); return offDiagOK && diagOK; + +} + +template +void check_extremity_accuracy(const VectorType &v, const typename VectorType::Scalar &low, const typename VectorType::Scalar &high) +{ + typedef typename VectorType::Scalar Scalar; + typedef typename VectorType::RealScalar RealScalar; + + RealScalar prec = internal::is_same::value ? NumTraits::dummy_precision()*10 : NumTraits::dummy_precision()/10; + Index size = v.size(); + + if(size<20) + return; + + for (int i=0; isize-6) + { + Scalar ref = (low*RealScalar(size-i-1))/RealScalar(size-1) + (high*RealScalar(i))/RealScalar(size-1); + if(std::abs(ref)>1) + { + if(!internal::isApprox(v(i), ref, prec)) + std::cout << v(i) << " != " << ref << " ; relative error: " << std::abs((v(i)-ref)/ref) << " ; required precision: " << prec << " ; range: " << low << "," << high << " ; i: " << i << "\n"; + VERIFY(internal::isApprox(v(i), (low*RealScalar(size-i-1))/RealScalar(size-1) + (high*RealScalar(i))/RealScalar(size-1), prec)); + } + } + } } template void testVectorType(const VectorType& base) { - typedef typename internal::traits::Index Index; - typedef typename internal::traits::Scalar Scalar; + typedef typename VectorType::Scalar Scalar; + typedef typename VectorType::RealScalar RealScalar; const Index size = base.size(); @@ -44,36 +72,61 @@ void testVectorType(const VectorType& base) Scalar low = (size == 1 ? high : internal::random(-500,500)); if (low>high) std::swap(low,high); + // check low==high + if(internal::random(0.f,1.f)<0.05f) + low = high; + // check abs(low) >> abs(high) + else if(size>2 && std::numeric_limits::max_exponent10>0 && internal::random(0.f,1.f)<0.1f) + low = -internal::random(1,2) * RealScalar(std::pow(RealScalar(10),std::numeric_limits::max_exponent10/2)); + const Scalar step = ((size == 1) ? 1 : (high-low)/(size-1)); // check whether the result yields what we expect it to do VectorType m(base); m.setLinSpaced(size,low,high); - VectorType n(size); - for (int i=0; i::IsInteger) + { + VectorType n(size); + for (int i=0; i::IsInteger) || ((high-low)>=size && (Index(high-low)%(size-1))==0) || (Index(high-low+1)::IsInteger) || (high-low>=size)) + for (int i=0; i::epsilon() ); + // random access version + m = VectorType::LinSpaced(size,low,high); + VERIFY_IS_APPROX(m,n); + VERIFY( internal::isApprox(m(m.size()-1),high) ); + VERIFY( size==1 || internal::isApprox(m(0),low) ); + VERIFY_IS_EQUAL(m(m.size()-1) , high); + if(!NumTraits::IsInteger) + CALL_SUBTEST( check_extremity_accuracy(m, low, high) ); + } - // These guys sometimes fail! This is not good. Any ideas how to fix them!? - //VERIFY( m(m.size()-1) == high ); - //VERIFY( m(0) == low ); + VERIFY( m(m.size()-1) <= high ); + VERIFY( (m.array() <= high).all() ); + VERIFY( (m.array() >= low).all() ); - // sequential access version - m = VectorType::LinSpaced(Sequential,size,low,high); - VERIFY_IS_APPROX(m,n); - // These guys sometimes fail! This is not good. Any ideas how to fix them!? - //VERIFY( m(m.size()-1) == high ); - //VERIFY( m(0) == low ); + VERIFY( m(m.size()-1) >= low ); + if(size>=1) + { + VERIFY( internal::isApprox(m(0),low) ); + VERIFY_IS_EQUAL(m(0) , low); + } // check whether everything works with row and col major vectors Matrix row_vector(size); @@ -95,23 +148,77 @@ void testVectorType(const VectorType& base) VERIFY_IS_APPROX( ScalarMatrix::LinSpaced(1,low,high), ScalarMatrix::Constant(high) ); // regression test for bug 526 (linear vectorized transversal) - if (size > 1) { + if (size > 1 && (!NumTraits::IsInteger)) { m.tail(size-1).setLinSpaced(low, high); VERIFY_IS_APPROX(m(size-1), high); } + + // regression test for bug 1383 (LinSpaced with empty size/range) + { + Index n0 = VectorType::SizeAtCompileTime==Dynamic ? 0 : VectorType::SizeAtCompileTime; + low = internal::random(); + m = VectorType::LinSpaced(n0,low,low-1); + VERIFY(m.size()==n0); + + if(VectorType::SizeAtCompileTime==Dynamic) + { + VERIFY_IS_EQUAL(VectorType::LinSpaced(n0,0,Scalar(n0-1)).sum(),Scalar(0)); + VERIFY_IS_EQUAL(VectorType::LinSpaced(n0,low,low-1).sum(),Scalar(0)); + } + + m.setLinSpaced(n0,0,Scalar(n0-1)); + VERIFY(m.size()==n0); + m.setLinSpaced(n0,low,low-1); + VERIFY(m.size()==n0); + + // empty range only: + VERIFY_IS_APPROX(VectorType::LinSpaced(size,low,low),VectorType::Constant(size,low)); + m.setLinSpaced(size,low,low); + VERIFY_IS_APPROX(m,VectorType::Constant(size,low)); + + if(NumTraits::IsInteger) + { + VERIFY_IS_APPROX( VectorType::LinSpaced(size,low,Scalar(low+size-1)), VectorType::LinSpaced(size,Scalar(low+size-1),low).reverse() ); + + if(VectorType::SizeAtCompileTime==Dynamic) + { + // Check negative multiplicator path: + for(Index k=1; k<5; ++k) + VERIFY_IS_APPROX( VectorType::LinSpaced(size,low,Scalar(low+(size-1)*k)), VectorType::LinSpaced(size,Scalar(low+(size-1)*k),low).reverse() ); + // Check negative divisor path: + for(Index k=1; k<5; ++k) + VERIFY_IS_APPROX( VectorType::LinSpaced(size*k,low,Scalar(low+size-1)), VectorType::LinSpaced(size*k,Scalar(low+size-1),low).reverse() ); + } + } + } } template void testMatrixType(const MatrixType& m) { - typedef typename MatrixType::Index Index; + using std::abs; const Index rows = m.rows(); const Index cols = m.cols(); + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + + Scalar s1; + do { + s1 = internal::random(); + } while(abs(s1)::IsInteger)); MatrixType A; A.setIdentity(rows, cols); VERIFY(equalsIdentity(A)); VERIFY(equalsIdentity(MatrixType::Identity(rows, cols))); + + + A = MatrixType::Constant(rows,cols,s1); + Index i = internal::random(0,rows-1); + Index j = internal::random(0,cols-1); + VERIFY_IS_APPROX( MatrixType::Constant(rows,cols,s1)(i,j), s1 ); + VERIFY_IS_APPROX( MatrixType::Constant(rows,cols,s1).coeff(i,j), s1 ); + VERIFY_IS_APPROX( A(i,j), s1 ); } void test_nullary() @@ -120,12 +227,78 @@ void test_nullary() CALL_SUBTEST_2( testMatrixType(MatrixXcf(internal::random(1,300),internal::random(1,300))) ); CALL_SUBTEST_3( testMatrixType(MatrixXf(internal::random(1,300),internal::random(1,300))) ); - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_4( testVectorType(VectorXd(internal::random(1,300))) ); + for(int i = 0; i < g_repeat*10; i++) { + CALL_SUBTEST_4( testVectorType(VectorXd(internal::random(1,30000))) ); CALL_SUBTEST_5( testVectorType(Vector4d()) ); // regression test for bug 232 CALL_SUBTEST_6( testVectorType(Vector3d()) ); - CALL_SUBTEST_7( testVectorType(VectorXf(internal::random(1,300))) ); + CALL_SUBTEST_7( testVectorType(VectorXf(internal::random(1,30000))) ); CALL_SUBTEST_8( testVectorType(Vector3f()) ); + CALL_SUBTEST_8( testVectorType(Vector4f()) ); + CALL_SUBTEST_8( testVectorType(Matrix()) ); CALL_SUBTEST_8( testVectorType(Matrix()) ); + + CALL_SUBTEST_9( testVectorType(VectorXi(internal::random(1,10))) ); + CALL_SUBTEST_9( testVectorType(VectorXi(internal::random(9,300))) ); + CALL_SUBTEST_9( testVectorType(Matrix()) ); } + +#ifdef EIGEN_TEST_PART_6 + // Assignment of a RowVectorXd to a MatrixXd (regression test for bug #79). + VERIFY( (MatrixXd(RowVectorXd::LinSpaced(3, 0, 1)) - RowVector3d(0, 0.5, 1)).norm() < std::numeric_limits::epsilon() ); +#endif + +#ifdef EIGEN_TEST_PART_9 + // Check possible overflow issue + { + int n = 60000; + ArrayXi a1(n), a2(n); + a1.setLinSpaced(n, 0, n-1); + for(int i=0; i >::value )); + VERIFY(( !internal::has_unary_operator >::value )); + VERIFY(( !internal::has_binary_operator >::value )); + VERIFY(( internal::functor_has_linear_access >::ret )); + + VERIFY(( !internal::has_nullary_operator >::value )); + VERIFY(( !internal::has_unary_operator >::value )); + VERIFY(( internal::has_binary_operator >::value )); + VERIFY(( !internal::functor_has_linear_access >::ret )); + + VERIFY(( !internal::has_nullary_operator >::value )); + VERIFY(( internal::has_unary_operator >::value )); + VERIFY(( !internal::has_binary_operator >::value )); + VERIFY(( internal::functor_has_linear_access >::ret )); + + // Regression unit test for a weird MSVC bug. + // Search "nullary_wrapper_workaround_msvc" in CoreEvaluators.h for the details. + // See also traits::match. + { + MatrixXf A = MatrixXf::Random(3,3); + Ref R = 2.0*A; + VERIFY_IS_APPROX(R, A+A); + + Ref R1 = MatrixXf::Random(3,3)+A; + + VectorXi V = VectorXi::Random(3); + Ref R2 = VectorXi::LinSpaced(3,1,3)+V; + VERIFY_IS_APPROX(R2, V+Vector3i(1,2,3)); + + VERIFY(( internal::has_nullary_operator >::value )); + VERIFY(( !internal::has_unary_operator >::value )); + VERIFY(( !internal::has_binary_operator >::value )); + VERIFY(( internal::functor_has_linear_access >::ret )); + + VERIFY(( !internal::has_nullary_operator >::value )); + VERIFY(( internal::has_unary_operator >::value )); + VERIFY(( !internal::has_binary_operator >::value )); + VERIFY(( internal::functor_has_linear_access >::ret )); + } +#endif } diff --git a/testbed/nanogui/ext/eigen/test/packetmath.cpp b/testbed/nanogui/ext/eigen/test/packetmath.cpp index 38aa256c..08b36034 100644 --- a/testbed/nanogui/ext/eigen/test/packetmath.cpp +++ b/testbed/nanogui/ext/eigen/test/packetmath.cpp @@ -9,16 +9,28 @@ // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. #include "main.h" +#include "unsupported/Eigen/SpecialFunctions" +#if defined __GNUC__ && __GNUC__>=6 + #pragma GCC diagnostic ignored "-Wignored-attributes" +#endif // using namespace Eigen; +#ifdef EIGEN_VECTORIZE_SSE +const bool g_vectorize_sse = true; +#else +const bool g_vectorize_sse = false; +#endif + namespace Eigen { namespace internal { template T negate(const T& x) { return -x; } } } -template bool isApproxAbs(const Scalar& a, const Scalar& b, const typename NumTraits::Real& refvalue) +// NOTE: we disbale inlining for this function to workaround a GCC issue when using -O3 and the i387 FPU. +template EIGEN_DONT_INLINE +bool isApproxAbs(const Scalar& a, const Scalar& b, const typename NumTraits::Real& refvalue) { return internal::isMuchSmallerThan(a-b, refvalue); } @@ -29,7 +41,7 @@ template bool areApproxAbs(const Scalar* a, const Scalar* b, in { if (!isApproxAbs(a[i],b[i],refvalue)) { - std::cout << "[" << Map >(a,size) << "]" << " != " << Map >(b,size) << "\n"; + std::cout << "ref: [" << Map >(a,size) << "]" << " != vec: [" << Map >(b,size) << "]\n"; return false; } } @@ -42,21 +54,13 @@ template bool areApprox(const Scalar* a, const Scalar* b, int s { if (a[i]!=b[i] && !internal::isApprox(a[i],b[i])) { - std::cout << "[" << Map >(a,size) << "]" << " != " << Map >(b,size) << "\n"; + std::cout << "ref: [" << Map >(a,size) << "]" << " != vec: [" << Map >(b,size) << "]\n"; return false; } } return true; } - -#define CHECK_CWISE2(REFOP, POP) { \ - for (int i=0; i(data1), internal::pload(data1+PacketSize))); \ - VERIFY(areApprox(ref, data2, PacketSize) && #POP); \ -} - #define CHECK_CWISE1(REFOP, POP) { \ for (int i=0; i VERIFY(areApprox(ref, data2, PacketSize) && #POP); \ } +#define CHECK_CWISE2_IF(COND, REFOP, POP) if(COND) { \ + packet_helper h; \ + for (int i=0; i template void packetmath() { using std::abs; - typedef typename internal::packet_traits::type Packet; - const int PacketSize = internal::packet_traits::size; + typedef internal::packet_traits PacketTraits; + typedef typename PacketTraits::type Packet; + const int PacketSize = PacketTraits::size; typedef typename NumTraits::Real RealScalar; - const int size = PacketSize*4; - EIGEN_ALIGN16 Scalar data1[internal::packet_traits::size*4]; - EIGEN_ALIGN16 Scalar data2[internal::packet_traits::size*4]; - EIGEN_ALIGN16 Packet packets[PacketSize*2]; - EIGEN_ALIGN16 Scalar ref[internal::packet_traits::size*4]; + const int max_size = PacketSize > 4 ? PacketSize : 4; + const int size = PacketSize*max_size; + EIGEN_ALIGN_MAX Scalar data1[size]; + EIGEN_ALIGN_MAX Scalar data2[size]; + EIGEN_ALIGN_MAX Packet packets[PacketSize*2]; + EIGEN_ALIGN_MAX Scalar ref[size]; RealScalar refvalue = 0; for (int i=0; i void packetmath() else if (offset==1) internal::palign<1>(packets[0], packets[1]); else if (offset==2) internal::palign<2>(packets[0], packets[1]); else if (offset==3) internal::palign<3>(packets[0], packets[1]); + else if (offset==4) internal::palign<4>(packets[0], packets[1]); + else if (offset==5) internal::palign<5>(packets[0], packets[1]); + else if (offset==6) internal::palign<6>(packets[0], packets[1]); + else if (offset==7) internal::palign<7>(packets[0], packets[1]); + else if (offset==8) internal::palign<8>(packets[0], packets[1]); + else if (offset==9) internal::palign<9>(packets[0], packets[1]); + else if (offset==10) internal::palign<10>(packets[0], packets[1]); + else if (offset==11) internal::palign<11>(packets[0], packets[1]); + else if (offset==12) internal::palign<12>(packets[0], packets[1]); + else if (offset==13) internal::palign<13>(packets[0], packets[1]); + else if (offset==14) internal::palign<14>(packets[0], packets[1]); + else if (offset==15) internal::palign<15>(packets[0], packets[1]); internal::pstore(data2, packets[0]); for (int i=0; i void packetmath() VERIFY(areApprox(ref, data2, PacketSize) && "internal::palign"); } - CHECK_CWISE2(REF_ADD, internal::padd); - CHECK_CWISE2(REF_SUB, internal::psub); - CHECK_CWISE2(REF_MUL, internal::pmul); - #ifndef EIGEN_VECTORIZE_ALTIVEC - if (!internal::is_same::value) - CHECK_CWISE2(REF_DIV, internal::pdiv); - #endif + VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasAdd); + VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasSub); + VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasMul); + VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasNegate); + VERIFY((internal::is_same::value) || (!PacketTraits::Vectorizable) || PacketTraits::HasDiv); + + CHECK_CWISE2_IF(PacketTraits::HasAdd, REF_ADD, internal::padd); + CHECK_CWISE2_IF(PacketTraits::HasSub, REF_SUB, internal::psub); + CHECK_CWISE2_IF(PacketTraits::HasMul, REF_MUL, internal::pmul); + CHECK_CWISE2_IF(PacketTraits::HasDiv, REF_DIV, internal::pdiv); + CHECK_CWISE1(internal::negate, internal::pnegate); CHECK_CWISE1(numext::conj, internal::pconj); @@ -165,9 +195,31 @@ template void packetmath() internal::pstore(data2, internal::pset1(data1[offset])); VERIFY(areApprox(ref, data2, PacketSize) && "internal::pset1"); } - + + { + for (int i=0; i(data1, A0, A1, A2, A3); + internal::pstore(data2+0*PacketSize, A0); + internal::pstore(data2+1*PacketSize, A1); + internal::pstore(data2+2*PacketSize, A2); + internal::pstore(data2+3*PacketSize, A3); + VERIFY(areApprox(ref, data2, 4*PacketSize) && "internal::pbroadcast4"); + } + + { + for (int i=0; i(data1, A0, A1); + internal::pstore(data2+0*PacketSize, A0); + internal::pstore(data2+1*PacketSize, A1); + VERIFY(areApprox(ref, data2, 2*PacketSize) && "internal::pbroadcast2"); + } + VERIFY(internal::isApprox(data1[0], internal::pfirst(internal::pload(data1))) && "internal::pfirst"); - + if(PacketSize>1) { for(int offset=0;offset<4;++offset) @@ -179,11 +231,31 @@ template void packetmath() } } + if(PacketSize>2) + { + for(int offset=0;offset<4;++offset) + { + for(int i=0;i(data1+offset)); + VERIFY(areApprox(ref, data2, PacketSize) && "ploadquad"); + } + } + ref[0] = 0; for (int i=0; i(data1)), refvalue) && "internal::predux"); + { + for (int i=0; i<4; ++i) + ref[i] = 0; + for (int i=0; i(data1))); + VERIFY(areApprox(ref, data2, PacketSize>4?PacketSize/2:PacketSize) && "internal::predux_downto4"); + } + ref[0] = 1; for (int i=0; i void packetmath() ref[i] = data1[PacketSize-i-1]; internal::pstore(data2, internal::preverse(internal::pload(data1))); VERIFY(areApprox(ref, data2, PacketSize) && "internal::preverse"); + + internal::PacketBlock kernel; + for (int i=0; i(data1+i*PacketSize); + } + ptranspose(kernel); + for (int i=0; i(data1); + Packet elsePacket = internal::pload(data2); + EIGEN_ALIGN_MAX internal::Selector selector; + for (int i = 0; i < PacketSize; ++i) { + selector.select[i] = i; + } + + Packet blend = internal::pblend(selector, thenPacket, elsePacket); + EIGEN_ALIGN_MAX Scalar result[size]; + internal::pstore(result, blend); + for (int i = 0; i < PacketSize; ++i) { + VERIFY(isApproxAbs(result[i], (selector.select[i] ? data1[i] : data2[i]), refvalue)); + } + } + + if (PacketTraits::HasBlend || g_vectorize_sse) { + // pinsertfirst + for (int i=0; i(); + ref[0] = s; + internal::pstore(data2, internal::pinsertfirst(internal::pload(data1),s)); + VERIFY(areApprox(ref, data2, PacketSize) && "internal::pinsertfirst"); + } + + if (PacketTraits::HasBlend || g_vectorize_sse) { + // pinsertlast + for (int i=0; i(); + ref[PacketSize-1] = s; + internal::pstore(data2, internal::pinsertlast(internal::pload(data1),s)); + VERIFY(areApprox(ref, data2, PacketSize) && "internal::pinsertlast"); + } } template void packetmath_real() { using std::abs; - typedef typename internal::packet_traits::type Packet; - const int PacketSize = internal::packet_traits::size; + typedef internal::packet_traits PacketTraits; + typedef typename PacketTraits::type Packet; + const int PacketSize = PacketTraits::size; const int size = PacketSize*4; - EIGEN_ALIGN16 Scalar data1[internal::packet_traits::size*4]; - EIGEN_ALIGN16 Scalar data2[internal::packet_traits::size*4]; - EIGEN_ALIGN16 Scalar ref[internal::packet_traits::size*4]; + EIGEN_ALIGN_MAX Scalar data1[PacketTraits::size*4]; + EIGEN_ALIGN_MAX Scalar data2[PacketTraits::size*4]; + EIGEN_ALIGN_MAX Scalar ref[PacketTraits::size*4]; for (int i=0; i(-1,1) * std::pow(Scalar(10), internal::random(-3,3)); data2[i] = internal::random(-1,1) * std::pow(Scalar(10), internal::random(-3,3)); } - CHECK_CWISE1_IF(internal::packet_traits::HasSin, std::sin, internal::psin); - CHECK_CWISE1_IF(internal::packet_traits::HasCos, std::cos, internal::pcos); - CHECK_CWISE1_IF(internal::packet_traits::HasTan, std::tan, internal::ptan); - + CHECK_CWISE1_IF(PacketTraits::HasSin, std::sin, internal::psin); + CHECK_CWISE1_IF(PacketTraits::HasCos, std::cos, internal::pcos); + CHECK_CWISE1_IF(PacketTraits::HasTan, std::tan, internal::ptan); + + CHECK_CWISE1_IF(PacketTraits::HasRound, numext::round, internal::pround); + CHECK_CWISE1_IF(PacketTraits::HasCeil, numext::ceil, internal::pceil); + CHECK_CWISE1_IF(PacketTraits::HasFloor, numext::floor, internal::pfloor); + for (int i=0; i(-1,1); data2[i] = internal::random(-1,1); } - CHECK_CWISE1_IF(internal::packet_traits::HasASin, std::asin, internal::pasin); - CHECK_CWISE1_IF(internal::packet_traits::HasACos, std::acos, internal::pacos); + CHECK_CWISE1_IF(PacketTraits::HasASin, std::asin, internal::pasin); + CHECK_CWISE1_IF(PacketTraits::HasACos, std::acos, internal::pacos); for (int i=0; i(-87,88); data2[i] = internal::random(-87,88); } - CHECK_CWISE1_IF(internal::packet_traits::HasExp, std::exp, internal::pexp); + CHECK_CWISE1_IF(PacketTraits::HasExp, std::exp, internal::pexp); + for (int i=0; i(-1,1) * std::pow(Scalar(10), internal::random(-6,6)); + data2[i] = internal::random(-1,1) * std::pow(Scalar(10), internal::random(-6,6)); + } + CHECK_CWISE1_IF(PacketTraits::HasTanh, std::tanh, internal::ptanh); + if(PacketTraits::HasExp && PacketTraits::size>=2) { data1[0] = std::numeric_limits::quiet_NaN(); - packet_helper::HasExp,Packet> h; - h.store(data2, internal::pexp(h.load(data1))); - VERIFY(isNaN(data2[0])); + data1[1] = std::numeric_limits::epsilon(); + packet_helper h; + h.store(data2, internal::pexp(h.load(data1))); + VERIFY((numext::isnan)(data2[0])); + VERIFY_IS_EQUAL(std::exp(std::numeric_limits::epsilon()), data2[1]); + + data1[0] = -std::numeric_limits::epsilon(); + data1[1] = 0; + h.store(data2, internal::pexp(h.load(data1))); + VERIFY_IS_EQUAL(std::exp(-std::numeric_limits::epsilon()), data2[0]); + VERIFY_IS_EQUAL(std::exp(Scalar(0)), data2[1]); + + data1[0] = (std::numeric_limits::min)(); + data1[1] = -(std::numeric_limits::min)(); + h.store(data2, internal::pexp(h.load(data1))); + VERIFY_IS_EQUAL(std::exp((std::numeric_limits::min)()), data2[0]); + VERIFY_IS_EQUAL(std::exp(-(std::numeric_limits::min)()), data2[1]); + + data1[0] = std::numeric_limits::denorm_min(); + data1[1] = -std::numeric_limits::denorm_min(); + h.store(data2, internal::pexp(h.load(data1))); + VERIFY_IS_EQUAL(std::exp(std::numeric_limits::denorm_min()), data2[0]); + VERIFY_IS_EQUAL(std::exp(-std::numeric_limits::denorm_min()), data2[1]); } + if (PacketTraits::HasTanh) { + // NOTE this test migh fail with GCC prior to 6.3, see MathFunctionsImpl.h for details. + data1[0] = std::numeric_limits::quiet_NaN(); + packet_helper::HasTanh,Packet> h; + h.store(data2, internal::ptanh(h.load(data1))); + VERIFY((numext::isnan)(data2[0])); + } + +#if EIGEN_HAS_C99_MATH + { + data1[0] = std::numeric_limits::quiet_NaN(); + packet_helper::HasLGamma,Packet> h; + h.store(data2, internal::plgamma(h.load(data1))); + VERIFY((numext::isnan)(data2[0])); + } + { + data1[0] = std::numeric_limits::quiet_NaN(); + packet_helper::HasErf,Packet> h; + h.store(data2, internal::perf(h.load(data1))); + VERIFY((numext::isnan)(data2[0])); + } + { + data1[0] = std::numeric_limits::quiet_NaN(); + packet_helper::HasErfc,Packet> h; + h.store(data2, internal::perfc(h.load(data1))); + VERIFY((numext::isnan)(data2[0])); + } +#endif // EIGEN_HAS_C99_MATH + for (int i=0; i(0,1) * std::pow(Scalar(10), internal::random(-6,6)); data2[i] = internal::random(0,1) * std::pow(Scalar(10), internal::random(-6,6)); } - if(internal::random(0,1)<0.1) + + if(internal::random(0,1)<0.1f) data1[internal::random(0, PacketSize)] = 0; - CHECK_CWISE1_IF(internal::packet_traits::HasSqrt, std::sqrt, internal::psqrt); - CHECK_CWISE1_IF(internal::packet_traits::HasLog, std::log, internal::plog); + CHECK_CWISE1_IF(PacketTraits::HasSqrt, std::sqrt, internal::psqrt); + CHECK_CWISE1_IF(PacketTraits::HasLog, std::log, internal::plog); +#if EIGEN_HAS_C99_MATH && (__cplusplus > 199711L) + CHECK_CWISE1_IF(PacketTraits::HasExpm1, std::expm1, internal::pexpm1); + CHECK_CWISE1_IF(PacketTraits::HasLog1p, std::log1p, internal::plog1p); + CHECK_CWISE1_IF(internal::packet_traits::HasLGamma, std::lgamma, internal::plgamma); + CHECK_CWISE1_IF(internal::packet_traits::HasErf, std::erf, internal::perf); + CHECK_CWISE1_IF(internal::packet_traits::HasErfc, std::erfc, internal::perfc); +#endif + + if(PacketTraits::HasLog && PacketTraits::size>=2) { data1[0] = std::numeric_limits::quiet_NaN(); - packet_helper::HasLog,Packet> h; + data1[1] = std::numeric_limits::epsilon(); + packet_helper h; h.store(data2, internal::plog(h.load(data1))); - VERIFY(isNaN(data2[0])); - data1[0] = -1.0f; + VERIFY((numext::isnan)(data2[0])); + VERIFY_IS_EQUAL(std::log(std::numeric_limits::epsilon()), data2[1]); + + data1[0] = -std::numeric_limits::epsilon(); + data1[1] = 0; h.store(data2, internal::plog(h.load(data1))); - VERIFY(isNaN(data2[0])); -#if !EIGEN_FAST_MATH + VERIFY((numext::isnan)(data2[0])); + VERIFY_IS_EQUAL(std::log(Scalar(0)), data2[1]); + + data1[0] = (std::numeric_limits::min)(); + data1[1] = -(std::numeric_limits::min)(); + h.store(data2, internal::plog(h.load(data1))); + VERIFY_IS_EQUAL(std::log((std::numeric_limits::min)()), data2[0]); + VERIFY((numext::isnan)(data2[1])); + + data1[0] = std::numeric_limits::denorm_min(); + data1[1] = -std::numeric_limits::denorm_min(); + h.store(data2, internal::plog(h.load(data1))); + // VERIFY_IS_EQUAL(std::log(std::numeric_limits::denorm_min()), data2[0]); + VERIFY((numext::isnan)(data2[1])); + + data1[0] = Scalar(-1.0f); + h.store(data2, internal::plog(h.load(data1))); + VERIFY((numext::isnan)(data2[0])); h.store(data2, internal::psqrt(h.load(data1))); - VERIFY(isNaN(data2[0])); - VERIFY(isNaN(data2[1])); -#endif + VERIFY((numext::isnan)(data2[0])); + VERIFY((numext::isnan)(data2[1])); } } template void packetmath_notcomplex() { using std::abs; - typedef typename internal::packet_traits::type Packet; - const int PacketSize = internal::packet_traits::size; + typedef internal::packet_traits PacketTraits; + typedef typename PacketTraits::type Packet; + const int PacketSize = PacketTraits::size; - EIGEN_ALIGN16 Scalar data1[internal::packet_traits::size*4]; - EIGEN_ALIGN16 Scalar data2[internal::packet_traits::size*4]; - EIGEN_ALIGN16 Scalar ref[internal::packet_traits::size*4]; - - Array::Map(data1, internal::packet_traits::size*4).setRandom(); + EIGEN_ALIGN_MAX Scalar data1[PacketTraits::size*4]; + EIGEN_ALIGN_MAX Scalar data2[PacketTraits::size*4]; + EIGEN_ALIGN_MAX Scalar ref[PacketTraits::size*4]; + + Array::Map(data1, PacketTraits::size*4).setRandom(); ref[0] = data1[0]; for (int i=0; i(data1))) && "internal::predux_min"); - CHECK_CWISE2((std::min), internal::pmin); - CHECK_CWISE2((std::max), internal::pmax); + VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasMin); + VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasMax); + + CHECK_CWISE2_IF(PacketTraits::HasMin, (std::min), internal::pmin); + CHECK_CWISE2_IF(PacketTraits::HasMax, (std::max), internal::pmax); CHECK_CWISE1(abs, internal::pabs); ref[0] = data1[0]; for (int i=0; i(data1))) && "internal::predux_max"); - + for (int i=0; i(data1[0])); VERIFY(areApprox(ref, data2, PacketSize) && "internal::plset"); } template void test_conj_helper(Scalar* data1, Scalar* data2, Scalar* ref, Scalar* pval) { - typedef typename internal::packet_traits::type Packet; - const int PacketSize = internal::packet_traits::size; - + typedef internal::packet_traits PacketTraits; + typedef typename PacketTraits::type Packet; + const int PacketSize = PacketTraits::size; + internal::conj_if cj0; internal::conj_if cj1; internal::conj_helper cj; internal::conj_helper pcj; - + for(int i=0;i void test_conj_helper(Scalar } internal::pstore(pval,pcj.pmul(internal::pload(data1),internal::pload(data2))); VERIFY(areApprox(ref, pval, PacketSize) && "conj_helper pmul"); - + for(int i=0;i void test_conj_helper(Scalar template void packetmath_complex() { - typedef typename internal::packet_traits::type Packet; - const int PacketSize = internal::packet_traits::size; + typedef internal::packet_traits PacketTraits; + typedef typename PacketTraits::type Packet; + const int PacketSize = PacketTraits::size; const int size = PacketSize*4; - EIGEN_ALIGN16 Scalar data1[PacketSize*4]; - EIGEN_ALIGN16 Scalar data2[PacketSize*4]; - EIGEN_ALIGN16 Scalar ref[PacketSize*4]; - EIGEN_ALIGN16 Scalar pval[PacketSize*4]; + EIGEN_ALIGN_MAX Scalar data1[PacketSize*4]; + EIGEN_ALIGN_MAX Scalar data2[PacketSize*4]; + EIGEN_ALIGN_MAX Scalar ref[PacketSize*4]; + EIGEN_ALIGN_MAX Scalar pval[PacketSize*4]; for (int i=0; i() * Scalar(1e2); data2[i] = internal::random() * Scalar(1e2); } - + test_conj_helper (data1,data2,ref,pval); test_conj_helper (data1,data2,ref,pval); test_conj_helper (data1,data2,ref,pval); test_conj_helper (data1,data2,ref,pval); - + { for(int i=0;i(data1))); VERIFY(areApprox(ref, pval, PacketSize) && "pcplxflip"); } - - +} + +template void packetmath_scatter_gather() +{ + typedef internal::packet_traits PacketTraits; + typedef typename PacketTraits::type Packet; + typedef typename NumTraits::Real RealScalar; + const int PacketSize = PacketTraits::size; + EIGEN_ALIGN_MAX Scalar data1[PacketSize]; + RealScalar refvalue = 0; + for (int i=0; i()/RealScalar(PacketSize); + } + + int stride = internal::random(1,20); + + EIGEN_ALIGN_MAX Scalar buffer[PacketSize*20]; + memset(buffer, 0, 20*PacketSize*sizeof(Scalar)); + Packet packet = internal::pload(data1); + internal::pscatter(buffer, packet, stride); + + for (int i = 0; i < PacketSize*20; ++i) { + if ((i%stride) == 0 && i()/RealScalar(PacketSize); + } + packet = internal::pgather(buffer, 7); + internal::pstore(data1, packet); + for (int i = 0; i < PacketSize; ++i) { + VERIFY(isApproxAbs(data1[i], buffer[i*7], refvalue) && "pgather"); + } } void test_packetmath() @@ -369,17 +620,23 @@ void test_packetmath() CALL_SUBTEST_1( packetmath() ); CALL_SUBTEST_2( packetmath() ); CALL_SUBTEST_3( packetmath() ); - CALL_SUBTEST_1( packetmath >() ); - CALL_SUBTEST_2( packetmath >() ); + CALL_SUBTEST_4( packetmath >() ); + CALL_SUBTEST_5( packetmath >() ); CALL_SUBTEST_1( packetmath_notcomplex() ); CALL_SUBTEST_2( packetmath_notcomplex() ); CALL_SUBTEST_3( packetmath_notcomplex() ); - + CALL_SUBTEST_1( packetmath_real() ); CALL_SUBTEST_2( packetmath_real() ); - CALL_SUBTEST_1( packetmath_complex >() ); - CALL_SUBTEST_2( packetmath_complex >() ); + CALL_SUBTEST_4( packetmath_complex >() ); + CALL_SUBTEST_5( packetmath_complex >() ); + + CALL_SUBTEST_1( packetmath_scatter_gather() ); + CALL_SUBTEST_2( packetmath_scatter_gather() ); + CALL_SUBTEST_3( packetmath_scatter_gather() ); + CALL_SUBTEST_4( packetmath_scatter_gather >() ); + CALL_SUBTEST_5( packetmath_scatter_gather >() ); } } diff --git a/testbed/nanogui/ext/eigen/test/pastix_support.cpp b/testbed/nanogui/ext/eigen/test/pastix_support.cpp index 14da0944..b62f8573 100644 --- a/testbed/nanogui/ext/eigen/test/pastix_support.cpp +++ b/testbed/nanogui/ext/eigen/test/pastix_support.cpp @@ -7,6 +7,8 @@ // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS #include "sparse_solver.h" #include #include @@ -25,6 +27,14 @@ template void test_pastix_T() check_sparse_spd_solving(pastix_llt_upper); check_sparse_spd_solving(pastix_ldlt_upper); check_sparse_square_solving(pastix_lu); + + // Some compilation check: + pastix_llt_lower.iparm(); + pastix_llt_lower.dparm(); + pastix_ldlt_lower.iparm(); + pastix_ldlt_lower.dparm(); + pastix_lu.iparm(); + pastix_lu.dparm(); } // There is no support for selfadjoint matrices with PaStiX. diff --git a/testbed/nanogui/ext/eigen/test/permutationmatrices.cpp b/testbed/nanogui/ext/eigen/test/permutationmatrices.cpp index 7b0dbc76..db126657 100644 --- a/testbed/nanogui/ext/eigen/test/permutationmatrices.cpp +++ b/testbed/nanogui/ext/eigen/test/permutationmatrices.cpp @@ -7,6 +7,8 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +#define TEST_ENABLE_TEMPORARY_TRACKING + #include "main.h" using namespace std; @@ -33,7 +35,9 @@ template void permutationmatrices(const MatrixType& m) RightPermutationVectorType rv; randomPermutationVector(rv, cols); RightPermutationType rp(rv); - MatrixType m_permuted = lp * m_original * rp; + MatrixType m_permuted = MatrixType::Random(rows,cols); + + VERIFY_EVALUATION_COUNT(m_permuted = lp * m_original * rp, 1); // 1 temp for sub expression "lp * m_original" for (int i=0; i void permutationmatrices(const MatrixType& m) Matrix rm(rp); VERIFY_IS_APPROX(m_permuted, lm*m_original*rm); - + + m_permuted = m_original; + VERIFY_EVALUATION_COUNT(m_permuted = lp * m_permuted * rp, 1); + VERIFY_IS_APPROX(m_permuted, lm*m_original*rm); + VERIFY_IS_APPROX(lp.inverse()*m_permuted*rp.inverse(), m_original); VERIFY_IS_APPROX(lv.asPermutation().inverse()*m_permuted*rv.asPermutation().inverse(), m_original); VERIFY_IS_APPROX(MapLeftPerm(lv.data(),lv.size()).inverse()*m_permuted*MapRightPerm(rv.data(),rv.size()).inverse(), m_original); @@ -63,22 +71,22 @@ template void permutationmatrices(const MatrixType& m) LeftPermutationType identityp; identityp.setIdentity(rows); VERIFY_IS_APPROX(m_original, identityp*m_original); - + // check inplace permutations m_permuted = m_original; - m_permuted = lp.inverse() * m_permuted; + VERIFY_EVALUATION_COUNT(m_permuted.noalias()= lp.inverse() * m_permuted, 1); // 1 temp to allocate the mask VERIFY_IS_APPROX(m_permuted, lp.inverse()*m_original); - + m_permuted = m_original; - m_permuted = m_permuted * rp.inverse(); + VERIFY_EVALUATION_COUNT(m_permuted.noalias() = m_permuted * rp.inverse(), 1); // 1 temp to allocate the mask VERIFY_IS_APPROX(m_permuted, m_original*rp.inverse()); - + m_permuted = m_original; - m_permuted = lp * m_permuted; + VERIFY_EVALUATION_COUNT(m_permuted.noalias() = lp * m_permuted, 1); // 1 temp to allocate the mask VERIFY_IS_APPROX(m_permuted, lp*m_original); - + m_permuted = m_original; - m_permuted = m_permuted * rp; + VERIFY_EVALUATION_COUNT(m_permuted.noalias() = m_permuted * rp, 1); // 1 temp to allocate the mask VERIFY_IS_APPROX(m_permuted, m_original*rp); if(rows>1 && cols>1) @@ -99,7 +107,38 @@ template void permutationmatrices(const MatrixType& m) rm = rp; rm.col(i).swap(rm.col(j)); VERIFY_IS_APPROX(rm, rp2.toDenseMatrix().template cast()); - } + } + + { + // simple compilation check + Matrix A = rp; + Matrix B = rp.transpose(); + VERIFY_IS_APPROX(A, B.transpose()); + } +} + +template +void bug890() +{ + typedef Matrix MatrixType; + typedef Matrix VectorType; + typedef Stride S; + typedef Map MapType; + typedef PermutationMatrix Perm; + + VectorType v1(2), v2(2), op(4), rhs(2); + v1 << 666,667; + op << 1,0,0,1; + rhs << 42,42; + + Perm P(2); + P.indices() << 1, 0; + + MapType(v1.data(),2,1,S(1,1)) = P * MapType(rhs.data(),2,1,S(1,1)); + VERIFY_IS_APPROX(v1, (P * rhs).eval()); + + MapType(v1.data(),2,1,S(1,1)) = P.inverse() * MapType(rhs.data(),2,1,S(1,1)); + VERIFY_IS_APPROX(v1, (P.inverse() * rhs).eval()); } void test_permutationmatrices() @@ -113,4 +152,5 @@ void test_permutationmatrices() CALL_SUBTEST_6( permutationmatrices(Matrix(20, 30)) ); CALL_SUBTEST_7( permutationmatrices(MatrixXcf(15, 10)) ); } + CALL_SUBTEST_5( bug890() ); } diff --git a/testbed/nanogui/ext/eigen/test/prec_inverse_4x4.cpp b/testbed/nanogui/ext/eigen/test/prec_inverse_4x4.cpp index c4ef2d4b..eb6ad18c 100644 --- a/testbed/nanogui/ext/eigen/test/prec_inverse_4x4.cpp +++ b/testbed/nanogui/ext/eigen/test/prec_inverse_4x4.cpp @@ -53,14 +53,29 @@ template void inverse_general_4x4(int repeat) // FIXME that 1.25 used to be 1.2 until we tested gcc 4.1 on 30 June 2010 and got 1.21. VERIFY(error_avg < (NumTraits::IsComplex ? 8.0 : 1.25)); VERIFY(error_max < (NumTraits::IsComplex ? 64.0 : 20.0)); + + { + int s = 5;//internal::random(4,10); + int i = 0;//internal::random(0,s-4); + int j = 0;//internal::random(0,s-4); + Matrix mat(s,s); + mat.setRandom(); + MatrixType submat = mat.template block<4,4>(i,j); + MatrixType mat_inv = mat.template block<4,4>(i,j).inverse(); + VERIFY_IS_APPROX(mat_inv, submat.inverse()); + mat.template block<4,4>(i,j) = submat.inverse(); + VERIFY_IS_APPROX(mat_inv, (mat.template block<4,4>(i,j))); + } } void test_prec_inverse_4x4() { CALL_SUBTEST_1((inverse_permutation_4x4())); CALL_SUBTEST_1(( inverse_general_4x4(200000 * g_repeat) )); + CALL_SUBTEST_1(( inverse_general_4x4 >(200000 * g_repeat) )); CALL_SUBTEST_2((inverse_permutation_4x4 >())); + CALL_SUBTEST_2(( inverse_general_4x4 >(200000 * g_repeat) )); CALL_SUBTEST_2(( inverse_general_4x4 >(200000 * g_repeat) )); CALL_SUBTEST_3((inverse_permutation_4x4())); diff --git a/testbed/nanogui/ext/eigen/test/product.h b/testbed/nanogui/ext/eigen/test/product.h index 0b3abe40..3b651127 100644 --- a/testbed/nanogui/ext/eigen/test/product.h +++ b/testbed/nanogui/ext/eigen/test/product.h @@ -22,7 +22,6 @@ template void product(const MatrixType& m) /* this test covers the following files: Identity.h Product.h */ - typedef typename MatrixType::Index Index; typedef typename MatrixType::Scalar Scalar; typedef Matrix RowVectorType; typedef Matrix ColVectorType; @@ -112,6 +111,23 @@ template void product(const MatrixType& m) vcres.noalias() -= m1.transpose() * v1; VERIFY_IS_APPROX(vcres, vc2 - m1.transpose() * v1); + // test d ?= a+b*c rules + res.noalias() = square + m1 * m2.transpose(); + VERIFY_IS_APPROX(res, square + m1 * m2.transpose()); + res.noalias() += square + m1 * m2.transpose(); + VERIFY_IS_APPROX(res, 2*(square + m1 * m2.transpose())); + res.noalias() -= square + m1 * m2.transpose(); + VERIFY_IS_APPROX(res, square + m1 * m2.transpose()); + + // test d ?= a-b*c rules + res.noalias() = square - m1 * m2.transpose(); + VERIFY_IS_APPROX(res, square - m1 * m2.transpose()); + res.noalias() += square - m1 * m2.transpose(); + VERIFY_IS_APPROX(res, 2*(square - m1 * m2.transpose())); + res.noalias() -= square - m1 * m2.transpose(); + VERIFY_IS_APPROX(res, square - m1 * m2.transpose()); + + tm1 = m1; VERIFY_IS_APPROX(tm1.transpose() * v1, m1.transpose() * v1); VERIFY_IS_APPROX(v1.transpose() * tm1, v1.transpose() * m1); @@ -136,15 +152,80 @@ template void product(const MatrixType& m) VERIFY_IS_APPROX(res.col(r).noalias() = square.adjoint() * square.col(r), (square.adjoint() * square.col(r)).eval()); VERIFY_IS_APPROX(res.col(r).noalias() = square * square.col(r), (square * square.col(r)).eval()); + // vector at runtime (see bug 1166) + { + RowSquareMatrixType ref(square); + ColSquareMatrixType ref2(square2); + ref = res = square; + VERIFY_IS_APPROX(res.block(0,0,1,rows).noalias() = m1.col(0).transpose() * square.transpose(), (ref.row(0) = m1.col(0).transpose() * square.transpose())); + VERIFY_IS_APPROX(res.block(0,0,1,rows).noalias() = m1.block(0,0,rows,1).transpose() * square.transpose(), (ref.row(0) = m1.col(0).transpose() * square.transpose())); + VERIFY_IS_APPROX(res.block(0,0,1,rows).noalias() = m1.col(0).transpose() * square, (ref.row(0) = m1.col(0).transpose() * square)); + VERIFY_IS_APPROX(res.block(0,0,1,rows).noalias() = m1.block(0,0,rows,1).transpose() * square, (ref.row(0) = m1.col(0).transpose() * square)); + ref2 = res2 = square2; + VERIFY_IS_APPROX(res2.block(0,0,1,cols).noalias() = m1.row(0) * square2.transpose(), (ref2.row(0) = m1.row(0) * square2.transpose())); + VERIFY_IS_APPROX(res2.block(0,0,1,cols).noalias() = m1.block(0,0,1,cols) * square2.transpose(), (ref2.row(0) = m1.row(0) * square2.transpose())); + VERIFY_IS_APPROX(res2.block(0,0,1,cols).noalias() = m1.row(0) * square2, (ref2.row(0) = m1.row(0) * square2)); + VERIFY_IS_APPROX(res2.block(0,0,1,cols).noalias() = m1.block(0,0,1,cols) * square2, (ref2.row(0) = m1.row(0) * square2)); + } + + // vector.block() (see bug 1283) + { + RowVectorType w1(rows); + VERIFY_IS_APPROX(square * v1.block(0,0,rows,1), square * v1); + VERIFY_IS_APPROX(w1.noalias() = square * v1.block(0,0,rows,1), square * v1); + VERIFY_IS_APPROX(w1.block(0,0,rows,1).noalias() = square * v1.block(0,0,rows,1), square * v1); + + Matrix w2(cols); + VERIFY_IS_APPROX(vc2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2); + VERIFY_IS_APPROX(w2.noalias() = vc2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2); + VERIFY_IS_APPROX(w2.block(0,0,1,cols).noalias() = vc2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2); + + vc2 = square2.block(0,0,1,cols).transpose(); + VERIFY_IS_APPROX(square2.block(0,0,1,cols) * square2, vc2.transpose() * square2); + VERIFY_IS_APPROX(w2.noalias() = square2.block(0,0,1,cols) * square2, vc2.transpose() * square2); + VERIFY_IS_APPROX(w2.block(0,0,1,cols).noalias() = square2.block(0,0,1,cols) * square2, vc2.transpose() * square2); + + vc2 = square2.block(0,0,cols,1); + VERIFY_IS_APPROX(square2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2); + VERIFY_IS_APPROX(w2.noalias() = square2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2); + VERIFY_IS_APPROX(w2.block(0,0,1,cols).noalias() = square2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2); + } + // inner product - Scalar x = square2.row(c) * square2.col(c2); - VERIFY_IS_APPROX(x, square2.row(c).transpose().cwiseProduct(square2.col(c2)).sum()); - + { + Scalar x = square2.row(c) * square2.col(c2); + VERIFY_IS_APPROX(x, square2.row(c).transpose().cwiseProduct(square2.col(c2)).sum()); + } + // outer product - VERIFY_IS_APPROX(m1.col(c) * m1.row(r), m1.block(0,c,rows,1) * m1.block(r,0,1,cols)); - VERIFY_IS_APPROX(m1.row(r).transpose() * m1.col(c).transpose(), m1.block(r,0,1,cols).transpose() * m1.block(0,c,rows,1).transpose()); - VERIFY_IS_APPROX(m1.block(0,c,rows,1) * m1.row(r), m1.block(0,c,rows,1) * m1.block(r,0,1,cols)); - VERIFY_IS_APPROX(m1.col(c) * m1.block(r,0,1,cols), m1.block(0,c,rows,1) * m1.block(r,0,1,cols)); - VERIFY_IS_APPROX(m1.leftCols(1) * m1.row(r), m1.block(0,0,rows,1) * m1.block(r,0,1,cols)); - VERIFY_IS_APPROX(m1.col(c) * m1.topRows(1), m1.block(0,c,rows,1) * m1.block(0,0,1,cols)); + { + VERIFY_IS_APPROX(m1.col(c) * m1.row(r), m1.block(0,c,rows,1) * m1.block(r,0,1,cols)); + VERIFY_IS_APPROX(m1.row(r).transpose() * m1.col(c).transpose(), m1.block(r,0,1,cols).transpose() * m1.block(0,c,rows,1).transpose()); + VERIFY_IS_APPROX(m1.block(0,c,rows,1) * m1.row(r), m1.block(0,c,rows,1) * m1.block(r,0,1,cols)); + VERIFY_IS_APPROX(m1.col(c) * m1.block(r,0,1,cols), m1.block(0,c,rows,1) * m1.block(r,0,1,cols)); + VERIFY_IS_APPROX(m1.leftCols(1) * m1.row(r), m1.block(0,0,rows,1) * m1.block(r,0,1,cols)); + VERIFY_IS_APPROX(m1.col(c) * m1.topRows(1), m1.block(0,c,rows,1) * m1.block(0,0,1,cols)); + } + + // Aliasing + { + ColVectorType x(cols); x.setRandom(); + ColVectorType z(x); + ColVectorType y(cols); y.setZero(); + ColSquareMatrixType A(cols,cols); A.setRandom(); + // CwiseBinaryOp + VERIFY_IS_APPROX(x = y + A*x, A*z); + x = z; + // CwiseUnaryOp + VERIFY_IS_APPROX(x = Scalar(1.)*(A*x), A*z); + } + + // regression for blas_trais + { + VERIFY_IS_APPROX(square * (square*square).transpose(), square * square.transpose() * square.transpose()); + VERIFY_IS_APPROX(square * (-(square*square)), -square * square * square); + VERIFY_IS_APPROX(square * (s1*(square*square)), s1 * square * square * square); + VERIFY_IS_APPROX(square * (square*square).conjugate(), square * square.conjugate() * square.conjugate()); + } + } diff --git a/testbed/nanogui/ext/eigen/test/product_extra.cpp b/testbed/nanogui/ext/eigen/test/product_extra.cpp index 744a1ef7..e2b855bf 100644 --- a/testbed/nanogui/ext/eigen/test/product_extra.cpp +++ b/testbed/nanogui/ext/eigen/test/product_extra.cpp @@ -98,6 +98,16 @@ template void product_extra(const MatrixType& m) // regression test MatrixType tmp = m1 * m1.adjoint() * s1; VERIFY_IS_APPROX(tmp, m1 * m1.adjoint() * s1); + + // regression test for bug 1343, assignment to arrays + Array a1 = m1 * vc2; + VERIFY_IS_APPROX(a1.matrix(),m1*vc2); + Array a2 = s1 * (m1 * vc2); + VERIFY_IS_APPROX(a2.matrix(),s1*m1*vc2); + Array a3 = v1 * m1; + VERIFY_IS_APPROX(a3.matrix(),v1*m1); + Array a4 = m1 * m2.adjoint(); + VERIFY_IS_APPROX(a4.matrix(),m1*m2.adjoint()); } // Regression test for bug reported at http://forum.kde.org/viewtopic.php?f=74&t=96947 @@ -109,8 +119,68 @@ void mat_mat_scalar_scalar_product() double det = 6.0, wt = 0.5; VERIFY_IS_APPROX(dNdxy.transpose()*dNdxy*det*wt, det*wt*dNdxy.transpose()*dNdxy); } + +template +void zero_sized_objects(const MatrixType& m) +{ + typedef typename MatrixType::Scalar Scalar; + const int PacketSize = internal::packet_traits::size; + const int PacketSize1 = PacketSize>1 ? PacketSize-1 : 1; + Index rows = m.rows(); + Index cols = m.cols(); -void zero_sized_objects() + { + MatrixType res, a(rows,0), b(0,cols); + VERIFY_IS_APPROX( (res=a*b), MatrixType::Zero(rows,cols) ); + VERIFY_IS_APPROX( (res=a*a.transpose()), MatrixType::Zero(rows,rows) ); + VERIFY_IS_APPROX( (res=b.transpose()*b), MatrixType::Zero(cols,cols) ); + VERIFY_IS_APPROX( (res=b.transpose()*a.transpose()), MatrixType::Zero(cols,rows) ); + } + + { + MatrixType res, a(rows,cols), b(cols,0); + res = a*b; + VERIFY(res.rows()==rows && res.cols()==0); + b.resize(0,rows); + res = b*a; + VERIFY(res.rows()==0 && res.cols()==cols); + } + + { + Matrix a; + Matrix b; + Matrix res; + VERIFY_IS_APPROX( (res=a*b), MatrixType::Zero(PacketSize,1) ); + VERIFY_IS_APPROX( (res=a.lazyProduct(b)), MatrixType::Zero(PacketSize,1) ); + } + + { + Matrix a; + Matrix b; + Matrix res; + VERIFY_IS_APPROX( (res=a*b), MatrixType::Zero(PacketSize1,1) ); + VERIFY_IS_APPROX( (res=a.lazyProduct(b)), MatrixType::Zero(PacketSize1,1) ); + } + + { + Matrix a(PacketSize,0); + Matrix b(0,1); + Matrix res; + VERIFY_IS_APPROX( (res=a*b), MatrixType::Zero(PacketSize,1) ); + VERIFY_IS_APPROX( (res=a.lazyProduct(b)), MatrixType::Zero(PacketSize,1) ); + } + + { + Matrix a(PacketSize1,0); + Matrix b(0,1); + Matrix res; + VERIFY_IS_APPROX( (res=a*b), MatrixType::Zero(PacketSize1,1) ); + VERIFY_IS_APPROX( (res=a.lazyProduct(b)), MatrixType::Zero(PacketSize1,1) ); + } +} + +template +void bug_127() { // Bug 127 // @@ -134,6 +204,16 @@ void zero_sized_objects() a*b; } +template void bug_817() +{ + ArrayXXf B = ArrayXXf::Random(10,10), C; + VectorXf x = VectorXf::Random(10); + C = (x.transpose()*B.matrix()); + B = (x.transpose()*B.matrix()); + VERIFY_IS_APPROX(B,C); +} + +template void unaligned_objects() { // Regression test for the bug reported here: @@ -163,6 +243,116 @@ void unaligned_objects() } } +template +EIGEN_DONT_INLINE +Index test_compute_block_size(Index m, Index n, Index k) +{ + Index mc(m), nc(n), kc(k); + internal::computeProductBlockingSizes(kc, mc, nc); + return kc+mc+nc; +} + +template +Index compute_block_size() +{ + Index ret = 0; + ret += test_compute_block_size(0,1,1); + ret += test_compute_block_size(1,0,1); + ret += test_compute_block_size(1,1,0); + ret += test_compute_block_size(0,0,1); + ret += test_compute_block_size(0,1,0); + ret += test_compute_block_size(1,0,0); + ret += test_compute_block_size(0,0,0); + return ret; +} + +template +void aliasing_with_resize() +{ + Index m = internal::random(10,50); + Index n = internal::random(10,50); + MatrixXd A, B, C(m,n), D(m,m); + VectorXd a, b, c(n); + C.setRandom(); + D.setRandom(); + c.setRandom(); + double s = internal::random(1,10); + + A = C; + B = A * A.transpose(); + A = A * A.transpose(); + VERIFY_IS_APPROX(A,B); + + A = C; + B = (A * A.transpose())/s; + A = (A * A.transpose())/s; + VERIFY_IS_APPROX(A,B); + + A = C; + B = (A * A.transpose()) + D; + A = (A * A.transpose()) + D; + VERIFY_IS_APPROX(A,B); + + A = C; + B = D + (A * A.transpose()); + A = D + (A * A.transpose()); + VERIFY_IS_APPROX(A,B); + + A = C; + B = s * (A * A.transpose()); + A = s * (A * A.transpose()); + VERIFY_IS_APPROX(A,B); + + A = C; + a = c; + b = (A * a)/s; + a = (A * a)/s; + VERIFY_IS_APPROX(a,b); +} + +template +void bug_1308() +{ + int n = 10; + MatrixXd r(n,n); + VectorXd v = VectorXd::Random(n); + r = v * RowVectorXd::Ones(n); + VERIFY_IS_APPROX(r, v.rowwise().replicate(n)); + r = VectorXd::Ones(n) * v.transpose(); + VERIFY_IS_APPROX(r, v.rowwise().replicate(n).transpose()); + + Matrix4d ones44 = Matrix4d::Ones(); + Matrix4d m44 = Matrix4d::Ones() * Matrix4d::Ones(); + VERIFY_IS_APPROX(m44,Matrix4d::Constant(4)); + VERIFY_IS_APPROX(m44.noalias()=ones44*Matrix4d::Ones(), Matrix4d::Constant(4)); + VERIFY_IS_APPROX(m44.noalias()=ones44.transpose()*Matrix4d::Ones(), Matrix4d::Constant(4)); + VERIFY_IS_APPROX(m44.noalias()=Matrix4d::Ones()*ones44, Matrix4d::Constant(4)); + VERIFY_IS_APPROX(m44.noalias()=Matrix4d::Ones()*ones44.transpose(), Matrix4d::Constant(4)); + + typedef Matrix RMatrix4d; + RMatrix4d r44 = Matrix4d::Ones() * Matrix4d::Ones(); + VERIFY_IS_APPROX(r44,Matrix4d::Constant(4)); + VERIFY_IS_APPROX(r44.noalias()=ones44*Matrix4d::Ones(), Matrix4d::Constant(4)); + VERIFY_IS_APPROX(r44.noalias()=ones44.transpose()*Matrix4d::Ones(), Matrix4d::Constant(4)); + VERIFY_IS_APPROX(r44.noalias()=Matrix4d::Ones()*ones44, Matrix4d::Constant(4)); + VERIFY_IS_APPROX(r44.noalias()=Matrix4d::Ones()*ones44.transpose(), Matrix4d::Constant(4)); + VERIFY_IS_APPROX(r44.noalias()=ones44*RMatrix4d::Ones(), Matrix4d::Constant(4)); + VERIFY_IS_APPROX(r44.noalias()=ones44.transpose()*RMatrix4d::Ones(), Matrix4d::Constant(4)); + VERIFY_IS_APPROX(r44.noalias()=RMatrix4d::Ones()*ones44, Matrix4d::Constant(4)); + VERIFY_IS_APPROX(r44.noalias()=RMatrix4d::Ones()*ones44.transpose(), Matrix4d::Constant(4)); + +// RowVector4d r4; + m44.setOnes(); + r44.setZero(); + VERIFY_IS_APPROX(r44.noalias() += m44.row(0).transpose() * RowVector4d::Ones(), ones44); + r44.setZero(); + VERIFY_IS_APPROX(r44.noalias() += m44.col(0) * RowVector4d::Ones(), ones44); + r44.setZero(); + VERIFY_IS_APPROX(r44.noalias() += Vector4d::Ones() * m44.row(0), ones44); + r44.setZero(); + VERIFY_IS_APPROX(r44.noalias() += Vector4d::Ones() * m44.col(0).transpose(), ones44); +} + void test_product_extra() { for(int i = 0; i < g_repeat; i++) { @@ -171,7 +361,15 @@ void test_product_extra() CALL_SUBTEST_2( mat_mat_scalar_scalar_product() ); CALL_SUBTEST_3( product_extra(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE/2), internal::random(1,EIGEN_TEST_MAX_SIZE/2))) ); CALL_SUBTEST_4( product_extra(MatrixXcd(internal::random(1,EIGEN_TEST_MAX_SIZE/2), internal::random(1,EIGEN_TEST_MAX_SIZE/2))) ); + CALL_SUBTEST_1( zero_sized_objects(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } - CALL_SUBTEST_5( zero_sized_objects() ); - CALL_SUBTEST_6( unaligned_objects() ); + CALL_SUBTEST_5( bug_127<0>() ); + CALL_SUBTEST_5( bug_817<0>() ); + CALL_SUBTEST_5( bug_1308<0>() ); + CALL_SUBTEST_6( unaligned_objects<0>() ); + CALL_SUBTEST_7( compute_block_size() ); + CALL_SUBTEST_7( compute_block_size() ); + CALL_SUBTEST_7( compute_block_size >() ); + CALL_SUBTEST_8( aliasing_with_resize() ); + } diff --git a/testbed/nanogui/ext/eigen/test/product_large.cpp b/testbed/nanogui/ext/eigen/test/product_large.cpp index 03d7bd8e..845cd40c 100644 --- a/testbed/nanogui/ext/eigen/test/product_large.cpp +++ b/testbed/nanogui/ext/eigen/test/product_large.cpp @@ -9,6 +9,27 @@ #include "product.h" +template +void test_aliasing() +{ + int rows = internal::random(1,12); + int cols = internal::random(1,12); + typedef Matrix MatrixType; + typedef Matrix VectorType; + VectorType x(cols); x.setRandom(); + VectorType z(x); + VectorType y(rows); y.setZero(); + MatrixType A(rows,cols); A.setRandom(); + // CwiseBinaryOp + VERIFY_IS_APPROX(x = y + A*x, A*z); // OK because "y + A*x" is marked as "assume-aliasing" + x = z; + // CwiseUnaryOp + VERIFY_IS_APPROX(x = T(1.)*(A*x), A*z); // OK because 1*(A*x) is replaced by (1*A*x) which is a Product<> expression + x = z; + // VERIFY_IS_APPROX(x = y-A*x, -A*z); // Not OK in 3.3 because x is resized before A*x gets evaluated + x = z; +} + void test_product_large() { for(int i = 0; i < g_repeat; i++) { @@ -17,6 +38,8 @@ void test_product_large() CALL_SUBTEST_3( product(MatrixXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); CALL_SUBTEST_4( product(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE/2), internal::random(1,EIGEN_TEST_MAX_SIZE/2))) ); CALL_SUBTEST_5( product(Matrix(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + + CALL_SUBTEST_1( test_aliasing() ); } #if defined EIGEN_TEST_PART_6 @@ -39,15 +62,16 @@ void test_product_large() // check the functions to setup blocking sizes compile and do not segfault // FIXME check they do what they are supposed to do !! std::ptrdiff_t l1 = internal::random(10000,20000); - std::ptrdiff_t l2 = internal::random(1000000,2000000); - setCpuCacheSizes(l1,l2); + std::ptrdiff_t l2 = internal::random(100000,200000); + std::ptrdiff_t l3 = internal::random(1000000,2000000); + setCpuCacheSizes(l1,l2,l3); VERIFY(l1==l1CacheSize()); VERIFY(l2==l2CacheSize()); std::ptrdiff_t k1 = internal::random(10,100)*16; std::ptrdiff_t m1 = internal::random(10,100)*16; std::ptrdiff_t n1 = internal::random(10,100)*16; // only makes sure it compiles fine - internal::computeProductBlockingSizes(k1,m1,n1); + internal::computeProductBlockingSizes(k1,m1,n1,1); } { @@ -60,5 +84,24 @@ void test_product_large() MatrixXf r2 = mat1.row(2)*mat2; VERIFY_IS_APPROX(r2, (mat1.row(2)*mat2).eval()); } + + { + Eigen::MatrixXd A(10,10), B, C; + A.setRandom(); + C = A; + for(int k=0; k<79; ++k) + C = C * A; + B.noalias() = (((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)) * ((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))) + * (((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)) * ((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))); + VERIFY_IS_APPROX(B,C); + } +#endif + + // Regression test for bug 714: +#if defined EIGEN_HAS_OPENMP + omp_set_dynamic(1); + for(int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_6( product(Matrix(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + } #endif } diff --git a/testbed/nanogui/ext/eigen/test/product_mmtr.cpp b/testbed/nanogui/ext/eigen/test/product_mmtr.cpp index 7d674680..f6e4bb1a 100644 --- a/testbed/nanogui/ext/eigen/test/product_mmtr.cpp +++ b/testbed/nanogui/ext/eigen/test/product_mmtr.cpp @@ -13,7 +13,8 @@ ref2 = ref1 = DEST; \ DEST.template triangularView() OP; \ ref1 OP; \ - ref2.template triangularView() = ref1; \ + ref2.template triangularView() \ + = ref1.template triangularView(); \ VERIFY_IS_APPROX(DEST,ref2); \ } @@ -24,14 +25,16 @@ template void mmtr(int size) DenseIndex othersize = internal::random(1,200); - MatrixColMaj matc(size, size); - MatrixRowMaj matr(size, size); + MatrixColMaj matc = MatrixColMaj::Zero(size, size); + MatrixRowMaj matr = MatrixRowMaj::Zero(size, size); MatrixColMaj ref1(size, size), ref2(size, size); MatrixColMaj soc(size,othersize); soc.setRandom(); MatrixColMaj osc(othersize,size); osc.setRandom(); MatrixRowMaj sor(size,othersize); sor.setRandom(); MatrixRowMaj osr(othersize,size); osr.setRandom(); + MatrixColMaj sqc(size,size); sqc.setRandom(); + MatrixRowMaj sqr(size,size); sqr.setRandom(); Scalar s = internal::random(); @@ -49,6 +52,29 @@ template void mmtr(int size) CHECK_MMTR(matc, Upper, -= s*(osc.transpose()*osc.conjugate())); CHECK_MMTR(matr, Lower, -= s*soc*soc.adjoint()); CHECK_MMTR(matr, Upper, -= soc*(s*soc.adjoint())); + + CHECK_MMTR(matc, Lower, -= s*sqr*sqc.template triangularView()); + CHECK_MMTR(matc, Upper, = s*sqc*sqr.template triangularView()); + CHECK_MMTR(matc, Lower, += s*sqr*sqc.template triangularView()); + CHECK_MMTR(matc, Upper, = s*sqc*sqc.template triangularView()); + + CHECK_MMTR(matc, Lower, = (s*sqr).template triangularView()*sqc); + CHECK_MMTR(matc, Upper, -= (s*sqc).template triangularView()*sqc); + CHECK_MMTR(matc, Lower, = (s*sqr).template triangularView()*sqc); + CHECK_MMTR(matc, Upper, += (s*sqc).template triangularView()*sqc); + + // check aliasing + ref2 = ref1 = matc; + ref1 = sqc.adjoint() * matc * sqc; + ref2.template triangularView() = ref1.template triangularView(); + matc.template triangularView() = sqc.adjoint() * matc * sqc; + VERIFY_IS_APPROX(matc, ref2); + + ref2 = ref1 = matc; + ref1 = sqc * matc * sqc.adjoint(); + ref2.template triangularView() = ref1.template triangularView(); + matc.template triangularView() = sqc * matc * sqc.adjoint(); + VERIFY_IS_APPROX(matc, ref2); } void test_product_mmtr() diff --git a/testbed/nanogui/ext/eigen/test/product_notemporary.cpp b/testbed/nanogui/ext/eigen/test/product_notemporary.cpp index 258d238e..8bf71b4f 100644 --- a/testbed/nanogui/ext/eigen/test/product_notemporary.cpp +++ b/testbed/nanogui/ext/eigen/test/product_notemporary.cpp @@ -7,25 +7,10 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. -static int nb_temporaries; - -inline void on_temporary_creation(int size) { - // here's a great place to set a breakpoint when debugging failures in this test! - if(size!=0) nb_temporaries++; -} - - -#define EIGEN_DENSE_STORAGE_CTOR_PLUGIN { on_temporary_creation(size); } +#define TEST_ENABLE_TEMPORARY_TRACKING #include "main.h" -#define VERIFY_EVALUATION_COUNT(XPR,N) {\ - nb_temporaries = 0; \ - XPR; \ - if(nb_temporaries!=N) std::cerr << "nb_temporaries == " << nb_temporaries << "\n"; \ - VERIFY( (#XPR) && nb_temporaries==N ); \ - } - template void product_notemporary(const MatrixType& m) { /* This test checks the number of temporaries created @@ -58,10 +43,23 @@ template void product_notemporary(const MatrixType& m) r1 = internal::random(8,rows-r0); VERIFY_EVALUATION_COUNT( m3 = (m1 * m2.adjoint()), 1); + VERIFY_EVALUATION_COUNT( m3 = (m1 * m2.adjoint()).transpose(), 1); VERIFY_EVALUATION_COUNT( m3.noalias() = m1 * m2.adjoint(), 0); + VERIFY_EVALUATION_COUNT( m3 = s1 * (m1 * m2.transpose()), 1); +// VERIFY_EVALUATION_COUNT( m3 = m3 + s1 * (m1 * m2.transpose()), 1); VERIFY_EVALUATION_COUNT( m3.noalias() = s1 * (m1 * m2.transpose()), 0); + VERIFY_EVALUATION_COUNT( m3 = m3 + (m1 * m2.adjoint()), 1); + + VERIFY_EVALUATION_COUNT( m3 = m3 + (m1 * m2.adjoint()).transpose(), 1); + VERIFY_EVALUATION_COUNT( m3.noalias() = m3 + m1 * m2.transpose(), 0); + VERIFY_EVALUATION_COUNT( m3.noalias() += m3 + m1 * m2.transpose(), 0); + VERIFY_EVALUATION_COUNT( m3.noalias() -= m3 + m1 * m2.transpose(), 0); + VERIFY_EVALUATION_COUNT( m3.noalias() = m3 - m1 * m2.transpose(), 0); + VERIFY_EVALUATION_COUNT( m3.noalias() += m3 - m1 * m2.transpose(), 0); + VERIFY_EVALUATION_COUNT( m3.noalias() -= m3 - m1 * m2.transpose(), 0); + VERIFY_EVALUATION_COUNT( m3.noalias() = s1 * m1 * s2 * m2.adjoint(), 0); VERIFY_EVALUATION_COUNT( m3.noalias() = s1 * m1 * s2 * (m1*s3+m2*s2).adjoint(), 1); VERIFY_EVALUATION_COUNT( m3.noalias() = (s1 * m1).adjoint() * s2 * m2, 0); @@ -77,7 +75,7 @@ template void product_notemporary(const MatrixType& m) VERIFY_EVALUATION_COUNT( m3.noalias() -= (s1 * m1).template triangularView() * m2, 0); VERIFY_EVALUATION_COUNT( rm3.noalias() = (s1 * m1.adjoint()).template triangularView() * (m2+m2), 1); VERIFY_EVALUATION_COUNT( rm3.noalias() = (s1 * m1.adjoint()).template triangularView() * m2.adjoint(), 0); - + VERIFY_EVALUATION_COUNT( m3.template triangularView() = (m1 * m2.adjoint()), 0); VERIFY_EVALUATION_COUNT( m3.template triangularView() -= (m1 * m2.adjoint()), 0); @@ -114,8 +112,7 @@ template void product_notemporary(const MatrixType& m) VERIFY_EVALUATION_COUNT( Scalar tmp = 0; tmp += Scalar(RealScalar(1)) / (m3.transpose() * m3).diagonal().array().abs().sum(), 0 ); // Zero temporaries for ... CoeffBasedProductMode - // - does not work with GCC because of the <..>, we'ld need variadic macros ... - //VERIFY_EVALUATION_COUNT( m3.col(0).head<5>() * m3.col(0).transpose() + m3.col(0).head<5>() * m3.col(0).transpose(), 0 ); + VERIFY_EVALUATION_COUNT( m3.col(0).template head<5>() * m3.col(0).transpose() + m3.col(0).template head<5>() * m3.col(0).transpose(), 0 ); // Check matrix * vectors VERIFY_EVALUATION_COUNT( cvres.noalias() = m1 * cv1, 0 ); @@ -123,6 +120,26 @@ template void product_notemporary(const MatrixType& m) VERIFY_EVALUATION_COUNT( cvres.noalias() -= m1 * m2.col(0), 0 ); VERIFY_EVALUATION_COUNT( cvres.noalias() -= m1 * rv1.adjoint(), 0 ); VERIFY_EVALUATION_COUNT( cvres.noalias() -= m1 * m2.row(0).transpose(), 0 ); + + VERIFY_EVALUATION_COUNT( cvres.noalias() = (m1+m1) * cv1, 0 ); + VERIFY_EVALUATION_COUNT( cvres.noalias() = (rm3+rm3) * cv1, 0 ); + VERIFY_EVALUATION_COUNT( cvres.noalias() = (m1+m1) * (m1*cv1), 1 ); + VERIFY_EVALUATION_COUNT( cvres.noalias() = (rm3+rm3) * (m1*cv1), 1 ); + + // Check outer products + m3 = cv1 * rv1; + VERIFY_EVALUATION_COUNT( m3.noalias() = cv1 * rv1, 0 ); + VERIFY_EVALUATION_COUNT( m3.noalias() = (cv1+cv1) * (rv1+rv1), 1 ); + VERIFY_EVALUATION_COUNT( m3.noalias() = (m1*cv1) * (rv1), 1 ); + VERIFY_EVALUATION_COUNT( m3.noalias() += (m1*cv1) * (rv1), 1 ); + VERIFY_EVALUATION_COUNT( rm3.noalias() = (cv1) * (rv1 * m1), 1 ); + VERIFY_EVALUATION_COUNT( rm3.noalias() -= (cv1) * (rv1 * m1), 1 ); + VERIFY_EVALUATION_COUNT( rm3.noalias() = (m1*cv1) * (rv1 * m1), 2 ); + VERIFY_EVALUATION_COUNT( rm3.noalias() += (m1*cv1) * (rv1 * m1), 2 ); + + // Check nested products + VERIFY_EVALUATION_COUNT( cvres.noalias() = m1.adjoint() * m1 * cv1, 1 ); + VERIFY_EVALUATION_COUNT( rvres.noalias() = rv1 * (m1 * m2.adjoint()), 1 ); } void test_product_notemporary() @@ -131,11 +148,12 @@ void test_product_notemporary() for(int i = 0; i < g_repeat; i++) { s = internal::random(16,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_1( product_notemporary(MatrixXf(s, s)) ); - s = internal::random(16,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_2( product_notemporary(MatrixXd(s, s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) + s = internal::random(16,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_3( product_notemporary(MatrixXcf(s,s)) ); - s = internal::random(16,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_4( product_notemporary(MatrixXcd(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) } } diff --git a/testbed/nanogui/ext/eigen/test/product_selfadjoint.cpp b/testbed/nanogui/ext/eigen/test/product_selfadjoint.cpp index 374e2393..3d768aa7 100644 --- a/testbed/nanogui/ext/eigen/test/product_selfadjoint.cpp +++ b/testbed/nanogui/ext/eigen/test/product_selfadjoint.cpp @@ -67,14 +67,21 @@ void test_product_selfadjoint() CALL_SUBTEST_1( product_selfadjoint(Matrix()) ); CALL_SUBTEST_2( product_selfadjoint(Matrix()) ); CALL_SUBTEST_3( product_selfadjoint(Matrix3d()) ); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_4( product_selfadjoint(MatrixXcf(s, s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) + s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_5( product_selfadjoint(MatrixXcd(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) + s = internal::random(1,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_6( product_selfadjoint(MatrixXd(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) + s = internal::random(1,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_7( product_selfadjoint(Matrix(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) } - TEST_SET_BUT_UNUSED_VARIABLE(s) } diff --git a/testbed/nanogui/ext/eigen/test/product_small.cpp b/testbed/nanogui/ext/eigen/test/product_small.cpp index 8b132abb..fdfdd9f6 100644 --- a/testbed/nanogui/ext/eigen/test/product_small.cpp +++ b/testbed/nanogui/ext/eigen/test/product_small.cpp @@ -9,8 +9,10 @@ #define EIGEN_NO_STATIC_ASSERT #include "product.h" +#include // regression test for bug 447 +template void product1x1() { Matrix matAstatic; @@ -28,16 +30,237 @@ void product1x1() matAdynamic.cwiseProduct(matBdynamic.transpose()).sum() ); } +template +const TC& ref_prod(TC &C, const TA &A, const TB &B) +{ + for(Index i=0;i +typename internal::enable_if::type +test_lazy_single(int rows, int cols, int depth) +{ + Matrix A(rows,depth); A.setRandom(); + Matrix B(depth,cols); B.setRandom(); + Matrix C(rows,cols); C.setRandom(); + Matrix D(C); + VERIFY_IS_APPROX(C+=A.lazyProduct(B), ref_prod(D,A,B)); +} + +template +typename internal::enable_if< ( (Rows ==1&&Depth!=1&&OA==ColMajor) + || (Depth==1&&Rows !=1&&OA==RowMajor) + || (Cols ==1&&Depth!=1&&OB==RowMajor) + || (Depth==1&&Cols !=1&&OB==ColMajor) + || (Rows ==1&&Cols !=1&&OC==ColMajor) + || (Cols ==1&&Rows !=1&&OC==RowMajor)),void>::type +test_lazy_single(int, int, int) +{ +} + +template +void test_lazy_all_layout(int rows=Rows, int cols=Cols, int depth=Depth) +{ + CALL_SUBTEST(( test_lazy_single(rows,cols,depth) )); + CALL_SUBTEST(( test_lazy_single(rows,cols,depth) )); + CALL_SUBTEST(( test_lazy_single(rows,cols,depth) )); + CALL_SUBTEST(( test_lazy_single(rows,cols,depth) )); + CALL_SUBTEST(( test_lazy_single(rows,cols,depth) )); + CALL_SUBTEST(( test_lazy_single(rows,cols,depth) )); + CALL_SUBTEST(( test_lazy_single(rows,cols,depth) )); + CALL_SUBTEST(( test_lazy_single(rows,cols,depth) )); +} + +template +void test_lazy_l1() +{ + int rows = internal::random(1,12); + int cols = internal::random(1,12); + int depth = internal::random(1,12); + + // Inner + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout(1,1,depth) )); + + // Outer + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout(4,cols) )); + CALL_SUBTEST(( test_lazy_all_layout(7,cols) )); + CALL_SUBTEST(( test_lazy_all_layout(rows) )); + CALL_SUBTEST(( test_lazy_all_layout(rows) )); + CALL_SUBTEST(( test_lazy_all_layout(rows,cols) )); +} + +template +void test_lazy_l2() +{ + int rows = internal::random(1,12); + int cols = internal::random(1,12); + int depth = internal::random(1,12); + + // mat-vec + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout(rows) )); + CALL_SUBTEST(( test_lazy_all_layout(4,1,depth) )); + CALL_SUBTEST(( test_lazy_all_layout(rows,1,depth) )); + + // vec-mat + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout(1,cols) )); + CALL_SUBTEST(( test_lazy_all_layout(1,4,depth) )); + CALL_SUBTEST(( test_lazy_all_layout(1,cols,depth) )); +} + +template +void test_lazy_l3() +{ + int rows = internal::random(1,12); + int cols = internal::random(1,12); + int depth = internal::random(1,12); + // mat-mat + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout(rows) )); + CALL_SUBTEST(( test_lazy_all_layout(4,3,depth) )); + CALL_SUBTEST(( test_lazy_all_layout(rows,6,depth) )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout(8,cols) )); + CALL_SUBTEST(( test_lazy_all_layout(3,4,depth) )); + CALL_SUBTEST(( test_lazy_all_layout(4,cols,depth) )); +} + +template +void test_linear_but_not_vectorizable() +{ + // Check tricky cases for which the result of the product is a vector and thus must exhibit the LinearBit flag, + // but is not vectorizable along the linear dimension. + Index n = N==Dynamic ? internal::random(1,32) : N; + Index m = M==Dynamic ? internal::random(1,32) : M; + Index k = K==Dynamic ? internal::random(1,32) : K; + + { + Matrix A; A.setRandom(n,m+1); + Matrix B; B.setRandom(m*2,k); + Matrix C; + Matrix R; + + C.noalias() = A.template topLeftCorner<1,M>() * (B.template topRows()+B.template bottomRows()); + R.noalias() = A.template topLeftCorner<1,M>() * (B.template topRows()+B.template bottomRows()).eval(); + VERIFY_IS_APPROX(C,R); + } + + { + Matrix A; A.setRandom(m+1,n); + Matrix B; B.setRandom(k,m*2); + Matrix C; + Matrix R; + + C.noalias() = (B.template leftCols()+B.template rightCols()) * A.template topLeftCorner(); + R.noalias() = (B.template leftCols()+B.template rightCols()).eval() * A.template topLeftCorner(); + VERIFY_IS_APPROX(C,R); + } +} + +template +void bug_1311() +{ + Matrix< double, Rows, 2 > A; A.setRandom(); + Vector2d b = Vector2d::Random() ; + Matrix res; + res.noalias() = 1. * (A * b); + VERIFY_IS_APPROX(res, A*b); + res.noalias() = 1.*A * b; + VERIFY_IS_APPROX(res, A*b); + res.noalias() = (1.*A).lazyProduct(b); + VERIFY_IS_APPROX(res, A*b); + res.noalias() = (1.*A).lazyProduct(1.*b); + VERIFY_IS_APPROX(res, A*b); + res.noalias() = (A).lazyProduct(1.*b); + VERIFY_IS_APPROX(res, A*b); +} void test_product_small() { for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( product(Matrix()) ); - CALL_SUBTEST_2( product(Matrix()) ); + CALL_SUBTEST_2( product(Matrix()) ); + CALL_SUBTEST_8( product(Matrix()) ); CALL_SUBTEST_3( product(Matrix3d()) ); CALL_SUBTEST_4( product(Matrix4d()) ); CALL_SUBTEST_5( product(Matrix4f()) ); - CALL_SUBTEST_6( product1x1() ); + CALL_SUBTEST_6( product1x1<0>() ); + + CALL_SUBTEST_11( test_lazy_l1() ); + CALL_SUBTEST_12( test_lazy_l2() ); + CALL_SUBTEST_13( test_lazy_l3() ); + + CALL_SUBTEST_21( test_lazy_l1() ); + CALL_SUBTEST_22( test_lazy_l2() ); + CALL_SUBTEST_23( test_lazy_l3() ); + + CALL_SUBTEST_31( test_lazy_l1 >() ); + CALL_SUBTEST_32( test_lazy_l2 >() ); + CALL_SUBTEST_33( test_lazy_l3 >() ); + + CALL_SUBTEST_41( test_lazy_l1 >() ); + CALL_SUBTEST_42( test_lazy_l2 >() ); + CALL_SUBTEST_43( test_lazy_l3 >() ); + + CALL_SUBTEST_7(( test_linear_but_not_vectorizable() )); + CALL_SUBTEST_7(( test_linear_but_not_vectorizable() )); + CALL_SUBTEST_7(( test_linear_but_not_vectorizable() )); + + CALL_SUBTEST_6( bug_1311<3>() ); + CALL_SUBTEST_6( bug_1311<5>() ); } #ifdef EIGEN_TEST_PART_6 @@ -46,5 +269,25 @@ void test_product_small() Vector3f v = Vector3f::Random(); VERIFY_IS_APPROX( (v * v.transpose()) * v, (v * v.transpose()).eval() * v); } + + { + // regression test for pull-request #93 + Eigen::Matrix A; A.setRandom(); + Eigen::Matrix B; B.setRandom(); + Eigen::Matrix C; C.setRandom(); + VERIFY_IS_APPROX(B * A.inverse(), B * A.inverse()[0]); + VERIFY_IS_APPROX(A.inverse() * C, A.inverse()[0] * C); + } + + { + Eigen::Matrix A, B, C; + A.setRandom(); + C = A; + for(int k=0; k<79; ++k) + C = C * A; + B.noalias() = (((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)) * ((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))) + * (((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)) * ((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))); + VERIFY_IS_APPROX(B,C); + } #endif } diff --git a/testbed/nanogui/ext/eigen/test/product_symm.cpp b/testbed/nanogui/ext/eigen/test/product_symm.cpp index 74d7329b..8c44383f 100644 --- a/testbed/nanogui/ext/eigen/test/product_symm.cpp +++ b/testbed/nanogui/ext/eigen/test/product_symm.cpp @@ -39,6 +39,24 @@ template void symm(int size = Size, in VERIFY_IS_APPROX(rhs12 = (s1*m2).template selfadjointView() * (s2*rhs1), rhs13 = (s1*m1) * (s2*rhs1)); + VERIFY_IS_APPROX(rhs12 = (s1*m2).transpose().template selfadjointView() * (s2*rhs1), + rhs13 = (s1*m1.transpose()) * (s2*rhs1)); + + VERIFY_IS_APPROX(rhs12 = (s1*m2).template selfadjointView().transpose() * (s2*rhs1), + rhs13 = (s1*m1.transpose()) * (s2*rhs1)); + + VERIFY_IS_APPROX(rhs12 = (s1*m2).conjugate().template selfadjointView() * (s2*rhs1), + rhs13 = (s1*m1).conjugate() * (s2*rhs1)); + + VERIFY_IS_APPROX(rhs12 = (s1*m2).template selfadjointView().conjugate() * (s2*rhs1), + rhs13 = (s1*m1).conjugate() * (s2*rhs1)); + + VERIFY_IS_APPROX(rhs12 = (s1*m2).adjoint().template selfadjointView() * (s2*rhs1), + rhs13 = (s1*m1).adjoint() * (s2*rhs1)); + + VERIFY_IS_APPROX(rhs12 = (s1*m2).template selfadjointView().adjoint() * (s2*rhs1), + rhs13 = (s1*m1).adjoint() * (s2*rhs1)); + m2 = m1.template triangularView(); rhs12.setRandom(); rhs13 = rhs12; m3 = m2.template selfadjointView(); VERIFY_IS_EQUAL(m1, m3); diff --git a/testbed/nanogui/ext/eigen/test/product_syrk.cpp b/testbed/nanogui/ext/eigen/test/product_syrk.cpp index 73c95000..e10f0f2f 100644 --- a/testbed/nanogui/ext/eigen/test/product_syrk.cpp +++ b/testbed/nanogui/ext/eigen/test/product_syrk.cpp @@ -125,11 +125,12 @@ void test_product_syrk() int s; s = internal::random(1,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_1( syrk(MatrixXf(s, s)) ); - s = internal::random(1,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_2( syrk(MatrixXd(s, s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) + s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_3( syrk(MatrixXcf(s, s)) ); - s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_4( syrk(MatrixXcd(s, s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) } } diff --git a/testbed/nanogui/ext/eigen/test/product_trmm.cpp b/testbed/nanogui/ext/eigen/test/product_trmm.cpp index d715b9a3..12e55441 100644 --- a/testbed/nanogui/ext/eigen/test/product_trmm.cpp +++ b/testbed/nanogui/ext/eigen/test/product_trmm.cpp @@ -9,10 +9,18 @@ #include "main.h" +template +int get_random_size() +{ + const int factor = NumTraits::ReadCost; + const int max_test_size = EIGEN_TEST_MAX_SIZE>2*factor ? EIGEN_TEST_MAX_SIZE/factor : EIGEN_TEST_MAX_SIZE; + return internal::random(1,max_test_size); +} + template -void trmm(int rows=internal::random(1,EIGEN_TEST_MAX_SIZE), - int cols=internal::random(1,EIGEN_TEST_MAX_SIZE), - int otherCols = OtherCols==Dynamic?internal::random(1,EIGEN_TEST_MAX_SIZE):OtherCols) +void trmm(int rows=get_random_size(), + int cols=get_random_size(), + int otherCols = OtherCols==Dynamic?get_random_size():OtherCols) { typedef Matrix TriMatrix; typedef Matrix OnTheRight; @@ -42,13 +50,13 @@ void trmm(int rows=internal::random(1,EIGEN_TEST_MAX_SIZE), VERIFY_IS_APPROX( ge_xs.noalias() = mat.template triangularView() * ge_right, tri * ge_right); VERIFY_IS_APPROX( ge_sx.noalias() = ge_left * mat.template triangularView(), ge_left * tri); - + VERIFY_IS_APPROX( ge_xs.noalias() = (s1*mat.adjoint()).template triangularView() * (s2*ge_left.transpose()), s1*triTr.conjugate() * (s2*ge_left.transpose())); VERIFY_IS_APPROX( ge_sx.noalias() = ge_right.transpose() * mat.adjoint().template triangularView(), ge_right.transpose() * triTr.conjugate()); VERIFY_IS_APPROX( ge_xs.noalias() = (s1*mat.adjoint()).template triangularView() * (s2*ge_left.adjoint()), s1*triTr.conjugate() * (s2*ge_left.adjoint())); VERIFY_IS_APPROX( ge_sx.noalias() = ge_right.adjoint() * mat.adjoint().template triangularView(), ge_right.adjoint() * triTr.conjugate()); - + ge_xs_save = ge_xs; VERIFY_IS_APPROX( (ge_xs_save + s1*triTr.conjugate() * (s2*ge_left.adjoint())).eval(), ge_xs.noalias() += (s1*mat.adjoint()).template triangularView() * (s2*ge_left.adjoint()) ); ge_sx.setRandom(); @@ -61,13 +69,13 @@ void trmm(int rows=internal::random(1,EIGEN_TEST_MAX_SIZE), } template -void trmv(int rows=internal::random(1,EIGEN_TEST_MAX_SIZE), int cols=internal::random(1,EIGEN_TEST_MAX_SIZE)) +void trmv(int rows=get_random_size(), int cols=get_random_size()) { trmm(rows,cols,1); } template -void trmm(int rows=internal::random(1,EIGEN_TEST_MAX_SIZE), int cols=internal::random(1,EIGEN_TEST_MAX_SIZE), int otherCols = internal::random(1,EIGEN_TEST_MAX_SIZE)) +void trmm(int rows=get_random_size(), int cols=get_random_size(), int otherCols = get_random_size()) { trmm(rows,cols,otherCols); } diff --git a/testbed/nanogui/ext/eigen/test/product_trmv.cpp b/testbed/nanogui/ext/eigen/test/product_trmv.cpp index 4c3c435c..57a202af 100644 --- a/testbed/nanogui/ext/eigen/test/product_trmv.cpp +++ b/testbed/nanogui/ext/eigen/test/product_trmv.cpp @@ -78,12 +78,14 @@ void test_product_trmv() CALL_SUBTEST_1( trmv(Matrix()) ); CALL_SUBTEST_2( trmv(Matrix()) ); CALL_SUBTEST_3( trmv(Matrix3d()) ); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_4( trmv(MatrixXcf(s,s)) ); - s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_5( trmv(MatrixXcd(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) + s = internal::random(1,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_6( trmv(Matrix(s, s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) } - TEST_SET_BUT_UNUSED_VARIABLE(s); } diff --git a/testbed/nanogui/ext/eigen/test/product_trsolve.cpp b/testbed/nanogui/ext/eigen/test/product_trsolve.cpp index 69892b3a..4b97fa9d 100644 --- a/testbed/nanogui/ext/eigen/test/product_trsolve.cpp +++ b/testbed/nanogui/ext/eigen/test/product_trsolve.cpp @@ -84,10 +84,18 @@ void test_product_trsolve() CALL_SUBTEST_4((trsolve,Dynamic,Dynamic>(internal::random(1,EIGEN_TEST_MAX_SIZE/2),internal::random(1,EIGEN_TEST_MAX_SIZE/2)))); // vectors - CALL_SUBTEST_1((trsolve(internal::random(1,EIGEN_TEST_MAX_SIZE)))); - CALL_SUBTEST_5((trsolve,Dynamic,1>(internal::random(1,EIGEN_TEST_MAX_SIZE)))); - CALL_SUBTEST_6((trsolve())); - CALL_SUBTEST_7((trsolve())); - CALL_SUBTEST_8((trsolve,4,1>())); + CALL_SUBTEST_5((trsolve(internal::random(1,EIGEN_TEST_MAX_SIZE)))); + CALL_SUBTEST_6((trsolve(internal::random(1,EIGEN_TEST_MAX_SIZE)))); + CALL_SUBTEST_7((trsolve,Dynamic,1>(internal::random(1,EIGEN_TEST_MAX_SIZE)))); + CALL_SUBTEST_8((trsolve,Dynamic,1>(internal::random(1,EIGEN_TEST_MAX_SIZE)))); + + // meta-unrollers + CALL_SUBTEST_9((trsolve())); + CALL_SUBTEST_10((trsolve())); + CALL_SUBTEST_11((trsolve,4,1>())); + CALL_SUBTEST_12((trsolve())); + CALL_SUBTEST_13((trsolve())); + CALL_SUBTEST_14((trsolve())); + } } diff --git a/testbed/nanogui/ext/eigen/test/qr.cpp b/testbed/nanogui/ext/eigen/test/qr.cpp index a79e0dd3..dfcc1e8f 100644 --- a/testbed/nanogui/ext/eigen/test/qr.cpp +++ b/testbed/nanogui/ext/eigen/test/qr.cpp @@ -54,6 +54,8 @@ template void qr_invertible() { using std::log; using std::abs; + using std::pow; + using std::max; typedef typename NumTraits::Real RealScalar; typedef typename MatrixType::Scalar Scalar; @@ -65,7 +67,7 @@ template void qr_invertible() if (internal::is_same::value) { // let's build a matrix more stable to inverse - MatrixType a = MatrixType::Random(size,size*2); + MatrixType a = MatrixType::Random(size,size*4); m1 += a * a.adjoint(); } @@ -81,8 +83,11 @@ template void qr_invertible() m3 = qr.householderQ(); // get a unitary m1 = m3 * m1 * m3; qr.compute(m1); - VERIFY_IS_APPROX(absdet, qr.absDeterminant()); VERIFY_IS_APPROX(log(absdet), qr.logAbsDeterminant()); + // This test is tricky if the determinant becomes too small. + // Since we generate random numbers with magnitude rrange [0,1], the average determinant is 0.5^size + VERIFY_IS_MUCH_SMALLER_THAN( abs(absdet-qr.absDeterminant()), numext::maxi(RealScalar(pow(0.5,size)),numext::maxi(abs(absdet),abs(qr.absDeterminant()))) ); + } template void qr_verify_assert() diff --git a/testbed/nanogui/ext/eigen/test/qr_colpivoting.cpp b/testbed/nanogui/ext/eigen/test/qr_colpivoting.cpp index eb3feac0..26ed27f5 100644 --- a/testbed/nanogui/ext/eigen/test/qr_colpivoting.cpp +++ b/testbed/nanogui/ext/eigen/test/qr_colpivoting.cpp @@ -10,21 +10,103 @@ #include "main.h" #include +#include + +template +void cod() { + typedef typename MatrixType::Index Index; + + Index rows = internal::random(2, EIGEN_TEST_MAX_SIZE); + Index cols = internal::random(2, EIGEN_TEST_MAX_SIZE); + Index cols2 = internal::random(2, EIGEN_TEST_MAX_SIZE); + Index rank = internal::random(1, (std::min)(rows, cols) - 1); + + typedef typename MatrixType::Scalar Scalar; + typedef Matrix + MatrixQType; + MatrixType matrix; + createRandomPIMatrixOfRank(rank, rows, cols, matrix); + CompleteOrthogonalDecomposition cod(matrix); + VERIFY(rank == cod.rank()); + VERIFY(cols - cod.rank() == cod.dimensionOfKernel()); + VERIFY(!cod.isInjective()); + VERIFY(!cod.isInvertible()); + VERIFY(!cod.isSurjective()); + + MatrixQType q = cod.householderQ(); + VERIFY_IS_UNITARY(q); + + MatrixType z = cod.matrixZ(); + VERIFY_IS_UNITARY(z); + + MatrixType t; + t.setZero(rows, cols); + t.topLeftCorner(rank, rank) = + cod.matrixT().topLeftCorner(rank, rank).template triangularView(); + + MatrixType c = q * t * z * cod.colsPermutation().inverse(); + VERIFY_IS_APPROX(matrix, c); + + MatrixType exact_solution = MatrixType::Random(cols, cols2); + MatrixType rhs = matrix * exact_solution; + MatrixType cod_solution = cod.solve(rhs); + VERIFY_IS_APPROX(rhs, matrix * cod_solution); + + // Verify that we get the same minimum-norm solution as the SVD. + JacobiSVD svd(matrix, ComputeThinU | ComputeThinV); + MatrixType svd_solution = svd.solve(rhs); + VERIFY_IS_APPROX(cod_solution, svd_solution); + + MatrixType pinv = cod.pseudoInverse(); + VERIFY_IS_APPROX(cod_solution, pinv * rhs); +} + +template +void cod_fixedsize() { + enum { + Rows = MatrixType::RowsAtCompileTime, + Cols = MatrixType::ColsAtCompileTime + }; + typedef typename MatrixType::Scalar Scalar; + int rank = internal::random(1, (std::min)(int(Rows), int(Cols)) - 1); + Matrix matrix; + createRandomPIMatrixOfRank(rank, Rows, Cols, matrix); + CompleteOrthogonalDecomposition > cod(matrix); + VERIFY(rank == cod.rank()); + VERIFY(Cols - cod.rank() == cod.dimensionOfKernel()); + VERIFY(cod.isInjective() == (rank == Rows)); + VERIFY(cod.isSurjective() == (rank == Cols)); + VERIFY(cod.isInvertible() == (cod.isInjective() && cod.isSurjective())); + + Matrix exact_solution; + exact_solution.setRandom(Cols, Cols2); + Matrix rhs = matrix * exact_solution; + Matrix cod_solution = cod.solve(rhs); + VERIFY_IS_APPROX(rhs, matrix * cod_solution); + + // Verify that we get the same minimum-norm solution as the SVD. + JacobiSVD svd(matrix, ComputeFullU | ComputeFullV); + Matrix svd_solution = svd.solve(rhs); + VERIFY_IS_APPROX(cod_solution, svd_solution); +} template void qr() { + using std::sqrt; typedef typename MatrixType::Index Index; Index rows = internal::random(2,EIGEN_TEST_MAX_SIZE), cols = internal::random(2,EIGEN_TEST_MAX_SIZE), cols2 = internal::random(2,EIGEN_TEST_MAX_SIZE); Index rank = internal::random(1, (std::min)(rows, cols)-1); typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; typedef Matrix MatrixQType; MatrixType m1; createRandomPIMatrixOfRank(rank,rows,cols,m1); ColPivHouseholderQR qr(m1); - VERIFY(rank == qr.rank()); - VERIFY(cols - qr.rank() == qr.dimensionOfKernel()); + VERIFY_IS_EQUAL(rank, qr.rank()); + VERIFY_IS_EQUAL(cols - qr.rank(), qr.dimensionOfKernel()); VERIFY(!qr.isInjective()); VERIFY(!qr.isInvertible()); VERIFY(!qr.isSurjective()); @@ -36,26 +118,59 @@ template void qr() MatrixType c = q * r * qr.colsPermutation().inverse(); VERIFY_IS_APPROX(m1, c); + // Verify that the absolute value of the diagonal elements in R are + // non-increasing until they reach the singularity threshold. + RealScalar threshold = + sqrt(RealScalar(rows)) * numext::abs(r(0, 0)) * NumTraits::epsilon(); + for (Index i = 0; i < (std::min)(rows, cols) - 1; ++i) { + RealScalar x = numext::abs(r(i, i)); + RealScalar y = numext::abs(r(i + 1, i + 1)); + if (x < threshold && y < threshold) continue; + if (!test_isApproxOrLessThan(y, x)) { + for (Index j = 0; j < (std::min)(rows, cols); ++j) { + std::cout << "i = " << j << ", |r_ii| = " << numext::abs(r(j, j)) << std::endl; + } + std::cout << "Failure at i=" << i << ", rank=" << rank + << ", threshold=" << threshold << std::endl; + } + VERIFY_IS_APPROX_OR_LESS_THAN(y, x); + } + MatrixType m2 = MatrixType::Random(cols,cols2); MatrixType m3 = m1*m2; m2 = MatrixType::Random(cols,cols2); m2 = qr.solve(m3); VERIFY_IS_APPROX(m3, m1*m2); + + { + Index size = rows; + do { + m1 = MatrixType::Random(size,size); + qr.compute(m1); + } while(!qr.isInvertible()); + MatrixType m1_inv = qr.inverse(); + m3 = m1 * MatrixType::Random(size,cols2); + m2 = qr.solve(m3); + VERIFY_IS_APPROX(m2, m1_inv*m3); + } } template void qr_fixedsize() { + using std::sqrt; + using std::abs; enum { Rows = MatrixType::RowsAtCompileTime, Cols = MatrixType::ColsAtCompileTime }; typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; int rank = internal::random(1, (std::min)(int(Rows), int(Cols))-1); Matrix m1; createRandomPIMatrixOfRank(rank,Rows,Cols,m1); ColPivHouseholderQR > qr(m1); - VERIFY(rank == qr.rank()); - VERIFY(Cols - qr.rank() == qr.dimensionOfKernel()); - VERIFY(qr.isInjective() == (rank == Rows)); - VERIFY(qr.isSurjective() == (rank == Cols)); - VERIFY(qr.isInvertible() == (qr.isInjective() && qr.isSurjective())); + VERIFY_IS_EQUAL(rank, qr.rank()); + VERIFY_IS_EQUAL(Cols - qr.rank(), qr.dimensionOfKernel()); + VERIFY_IS_EQUAL(qr.isInjective(), (rank == Rows)); + VERIFY_IS_EQUAL(qr.isSurjective(), (rank == Cols)); + VERIFY_IS_EQUAL(qr.isInvertible(), (qr.isInjective() && qr.isSurjective())); Matrix r = qr.matrixQR().template triangularView(); Matrix c = qr.householderQ() * r * qr.colsPermutation().inverse(); @@ -66,6 +181,71 @@ template void qr_fixedsize() m2 = Matrix::Random(Cols,Cols2); m2 = qr.solve(m3); VERIFY_IS_APPROX(m3, m1*m2); + // Verify that the absolute value of the diagonal elements in R are + // non-increasing until they reache the singularity threshold. + RealScalar threshold = + sqrt(RealScalar(Rows)) * (std::abs)(r(0, 0)) * NumTraits::epsilon(); + for (Index i = 0; i < (std::min)(int(Rows), int(Cols)) - 1; ++i) { + RealScalar x = numext::abs(r(i, i)); + RealScalar y = numext::abs(r(i + 1, i + 1)); + if (x < threshold && y < threshold) continue; + if (!test_isApproxOrLessThan(y, x)) { + for (Index j = 0; j < (std::min)(int(Rows), int(Cols)); ++j) { + std::cout << "i = " << j << ", |r_ii| = " << numext::abs(r(j, j)) << std::endl; + } + std::cout << "Failure at i=" << i << ", rank=" << rank + << ", threshold=" << threshold << std::endl; + } + VERIFY_IS_APPROX_OR_LESS_THAN(y, x); + } +} + +// This test is meant to verify that pivots are chosen such that +// even for a graded matrix, the diagonal of R falls of roughly +// monotonically until it reaches the threshold for singularity. +// We use the so-called Kahan matrix, which is a famous counter-example +// for rank-revealing QR. See +// http://www.netlib.org/lapack/lawnspdf/lawn176.pdf +// page 3 for more detail. +template void qr_kahan_matrix() +{ + using std::sqrt; + using std::abs; + typedef typename MatrixType::Index Index; + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + + Index rows = 300, cols = rows; + + MatrixType m1; + m1.setZero(rows,cols); + RealScalar s = std::pow(NumTraits::epsilon(), 1.0 / rows); + RealScalar c = std::sqrt(1 - s*s); + RealScalar pow_s_i(1.0); // pow(s,i) + for (Index i = 0; i < rows; ++i) { + m1(i, i) = pow_s_i; + m1.row(i).tail(rows - i - 1) = -pow_s_i * c * MatrixType::Ones(1, rows - i - 1); + pow_s_i *= s; + } + m1 = (m1 + m1.transpose()).eval(); + ColPivHouseholderQR qr(m1); + MatrixType r = qr.matrixQR().template triangularView(); + + RealScalar threshold = + std::sqrt(RealScalar(rows)) * numext::abs(r(0, 0)) * NumTraits::epsilon(); + for (Index i = 0; i < (std::min)(rows, cols) - 1; ++i) { + RealScalar x = numext::abs(r(i, i)); + RealScalar y = numext::abs(r(i + 1, i + 1)); + if (x < threshold && y < threshold) continue; + if (!test_isApproxOrLessThan(y, x)) { + for (Index j = 0; j < (std::min)(rows, cols); ++j) { + std::cout << "i = " << j << ", |r_ii| = " << numext::abs(r(j, j)) << std::endl; + } + std::cout << "Failure at i=" << i << ", rank=" << qr.rank() + << ", threshold=" << threshold << std::endl; + } + VERIFY_IS_APPROX_OR_LESS_THAN(y, x); + } } template void qr_invertible() @@ -131,6 +311,15 @@ void test_qr_colpivoting() CALL_SUBTEST_5(( qr_fixedsize, 1 >() )); } + for(int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_1( cod() ); + CALL_SUBTEST_2( cod() ); + CALL_SUBTEST_3( cod() ); + CALL_SUBTEST_4(( cod_fixedsize, 4 >() )); + CALL_SUBTEST_5(( cod_fixedsize, 3 >() )); + CALL_SUBTEST_5(( cod_fixedsize, 1 >() )); + } + for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( qr_invertible() ); CALL_SUBTEST_2( qr_invertible() ); @@ -147,4 +336,7 @@ void test_qr_colpivoting() // Test problem size constructors CALL_SUBTEST_9(ColPivHouseholderQR(10, 20)); + + CALL_SUBTEST_1( qr_kahan_matrix() ); + CALL_SUBTEST_2( qr_kahan_matrix() ); } diff --git a/testbed/nanogui/ext/eigen/test/qr_fullpivoting.cpp b/testbed/nanogui/ext/eigen/test/qr_fullpivoting.cpp index 511f2473..70e89c19 100644 --- a/testbed/nanogui/ext/eigen/test/qr_fullpivoting.cpp +++ b/testbed/nanogui/ext/eigen/test/qr_fullpivoting.cpp @@ -15,16 +15,20 @@ template void qr() { typedef typename MatrixType::Index Index; - Index rows = internal::random(20,200), cols = internal::random(20,200), cols2 = internal::random(20,200); - Index rank = internal::random(1, (std::min)(rows, cols)-1); + Index max_size = EIGEN_TEST_MAX_SIZE; + Index min_size = numext::maxi(1,EIGEN_TEST_MAX_SIZE/10); + Index rows = internal::random(min_size,max_size), + cols = internal::random(min_size,max_size), + cols2 = internal::random(min_size,max_size), + rank = internal::random(1, (std::min)(rows, cols)-1); typedef typename MatrixType::Scalar Scalar; typedef Matrix MatrixQType; MatrixType m1; createRandomPIMatrixOfRank(rank,rows,cols,m1); FullPivHouseholderQR qr(m1); - VERIFY(rank == qr.rank()); - VERIFY(cols - qr.rank() == qr.dimensionOfKernel()); + VERIFY_IS_EQUAL(rank, qr.rank()); + VERIFY_IS_EQUAL(cols - qr.rank(), qr.dimensionOfKernel()); VERIFY(!qr.isInjective()); VERIFY(!qr.isInvertible()); VERIFY(!qr.isSurjective()); @@ -40,12 +44,28 @@ template void qr() MatrixType c = qr.matrixQ() * r * qr.colsPermutation().inverse(); VERIFY_IS_APPROX(m1, c); - + + // stress the ReturnByValue mechanism + MatrixType tmp; + VERIFY_IS_APPROX(tmp.noalias() = qr.matrixQ() * r, (qr.matrixQ() * r).eval()); + MatrixType m2 = MatrixType::Random(cols,cols2); MatrixType m3 = m1*m2; m2 = MatrixType::Random(cols,cols2); m2 = qr.solve(m3); VERIFY_IS_APPROX(m3, m1*m2); + + { + Index size = rows; + do { + m1 = MatrixType::Random(size,size); + qr.compute(m1); + } while(!qr.isInvertible()); + MatrixType m1_inv = qr.inverse(); + m3 = m1 * MatrixType::Random(size,cols2); + m2 = qr.solve(m3); + VERIFY_IS_APPROX(m2, m1_inv*m3); + } } template void qr_invertible() @@ -55,7 +75,9 @@ template void qr_invertible() typedef typename NumTraits::Real RealScalar; typedef typename MatrixType::Scalar Scalar; - int size = internal::random(10,50); + Index max_size = numext::mini(50,EIGEN_TEST_MAX_SIZE); + Index min_size = numext::maxi(1,EIGEN_TEST_MAX_SIZE/10); + Index size = internal::random(min_size,max_size); MatrixType m1(size, size), m2(size, size), m3(size, size); m1 = MatrixType::Random(size,size); diff --git a/testbed/nanogui/ext/eigen/test/rand.cpp b/testbed/nanogui/ext/eigen/test/rand.cpp new file mode 100644 index 00000000..51cf0177 --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/rand.cpp @@ -0,0 +1,118 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "main.h" + +typedef long long int64; + +template Scalar check_in_range(Scalar x, Scalar y) +{ + Scalar r = internal::random(x,y); + VERIFY(r>=x); + if(y>=x) + { + VERIFY(r<=y); + } + return r; +} + +template void check_all_in_range(Scalar x, Scalar y) +{ + Array mask(y-x+1); + mask.fill(0); + long n = (y-x+1)*32; + for(long k=0; k0).all() ); +} + +template void check_histogram(Scalar x, Scalar y, int bins) +{ + Array hist(bins); + hist.fill(0); + int f = 100000; + int n = bins*f; + int64 range = int64(y)-int64(x); + int divisor = int((range+1)/bins); + assert(((range+1)%bins)==0); + for(int k=0; k()/double(f))-1.0).abs()<0.02).all() ); +} + +void test_rand() +{ + long long_ref = NumTraits::highest()/10; + signed char char_offset = (std::min)(g_repeat,64); + signed char short_offset = (std::min)(g_repeat,16000); + + for(int i = 0; i < g_repeat*10000; i++) { + CALL_SUBTEST(check_in_range(10,11)); + CALL_SUBTEST(check_in_range(1.24234523,1.24234523)); + CALL_SUBTEST(check_in_range(-1,1)); + CALL_SUBTEST(check_in_range(-1432.2352,-1432.2352)); + + CALL_SUBTEST(check_in_range(10,11)); + CALL_SUBTEST(check_in_range(1.24234523,1.24234523)); + CALL_SUBTEST(check_in_range(-1,1)); + CALL_SUBTEST(check_in_range(-1432.2352,-1432.2352)); + + CALL_SUBTEST(check_in_range(0,-1)); + CALL_SUBTEST(check_in_range(0,-1)); + CALL_SUBTEST(check_in_range(0,-1)); + CALL_SUBTEST(check_in_range(-673456,673456)); + CALL_SUBTEST(check_in_range(-RAND_MAX+10,RAND_MAX-10)); + CALL_SUBTEST(check_in_range(-24345,24345)); + CALL_SUBTEST(check_in_range(-long_ref,long_ref)); + } + + CALL_SUBTEST(check_all_in_range(11,11)); + CALL_SUBTEST(check_all_in_range(11,11+char_offset)); + CALL_SUBTEST(check_all_in_range(-5,5)); + CALL_SUBTEST(check_all_in_range(-11-char_offset,-11)); + CALL_SUBTEST(check_all_in_range(-126,-126+char_offset)); + CALL_SUBTEST(check_all_in_range(126-char_offset,126)); + CALL_SUBTEST(check_all_in_range(-126,126)); + + CALL_SUBTEST(check_all_in_range(11,11)); + CALL_SUBTEST(check_all_in_range(11,11+short_offset)); + CALL_SUBTEST(check_all_in_range(-5,5)); + CALL_SUBTEST(check_all_in_range(-11-short_offset,-11)); + CALL_SUBTEST(check_all_in_range(-24345,-24345+short_offset)); + CALL_SUBTEST(check_all_in_range(24345,24345+short_offset)); + + CALL_SUBTEST(check_all_in_range(11,11)); + CALL_SUBTEST(check_all_in_range(11,11+g_repeat)); + CALL_SUBTEST(check_all_in_range(-5,5)); + CALL_SUBTEST(check_all_in_range(-11-g_repeat,-11)); + CALL_SUBTEST(check_all_in_range(-673456,-673456+g_repeat)); + CALL_SUBTEST(check_all_in_range(673456,673456+g_repeat)); + + CALL_SUBTEST(check_all_in_range(11,11)); + CALL_SUBTEST(check_all_in_range(11,11+g_repeat)); + CALL_SUBTEST(check_all_in_range(-5,5)); + CALL_SUBTEST(check_all_in_range(-11-g_repeat,-11)); + CALL_SUBTEST(check_all_in_range(-long_ref,-long_ref+g_repeat)); + CALL_SUBTEST(check_all_in_range( long_ref, long_ref+g_repeat)); + + CALL_SUBTEST(check_histogram(-5,5,11)); + int bins = 100; + CALL_SUBTEST(check_histogram(-3333,-3333+bins*(3333/bins)-1,bins)); + bins = 1000; + CALL_SUBTEST(check_histogram(-RAND_MAX+10,-RAND_MAX+10+bins*(RAND_MAX/bins)-1,bins)); + CALL_SUBTEST(check_histogram(-RAND_MAX+10,-int64(RAND_MAX)+10+bins*(2*int64(RAND_MAX)/bins)-1,bins)); +} diff --git a/testbed/nanogui/ext/eigen/test/real_qz.cpp b/testbed/nanogui/ext/eigen/test/real_qz.cpp index 7d743a73..99ac3123 100644 --- a/testbed/nanogui/ext/eigen/test/real_qz.cpp +++ b/testbed/nanogui/ext/eigen/test/real_qz.cpp @@ -7,6 +7,7 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +#define EIGEN_RUNTIME_NO_MALLOC #include "main.h" #include #include @@ -25,7 +26,27 @@ template void real_qz(const MatrixType& m) MatrixType A = MatrixType::Random(dim,dim), B = MatrixType::Random(dim,dim); - RealQZ qz(A,B); + + // Regression test for bug 985: Randomly set rows or columns to zero + Index k=internal::random(0, dim-1); + switch(internal::random(0,10)) { + case 0: + A.row(k).setZero(); break; + case 1: + A.col(k).setZero(); break; + case 2: + B.row(k).setZero(); break; + case 3: + B.col(k).setZero(); break; + default: + break; + } + + RealQZ qz(dim); + // TODO enable full-prealocation of required memory, this probably requires an in-place mode for HessenbergDecomposition + //Eigen::internal::set_is_malloc_allowed(false); + qz.compute(A,B); + //Eigen::internal::set_is_malloc_allowed(true); VERIFY_IS_EQUAL(qz.info(), Success); // check for zeros @@ -33,11 +54,20 @@ template void real_qz(const MatrixType& m) for (Index i=0; i void matrixRedux(const MatrixType& m) @@ -21,7 +24,7 @@ template void matrixRedux(const MatrixType& m) MatrixType m1 = MatrixType::Random(rows, cols); // The entries of m1 are uniformly distributed in [0,1], so m1.prod() is very small. This may lead to test - // failures if we underflow into denormals. Thus, we scale so that entires are close to 1. + // failures if we underflow into denormals. Thus, we scale so that entries are close to 1. MatrixType m1_for_prod = MatrixType::Ones(rows, cols) + RealScalar(0.2) * m1; VERIFY_IS_MUCH_SMALLER_THAN(MatrixType::Zero(rows, cols).sum(), Scalar(1)); @@ -53,10 +56,24 @@ template void matrixRedux(const MatrixType& m) VERIFY_IS_APPROX(m1_for_prod.block(r0,c0,r1,c1).prod(), m1_for_prod.block(r0,c0,r1,c1).eval().prod()); VERIFY_IS_APPROX(m1.block(r0,c0,r1,c1).real().minCoeff(), m1.block(r0,c0,r1,c1).real().eval().minCoeff()); VERIFY_IS_APPROX(m1.block(r0,c0,r1,c1).real().maxCoeff(), m1.block(r0,c0,r1,c1).real().eval().maxCoeff()); + + // regression for bug 1090 + const int R1 = MatrixType::RowsAtCompileTime>=2 ? MatrixType::RowsAtCompileTime/2 : 6; + const int C1 = MatrixType::ColsAtCompileTime>=2 ? MatrixType::ColsAtCompileTime/2 : 6; + if(R1<=rows-r0 && C1<=cols-c0) + { + VERIFY_IS_APPROX( (m1.template block(r0,c0).sum()), m1.block(r0,c0,R1,C1).sum() ); + } // test empty objects VERIFY_IS_APPROX(m1.block(r0,c0,0,0).sum(), Scalar(0)); VERIFY_IS_APPROX(m1.block(r0,c0,0,0).prod(), Scalar(1)); + + // test nesting complex expression + VERIFY_EVALUATION_COUNT( (m1.matrix()*m1.matrix().transpose()).sum(), (MatrixType::IsVectorAtCompileTime && MatrixType::SizeAtCompileTime!=1 ? 0 : 1) ); + Matrix m2(rows,rows); + m2.setRandom(); + VERIFY_EVALUATION_COUNT( ((m1.matrix()*m1.matrix().transpose())+m2).sum(),(MatrixType::IsVectorAtCompileTime && MatrixType::SizeAtCompileTime!=1 ? 0 : 1)); } template void vectorRedux(const VectorType& w) @@ -139,8 +156,10 @@ void test_redux() CALL_SUBTEST_1( matrixRedux(Array()) ); CALL_SUBTEST_2( matrixRedux(Matrix2f()) ); CALL_SUBTEST_2( matrixRedux(Array2f()) ); + CALL_SUBTEST_2( matrixRedux(Array22f()) ); CALL_SUBTEST_3( matrixRedux(Matrix4d()) ); CALL_SUBTEST_3( matrixRedux(Array4d()) ); + CALL_SUBTEST_3( matrixRedux(Array44d()) ); CALL_SUBTEST_4( matrixRedux(MatrixXcf(internal::random(1,maxsize), internal::random(1,maxsize))) ); CALL_SUBTEST_4( matrixRedux(ArrayXXcf(internal::random(1,maxsize), internal::random(1,maxsize))) ); CALL_SUBTEST_5( matrixRedux(MatrixXd (internal::random(1,maxsize), internal::random(1,maxsize))) ); diff --git a/testbed/nanogui/ext/eigen/test/ref.cpp b/testbed/nanogui/ext/eigen/test/ref.cpp index 32eb3104..769db041 100644 --- a/testbed/nanogui/ext/eigen/test/ref.cpp +++ b/testbed/nanogui/ext/eigen/test/ref.cpp @@ -12,28 +12,24 @@ #undef EIGEN_DEFAULT_TO_ROW_MAJOR #endif -static int nb_temporaries; - -inline void on_temporary_creation(int) { - // here's a great place to set a breakpoint when debugging failures in this test! - nb_temporaries++; -} - - -#define EIGEN_DENSE_STORAGE_CTOR_PLUGIN { on_temporary_creation(size); } +#define TEST_ENABLE_TEMPORARY_TRACKING #include "main.h" -#define VERIFY_EVALUATION_COUNT(XPR,N) {\ - nb_temporaries = 0; \ - XPR; \ - if(nb_temporaries!=N) std::cerr << "nb_temporaries == " << nb_temporaries << "\n"; \ - VERIFY( (#XPR) && nb_temporaries==N ); \ - } - - // test Ref.h +// Deal with i387 extended precision +#if EIGEN_ARCH_i386 && !(EIGEN_ARCH_x86_64) + +#if EIGEN_COMP_GNUC_STRICT && EIGEN_GNUC_AT_LEAST(4,4) +#pragma GCC optimize ("-ffloat-store") +#else +#undef VERIFY_IS_EQUAL +#define VERIFY_IS_EQUAL(X,Y) VERIFY_IS_APPROX(X,Y) +#endif + +#endif + template void ref_matrix(const MatrixType& m) { typedef typename MatrixType::Index Index; @@ -71,7 +67,6 @@ template void ref_matrix(const MatrixType& m) rm2 = m2.block(i,j,brows,bcols); VERIFY_IS_EQUAL(m1, m2); - ConstRefDynMat rm3 = m1.block(i,j,brows,bcols); m1.block(i,j,brows,bcols) *= 2; m2.block(i,j,brows,bcols) *= 2; @@ -229,6 +224,37 @@ void call_ref() VERIFY_EVALUATION_COUNT( call_ref_7(c,c), 0); } +typedef Matrix RowMatrixXd; +int test_ref_overload_fun1(Ref ) { return 1; } +int test_ref_overload_fun1(Ref ) { return 2; } +int test_ref_overload_fun1(Ref ) { return 3; } + +int test_ref_overload_fun2(Ref ) { return 4; } +int test_ref_overload_fun2(Ref ) { return 5; } + +void test_ref_ambiguous(const Ref &A, Ref B) +{ + B = A; + B = A - A; +} + +// See also bug 969 +void test_ref_overloads() +{ + MatrixXd Ad, Bd; + RowMatrixXd rAd, rBd; + VERIFY( test_ref_overload_fun1(Ad)==1 ); + VERIFY( test_ref_overload_fun1(rAd)==2 ); + + MatrixXf Af, Bf; + VERIFY( test_ref_overload_fun2(Ad)==4 ); + VERIFY( test_ref_overload_fun2(Ad+Bd)==4 ); + VERIFY( test_ref_overload_fun2(Af+Bf)==5 ); + + ArrayXd A, B; + test_ref_ambiguous(A, B); +} + void test_ref() { for(int i = 0; i < g_repeat; i++) { @@ -249,4 +275,6 @@ void test_ref() CALL_SUBTEST_5( ref_matrix(MatrixXi(internal::random(1,10),internal::random(1,10))) ); CALL_SUBTEST_6( call_ref() ); } + + CALL_SUBTEST_7( test_ref_overloads() ); } diff --git a/testbed/nanogui/ext/eigen/test/runtest.sh b/testbed/nanogui/ext/eigen/test/runtest.sh deleted file mode 100755 index 2be25081..00000000 --- a/testbed/nanogui/ext/eigen/test/runtest.sh +++ /dev/null @@ -1,20 +0,0 @@ -#!/bin/bash - -black='\E[30m' -red='\E[31m' -green='\E[32m' -yellow='\E[33m' -blue='\E[34m' -magenta='\E[35m' -cyan='\E[36m' -white='\E[37m' - -if ! ./$1 > /dev/null 2> .runtest.log ; then - echo -e $red Test $1 failed: $black - echo -e $blue - cat .runtest.log - echo -e $black - exit 1 -else -echo -e $green Test $1 passed$black -fi diff --git a/testbed/nanogui/ext/eigen/test/rvalue_types.cpp b/testbed/nanogui/ext/eigen/test/rvalue_types.cpp new file mode 100644 index 00000000..8887f1b1 --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/rvalue_types.cpp @@ -0,0 +1,64 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2013 Hauke Heibel +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "main.h" + +#include + +using internal::UIntPtr; + +#if EIGEN_HAS_RVALUE_REFERENCES +template +void rvalue_copyassign(const MatrixType& m) +{ + + typedef typename internal::traits::Scalar Scalar; + + // create a temporary which we are about to destroy by moving + MatrixType tmp = m; + UIntPtr src_address = reinterpret_cast(tmp.data()); + + // move the temporary to n + MatrixType n = std::move(tmp); + UIntPtr dst_address = reinterpret_cast(n.data()); + + if (MatrixType::RowsAtCompileTime==Dynamic|| MatrixType::ColsAtCompileTime==Dynamic) + { + // verify that we actually moved the guts + VERIFY_IS_EQUAL(src_address, dst_address); + } + + // verify that the content did not change + Scalar abs_diff = (m-n).array().abs().sum(); + VERIFY_IS_EQUAL(abs_diff, Scalar(0)); +} +#else +template +void rvalue_copyassign(const MatrixType&) {} +#endif + +void test_rvalue_types() +{ + CALL_SUBTEST_1(rvalue_copyassign( MatrixXf::Random(50,50).eval() )); + CALL_SUBTEST_1(rvalue_copyassign( ArrayXXf::Random(50,50).eval() )); + + CALL_SUBTEST_1(rvalue_copyassign( Matrix::Random(50).eval() )); + CALL_SUBTEST_1(rvalue_copyassign( Array::Random(50).eval() )); + + CALL_SUBTEST_1(rvalue_copyassign( Matrix::Random(50).eval() )); + CALL_SUBTEST_1(rvalue_copyassign( Array::Random(50).eval() )); + + CALL_SUBTEST_2(rvalue_copyassign( Array::Random().eval() )); + CALL_SUBTEST_2(rvalue_copyassign( Array::Random().eval() )); + CALL_SUBTEST_2(rvalue_copyassign( Array::Random().eval() )); + + CALL_SUBTEST_2(rvalue_copyassign( Array::Random().eval() )); + CALL_SUBTEST_2(rvalue_copyassign( Array::Random().eval() )); + CALL_SUBTEST_2(rvalue_copyassign( Array::Random().eval() )); +} diff --git a/testbed/nanogui/ext/eigen/test/schur_complex.cpp b/testbed/nanogui/ext/eigen/test/schur_complex.cpp index 5e869790..deb78e44 100644 --- a/testbed/nanogui/ext/eigen/test/schur_complex.cpp +++ b/testbed/nanogui/ext/eigen/test/schur_complex.cpp @@ -25,7 +25,7 @@ template void schur(int size = MatrixType::ColsAtCompileTim ComplexMatrixType T = schurOfA.matrixT(); for(int row = 1; row < size; ++row) { for(int col = 0; col < row; ++col) { - VERIFY(T(row,col) == (typename MatrixType::Scalar)0); + VERIFY(T(row,col) == (typename MatrixType::Scalar)0); } } VERIFY_IS_APPROX(A.template cast(), U * T * U.adjoint()); @@ -70,7 +70,7 @@ template void schur(int size = MatrixType::ColsAtCompileTim VERIFY_IS_EQUAL(cs1.matrixT(), csOnlyT.matrixT()); VERIFY_RAISES_ASSERT(csOnlyT.matrixU()); - if (size > 1) + if (size > 1 && size < 20) { // Test matrix with NaN A(0,0) = std::numeric_limits::quiet_NaN(); diff --git a/testbed/nanogui/ext/eigen/test/schur_real.cpp b/testbed/nanogui/ext/eigen/test/schur_real.cpp index 36b9c24d..4aede87d 100644 --- a/testbed/nanogui/ext/eigen/test/schur_real.cpp +++ b/testbed/nanogui/ext/eigen/test/schur_real.cpp @@ -82,7 +82,7 @@ template void schur(int size = MatrixType::ColsAtCompileTim Atriangular.template triangularView().setZero(); rs3.setMaxIterations(1).compute(Atriangular); // triangular matrices do not need any iterations VERIFY_IS_EQUAL(rs3.info(), Success); - VERIFY_IS_EQUAL(rs3.matrixT(), Atriangular); + VERIFY_IS_APPROX(rs3.matrixT(), Atriangular); // approx because of scaling... VERIFY_IS_EQUAL(rs3.matrixU(), MatrixType::Identity(size, size)); // Test computation of only T, not U @@ -91,7 +91,7 @@ template void schur(int size = MatrixType::ColsAtCompileTim VERIFY_IS_EQUAL(rs1.matrixT(), rsOnlyT.matrixT()); VERIFY_RAISES_ASSERT(rsOnlyT.matrixU()); - if (size > 2) + if (size > 2 && size < 20) { // Test matrix with NaN A(0,0) = std::numeric_limits::quiet_NaN(); diff --git a/testbed/nanogui/ext/eigen/test/selfadjoint.cpp b/testbed/nanogui/ext/eigen/test/selfadjoint.cpp index 76dab6d6..92401e50 100644 --- a/testbed/nanogui/ext/eigen/test/selfadjoint.cpp +++ b/testbed/nanogui/ext/eigen/test/selfadjoint.cpp @@ -21,7 +21,9 @@ template void selfadjoint(const MatrixType& m) Index cols = m.cols(); MatrixType m1 = MatrixType::Random(rows, cols), - m3(rows, cols); + m2 = MatrixType::Random(rows, cols), + m3(rows, cols), + m4(rows, cols); m1.diagonal() = m1.diagonal().real().template cast(); @@ -30,10 +32,19 @@ template void selfadjoint(const MatrixType& m) VERIFY_IS_APPROX(MatrixType(m3.template triangularView()), MatrixType(m1.template triangularView())); VERIFY_IS_APPROX(m3, m3.adjoint()); - m3 = m1.template selfadjointView(); VERIFY_IS_APPROX(MatrixType(m3.template triangularView()), MatrixType(m1.template triangularView())); VERIFY_IS_APPROX(m3, m3.adjoint()); + + m3 = m1.template selfadjointView(); + m4 = m2; + m4 += m1.template selfadjointView(); + VERIFY_IS_APPROX(m4, m2+m3); + + m3 = m1.template selfadjointView(); + m4 = m2; + m4 -= m1.template selfadjointView(); + VERIFY_IS_APPROX(m4, m2-m3); } void bug_159() diff --git a/testbed/nanogui/ext/eigen/test/simplicial_cholesky.cpp b/testbed/nanogui/ext/eigen/test/simplicial_cholesky.cpp index 78646842..649c817b 100644 --- a/testbed/nanogui/ext/eigen/test/simplicial_cholesky.cpp +++ b/testbed/nanogui/ext/eigen/test/simplicial_cholesky.cpp @@ -9,16 +9,17 @@ #include "sparse_solver.h" -template void test_simplicial_cholesky_T() +template void test_simplicial_cholesky_T() { - SimplicialCholesky, Lower> chol_colmajor_lower_amd; - SimplicialCholesky, Upper> chol_colmajor_upper_amd; - SimplicialLLT, Lower> llt_colmajor_lower_amd; - SimplicialLLT, Upper> llt_colmajor_upper_amd; - SimplicialLDLT, Lower> ldlt_colmajor_lower_amd; - SimplicialLDLT, Upper> ldlt_colmajor_upper_amd; - SimplicialLDLT, Lower, NaturalOrdering > ldlt_colmajor_lower_nat; - SimplicialLDLT, Upper, NaturalOrdering > ldlt_colmajor_upper_nat; + typedef SparseMatrix SparseMatrixType; + SimplicialCholesky chol_colmajor_lower_amd; + SimplicialCholesky chol_colmajor_upper_amd; + SimplicialLLT< SparseMatrixType, Lower> llt_colmajor_lower_amd; + SimplicialLLT< SparseMatrixType, Upper> llt_colmajor_upper_amd; + SimplicialLDLT< SparseMatrixType, Lower> ldlt_colmajor_lower_amd; + SimplicialLDLT< SparseMatrixType, Upper> ldlt_colmajor_upper_amd; + SimplicialLDLT< SparseMatrixType, Lower, NaturalOrdering > ldlt_colmajor_lower_nat; + SimplicialLDLT< SparseMatrixType, Upper, NaturalOrdering > ldlt_colmajor_upper_nat; check_sparse_spd_solving(chol_colmajor_lower_amd); check_sparse_spd_solving(chol_colmajor_upper_amd); @@ -34,12 +35,13 @@ template void test_simplicial_cholesky_T() check_sparse_spd_determinant(ldlt_colmajor_lower_amd); check_sparse_spd_determinant(ldlt_colmajor_upper_amd); - check_sparse_spd_solving(ldlt_colmajor_lower_nat); - check_sparse_spd_solving(ldlt_colmajor_upper_nat); + check_sparse_spd_solving(ldlt_colmajor_lower_nat, 300, 1000); + check_sparse_spd_solving(ldlt_colmajor_upper_nat, 300, 1000); } void test_simplicial_cholesky() { - CALL_SUBTEST_1(test_simplicial_cholesky_T()); - CALL_SUBTEST_2(test_simplicial_cholesky_T >()); + CALL_SUBTEST_1(( test_simplicial_cholesky_T() )); + CALL_SUBTEST_2(( test_simplicial_cholesky_T, int>() )); + CALL_SUBTEST_3(( test_simplicial_cholesky_T() )); } diff --git a/testbed/nanogui/ext/eigen/test/sizeof.cpp b/testbed/nanogui/ext/eigen/test/sizeof.cpp index d9ad3562..03ad2045 100644 --- a/testbed/nanogui/ext/eigen/test/sizeof.cpp +++ b/testbed/nanogui/ext/eigen/test/sizeof.cpp @@ -13,14 +13,27 @@ template void verifySizeOf(const MatrixType&) { typedef typename MatrixType::Scalar Scalar; if (MatrixType::RowsAtCompileTime!=Dynamic && MatrixType::ColsAtCompileTime!=Dynamic) - VERIFY(std::ptrdiff_t(sizeof(MatrixType))==std::ptrdiff_t(sizeof(Scalar))*std::ptrdiff_t(MatrixType::SizeAtCompileTime)); + VERIFY_IS_EQUAL(std::ptrdiff_t(sizeof(MatrixType)),std::ptrdiff_t(sizeof(Scalar))*std::ptrdiff_t(MatrixType::SizeAtCompileTime)); else - VERIFY(sizeof(MatrixType)==sizeof(Scalar*) + 2 * sizeof(typename MatrixType::Index)); + VERIFY_IS_EQUAL(sizeof(MatrixType),sizeof(Scalar*) + 2 * sizeof(typename MatrixType::Index)); } void test_sizeof() { CALL_SUBTEST(verifySizeOf(Matrix()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Vector2d()) ); + CALL_SUBTEST(verifySizeOf(Vector4f()) ); CALL_SUBTEST(verifySizeOf(Matrix4d()) ); CALL_SUBTEST(verifySizeOf(Matrix()) ); CALL_SUBTEST(verifySizeOf(Matrix()) ); diff --git a/testbed/nanogui/ext/eigen/test/sizeoverflow.cpp b/testbed/nanogui/ext/eigen/test/sizeoverflow.cpp index 16d6f8d0..240d2229 100644 --- a/testbed/nanogui/ext/eigen/test/sizeoverflow.cpp +++ b/testbed/nanogui/ext/eigen/test/sizeoverflow.cpp @@ -18,8 +18,6 @@ VERIFY(threw && "should have thrown bad_alloc: " #a); \ } -typedef DenseIndex Index; - template void triggerMatrixBadAlloc(Index rows, Index cols) { diff --git a/testbed/nanogui/ext/eigen/test/sparse.h b/testbed/nanogui/ext/eigen/test/sparse.h index e19a7631..9912e1e2 100644 --- a/testbed/nanogui/ext/eigen/test/sparse.h +++ b/testbed/nanogui/ext/eigen/test/sparse.h @@ -53,15 +53,15 @@ enum { * \param zeroCoords and nonzeroCoords allows to get the coordinate lists of the non zero, * and zero coefficients respectively. */ -template void +template void initSparse(double density, Matrix& refMat, - SparseMatrix& sparseMat, + SparseMatrix& sparseMat, int flags = 0, - std::vector >* zeroCoords = 0, - std::vector >* nonzeroCoords = 0) + std::vector >* zeroCoords = 0, + std::vector >* nonzeroCoords = 0) { - enum { IsRowMajor = SparseMatrix::IsRowMajor }; + enum { IsRowMajor = SparseMatrix::IsRowMajor }; sparseMat.setZero(); //sparseMat.reserve(int(refMat.rows()*refMat.cols()*density)); sparseMat.reserve(VectorXi::Constant(IsRowMajor ? refMat.rows() : refMat.cols(), int((1.5*density)*(IsRowMajor?refMat.cols():refMat.rows())))); @@ -71,14 +71,17 @@ initSparse(double density, //sparseMat.startVec(j); for(Index i=0; i(0,1) < density) ? internal::random() : Scalar(0); if ((flags&ForceNonZeroDiag) && (i==j)) { + // FIXME: the following is too conservative v = internal::random()*Scalar(3.); - v = v*v + Scalar(5.); + v = v*v; + if(numext::real(v)>0) v += Scalar(5); + else v -= Scalar(5); } if ((flags & MakeLowerTriangular) && aj>ai) v = Scalar(0); @@ -93,11 +96,11 @@ initSparse(double density, //sparseMat.insertBackByOuterInner(j,i) = v; sparseMat.insertByOuterInner(j,i) = v; if (nonzeroCoords) - nonzeroCoords->push_back(Matrix (ai,aj)); + nonzeroCoords->push_back(Matrix (ai,aj)); } else if (zeroCoords) { - zeroCoords->push_back(Matrix (ai,aj)); + zeroCoords->push_back(Matrix (ai,aj)); } refMat(ai,aj) = v; } @@ -163,7 +166,7 @@ initSparse(double density, { sparseVec.reserve(int(refVec.size()*density)); sparseVec.setZero(); - for(Index i=0; i(0,1) < density) ? internal::random() : Scalar(0); if (v!=Scalar(0)) diff --git a/testbed/nanogui/ext/eigen/test/sparse_basic.cpp b/testbed/nanogui/ext/eigen/test/sparse_basic.cpp index 498ecfe2..38498502 100644 --- a/testbed/nanogui/ext/eigen/test/sparse_basic.cpp +++ b/testbed/nanogui/ext/eigen/test/sparse_basic.cpp @@ -9,16 +9,23 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +static long g_realloc_count = 0; +#define EIGEN_SPARSE_COMPRESSED_STORAGE_REALLOCATE_PLUGIN g_realloc_count++; + #include "sparse.h" template void sparse_basic(const SparseMatrixType& ref) { - typedef typename SparseMatrixType::Index Index; - typedef Matrix Vector2; + typedef typename SparseMatrixType::StorageIndex StorageIndex; + typedef Matrix Vector2; const Index rows = ref.rows(); const Index cols = ref.cols(); + //const Index inner = ref.innerSize(); + //const Index outer = ref.outerSize(); + typedef typename SparseMatrixType::Scalar Scalar; + typedef typename SparseMatrixType::RealScalar RealScalar; enum { Flags = SparseMatrixType::Flags }; double density = (std::max)(8./(rows*cols), 0.01); @@ -36,63 +43,22 @@ template void sparse_basic(const SparseMatrixType& re std::vector nonzeroCoords; initSparse(density, refMat, m, 0, &zeroCoords, &nonzeroCoords); - if (zeroCoords.size()==0 || nonzeroCoords.size()==0) - return; - // test coeff and coeffRef - for (int i=0; i<(int)zeroCoords.size(); ++i) + for (std::size_t i=0; i >::value) - VERIFY_RAISES_ASSERT( m.coeffRef(zeroCoords[0].x(),zeroCoords[0].y()) = 5 ); + VERIFY_RAISES_ASSERT( m.coeffRef(zeroCoords[i].x(),zeroCoords[i].y()) = 5 ); } VERIFY_IS_APPROX(m, refMat); - m.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5); - refMat.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5); + if(!nonzeroCoords.empty()) { + m.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5); + refMat.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5); + } VERIFY_IS_APPROX(m, refMat); - /* - // test InnerIterators and Block expressions - for (int t=0; t<10; ++t) - { - int j = internal::random(0,cols-1); - int i = internal::random(0,rows-1); - int w = internal::random(1,cols-j-1); - int h = internal::random(1,rows-i-1); - // VERIFY_IS_APPROX(m.block(i,j,h,w), refMat.block(i,j,h,w)); - for(int c=0; c void sparse_basic(const SparseMatrixType& re DenseMatrix m1(rows,cols); m1.setZero(); SparseMatrixType m2(rows,cols); - if(internal::random()%2) - m2.reserve(VectorXi::Constant(m2.outerSize(), 2)); + bool call_reserve = internal::random()%2; + Index nnz = internal::random(1,int(rows)/2); + if(call_reserve) + { + if(internal::random()%2) + m2.reserve(VectorXi::Constant(m2.outerSize(), int(nnz))); + else + m2.reserve(m2.outerSize() * nnz); + } + g_realloc_count = 0; for (Index j=0; j(0,rows-1); if (m1.coeff(i,j)==Scalar(0)) m2.insert(i,j) = m1(i,j) = internal::random(); } } + + if(call_reserve && !SparseMatrixType::IsRowMajor) + { + VERIFY(g_realloc_count==0); + } + m2.finalize(); VERIFY_IS_APPROX(m2,m1); } @@ -147,9 +127,9 @@ template void sparse_basic(const SparseMatrixType& re DenseMatrix m1(rows,cols); m1.setZero(); SparseMatrixType m2(rows,cols); - VectorXi r(VectorXi::Constant(m2.outerSize(), ((mode%2)==0) ? m2.innerSize() : std::max(1,m2.innerSize()/8))); + VectorXi r(VectorXi::Constant(m2.outerSize(), ((mode%2)==0) ? int(m2.innerSize()) : std::max(1,int(m2.innerSize())/8))); m2.reserve(r); - for (int k=0; k(0,rows-1); Index j = internal::random(0,cols-1); @@ -163,110 +143,46 @@ template void sparse_basic(const SparseMatrixType& re VERIFY_IS_APPROX(m2,m1); } - // test innerVector() - { - DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows); - SparseMatrixType m2(rows, rows); - initSparse(density, refMat2, m2); - Index j0 = internal::random(0,rows-1); - Index j1 = internal::random(0,rows-1); - if(SparseMatrixType::IsRowMajor) - VERIFY_IS_APPROX(m2.innerVector(j0), refMat2.row(j0)); - else - VERIFY_IS_APPROX(m2.innerVector(j0), refMat2.col(j0)); - - if(SparseMatrixType::IsRowMajor) - VERIFY_IS_APPROX(m2.innerVector(j0)+m2.innerVector(j1), refMat2.row(j0)+refMat2.row(j1)); - else - VERIFY_IS_APPROX(m2.innerVector(j0)+m2.innerVector(j1), refMat2.col(j0)+refMat2.col(j1)); - - SparseMatrixType m3(rows,rows); - m3.reserve(VectorXi::Constant(rows,rows/2)); - for(Index j=0; j0) - VERIFY(j==numext::real(m3.innerVector(j).lastCoeff())); - } - m3.makeCompressed(); - for(Index j=0; j0) - VERIFY(j==numext::real(m3.innerVector(j).lastCoeff())); - } - - //m2.innerVector(j0) = 2*m2.innerVector(j1); - //refMat2.col(j0) = 2*refMat2.col(j1); - //VERIFY_IS_APPROX(m2, refMat2); - } - - // test innerVectors() - { - DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows); - SparseMatrixType m2(rows, rows); - initSparse(density, refMat2, m2); - if(internal::random(0,1)>0.5) m2.makeCompressed(); - - Index j0 = internal::random(0,rows-2); - Index j1 = internal::random(0,rows-2); - Index n0 = internal::random(1,rows-(std::max)(j0,j1)); - if(SparseMatrixType::IsRowMajor) - VERIFY_IS_APPROX(m2.innerVectors(j0,n0), refMat2.block(j0,0,n0,cols)); - else - VERIFY_IS_APPROX(m2.innerVectors(j0,n0), refMat2.block(0,j0,rows,n0)); - if(SparseMatrixType::IsRowMajor) - VERIFY_IS_APPROX(m2.innerVectors(j0,n0)+m2.innerVectors(j1,n0), - refMat2.middleRows(j0,n0)+refMat2.middleRows(j1,n0)); - else - VERIFY_IS_APPROX(m2.innerVectors(j0,n0)+m2.innerVectors(j1,n0), - refMat2.block(0,j0,rows,n0)+refMat2.block(0,j1,rows,n0)); - - VERIFY_IS_APPROX(m2, refMat2); - - m2.innerVectors(j0,n0) = m2.innerVectors(j0,n0) + m2.innerVectors(j1,n0); - if(SparseMatrixType::IsRowMajor) - refMat2.middleRows(j0,n0) = (refMat2.middleRows(j0,n0) + refMat2.middleRows(j1,n0)).eval(); - else - refMat2.middleCols(j0,n0) = (refMat2.middleCols(j0,n0) + refMat2.middleCols(j1,n0)).eval(); - - VERIFY_IS_APPROX(m2, refMat2); - - } - // test basic computations { - DenseMatrix refM1 = DenseMatrix::Zero(rows, rows); - DenseMatrix refM2 = DenseMatrix::Zero(rows, rows); - DenseMatrix refM3 = DenseMatrix::Zero(rows, rows); - DenseMatrix refM4 = DenseMatrix::Zero(rows, rows); - SparseMatrixType m1(rows, rows); - SparseMatrixType m2(rows, rows); - SparseMatrixType m3(rows, rows); - SparseMatrixType m4(rows, rows); + DenseMatrix refM1 = DenseMatrix::Zero(rows, cols); + DenseMatrix refM2 = DenseMatrix::Zero(rows, cols); + DenseMatrix refM3 = DenseMatrix::Zero(rows, cols); + DenseMatrix refM4 = DenseMatrix::Zero(rows, cols); + SparseMatrixType m1(rows, cols); + SparseMatrixType m2(rows, cols); + SparseMatrixType m3(rows, cols); + SparseMatrixType m4(rows, cols); initSparse(density, refM1, m1); initSparse(density, refM2, m2); initSparse(density, refM3, m3); initSparse(density, refM4, m4); + if(internal::random()) + m1.makeCompressed(); + + Index m1_nnz = m1.nonZeros(); + + VERIFY_IS_APPROX(m1*s1, refM1*s1); VERIFY_IS_APPROX(m1+m2, refM1+refM2); VERIFY_IS_APPROX(m1+m2+m3, refM1+refM2+refM3); VERIFY_IS_APPROX(m3.cwiseProduct(m1+m2), refM3.cwiseProduct(refM1+refM2)); VERIFY_IS_APPROX(m1*s1-m2, refM1*s1-refM2); - - VERIFY_IS_APPROX(m1*=s1, refM1*=s1); - VERIFY_IS_APPROX(m1/=s1, refM1/=s1); - - VERIFY_IS_APPROX(m1+=m2, refM1+=refM2); - VERIFY_IS_APPROX(m1-=m2, refM1-=refM2); + VERIFY_IS_APPROX(m4=m1/s1, refM1/s1); + VERIFY_IS_EQUAL(m4.nonZeros(), m1_nnz); if(SparseMatrixType::IsRowMajor) VERIFY_IS_APPROX(m1.innerVector(0).dot(refM2.row(0)), refM1.row(0).dot(refM2.row(0))); else - VERIFY_IS_APPROX(m1.innerVector(0).dot(refM2.row(0)), refM1.col(0).dot(refM2.row(0))); + VERIFY_IS_APPROX(m1.innerVector(0).dot(refM2.col(0)), refM1.col(0).dot(refM2.col(0))); + + DenseVector rv = DenseVector::Random(m1.cols()); + DenseVector cv = DenseVector::Random(m1.rows()); + Index r = internal::random(0,m1.rows()-2); + Index c = internal::random(0,m1.cols()-1); + VERIFY_IS_APPROX(( m1.template block<1,Dynamic>(r,0,1,m1.cols()).dot(rv)) , refM1.row(r).dot(rv)); + VERIFY_IS_APPROX(m1.row(r).dot(rv), refM1.row(r).dot(rv)); + VERIFY_IS_APPROX(m1.col(c).dot(cv), refM1.col(c).dot(cv)); VERIFY_IS_APPROX(m1.conjugate(), refM1.conjugate()); VERIFY_IS_APPROX(m1.real(), refM1.real()); @@ -274,96 +190,167 @@ template void sparse_basic(const SparseMatrixType& re refM4.setRandom(); // sparse cwise* dense VERIFY_IS_APPROX(m3.cwiseProduct(refM4), refM3.cwiseProduct(refM4)); + // dense cwise* sparse + VERIFY_IS_APPROX(refM4.cwiseProduct(m3), refM4.cwiseProduct(refM3)); // VERIFY_IS_APPROX(m3.cwise()/refM4, refM3.cwise()/refM4); + VERIFY_IS_APPROX(refM4 + m3, refM4 + refM3); + VERIFY_IS_APPROX(m3 + refM4, refM3 + refM4); + VERIFY_IS_APPROX(refM4 - m3, refM4 - refM3); + VERIFY_IS_APPROX(m3 - refM4, refM3 - refM4); + VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + RealScalar(0.5)*m3).eval(), RealScalar(0.5)*refM4 + RealScalar(0.5)*refM3); + VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + m3*RealScalar(0.5)).eval(), RealScalar(0.5)*refM4 + RealScalar(0.5)*refM3); + VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + m3.cwiseProduct(m3)).eval(), RealScalar(0.5)*refM4 + refM3.cwiseProduct(refM3)); + + VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + RealScalar(0.5)*m3).eval(), RealScalar(0.5)*refM4 + RealScalar(0.5)*refM3); + VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + m3*RealScalar(0.5)).eval(), RealScalar(0.5)*refM4 + RealScalar(0.5)*refM3); + VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + (m3+m3)).eval(), RealScalar(0.5)*refM4 + (refM3+refM3)); + VERIFY_IS_APPROX(((refM3+m3)+RealScalar(0.5)*m3).eval(), RealScalar(0.5)*refM3 + (refM3+refM3)); + VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + (refM3+m3)).eval(), RealScalar(0.5)*refM4 + (refM3+refM3)); + VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + (m3+refM3)).eval(), RealScalar(0.5)*refM4 + (refM3+refM3)); + + + VERIFY_IS_APPROX(m1.sum(), refM1.sum()); + + m4 = m1; refM4 = m4; + + VERIFY_IS_APPROX(m1*=s1, refM1*=s1); + VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz); + VERIFY_IS_APPROX(m1/=s1, refM1/=s1); + VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz); + + VERIFY_IS_APPROX(m1+=m2, refM1+=refM2); + VERIFY_IS_APPROX(m1-=m2, refM1-=refM2); + + if (rows>=2 && cols>=2) + { + VERIFY_RAISES_ASSERT( m1 += m1.innerVector(0) ); + VERIFY_RAISES_ASSERT( m1 -= m1.innerVector(0) ); + VERIFY_RAISES_ASSERT( refM1 -= m1.innerVector(0) ); + VERIFY_RAISES_ASSERT( refM1 += m1.innerVector(0) ); + m1 = m4; refM1 = refM4; + } + // test aliasing VERIFY_IS_APPROX((m1 = -m1), (refM1 = -refM1)); + VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz); + m1 = m4; refM1 = refM4; VERIFY_IS_APPROX((m1 = m1.transpose()), (refM1 = refM1.transpose().eval())); + VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz); + m1 = m4; refM1 = refM4; VERIFY_IS_APPROX((m1 = -m1.transpose()), (refM1 = -refM1.transpose().eval())); + VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz); + m1 = m4; refM1 = refM4; VERIFY_IS_APPROX((m1 += -m1), (refM1 += -refM1)); + VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz); + m1 = m4; refM1 = refM4; + + if(m1.isCompressed()) + { + VERIFY_IS_APPROX(m1.coeffs().sum(), m1.sum()); + m1.coeffs() += s1; + for(Index j = 0; j SpBool; + SpBool mb1 = m1.real().template cast(); + SpBool mb2 = m2.real().template cast(); + VERIFY_IS_EQUAL(mb1.template cast().sum(), refM1.real().template cast().count()); + VERIFY_IS_EQUAL((mb1 && mb2).template cast().sum(), (refM1.real().template cast() && refM2.real().template cast()).count()); + VERIFY_IS_EQUAL((mb1 || mb2).template cast().sum(), (refM1.real().template cast() || refM2.real().template cast()).count()); + SpBool mb3 = mb1 && mb2; + if(mb1.coeffs().all() && mb2.coeffs().all()) + { + VERIFY_IS_EQUAL(mb3.nonZeros(), (refM1.real().template cast() && refM2.real().template cast()).count()); + } + } + } + + // test reverse iterators + { + DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols); + SparseMatrixType m2(rows, cols); + initSparse(density, refMat2, m2); + std::vector ref_value(m2.innerSize()); + std::vector ref_index(m2.innerSize()); + if(internal::random()) + m2.makeCompressed(); + for(Index j = 0; j(density, refMat2, m2); VERIFY_IS_APPROX(m2.transpose().eval(), refMat2.transpose().eval()); VERIFY_IS_APPROX(m2.transpose(), refMat2.transpose()); VERIFY_IS_APPROX(SparseMatrixType(m2.adjoint()), refMat2.adjoint()); - } - - - - // test generic blocks - { - DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows); - SparseMatrixType m2(rows, rows); - initSparse(density, refMat2, m2); - Index j0 = internal::random(0,rows-2); - Index j1 = internal::random(0,rows-2); - Index n0 = internal::random(1,rows-(std::max)(j0,j1)); - if(SparseMatrixType::IsRowMajor) - VERIFY_IS_APPROX(m2.block(j0,0,n0,cols), refMat2.block(j0,0,n0,cols)); - else - VERIFY_IS_APPROX(m2.block(0,j0,rows,n0), refMat2.block(0,j0,rows,n0)); - if(SparseMatrixType::IsRowMajor) - VERIFY_IS_APPROX(m2.block(j0,0,n0,cols)+m2.block(j1,0,n0,cols), - refMat2.block(j0,0,n0,cols)+refMat2.block(j1,0,n0,cols)); - else - VERIFY_IS_APPROX(m2.block(0,j0,rows,n0)+m2.block(0,j1,rows,n0), - refMat2.block(0,j0,rows,n0)+refMat2.block(0,j1,rows,n0)); - - Index i = internal::random(0,m2.outerSize()-1); - if(SparseMatrixType::IsRowMajor) { - m2.innerVector(i) = m2.innerVector(i) * s1; - refMat2.row(i) = refMat2.row(i) * s1; - VERIFY_IS_APPROX(m2,refMat2); - } else { - m2.innerVector(i) = m2.innerVector(i) * s1; - refMat2.col(i) = refMat2.col(i) * s1; - VERIFY_IS_APPROX(m2,refMat2); - } + // check isApprox handles opposite storage order + typename Transpose::PlainObject m3(m2); + VERIFY(m2.isApprox(m3)); } // test prune { - SparseMatrixType m2(rows, rows); - DenseMatrix refM2(rows, rows); + SparseMatrixType m2(rows, cols); + DenseMatrix refM2(rows, cols); refM2.setZero(); int countFalseNonZero = 0; int countTrueNonZero = 0; - for (Index j=0; j(0,1); - if (x<0.1) + if (x<0.1f) { // do nothing } - else if (x<0.5) + else if (x<0.5f) { countFalseNonZero++; - m2.insertBackByOuterInner(j,i) = Scalar(0); + m2.insert(i,j) = Scalar(0); } else { countTrueNonZero++; - m2.insertBackByOuterInner(j,i) = Scalar(1); - if(SparseMatrixType::IsRowMajor) - refM2(j,i) = Scalar(1); - else - refM2(i,j) = Scalar(1); + m2.insert(i,j) = Scalar(1); + refM2(i,j) = Scalar(1); } } } - m2.finalize(); + if(internal::random()) + m2.makeCompressed(); VERIFY(countFalseNonZero+countTrueNonZero == m2.nonZeros()); - VERIFY_IS_APPROX(m2, refM2); + if(countTrueNonZero>0) + VERIFY_IS_APPROX(m2, refM2); m2.prune(Scalar(1)); VERIFY(countTrueNonZero==m2.nonZeros()); VERIFY_IS_APPROX(m2, refM2); @@ -371,29 +358,74 @@ template void sparse_basic(const SparseMatrixType& re // test setFromTriplets { - typedef Triplet TripletType; + typedef Triplet TripletType; std::vector triplets; - int ntriplets = rows*cols; + Index ntriplets = rows*cols; triplets.reserve(ntriplets); - DenseMatrix refMat(rows,cols); - refMat.setZero(); - for(int i=0;i(0,rows-1); - Index c = internal::random(0,cols-1); + StorageIndex r = internal::random(0,StorageIndex(rows-1)); + StorageIndex c = internal::random(0,StorageIndex(cols-1)); Scalar v = internal::random(); triplets.push_back(TripletType(r,c,v)); - refMat(r,c) += v; + refMat_sum(r,c) += v; + if(std::abs(refMat_prod(r,c))==0) + refMat_prod(r,c) = v; + else + refMat_prod(r,c) *= v; + refMat_last(r,c) = v; } SparseMatrixType m(rows,cols); m.setFromTriplets(triplets.begin(), triplets.end()); - VERIFY_IS_APPROX(m, refMat); + VERIFY_IS_APPROX(m, refMat_sum); + + m.setFromTriplets(triplets.begin(), triplets.end(), std::multiplies()); + VERIFY_IS_APPROX(m, refMat_prod); +#if (defined(__cplusplus) && __cplusplus >= 201103L) + m.setFromTriplets(triplets.begin(), triplets.end(), [] (Scalar,Scalar b) { return b; }); + VERIFY_IS_APPROX(m, refMat_last); +#endif + } + + // test Map + { + DenseMatrix refMat2(rows, cols), refMat3(rows, cols); + SparseMatrixType m2(rows, cols), m3(rows, cols); + initSparse(density, refMat2, m2); + initSparse(density, refMat3, m3); + { + Map mapMat2(m2.rows(), m2.cols(), m2.nonZeros(), m2.outerIndexPtr(), m2.innerIndexPtr(), m2.valuePtr(), m2.innerNonZeroPtr()); + Map mapMat3(m3.rows(), m3.cols(), m3.nonZeros(), m3.outerIndexPtr(), m3.innerIndexPtr(), m3.valuePtr(), m3.innerNonZeroPtr()); + VERIFY_IS_APPROX(mapMat2+mapMat3, refMat2+refMat3); + VERIFY_IS_APPROX(mapMat2+mapMat3, refMat2+refMat3); + } + { + MappedSparseMatrix mapMat2(m2.rows(), m2.cols(), m2.nonZeros(), m2.outerIndexPtr(), m2.innerIndexPtr(), m2.valuePtr(), m2.innerNonZeroPtr()); + MappedSparseMatrix mapMat3(m3.rows(), m3.cols(), m3.nonZeros(), m3.outerIndexPtr(), m3.innerIndexPtr(), m3.valuePtr(), m3.innerNonZeroPtr()); + VERIFY_IS_APPROX(mapMat2+mapMat3, refMat2+refMat3); + VERIFY_IS_APPROX(mapMat2+mapMat3, refMat2+refMat3); + } + + Index i = internal::random(0,rows-1); + Index j = internal::random(0,cols-1); + m2.coeffRef(i,j) = 123; + if(internal::random()) + m2.makeCompressed(); + Map mapMat2(rows, cols, m2.nonZeros(), m2.outerIndexPtr(), m2.innerIndexPtr(), m2.valuePtr(), m2.innerNonZeroPtr()); + VERIFY_IS_EQUAL(m2.coeff(i,j),Scalar(123)); + VERIFY_IS_EQUAL(mapMat2.coeff(i,j),Scalar(123)); + mapMat2.coeffRef(i,j) = -123; + VERIFY_IS_EQUAL(m2.coeff(i,j),Scalar(-123)); } // test triangularView { - DenseMatrix refMat2(rows, rows), refMat3(rows, rows); - SparseMatrixType m2(rows, rows), m3(rows, rows); + DenseMatrix refMat2(rows, cols), refMat3(rows, cols); + SparseMatrixType m2(rows, cols), m3(rows, cols); initSparse(density, refMat2, m2); refMat3 = refMat2.template triangularView(); m3 = m2.template triangularView(); @@ -403,13 +435,15 @@ template void sparse_basic(const SparseMatrixType& re m3 = m2.template triangularView(); VERIFY_IS_APPROX(m3, refMat3); - refMat3 = refMat2.template triangularView(); - m3 = m2.template triangularView(); - VERIFY_IS_APPROX(m3, refMat3); + { + refMat3 = refMat2.template triangularView(); + m3 = m2.template triangularView(); + VERIFY_IS_APPROX(m3, refMat3); - refMat3 = refMat2.template triangularView(); - m3 = m2.template triangularView(); - VERIFY_IS_APPROX(m3, refMat3); + refMat3 = refMat2.template triangularView(); + m3 = m2.template triangularView(); + VERIFY_IS_APPROX(m3, refMat3); + } refMat3 = refMat2.template triangularView(); m3 = m2.template triangularView(); @@ -418,6 +452,10 @@ template void sparse_basic(const SparseMatrixType& re refMat3 = refMat2.template triangularView(); m3 = m2.template triangularView(); VERIFY_IS_APPROX(m3, refMat3); + + // check sparse-triangular to dense + refMat3 = m2.template triangularView(); + VERIFY_IS_APPROX(refMat3, DenseMatrix(refMat2.template triangularView())); } // test selfadjointView @@ -429,6 +467,19 @@ template void sparse_basic(const SparseMatrixType& re refMat3 = refMat2.template selfadjointView(); m3 = m2.template selfadjointView(); VERIFY_IS_APPROX(m3, refMat3); + + refMat3 += refMat2.template selfadjointView(); + m3 += m2.template selfadjointView(); + VERIFY_IS_APPROX(m3, refMat3); + + refMat3 -= refMat2.template selfadjointView(); + m3 -= m2.template selfadjointView(); + VERIFY_IS_APPROX(m3, refMat3); + + // selfadjointView only works for square matrices: + SparseMatrixType m4(rows, rows+1); + VERIFY_RAISES_ASSERT(m4.template selfadjointView()); + VERIFY_RAISES_ASSERT(m4.template selfadjointView()); } // test sparseView @@ -437,28 +488,59 @@ template void sparse_basic(const SparseMatrixType& re SparseMatrixType m2(rows, rows); initSparse(density, refMat2, m2); VERIFY_IS_APPROX(m2.eval(), refMat2.sparseView().eval()); + + // sparse view on expressions: + VERIFY_IS_APPROX((s1*m2).eval(), (s1*refMat2).sparseView().eval()); + VERIFY_IS_APPROX((m2+m2).eval(), (refMat2+refMat2).sparseView().eval()); + VERIFY_IS_APPROX((m2*m2).eval(), (refMat2.lazyProduct(refMat2)).sparseView().eval()); + VERIFY_IS_APPROX((m2*m2).eval(), (refMat2*refMat2).sparseView().eval()); } // test diagonal { - DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows); - SparseMatrixType m2(rows, rows); + DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols); + SparseMatrixType m2(rows, cols); initSparse(density, refMat2, m2); VERIFY_IS_APPROX(m2.diagonal(), refMat2.diagonal().eval()); + DenseVector d = m2.diagonal(); + VERIFY_IS_APPROX(d, refMat2.diagonal().eval()); + d = m2.diagonal().array(); + VERIFY_IS_APPROX(d, refMat2.diagonal().eval()); + VERIFY_IS_APPROX(const_cast(m2).diagonal(), refMat2.diagonal().eval()); + + initSparse(density, refMat2, m2, ForceNonZeroDiag); + m2.diagonal() += refMat2.diagonal(); + refMat2.diagonal() += refMat2.diagonal(); + VERIFY_IS_APPROX(m2, refMat2); + } + + // test diagonal to sparse + { + DenseVector d = DenseVector::Random(rows); + DenseMatrix refMat2 = d.asDiagonal(); + SparseMatrixType m2(rows, rows); + m2 = d.asDiagonal(); + VERIFY_IS_APPROX(m2, refMat2); + SparseMatrixType m3(d.asDiagonal()); + VERIFY_IS_APPROX(m3, refMat2); + refMat2 += d.asDiagonal(); + m2 += d.asDiagonal(); + VERIFY_IS_APPROX(m2, refMat2); } // test conservative resize { - std::vector< std::pair > inc; - inc.push_back(std::pair(-3,-2)); - inc.push_back(std::pair(0,0)); - inc.push_back(std::pair(3,2)); - inc.push_back(std::pair(3,0)); - inc.push_back(std::pair(0,3)); + std::vector< std::pair > inc; + if(rows > 3 && cols > 2) + inc.push_back(std::pair(-3,-2)); + inc.push_back(std::pair(0,0)); + inc.push_back(std::pair(3,2)); + inc.push_back(std::pair(3,0)); + inc.push_back(std::pair(0,3)); for(size_t i = 0; i< inc.size(); i++) { - Index incRows = inc[i].first; - Index incCols = inc[i].second; + StorageIndex incRows = inc[i].first; + StorageIndex incCols = inc[i].second; SparseMatrixType m1(rows, cols); DenseMatrix refMat1 = DenseMatrix::Zero(rows, cols); initSparse(density, refMat1, m1); @@ -488,22 +570,119 @@ template void sparse_basic(const SparseMatrixType& re SparseMatrixType m1(rows, rows); m1.setIdentity(); VERIFY_IS_APPROX(m1, refMat1); + for(int k=0; k(0,rows-1); + Index j = internal::random(0,rows-1); + Scalar v = internal::random(); + m1.coeffRef(i,j) = v; + refMat1.coeffRef(i,j) = v; + VERIFY_IS_APPROX(m1, refMat1); + if(internal::random(0,10)<2) + m1.makeCompressed(); + } + m1.setIdentity(); + refMat1.setIdentity(); + VERIFY_IS_APPROX(m1, refMat1); + } + + // test array/vector of InnerIterator + { + typedef typename SparseMatrixType::InnerIterator IteratorType; + + DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols); + SparseMatrixType m2(rows, cols); + initSparse(density, refMat2, m2); + IteratorType static_array[2]; + static_array[0] = IteratorType(m2,0); + static_array[1] = IteratorType(m2,m2.outerSize()-1); + VERIFY( static_array[0] || m2.innerVector(static_array[0].outer()).nonZeros() == 0 ); + VERIFY( static_array[1] || m2.innerVector(static_array[1].outer()).nonZeros() == 0 ); + if(static_array[0] && static_array[1]) + { + ++(static_array[1]); + static_array[1] = IteratorType(m2,0); + VERIFY( static_array[1] ); + VERIFY( static_array[1].index() == static_array[0].index() ); + VERIFY( static_array[1].outer() == static_array[0].outer() ); + VERIFY( static_array[1].value() == static_array[0].value() ); + } + + std::vector iters(2); + iters[0] = IteratorType(m2,0); + iters[1] = IteratorType(m2,m2.outerSize()-1); } } + +template +void big_sparse_triplet(Index rows, Index cols, double density) { + typedef typename SparseMatrixType::StorageIndex StorageIndex; + typedef typename SparseMatrixType::Scalar Scalar; + typedef Triplet TripletType; + std::vector triplets; + double nelements = density * rows*cols; + VERIFY(nelements>=0 && nelements < NumTraits::highest()); + Index ntriplets = Index(nelements); + triplets.reserve(ntriplets); + Scalar sum = Scalar(0); + for(Index i=0;i(0,rows-1); + Index c = internal::random(0,cols-1); + Scalar v = internal::random(); + triplets.push_back(TripletType(r,c,v)); + sum += v; + } + SparseMatrixType m(rows,cols); + m.setFromTriplets(triplets.begin(), triplets.end()); + VERIFY(m.nonZeros() <= ntriplets); + VERIFY_IS_APPROX(sum, m.sum()); +} + + void test_sparse_basic() { for(int i = 0; i < g_repeat; i++) { - int s = Eigen::internal::random(1,50); - EIGEN_UNUSED_VARIABLE(s); + int r = Eigen::internal::random(1,200), c = Eigen::internal::random(1,200); + if(Eigen::internal::random(0,4) == 0) { + r = c; // check square matrices in 25% of tries + } + EIGEN_UNUSED_VARIABLE(r+c); + CALL_SUBTEST_1(( sparse_basic(SparseMatrix(1, 1)) )); CALL_SUBTEST_1(( sparse_basic(SparseMatrix(8, 8)) )); - CALL_SUBTEST_2(( sparse_basic(SparseMatrix, ColMajor>(s, s)) )); - CALL_SUBTEST_2(( sparse_basic(SparseMatrix, RowMajor>(s, s)) )); - CALL_SUBTEST_1(( sparse_basic(SparseMatrix(s, s)) )); - CALL_SUBTEST_1(( sparse_basic(SparseMatrix(s, s)) )); - CALL_SUBTEST_1(( sparse_basic(SparseMatrix(s, s)) )); + CALL_SUBTEST_2(( sparse_basic(SparseMatrix, ColMajor>(r, c)) )); + CALL_SUBTEST_2(( sparse_basic(SparseMatrix, RowMajor>(r, c)) )); + CALL_SUBTEST_1(( sparse_basic(SparseMatrix(r, c)) )); + CALL_SUBTEST_5(( sparse_basic(SparseMatrix(r, c)) )); + CALL_SUBTEST_5(( sparse_basic(SparseMatrix(r, c)) )); - CALL_SUBTEST_1(( sparse_basic(SparseMatrix(short(s), short(s))) )); - CALL_SUBTEST_1(( sparse_basic(SparseMatrix(short(s), short(s))) )); + r = Eigen::internal::random(1,100); + c = Eigen::internal::random(1,100); + if(Eigen::internal::random(0,4) == 0) { + r = c; // check square matrices in 25% of tries + } + + CALL_SUBTEST_6(( sparse_basic(SparseMatrix(short(r), short(c))) )); + CALL_SUBTEST_6(( sparse_basic(SparseMatrix(short(r), short(c))) )); } + + // Regression test for bug 900: (manually insert higher values here, if you have enough RAM): + CALL_SUBTEST_3((big_sparse_triplet >(10000, 10000, 0.125))); + CALL_SUBTEST_4((big_sparse_triplet >(10000, 10000, 0.125))); + + // Regression test for bug 1105 +#ifdef EIGEN_TEST_PART_7 + { + int n = Eigen::internal::random(200,600); + SparseMatrix,0, long> mat(n, n); + std::complex val; + + for(int i=0; i +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "sparse.h" + +template +typename Eigen::internal::enable_if<(T::Flags&RowMajorBit)==RowMajorBit, typename T::RowXpr>::type +innervec(T& A, Index i) +{ + return A.row(i); +} + +template +typename Eigen::internal::enable_if<(T::Flags&RowMajorBit)==0, typename T::ColXpr>::type +innervec(T& A, Index i) +{ + return A.col(i); +} + +template void sparse_block(const SparseMatrixType& ref) +{ + const Index rows = ref.rows(); + const Index cols = ref.cols(); + const Index inner = ref.innerSize(); + const Index outer = ref.outerSize(); + + typedef typename SparseMatrixType::Scalar Scalar; + typedef typename SparseMatrixType::StorageIndex StorageIndex; + + double density = (std::max)(8./(rows*cols), 0.01); + typedef Matrix DenseMatrix; + typedef Matrix DenseVector; + typedef Matrix RowDenseVector; + typedef SparseVector SparseVectorType; + + Scalar s1 = internal::random(); + { + SparseMatrixType m(rows, cols); + DenseMatrix refMat = DenseMatrix::Zero(rows, cols); + initSparse(density, refMat, m); + + VERIFY_IS_APPROX(m, refMat); + + // test InnerIterators and Block expressions + for (int t=0; t<10; ++t) + { + Index j = internal::random(0,cols-2); + Index i = internal::random(0,rows-2); + Index w = internal::random(1,cols-j); + Index h = internal::random(1,rows-i); + + VERIFY_IS_APPROX(m.block(i,j,h,w), refMat.block(i,j,h,w)); + for(Index c=0; c(density, refMat2, m2); + Index j0 = internal::random(0,outer-1); + Index j1 = internal::random(0,outer-1); + Index r0 = internal::random(0,rows-1); + Index c0 = internal::random(0,cols-1); + + VERIFY_IS_APPROX(m2.innerVector(j0), innervec(refMat2,j0)); + VERIFY_IS_APPROX(m2.innerVector(j0)+m2.innerVector(j1), innervec(refMat2,j0)+innervec(refMat2,j1)); + + m2.innerVector(j0) *= Scalar(2); + innervec(refMat2,j0) *= Scalar(2); + VERIFY_IS_APPROX(m2, refMat2); + + m2.row(r0) *= Scalar(3); + refMat2.row(r0) *= Scalar(3); + VERIFY_IS_APPROX(m2, refMat2); + + m2.col(c0) *= Scalar(4); + refMat2.col(c0) *= Scalar(4); + VERIFY_IS_APPROX(m2, refMat2); + + m2.row(r0) /= Scalar(3); + refMat2.row(r0) /= Scalar(3); + VERIFY_IS_APPROX(m2, refMat2); + + m2.col(c0) /= Scalar(4); + refMat2.col(c0) /= Scalar(4); + VERIFY_IS_APPROX(m2, refMat2); + + SparseVectorType v1; + VERIFY_IS_APPROX(v1 = m2.col(c0) * 4, refMat2.col(c0)*4); + VERIFY_IS_APPROX(v1 = m2.row(r0) * 4, refMat2.row(r0).transpose()*4); + + SparseMatrixType m3(rows,cols); + m3.reserve(VectorXi::Constant(outer,int(inner/2))); + for(Index j=0; j(k+1); + for(Index j=0; j<(std::min)(outer, inner); ++j) + { + VERIFY(j==numext::real(m3.innerVector(j).nonZeros())); + if(j>0) + VERIFY(j==numext::real(m3.innerVector(j).lastCoeff())); + } + m3.makeCompressed(); + for(Index j=0; j<(std::min)(outer, inner); ++j) + { + VERIFY(j==numext::real(m3.innerVector(j).nonZeros())); + if(j>0) + VERIFY(j==numext::real(m3.innerVector(j).lastCoeff())); + } + + VERIFY(m3.innerVector(j0).nonZeros() == m3.transpose().innerVector(j0).nonZeros()); + +// m2.innerVector(j0) = 2*m2.innerVector(j1); +// refMat2.col(j0) = 2*refMat2.col(j1); +// VERIFY_IS_APPROX(m2, refMat2); + } + + // test innerVectors() + { + DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols); + SparseMatrixType m2(rows, cols); + initSparse(density, refMat2, m2); + if(internal::random(0,1)>0.5f) m2.makeCompressed(); + Index j0 = internal::random(0,outer-2); + Index j1 = internal::random(0,outer-2); + Index n0 = internal::random(1,outer-(std::max)(j0,j1)); + if(SparseMatrixType::IsRowMajor) + VERIFY_IS_APPROX(m2.innerVectors(j0,n0), refMat2.block(j0,0,n0,cols)); + else + VERIFY_IS_APPROX(m2.innerVectors(j0,n0), refMat2.block(0,j0,rows,n0)); + if(SparseMatrixType::IsRowMajor) + VERIFY_IS_APPROX(m2.innerVectors(j0,n0)+m2.innerVectors(j1,n0), + refMat2.middleRows(j0,n0)+refMat2.middleRows(j1,n0)); + else + VERIFY_IS_APPROX(m2.innerVectors(j0,n0)+m2.innerVectors(j1,n0), + refMat2.block(0,j0,rows,n0)+refMat2.block(0,j1,rows,n0)); + + VERIFY_IS_APPROX(m2, refMat2); + + VERIFY(m2.innerVectors(j0,n0).nonZeros() == m2.transpose().innerVectors(j0,n0).nonZeros()); + + m2.innerVectors(j0,n0) = m2.innerVectors(j0,n0) + m2.innerVectors(j1,n0); + if(SparseMatrixType::IsRowMajor) + refMat2.middleRows(j0,n0) = (refMat2.middleRows(j0,n0) + refMat2.middleRows(j1,n0)).eval(); + else + refMat2.middleCols(j0,n0) = (refMat2.middleCols(j0,n0) + refMat2.middleCols(j1,n0)).eval(); + + VERIFY_IS_APPROX(m2, refMat2); + } + + // test generic blocks + { + DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols); + SparseMatrixType m2(rows, cols); + initSparse(density, refMat2, m2); + Index j0 = internal::random(0,outer-2); + Index j1 = internal::random(0,outer-2); + Index n0 = internal::random(1,outer-(std::max)(j0,j1)); + if(SparseMatrixType::IsRowMajor) + VERIFY_IS_APPROX(m2.block(j0,0,n0,cols), refMat2.block(j0,0,n0,cols)); + else + VERIFY_IS_APPROX(m2.block(0,j0,rows,n0), refMat2.block(0,j0,rows,n0)); + + if(SparseMatrixType::IsRowMajor) + VERIFY_IS_APPROX(m2.block(j0,0,n0,cols)+m2.block(j1,0,n0,cols), + refMat2.block(j0,0,n0,cols)+refMat2.block(j1,0,n0,cols)); + else + VERIFY_IS_APPROX(m2.block(0,j0,rows,n0)+m2.block(0,j1,rows,n0), + refMat2.block(0,j0,rows,n0)+refMat2.block(0,j1,rows,n0)); + + Index i = internal::random(0,m2.outerSize()-1); + if(SparseMatrixType::IsRowMajor) { + m2.innerVector(i) = m2.innerVector(i) * s1; + refMat2.row(i) = refMat2.row(i) * s1; + VERIFY_IS_APPROX(m2,refMat2); + } else { + m2.innerVector(i) = m2.innerVector(i) * s1; + refMat2.col(i) = refMat2.col(i) * s1; + VERIFY_IS_APPROX(m2,refMat2); + } + + Index r0 = internal::random(0,rows-2); + Index c0 = internal::random(0,cols-2); + Index r1 = internal::random(1,rows-r0); + Index c1 = internal::random(1,cols-c0); + + VERIFY_IS_APPROX(DenseVector(m2.col(c0)), refMat2.col(c0)); + VERIFY_IS_APPROX(m2.col(c0), refMat2.col(c0)); + + VERIFY_IS_APPROX(RowDenseVector(m2.row(r0)), refMat2.row(r0)); + VERIFY_IS_APPROX(m2.row(r0), refMat2.row(r0)); + + VERIFY_IS_APPROX(m2.block(r0,c0,r1,c1), refMat2.block(r0,c0,r1,c1)); + VERIFY_IS_APPROX((2*m2).block(r0,c0,r1,c1), (2*refMat2).block(r0,c0,r1,c1)); + + if(m2.nonZeros()>0) + { + VERIFY_IS_APPROX(m2, refMat2); + SparseMatrixType m3(rows, cols); + DenseMatrix refMat3(rows, cols); refMat3.setZero(); + Index n = internal::random(1,10); + for(Index k=0; k(0,outer-1); + Index o2 = internal::random(0,outer-1); + if(SparseMatrixType::IsRowMajor) + { + m3.innerVector(o1) = m2.row(o2); + refMat3.row(o1) = refMat2.row(o2); + } + else + { + m3.innerVector(o1) = m2.col(o2); + refMat3.col(o1) = refMat2.col(o2); + } + if(internal::random()) + m3.makeCompressed(); + } + if(m3.nonZeros()>0) + VERIFY_IS_APPROX(m3, refMat3); + } + } +} + +void test_sparse_block() +{ + for(int i = 0; i < g_repeat; i++) { + int r = Eigen::internal::random(1,200), c = Eigen::internal::random(1,200); + if(Eigen::internal::random(0,4) == 0) { + r = c; // check square matrices in 25% of tries + } + EIGEN_UNUSED_VARIABLE(r+c); + CALL_SUBTEST_1(( sparse_block(SparseMatrix(1, 1)) )); + CALL_SUBTEST_1(( sparse_block(SparseMatrix(8, 8)) )); + CALL_SUBTEST_1(( sparse_block(SparseMatrix(r, c)) )); + CALL_SUBTEST_2(( sparse_block(SparseMatrix, ColMajor>(r, c)) )); + CALL_SUBTEST_2(( sparse_block(SparseMatrix, RowMajor>(r, c)) )); + + CALL_SUBTEST_3(( sparse_block(SparseMatrix(r, c)) )); + CALL_SUBTEST_3(( sparse_block(SparseMatrix(r, c)) )); + + r = Eigen::internal::random(1,100); + c = Eigen::internal::random(1,100); + if(Eigen::internal::random(0,4) == 0) { + r = c; // check square matrices in 25% of tries + } + + CALL_SUBTEST_4(( sparse_block(SparseMatrix(short(r), short(c))) )); + CALL_SUBTEST_4(( sparse_block(SparseMatrix(short(r), short(c))) )); + } +} diff --git a/testbed/nanogui/ext/eigen/test/sparse_permutations.cpp b/testbed/nanogui/ext/eigen/test/sparse_permutations.cpp index e4ce1d67..b82cceff 100644 --- a/testbed/nanogui/ext/eigen/test/sparse_permutations.cpp +++ b/testbed/nanogui/ext/eigen/test/sparse_permutations.cpp @@ -1,25 +1,57 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2011 Gael Guennebaud +// Copyright (C) 2011-2015 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +static long int nb_transposed_copies; +#define EIGEN_SPARSE_TRANSPOSED_COPY_PLUGIN {nb_transposed_copies++;} +#define VERIFY_TRANSPOSITION_COUNT(XPR,N) {\ + nb_transposed_copies = 0; \ + XPR; \ + if(nb_transposed_copies!=N) std::cerr << "nb_transposed_copies == " << nb_transposed_copies << "\n"; \ + VERIFY( (#XPR) && nb_transposed_copies==N ); \ + } + #include "sparse.h" +template +bool is_sorted(const T& mat) { + for(Index k = 0; k=it.index()) + return false; + prev = it.index(); + } + } + return true; +} + +template +typename internal::nested_eval::type eval(const T &xpr) +{ + VERIFY( int(internal::nested_eval::type::Flags&RowMajorBit) == int(internal::evaluator::Flags&RowMajorBit) ); + return xpr; +} + template void sparse_permutations(const SparseMatrixType& ref) { - typedef typename SparseMatrixType::Index Index; - const Index rows = ref.rows(); const Index cols = ref.cols(); typedef typename SparseMatrixType::Scalar Scalar; - typedef typename SparseMatrixType::Index Index; - typedef SparseMatrix OtherSparseMatrixType; + typedef typename SparseMatrixType::StorageIndex StorageIndex; + typedef SparseMatrix OtherSparseMatrixType; typedef Matrix DenseMatrix; - typedef Matrix VectorI; + typedef Matrix VectorI; +// bool IsRowMajor1 = SparseMatrixType::IsRowMajor; +// bool IsRowMajor2 = OtherSparseMatrixType::IsRowMajor; double density = (std::max)(8./(rows*cols), 0.01); @@ -44,58 +76,69 @@ template void sparse_permutations(c randomPermutationVector(pi, cols); p.indices() = pi; - res = mat*p; + VERIFY( is_sorted( ::eval(mat*p) )); + VERIFY( is_sorted( res = mat*p )); + VERIFY_TRANSPOSITION_COUNT( ::eval(mat*p), 0); + //VERIFY_TRANSPOSITION_COUNT( res = mat*p, IsRowMajor ? 1 : 0 ); res_d = mat_d*p; VERIFY(res.isApprox(res_d) && "mat*p"); - res = p*mat; + VERIFY( is_sorted( ::eval(p*mat) )); + VERIFY( is_sorted( res = p*mat )); + VERIFY_TRANSPOSITION_COUNT( ::eval(p*mat), 0); res_d = p*mat_d; VERIFY(res.isApprox(res_d) && "p*mat"); - res = mat*p.inverse(); + VERIFY( is_sorted( (mat*p).eval() )); + VERIFY( is_sorted( res = mat*p.inverse() )); + VERIFY_TRANSPOSITION_COUNT( ::eval(mat*p.inverse()), 0); res_d = mat*p.inverse(); VERIFY(res.isApprox(res_d) && "mat*inv(p)"); - res = p.inverse()*mat; + VERIFY( is_sorted( (p*mat+p*mat).eval() )); + VERIFY( is_sorted( res = p.inverse()*mat )); + VERIFY_TRANSPOSITION_COUNT( ::eval(p.inverse()*mat), 0); res_d = p.inverse()*mat_d; VERIFY(res.isApprox(res_d) && "inv(p)*mat"); - res = mat.twistedBy(p); + VERIFY( is_sorted( (p * mat * p.inverse()).eval() )); + VERIFY( is_sorted( res = mat.twistedBy(p) )); + VERIFY_TRANSPOSITION_COUNT( ::eval(p * mat * p.inverse()), 0); res_d = (p * mat_d) * p.inverse(); VERIFY(res.isApprox(res_d) && "p*mat*inv(p)"); - res = mat.template selfadjointView().twistedBy(p_null); + VERIFY( is_sorted( res = mat.template selfadjointView().twistedBy(p_null) )); res_d = up_sym_d; VERIFY(res.isApprox(res_d) && "full selfadjoint upper to full"); - res = mat.template selfadjointView().twistedBy(p_null); + VERIFY( is_sorted( res = mat.template selfadjointView().twistedBy(p_null) )); res_d = lo_sym_d; VERIFY(res.isApprox(res_d) && "full selfadjoint lower to full"); - res = up.template selfadjointView().twistedBy(p_null); + VERIFY( is_sorted( res = up.template selfadjointView().twistedBy(p_null) )); res_d = up_sym_d; VERIFY(res.isApprox(res_d) && "upper selfadjoint to full"); - res = lo.template selfadjointView().twistedBy(p_null); + VERIFY( is_sorted( res = lo.template selfadjointView().twistedBy(p_null) )); res_d = lo_sym_d; VERIFY(res.isApprox(res_d) && "lower selfadjoint full"); - res = mat.template selfadjointView(); + VERIFY( is_sorted( res = mat.template selfadjointView() )); res_d = up_sym_d; VERIFY(res.isApprox(res_d) && "full selfadjoint upper to full"); - res = mat.template selfadjointView(); + VERIFY( is_sorted( res = mat.template selfadjointView() )); res_d = lo_sym_d; VERIFY(res.isApprox(res_d) && "full selfadjoint lower to full"); - res = up.template selfadjointView(); + VERIFY( is_sorted( res = up.template selfadjointView() )); res_d = up_sym_d; VERIFY(res.isApprox(res_d) && "upper selfadjoint to full"); - res = lo.template selfadjointView(); + VERIFY( is_sorted( res = lo.template selfadjointView() )); res_d = lo_sym_d; VERIFY(res.isApprox(res_d) && "lower selfadjoint full"); @@ -152,19 +195,19 @@ template void sparse_permutations(c VERIFY(res.isApprox(res_d) && "upper selfadjoint twisted to lower"); - res = mat.template selfadjointView().twistedBy(p); + VERIFY( is_sorted( res = mat.template selfadjointView().twistedBy(p) )); res_d = (p * up_sym_d) * p.inverse(); VERIFY(res.isApprox(res_d) && "full selfadjoint upper twisted to full"); - res = mat.template selfadjointView().twistedBy(p); + VERIFY( is_sorted( res = mat.template selfadjointView().twistedBy(p) )); res_d = (p * lo_sym_d) * p.inverse(); VERIFY(res.isApprox(res_d) && "full selfadjoint lower twisted to full"); - res = up.template selfadjointView().twistedBy(p); + VERIFY( is_sorted( res = up.template selfadjointView().twistedBy(p) )); res_d = (p * up_sym_d) * p.inverse(); VERIFY(res.isApprox(res_d) && "upper selfadjoint twisted to full"); - res = lo.template selfadjointView().twistedBy(p); + VERIFY( is_sorted( res = lo.template selfadjointView().twistedBy(p) )); res_d = (p * lo_sym_d) * p.inverse(); VERIFY(res.isApprox(res_d) && "lower selfadjoint twisted to full"); } @@ -184,4 +227,10 @@ void test_sparse_permutations() CALL_SUBTEST_1(( sparse_permutations_all(s) )); CALL_SUBTEST_2(( sparse_permutations_all >(s) )); } + + VERIFY((internal::is_same,OnTheRight,false,SparseShape>::ReturnType, + internal::nested_eval,PermutationMatrix,AliasFreeProduct>,1>::type>::value)); + + VERIFY((internal::is_same,OnTheLeft,false,SparseShape>::ReturnType, + internal::nested_eval,SparseMatrix,AliasFreeProduct>,1>::type>::value)); } diff --git a/testbed/nanogui/ext/eigen/test/sparse_product.cpp b/testbed/nanogui/ext/eigen/test/sparse_product.cpp index a2ea9d5b..c1edd26e 100644 --- a/testbed/nanogui/ext/eigen/test/sparse_product.cpp +++ b/testbed/nanogui/ext/eigen/test/sparse_product.cpp @@ -7,37 +7,29 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +static long int nb_temporaries; + +inline void on_temporary_creation() { + // here's a great place to set a breakpoint when debugging failures in this test! + nb_temporaries++; +} + +#define EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN { on_temporary_creation(); } + #include "sparse.h" -template struct test_outer; - -template struct test_outer { - static void run(SparseMatrixType& m2, SparseMatrixType& m4, DenseMatrix& refMat2, DenseMatrix& refMat4) { - typedef typename SparseMatrixType::Index Index; - Index c = internal::random(0,m2.cols()-1); - Index c1 = internal::random(0,m2.cols()-1); - VERIFY_IS_APPROX(m4=m2.col(c)*refMat2.col(c1).transpose(), refMat4=refMat2.col(c)*refMat2.col(c1).transpose()); - VERIFY_IS_APPROX(m4=refMat2.col(c1)*m2.col(c).transpose(), refMat4=refMat2.col(c1)*refMat2.col(c).transpose()); +#define VERIFY_EVALUATION_COUNT(XPR,N) {\ + nb_temporaries = 0; \ + CALL_SUBTEST( XPR ); \ + if(nb_temporaries!=N) std::cerr << "nb_temporaries == " << nb_temporaries << "\n"; \ + VERIFY( (#XPR) && nb_temporaries==N ); \ } -}; -template struct test_outer { - static void run(SparseMatrixType& m2, SparseMatrixType& m4, DenseMatrix& refMat2, DenseMatrix& refMat4) { - typedef typename SparseMatrixType::Index Index; - Index r = internal::random(0,m2.rows()-1); - Index c1 = internal::random(0,m2.cols()-1); - VERIFY_IS_APPROX(m4=m2.row(r).transpose()*refMat2.col(c1).transpose(), refMat4=refMat2.row(r).transpose()*refMat2.col(c1).transpose()); - VERIFY_IS_APPROX(m4=refMat2.col(c1)*m2.row(r), refMat4=refMat2.col(c1)*refMat2.row(r)); - } -}; -// (m2,m4,refMat2,refMat4,dv1); -// VERIFY_IS_APPROX(m4=m2.innerVector(c)*dv1.transpose(), refMat4=refMat2.colVector(c)*dv1.transpose()); -// VERIFY_IS_APPROX(m4=dv1*mcm.col(c).transpose(), refMat4=dv1*refMat2.col(c).transpose()); template void sparse_product() { - typedef typename SparseMatrixType::Index Index; + typedef typename SparseMatrixType::StorageIndex StorageIndex; Index n = 100; const Index rows = internal::random(1,n); const Index cols = internal::random(1,n); @@ -45,12 +37,12 @@ template void sparse_product() typedef typename SparseMatrixType::Scalar Scalar; enum { Flags = SparseMatrixType::Flags }; - double density = (std::max)(8./(rows*cols), 0.1); + double density = (std::max)(8./(rows*cols), 0.2); typedef Matrix DenseMatrix; typedef Matrix DenseVector; typedef Matrix RowDenseVector; - typedef SparseVector ColSpVector; - typedef SparseVector RowSpVector; + typedef SparseVector ColSpVector; + typedef SparseVector RowSpVector; Scalar s1 = internal::random(); Scalar s2 = internal::random(); @@ -93,33 +85,124 @@ template void sparse_product() VERIFY_IS_APPROX(m4 = m2*m3/s1, refMat4 = refMat2*refMat3/s1); VERIFY_IS_APPROX(m4 = m2*m3*s1, refMat4 = refMat2*refMat3*s1); VERIFY_IS_APPROX(m4 = s2*m2*m3*s1, refMat4 = s2*refMat2*refMat3*s1); + VERIFY_IS_APPROX(m4 = (m2+m2)*m3, refMat4 = (refMat2+refMat2)*refMat3); + VERIFY_IS_APPROX(m4 = m2*m3.leftCols(cols/2), refMat4 = refMat2*refMat3.leftCols(cols/2)); + VERIFY_IS_APPROX(m4 = m2*(m3+m3).leftCols(cols/2), refMat4 = refMat2*(refMat3+refMat3).leftCols(cols/2)); VERIFY_IS_APPROX(m4=(m2*m3).pruned(0), refMat4=refMat2*refMat3); VERIFY_IS_APPROX(m4=(m2t.transpose()*m3).pruned(0), refMat4=refMat2t.transpose()*refMat3); VERIFY_IS_APPROX(m4=(m2t.transpose()*m3t.transpose()).pruned(0), refMat4=refMat2t.transpose()*refMat3t.transpose()); VERIFY_IS_APPROX(m4=(m2*m3t.transpose()).pruned(0), refMat4=refMat2*refMat3t.transpose()); + // make sure the right product implementation is called: + if((!SparseMatrixType::IsRowMajor) && m2.rows()<=m3.cols()) + { + VERIFY_EVALUATION_COUNT(m4 = m2*m3, 3); // 1 temp for the result + 2 for transposing and get a sorted result. + VERIFY_EVALUATION_COUNT(m4 = (m2*m3).pruned(0), 1); + VERIFY_EVALUATION_COUNT(m4 = (m2*m3).eval().pruned(0), 4); + } + + // and that pruning is effective: + { + DenseMatrix Ad(2,2); + Ad << -1, 1, 1, 1; + SparseMatrixType As(Ad.sparseView()), B(2,2); + VERIFY_IS_EQUAL( (As*As.transpose()).eval().nonZeros(), 4); + VERIFY_IS_EQUAL( (Ad*Ad.transpose()).eval().sparseView().eval().nonZeros(), 2); + VERIFY_IS_EQUAL( (As*As.transpose()).pruned(1e-6).eval().nonZeros(), 2); + } + + // dense ?= sparse * sparse + VERIFY_IS_APPROX(dm4 =m2*m3, refMat4 =refMat2*refMat3); + VERIFY_IS_APPROX(dm4+=m2*m3, refMat4+=refMat2*refMat3); + VERIFY_IS_APPROX(dm4-=m2*m3, refMat4-=refMat2*refMat3); + VERIFY_IS_APPROX(dm4 =m2t.transpose()*m3, refMat4 =refMat2t.transpose()*refMat3); + VERIFY_IS_APPROX(dm4+=m2t.transpose()*m3, refMat4+=refMat2t.transpose()*refMat3); + VERIFY_IS_APPROX(dm4-=m2t.transpose()*m3, refMat4-=refMat2t.transpose()*refMat3); + VERIFY_IS_APPROX(dm4 =m2t.transpose()*m3t.transpose(), refMat4 =refMat2t.transpose()*refMat3t.transpose()); + VERIFY_IS_APPROX(dm4+=m2t.transpose()*m3t.transpose(), refMat4+=refMat2t.transpose()*refMat3t.transpose()); + VERIFY_IS_APPROX(dm4-=m2t.transpose()*m3t.transpose(), refMat4-=refMat2t.transpose()*refMat3t.transpose()); + VERIFY_IS_APPROX(dm4 =m2*m3t.transpose(), refMat4 =refMat2*refMat3t.transpose()); + VERIFY_IS_APPROX(dm4+=m2*m3t.transpose(), refMat4+=refMat2*refMat3t.transpose()); + VERIFY_IS_APPROX(dm4-=m2*m3t.transpose(), refMat4-=refMat2*refMat3t.transpose()); + VERIFY_IS_APPROX(dm4 = m2*m3*s1, refMat4 = refMat2*refMat3*s1); + // test aliasing m4 = m2; refMat4 = refMat2; VERIFY_IS_APPROX(m4=m4*m3, refMat4=refMat4*refMat3); - // sparse * dense + // sparse * dense matrix VERIFY_IS_APPROX(dm4=m2*refMat3, refMat4=refMat2*refMat3); VERIFY_IS_APPROX(dm4=m2*refMat3t.transpose(), refMat4=refMat2*refMat3t.transpose()); VERIFY_IS_APPROX(dm4=m2t.transpose()*refMat3, refMat4=refMat2t.transpose()*refMat3); VERIFY_IS_APPROX(dm4=m2t.transpose()*refMat3t.transpose(), refMat4=refMat2t.transpose()*refMat3t.transpose()); + VERIFY_IS_APPROX(dm4=m2*refMat3, refMat4=refMat2*refMat3); + VERIFY_IS_APPROX(dm4=dm4+m2*refMat3, refMat4=refMat4+refMat2*refMat3); + VERIFY_IS_APPROX(dm4+=m2*refMat3, refMat4+=refMat2*refMat3); + VERIFY_IS_APPROX(dm4-=m2*refMat3, refMat4-=refMat2*refMat3); + VERIFY_IS_APPROX(dm4.noalias()+=m2*refMat3, refMat4+=refMat2*refMat3); + VERIFY_IS_APPROX(dm4.noalias()-=m2*refMat3, refMat4-=refMat2*refMat3); VERIFY_IS_APPROX(dm4=m2*(refMat3+refMat3), refMat4=refMat2*(refMat3+refMat3)); VERIFY_IS_APPROX(dm4=m2t.transpose()*(refMat3+refMat5)*0.5, refMat4=refMat2t.transpose()*(refMat3+refMat5)*0.5); + + // sparse * dense vector + VERIFY_IS_APPROX(dm4.col(0)=m2*refMat3.col(0), refMat4.col(0)=refMat2*refMat3.col(0)); + VERIFY_IS_APPROX(dm4.col(0)=m2*refMat3t.transpose().col(0), refMat4.col(0)=refMat2*refMat3t.transpose().col(0)); + VERIFY_IS_APPROX(dm4.col(0)=m2t.transpose()*refMat3.col(0), refMat4.col(0)=refMat2t.transpose()*refMat3.col(0)); + VERIFY_IS_APPROX(dm4.col(0)=m2t.transpose()*refMat3t.transpose().col(0), refMat4.col(0)=refMat2t.transpose()*refMat3t.transpose().col(0)); // dense * sparse VERIFY_IS_APPROX(dm4=refMat2*m3, refMat4=refMat2*refMat3); + VERIFY_IS_APPROX(dm4=dm4+refMat2*m3, refMat4=refMat4+refMat2*refMat3); + VERIFY_IS_APPROX(dm4+=refMat2*m3, refMat4+=refMat2*refMat3); + VERIFY_IS_APPROX(dm4-=refMat2*m3, refMat4-=refMat2*refMat3); + VERIFY_IS_APPROX(dm4.noalias()+=refMat2*m3, refMat4+=refMat2*refMat3); + VERIFY_IS_APPROX(dm4.noalias()-=refMat2*m3, refMat4-=refMat2*refMat3); VERIFY_IS_APPROX(dm4=refMat2*m3t.transpose(), refMat4=refMat2*refMat3t.transpose()); VERIFY_IS_APPROX(dm4=refMat2t.transpose()*m3, refMat4=refMat2t.transpose()*refMat3); VERIFY_IS_APPROX(dm4=refMat2t.transpose()*m3t.transpose(), refMat4=refMat2t.transpose()*refMat3t.transpose()); // sparse * dense and dense * sparse outer product - test_outer::run(m2,m4,refMat2,refMat4); + { + Index c = internal::random(0,depth-1); + Index r = internal::random(0,rows-1); + Index c1 = internal::random(0,cols-1); + Index r1 = internal::random(0,depth-1); + DenseMatrix dm5 = DenseMatrix::Random(depth, cols); + + VERIFY_IS_APPROX( m4=m2.col(c)*dm5.col(c1).transpose(), refMat4=refMat2.col(c)*dm5.col(c1).transpose()); + VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count()); + VERIFY_IS_APPROX( m4=m2.middleCols(c,1)*dm5.col(c1).transpose(), refMat4=refMat2.col(c)*dm5.col(c1).transpose()); + VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count()); + VERIFY_IS_APPROX(dm4=m2.col(c)*dm5.col(c1).transpose(), refMat4=refMat2.col(c)*dm5.col(c1).transpose()); + + VERIFY_IS_APPROX(m4=dm5.col(c1)*m2.col(c).transpose(), refMat4=dm5.col(c1)*refMat2.col(c).transpose()); + VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count()); + VERIFY_IS_APPROX(m4=dm5.col(c1)*m2.middleCols(c,1).transpose(), refMat4=dm5.col(c1)*refMat2.col(c).transpose()); + VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count()); + VERIFY_IS_APPROX(dm4=dm5.col(c1)*m2.col(c).transpose(), refMat4=dm5.col(c1)*refMat2.col(c).transpose()); + + VERIFY_IS_APPROX( m4=dm5.row(r1).transpose()*m2.col(c).transpose(), refMat4=dm5.row(r1).transpose()*refMat2.col(c).transpose()); + VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count()); + VERIFY_IS_APPROX(dm4=dm5.row(r1).transpose()*m2.col(c).transpose(), refMat4=dm5.row(r1).transpose()*refMat2.col(c).transpose()); + + VERIFY_IS_APPROX( m4=m2.row(r).transpose()*dm5.col(c1).transpose(), refMat4=refMat2.row(r).transpose()*dm5.col(c1).transpose()); + VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count()); + VERIFY_IS_APPROX( m4=m2.middleRows(r,1).transpose()*dm5.col(c1).transpose(), refMat4=refMat2.row(r).transpose()*dm5.col(c1).transpose()); + VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count()); + VERIFY_IS_APPROX(dm4=m2.row(r).transpose()*dm5.col(c1).transpose(), refMat4=refMat2.row(r).transpose()*dm5.col(c1).transpose()); + + VERIFY_IS_APPROX( m4=dm5.col(c1)*m2.row(r), refMat4=dm5.col(c1)*refMat2.row(r)); + VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count()); + VERIFY_IS_APPROX( m4=dm5.col(c1)*m2.middleRows(r,1), refMat4=dm5.col(c1)*refMat2.row(r)); + VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count()); + VERIFY_IS_APPROX(dm4=dm5.col(c1)*m2.row(r), refMat4=dm5.col(c1)*refMat2.row(r)); + + VERIFY_IS_APPROX( m4=dm5.row(r1).transpose()*m2.row(r), refMat4=dm5.row(r1).transpose()*refMat2.row(r)); + VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count()); + VERIFY_IS_APPROX(dm4=dm5.row(r1).transpose()*m2.row(r), refMat4=dm5.row(r1).transpose()*refMat2.row(r)); + } VERIFY_IS_APPROX(m6=m6*m6, refMat6=refMat6*refMat6); @@ -131,11 +214,11 @@ template void sparse_product() RowSpVector rv0(depth), rv1; RowDenseVector drv0(depth), drv1(rv1); initSparse(2*density,drv0, rv0); - - VERIFY_IS_APPROX(cv1=rv0*m3, dcv1=drv0*refMat3); + + VERIFY_IS_APPROX(cv1=m3*cv0, dcv1=refMat3*dcv0); VERIFY_IS_APPROX(rv1=rv0*m3, drv1=drv0*refMat3); - VERIFY_IS_APPROX(cv1=m3*cv0, dcv1=refMat3*dcv0); VERIFY_IS_APPROX(cv1=m3t.adjoint()*cv0, dcv1=refMat3t.adjoint()*dcv0); + VERIFY_IS_APPROX(cv1=rv0*m3, dcv1=drv0*refMat3); VERIFY_IS_APPROX(rv1=m3*cv0, drv1=refMat3*dcv0); } @@ -158,12 +241,16 @@ template void sparse_product() // also check with a SparseWrapper: DenseVector v1 = DenseVector::Random(cols); DenseVector v2 = DenseVector::Random(rows); + DenseVector v3 = DenseVector::Random(rows); VERIFY_IS_APPROX(m3=m2*v1.asDiagonal(), refM3=refM2*v1.asDiagonal()); VERIFY_IS_APPROX(m3=m2.transpose()*v2.asDiagonal(), refM3=refM2.transpose()*v2.asDiagonal()); VERIFY_IS_APPROX(m3=v2.asDiagonal()*m2, refM3=v2.asDiagonal()*refM2); VERIFY_IS_APPROX(m3=v1.asDiagonal()*m2.transpose(), refM3=v1.asDiagonal()*refM2.transpose()); VERIFY_IS_APPROX(m3=v2.asDiagonal()*m2*v1.asDiagonal(), refM3=v2.asDiagonal()*refM2*v1.asDiagonal()); + + VERIFY_IS_APPROX(v2=m2*v1.asDiagonal()*v1, refM2*v1.asDiagonal()*v1); + VERIFY_IS_APPROX(v3=v2.asDiagonal()*m2*v1, v2.asDiagonal()*refM2*v1); // evaluate to a dense matrix to check the .row() and .col() iterator functions VERIFY_IS_APPROX(d3=m2*d1, refM3=refM2*d1); @@ -172,7 +259,7 @@ template void sparse_product() VERIFY_IS_APPROX(d3=d1*m2.transpose(), refM3=d1*refM2.transpose()); } - // test self adjoint products + // test self-adjoint and triangular-view products { DenseMatrix b = DenseMatrix::Random(rows, rows); DenseMatrix x = DenseMatrix::Random(rows, rows); @@ -180,9 +267,12 @@ template void sparse_product() DenseMatrix refUp = DenseMatrix::Zero(rows, rows); DenseMatrix refLo = DenseMatrix::Zero(rows, rows); DenseMatrix refS = DenseMatrix::Zero(rows, rows); + DenseMatrix refA = DenseMatrix::Zero(rows, rows); SparseMatrixType mUp(rows, rows); SparseMatrixType mLo(rows, rows); SparseMatrixType mS(rows, rows); + SparseMatrixType mA(rows, rows); + initSparse(density, refA, mA); do { initSparse(density, refUp, mUp, ForceRealDiag|/*ForceNonZeroDiag|*/MakeUpperTriangular); } while (refUp.isZero()); @@ -195,26 +285,41 @@ template void sparse_product() for (int k=0; k()*b, refX=refS*b); VERIFY_IS_APPROX(x=mLo.template selfadjointView()*b, refX=refS*b); VERIFY_IS_APPROX(x=mS.template selfadjointView()*b, refX=refS*b); + + VERIFY_IS_APPROX(x.noalias()+=mUp.template selfadjointView()*b, refX+=refS*b); + VERIFY_IS_APPROX(x.noalias()-=mLo.template selfadjointView()*b, refX-=refS*b); + VERIFY_IS_APPROX(x.noalias()+=mS.template selfadjointView()*b, refX+=refS*b); - // sparse selfadjointView * sparse + // sparse selfadjointView with sparse matrices SparseMatrixType mSres(rows,rows); VERIFY_IS_APPROX(mSres = mLo.template selfadjointView()*mS, refX = refLo.template selfadjointView()*refS); - // sparse * sparse selfadjointview VERIFY_IS_APPROX(mSres = mS * mLo.template selfadjointView(), refX = refS * refLo.template selfadjointView()); + + // sparse triangularView with dense matrices + VERIFY_IS_APPROX(x=mA.template triangularView()*b, refX=refA.template triangularView()*b); + VERIFY_IS_APPROX(x=mA.template triangularView()*b, refX=refA.template triangularView()*b); + VERIFY_IS_APPROX(x=b*mA.template triangularView(), refX=b*refA.template triangularView()); + VERIFY_IS_APPROX(x=b*mA.template triangularView(), refX=b*refA.template triangularView()); + + // sparse triangularView with sparse matrices + VERIFY_IS_APPROX(mSres = mA.template triangularView()*mS, refX = refA.template triangularView()*refS); + VERIFY_IS_APPROX(mSres = mS * mA.template triangularView(), refX = refS * refA.template triangularView()); + VERIFY_IS_APPROX(mSres = mA.template triangularView()*mS, refX = refA.template triangularView()*refS); + VERIFY_IS_APPROX(mSres = mS * mA.template triangularView(), refX = refS * refA.template triangularView()); } - } // New test for Bug in SparseTimeDenseProduct @@ -239,11 +344,35 @@ template void sparse_produc VERIFY_IS_APPROX( m4(0,0), 0.0 ); } +template +void bug_942() +{ + typedef Matrix Vector; + typedef SparseMatrix ColSpMat; + typedef SparseMatrix RowSpMat; + ColSpMat cmA(1,1); + cmA.insert(0,0) = 1; + + RowSpMat rmA(1,1); + rmA.insert(0,0) = 1; + + Vector d(1); + d[0] = 2; + + double res = 2; + + VERIFY_IS_APPROX( ( cmA*d.asDiagonal() ).eval().coeff(0,0), res ); + VERIFY_IS_APPROX( ( d.asDiagonal()*rmA ).eval().coeff(0,0), res ); + VERIFY_IS_APPROX( ( rmA*d.asDiagonal() ).eval().coeff(0,0), res ); + VERIFY_IS_APPROX( ( d.asDiagonal()*cmA ).eval().coeff(0,0), res ); +} + void test_sparse_product() { for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( (sparse_product >()) ); CALL_SUBTEST_1( (sparse_product >()) ); + CALL_SUBTEST_1( (bug_942()) ); CALL_SUBTEST_2( (sparse_product, ColMajor > >()) ); CALL_SUBTEST_2( (sparse_product, RowMajor > >()) ); CALL_SUBTEST_3( (sparse_product >()) ); diff --git a/testbed/nanogui/ext/eigen/test/sparse_ref.cpp b/testbed/nanogui/ext/eigen/test/sparse_ref.cpp new file mode 100644 index 00000000..5e960723 --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/sparse_ref.cpp @@ -0,0 +1,139 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 20015 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +// This unit test cannot be easily written to work with EIGEN_DEFAULT_TO_ROW_MAJOR +#ifdef EIGEN_DEFAULT_TO_ROW_MAJOR +#undef EIGEN_DEFAULT_TO_ROW_MAJOR +#endif + +static long int nb_temporaries; + +inline void on_temporary_creation() { + // here's a great place to set a breakpoint when debugging failures in this test! + nb_temporaries++; +} + +#define EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN { on_temporary_creation(); } + +#include "main.h" +#include + +#define VERIFY_EVALUATION_COUNT(XPR,N) {\ + nb_temporaries = 0; \ + CALL_SUBTEST( XPR ); \ + if(nb_temporaries!=N) std::cerr << "nb_temporaries == " << nb_temporaries << "\n"; \ + VERIFY( (#XPR) && nb_temporaries==N ); \ + } + +template void check_const_correctness(const PlainObjectType&) +{ + // verify that ref-to-const don't have LvalueBit + typedef typename internal::add_const::type ConstPlainObjectType; + VERIFY( !(internal::traits >::Flags & LvalueBit) ); + VERIFY( !(internal::traits >::Flags & LvalueBit) ); + VERIFY( !(Ref::Flags & LvalueBit) ); + VERIFY( !(Ref::Flags & LvalueBit) ); +} + +template +EIGEN_DONT_INLINE void call_ref_1(Ref > a, const B &b) { VERIFY_IS_EQUAL(a.toDense(),b.toDense()); } + +template +EIGEN_DONT_INLINE void call_ref_2(const Ref >& a, const B &b) { VERIFY_IS_EQUAL(a.toDense(),b.toDense()); } + +template +EIGEN_DONT_INLINE void call_ref_3(const Ref, StandardCompressedFormat>& a, const B &b) { + VERIFY(a.isCompressed()); + VERIFY_IS_EQUAL(a.toDense(),b.toDense()); +} + +template +EIGEN_DONT_INLINE void call_ref_4(Ref > a, const B &b) { VERIFY_IS_EQUAL(a.toDense(),b.toDense()); } + +template +EIGEN_DONT_INLINE void call_ref_5(const Ref >& a, const B &b) { VERIFY_IS_EQUAL(a.toDense(),b.toDense()); } + +void call_ref() +{ + SparseMatrix A = MatrixXf::Random(10,10).sparseView(0.5,1); + SparseMatrix B = MatrixXf::Random(10,10).sparseView(0.5,1); + SparseMatrix C = MatrixXf::Random(10,10).sparseView(0.5,1); + C.reserve(VectorXi::Constant(C.outerSize(), 2)); + const SparseMatrix& Ac(A); + Block > Ab(A,0,1, 3,3); + const Block > Abc(A,0,1,3,3); + SparseVector vc = VectorXf::Random(10).sparseView(0.5,1); + SparseVector vr = VectorXf::Random(10).sparseView(0.5,1); + SparseMatrix AA = A*A; + + + VERIFY_EVALUATION_COUNT( call_ref_1(A, A), 0); +// VERIFY_EVALUATION_COUNT( call_ref_1(Ac, Ac), 0); // does not compile on purpose + VERIFY_EVALUATION_COUNT( call_ref_2(A, A), 0); + VERIFY_EVALUATION_COUNT( call_ref_3(A, A), 0); + VERIFY_EVALUATION_COUNT( call_ref_2(A.transpose(), A.transpose()), 1); + VERIFY_EVALUATION_COUNT( call_ref_3(A.transpose(), A.transpose()), 1); + VERIFY_EVALUATION_COUNT( call_ref_2(Ac,Ac), 0); + VERIFY_EVALUATION_COUNT( call_ref_3(Ac,Ac), 0); + VERIFY_EVALUATION_COUNT( call_ref_2(A+A,2*Ac), 1); + VERIFY_EVALUATION_COUNT( call_ref_3(A+A,2*Ac), 1); + VERIFY_EVALUATION_COUNT( call_ref_2(B, B), 1); + VERIFY_EVALUATION_COUNT( call_ref_3(B, B), 1); + VERIFY_EVALUATION_COUNT( call_ref_2(B.transpose(), B.transpose()), 0); + VERIFY_EVALUATION_COUNT( call_ref_3(B.transpose(), B.transpose()), 0); + VERIFY_EVALUATION_COUNT( call_ref_2(A*A, AA), 3); + VERIFY_EVALUATION_COUNT( call_ref_3(A*A, AA), 3); + + VERIFY(!C.isCompressed()); + VERIFY_EVALUATION_COUNT( call_ref_3(C, C), 1); + + Ref > Ar(A); + VERIFY_IS_APPROX(Ar+Ar, A+A); + VERIFY_EVALUATION_COUNT( call_ref_1(Ar, A), 0); + VERIFY_EVALUATION_COUNT( call_ref_2(Ar, A), 0); + + Ref > Br(B); + VERIFY_EVALUATION_COUNT( call_ref_1(Br.transpose(), Br.transpose()), 0); + VERIFY_EVALUATION_COUNT( call_ref_2(Br, Br), 1); + VERIFY_EVALUATION_COUNT( call_ref_2(Br.transpose(), Br.transpose()), 0); + + Ref > Arc(A); +// VERIFY_EVALUATION_COUNT( call_ref_1(Arc, Arc), 0); // does not compile on purpose + VERIFY_EVALUATION_COUNT( call_ref_2(Arc, Arc), 0); + + VERIFY_EVALUATION_COUNT( call_ref_2(A.middleCols(1,3), A.middleCols(1,3)), 0); + + VERIFY_EVALUATION_COUNT( call_ref_2(A.col(2), A.col(2)), 0); + VERIFY_EVALUATION_COUNT( call_ref_2(vc, vc), 0); + VERIFY_EVALUATION_COUNT( call_ref_2(vr.transpose(), vr.transpose()), 0); + VERIFY_EVALUATION_COUNT( call_ref_2(vr, vr.transpose()), 0); + + VERIFY_EVALUATION_COUNT( call_ref_2(A.block(1,1,3,3), A.block(1,1,3,3)), 1); // should be 0 (allocate starts/nnz only) + + VERIFY_EVALUATION_COUNT( call_ref_4(vc, vc), 0); + VERIFY_EVALUATION_COUNT( call_ref_4(vr, vr.transpose()), 0); + VERIFY_EVALUATION_COUNT( call_ref_5(vc, vc), 0); + VERIFY_EVALUATION_COUNT( call_ref_5(vr, vr.transpose()), 0); + VERIFY_EVALUATION_COUNT( call_ref_4(A.col(2), A.col(2)), 0); + VERIFY_EVALUATION_COUNT( call_ref_5(A.col(2), A.col(2)), 0); + // VERIFY_EVALUATION_COUNT( call_ref_4(A.row(2), A.row(2).transpose()), 1); // does not compile on purpose + VERIFY_EVALUATION_COUNT( call_ref_5(A.row(2), A.row(2).transpose()), 1); +} + +void test_sparse_ref() +{ + for(int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_1( check_const_correctness(SparseMatrix()) ); + CALL_SUBTEST_1( check_const_correctness(SparseMatrix()) ); + CALL_SUBTEST_2( call_ref() ); + + CALL_SUBTEST_3( check_const_correctness(SparseVector()) ); + CALL_SUBTEST_3( check_const_correctness(SparseVector()) ); + } +} diff --git a/testbed/nanogui/ext/eigen/test/sparse_solver.h b/testbed/nanogui/ext/eigen/test/sparse_solver.h index 244e81c1..5145bc3e 100644 --- a/testbed/nanogui/ext/eigen/test/sparse_solver.h +++ b/testbed/nanogui/ext/eigen/test/sparse_solver.h @@ -9,102 +9,167 @@ #include "sparse.h" #include +#include + +template +void solve_with_guess(IterativeSolverBase& solver, const MatrixBase& b, const Guess& g, Result &x) { + if(internal::random()) + { + // With a temporary through evaluator + x = solver.derived().solveWithGuess(b,g) + Result::Zero(x.rows(), x.cols()); + } + else + { + // direct evaluation within x through Assignment + x = solver.derived().solveWithGuess(b.derived(),g); + } +} + +template +void solve_with_guess(SparseSolverBase& solver, const MatrixBase& b, const Guess& , Result& x) { + if(internal::random()) + x = solver.derived().solve(b) + Result::Zero(x.rows(), x.cols()); + else + x = solver.derived().solve(b); +} + +template +void solve_with_guess(SparseSolverBase& solver, const SparseMatrixBase& b, const Guess& , Result& x) { + x = solver.derived().solve(b); +} template void check_sparse_solving(Solver& solver, const typename Solver::MatrixType& A, const Rhs& b, const DenseMat& dA, const DenseRhs& db) { typedef typename Solver::MatrixType Mat; typedef typename Mat::Scalar Scalar; + typedef typename Mat::StorageIndex StorageIndex; - DenseRhs refX = dA.lu().solve(db); + DenseRhs refX = dA.householderQr().solve(db); { - Rhs x(b.rows(), b.cols()); + Rhs x(A.cols(), b.cols()); Rhs oldb = b; solver.compute(A); if (solver.info() != Success) { - std::cerr << "sparse solver testing: factorization failed (check_sparse_solving)\n"; - exit(0); - return; + std::cerr << "ERROR | sparse solver testing, factorization failed (" << typeid(Solver).name() << ")\n"; + VERIFY(solver.info() == Success); } x = solver.solve(b); if (solver.info() != Success) { - std::cerr << "sparse solver testing: solving failed\n"; + std::cerr << "WARNING | sparse solver testing: solving failed (" << typeid(Solver).name() << ")\n"; return; } VERIFY(oldb.isApprox(b) && "sparse solver testing: the rhs should not be modified!"); - VERIFY(x.isApprox(refX,test_precision())); + + x.setZero(); + solve_with_guess(solver, b, x, x); + VERIFY(solver.info() == Success && "solving failed when using analyzePattern/factorize API"); + VERIFY(oldb.isApprox(b) && "sparse solver testing: the rhs should not be modified!"); + VERIFY(x.isApprox(refX,test_precision())); + x.setZero(); // test the analyze/factorize API solver.analyzePattern(A); solver.factorize(A); - if (solver.info() != Success) - { - std::cerr << "sparse solver testing: factorization failed (check_sparse_solving)\n"; - exit(0); - return; - } + VERIFY(solver.info() == Success && "factorization failed when using analyzePattern/factorize API"); x = solver.solve(b); - if (solver.info() != Success) - { - std::cerr << "sparse solver testing: solving failed\n"; - return; - } + VERIFY(solver.info() == Success && "solving failed when using analyzePattern/factorize API"); VERIFY(oldb.isApprox(b) && "sparse solver testing: the rhs should not be modified!"); - VERIFY(x.isApprox(refX,test_precision())); + + x.setZero(); + // test with Map + MappedSparseMatrix Am(A.rows(), A.cols(), A.nonZeros(), const_cast(A.outerIndexPtr()), const_cast(A.innerIndexPtr()), const_cast(A.valuePtr())); + solver.compute(Am); + VERIFY(solver.info() == Success && "factorization failed when using Map"); + DenseRhs dx(refX); + dx.setZero(); + Map xm(dx.data(), dx.rows(), dx.cols()); + Map bm(db.data(), db.rows(), db.cols()); + xm = solver.solve(bm); + VERIFY(solver.info() == Success && "solving failed when using Map"); + VERIFY(oldb.isApprox(bm) && "sparse solver testing: the rhs should not be modified!"); + VERIFY(xm.isApprox(refX,test_precision())); } - // test dense Block as the result and rhs: + // if not too large, do some extra check: + if(A.rows()<2000) { - DenseRhs x(db.rows(), db.cols()); - DenseRhs oldb(db); - x.setZero(); - x.block(0,0,x.rows(),x.cols()) = solver.solve(db.block(0,0,db.rows(),db.cols())); - VERIFY(oldb.isApprox(db) && "sparse solver testing: the rhs should not be modified!"); - VERIFY(x.isApprox(refX,test_precision())); + // test initialization ctor + { + Rhs x(b.rows(), b.cols()); + Solver solver2(A); + VERIFY(solver2.info() == Success); + x = solver2.solve(b); + VERIFY(x.isApprox(refX,test_precision())); + } + + // test dense Block as the result and rhs: + { + DenseRhs x(refX.rows(), refX.cols()); + DenseRhs oldb(db); + x.setZero(); + x.block(0,0,x.rows(),x.cols()) = solver.solve(db.block(0,0,db.rows(),db.cols())); + VERIFY(oldb.isApprox(db) && "sparse solver testing: the rhs should not be modified!"); + VERIFY(x.isApprox(refX,test_precision())); + } + + // test uncompressed inputs + { + Mat A2 = A; + A2.reserve((ArrayXf::Random(A.outerSize())+2).template cast().eval()); + solver.compute(A2); + Rhs x = solver.solve(b); + VERIFY(x.isApprox(refX,test_precision())); + } + + // test expression as input + { + solver.compute(0.5*(A+A)); + Rhs x = solver.solve(b); + VERIFY(x.isApprox(refX,test_precision())); + + Solver solver2(0.5*(A+A)); + Rhs x2 = solver2.solve(b); + VERIFY(x2.isApprox(refX,test_precision())); + } } } template -void check_sparse_solving_real_cases(Solver& solver, const typename Solver::MatrixType& A, const Rhs& b, const Rhs& refX) +void check_sparse_solving_real_cases(Solver& solver, const typename Solver::MatrixType& A, const Rhs& b, const typename Solver::MatrixType& fullA, const Rhs& refX) { typedef typename Solver::MatrixType Mat; typedef typename Mat::Scalar Scalar; typedef typename Mat::RealScalar RealScalar; - Rhs x(b.rows(), b.cols()); - + Rhs x(A.cols(), b.cols()); + solver.compute(A); if (solver.info() != Success) { - std::cerr << "sparse solver testing: factorization failed (check_sparse_solving_real_cases)\n"; - exit(0); - return; + std::cerr << "ERROR | sparse solver testing, factorization failed (" << typeid(Solver).name() << ")\n"; + VERIFY(solver.info() == Success); } x = solver.solve(b); + if (solver.info() != Success) { - std::cerr << "sparse solver testing: solving failed\n"; + std::cerr << "WARNING | sparse solver testing, solving failed (" << typeid(Solver).name() << ")\n"; return; } - RealScalar res_error; - // Compute the norm of the relative error - if(refX.size() != 0) - res_error = (refX - x).norm()/refX.norm(); - else - { - // Compute the relative residual norm - res_error = (b - A * x).norm()/b.norm(); - } - if (res_error > test_precision() ){ - std::cerr << "Test " << g_test_stack.back() << " failed in "EI_PP_MAKE_STRING(__FILE__) - << " (" << EI_PP_MAKE_STRING(__LINE__) << ")" << std::endl << std::endl; - abort(); + RealScalar res_error = (fullA*x-b).norm()/b.norm(); + VERIFY( (res_error <= test_precision() ) && "sparse solver failed without noticing it"); + + + if(refX.size() != 0 && (refX - x).norm()/refX.norm() > test_precision()) + { + std::cerr << "WARNING | found solution is different from the provided reference one\n"; } } @@ -117,7 +182,7 @@ void check_sparse_determinant(Solver& solver, const typename Solver::MatrixType& solver.compute(A); if (solver.info() != Success) { - std::cerr << "sparse solver testing: factorization failed (check_sparse_determinant)\n"; + std::cerr << "WARNING | sparse solver testing: factorization failed (check_sparse_determinant)\n"; return; } @@ -134,7 +199,7 @@ void check_sparse_abs_determinant(Solver& solver, const typename Solver::MatrixT solver.compute(A); if (solver.info() != Success) { - std::cerr << "sparse solver testing: factorization failed (check_sparse_abs_determinant)\n"; + std::cerr << "WARNING | sparse solver testing: factorization failed (check_sparse_abs_determinant)\n"; return; } @@ -161,7 +226,10 @@ int generate_sparse_spd_problem(Solver& , typename Solver::MatrixType& A, typena dA = dM * dM.adjoint(); halfA.resize(size,size); - halfA.template selfadjointView().rankUpdate(M); + if(Solver::UpLo==(Lower|Upper)) + halfA = A; + else + halfA.template selfadjointView().rankUpdate(M); return size; } @@ -178,13 +246,33 @@ inline std::string get_matrixfolder() mat_folder = mat_folder + static_cast("/real/"); return mat_folder; } +std::string sym_to_string(int sym) +{ + if(sym==Symmetric) return "Symmetric "; + if(sym==SPD) return "SPD "; + return ""; +} +template +std::string solver_stats(const IterativeSolverBase &solver) +{ + std::stringstream ss; + ss << solver.iterations() << " iters, error: " << solver.error(); + return ss.str(); +} +template +std::string solver_stats(const SparseSolverBase &/*solver*/) +{ + return ""; +} #endif -template void check_sparse_spd_solving(Solver& solver) +template void check_sparse_spd_solving(Solver& solver, int maxSize = 300, int maxRealWorldSize = 100000) { typedef typename Solver::MatrixType Mat; typedef typename Mat::Scalar Scalar; - typedef SparseMatrix SpMat; + typedef typename Mat::StorageIndex StorageIndex; + typedef SparseMatrix SpMat; + typedef SparseVector SpVec; typedef Matrix DenseMatrix; typedef Matrix DenseVector; @@ -192,7 +280,7 @@ template void check_sparse_spd_solving(Solver& solver) Mat A, halfA; DenseMatrix dA; for (int i = 0; i < g_repeat; i++) { - int size = generate_sparse_spd_problem(solver, A, halfA, dA); + int size = generate_sparse_spd_problem(solver, A, halfA, dA, maxSize); // generate the right hand sides int rhsCols = internal::random(1,16); @@ -201,13 +289,17 @@ template void check_sparse_spd_solving(Solver& solver) DenseVector b = DenseVector::Random(size); DenseMatrix dB(size,rhsCols); initSparse(density, dB, B, ForceNonZeroDiag); + SpVec c = B.col(0); + DenseVector dc = dB.col(0); - check_sparse_solving(solver, A, b, dA, b); - check_sparse_solving(solver, halfA, b, dA, b); - check_sparse_solving(solver, A, dB, dA, dB); - check_sparse_solving(solver, halfA, dB, dA, dB); - check_sparse_solving(solver, A, B, dA, dB); - check_sparse_solving(solver, halfA, B, dA, dB); + CALL_SUBTEST( check_sparse_solving(solver, A, b, dA, b) ); + CALL_SUBTEST( check_sparse_solving(solver, halfA, b, dA, b) ); + CALL_SUBTEST( check_sparse_solving(solver, A, dB, dA, dB) ); + CALL_SUBTEST( check_sparse_solving(solver, halfA, dB, dA, dB) ); + CALL_SUBTEST( check_sparse_solving(solver, A, B, dA, dB) ); + CALL_SUBTEST( check_sparse_solving(solver, halfA, B, dA, dB) ); + CALL_SUBTEST( check_sparse_solving(solver, A, c, dA, dc) ); + CALL_SUBTEST( check_sparse_solving(solver, halfA, c, dA, dc) ); // check only once if(i==0) @@ -218,25 +310,44 @@ template void check_sparse_spd_solving(Solver& solver) } // First, get the folder -#ifdef TEST_REAL_CASES - if (internal::is_same::value - || internal::is_same >::value) - return ; - - std::string mat_folder = get_matrixfolder(); - MatrixMarketIterator it(mat_folder); - for (; it; ++it) +#ifdef TEST_REAL_CASES + // Test real problems with double precision only + if (internal::is_same::Real, double>::value) { - if (it.sym() == SPD){ - Mat halfA; - PermutationMatrix pnull; - halfA.template selfadjointView() = it.matrix().template triangularView().twistedBy(pnull); - - std::cout<< " ==== SOLVING WITH MATRIX " << it.matname() << " ==== \n"; - check_sparse_solving_real_cases(solver, it.matrix(), it.rhs(), it.refX()); - check_sparse_solving_real_cases(solver, halfA, it.rhs(), it.refX()); + std::string mat_folder = get_matrixfolder(); + MatrixMarketIterator it(mat_folder); + for (; it; ++it) + { + if (it.sym() == SPD){ + A = it.matrix(); + if(A.diagonal().size() <= maxRealWorldSize) + { + DenseVector b = it.rhs(); + DenseVector refX = it.refX(); + PermutationMatrix pnull; + halfA.resize(A.rows(), A.cols()); + if(Solver::UpLo == (Lower|Upper)) + halfA = A; + else + halfA.template selfadjointView() = A.template triangularView().twistedBy(pnull); + + std::cout << "INFO | Testing " << sym_to_string(it.sym()) << "sparse problem " << it.matname() + << " (" << A.rows() << "x" << A.cols() << ") using " << typeid(Solver).name() << "..." << std::endl; + CALL_SUBTEST( check_sparse_solving_real_cases(solver, A, b, A, refX) ); + std::string stats = solver_stats(solver); + if(stats.size()>0) + std::cout << "INFO | " << stats << std::endl; + CALL_SUBTEST( check_sparse_solving_real_cases(solver, halfA, b, A, refX) ); + } + else + { + std::cout << "INFO | Skip sparse problem \"" << it.matname() << "\" (too large)" << std::endl; + } + } } } +#else + EIGEN_UNUSED_VARIABLE(maxRealWorldSize); #endif } @@ -258,27 +369,39 @@ template void check_sparse_spd_determinant(Solver& solver) } template -int generate_sparse_square_problem(Solver&, typename Solver::MatrixType& A, DenseMat& dA, int maxSize = 300) +Index generate_sparse_square_problem(Solver&, typename Solver::MatrixType& A, DenseMat& dA, int maxSize = 300, int options = ForceNonZeroDiag) { typedef typename Solver::MatrixType Mat; typedef typename Mat::Scalar Scalar; - int size = internal::random(1,maxSize); + Index size = internal::random(1,maxSize); double density = (std::max)(8./(size*size), 0.01); A.resize(size,size); dA.resize(size,size); - initSparse(density, dA, A, ForceNonZeroDiag); + initSparse(density, dA, A, options); return size; } -template void check_sparse_square_solving(Solver& solver) + +struct prune_column { + Index m_col; + prune_column(Index col) : m_col(col) {} + template + bool operator()(Index, Index col, const Scalar&) const { + return col != m_col; + } +}; + + +template void check_sparse_square_solving(Solver& solver, int maxSize = 300, int maxRealWorldSize = 100000, bool checkDeficient = false) { typedef typename Solver::MatrixType Mat; typedef typename Mat::Scalar Scalar; - typedef SparseMatrix SpMat; + typedef SparseMatrix SpMat; + typedef SparseVector SpVec; typedef Matrix DenseMatrix; typedef Matrix DenseVector; @@ -287,7 +410,7 @@ template void check_sparse_square_solving(Solver& solver) Mat A; DenseMatrix dA; for (int i = 0; i < g_repeat; i++) { - int size = generate_sparse_square_problem(solver, A, dA); + Index size = generate_sparse_square_problem(solver, A, dA, maxSize); A.makeCompressed(); DenseVector b = DenseVector::Random(size); @@ -296,9 +419,12 @@ template void check_sparse_square_solving(Solver& solver) double density = (std::max)(8./(size*rhsCols), 0.1); initSparse(density, dB, B, ForceNonZeroDiag); B.makeCompressed(); - check_sparse_solving(solver, A, b, dA, b); - check_sparse_solving(solver, A, dB, dA, dB); - check_sparse_solving(solver, A, B, dA, dB); + SpVec c = B.col(0); + DenseVector dc = dB.col(0); + CALL_SUBTEST(check_sparse_solving(solver, A, b, dA, b)); + CALL_SUBTEST(check_sparse_solving(solver, A, dB, dA, dB)); + CALL_SUBTEST(check_sparse_solving(solver, A, B, dA, dB)); + CALL_SUBTEST(check_sparse_solving(solver, A, c, dA, dc)); // check only once if(i==0) @@ -306,21 +432,44 @@ template void check_sparse_square_solving(Solver& solver) b = DenseVector::Zero(size); check_sparse_solving(solver, A, b, dA, b); } + // regression test for Bug 792 (structurally rank deficient matrices): + if(checkDeficient && size>1) { + Index col = internal::random(0,int(size-1)); + A.prune(prune_column(col)); + solver.compute(A); + VERIFY_IS_EQUAL(solver.info(), NumericalIssue); + } } // First, get the folder #ifdef TEST_REAL_CASES - if (internal::is_same::value - || internal::is_same >::value) - return ; - - std::string mat_folder = get_matrixfolder(); - MatrixMarketIterator it(mat_folder); - for (; it; ++it) + // Test real problems with double precision only + if (internal::is_same::Real, double>::value) { - std::cout<< " ==== SOLVING WITH MATRIX " << it.matname() << " ==== \n"; - check_sparse_solving_real_cases(solver, it.matrix(), it.rhs(), it.refX()); + std::string mat_folder = get_matrixfolder(); + MatrixMarketIterator it(mat_folder); + for (; it; ++it) + { + A = it.matrix(); + if(A.diagonal().size() <= maxRealWorldSize) + { + DenseVector b = it.rhs(); + DenseVector refX = it.refX(); + std::cout << "INFO | Testing " << sym_to_string(it.sym()) << "sparse problem " << it.matname() + << " (" << A.rows() << "x" << A.cols() << ") using " << typeid(Solver).name() << "..." << std::endl; + CALL_SUBTEST(check_sparse_solving_real_cases(solver, A, b, A, refX)); + std::string stats = solver_stats(solver); + if(stats.size()>0) + std::cout << "INFO | " << stats << std::endl; + } + else + { + std::cout << "INFO | SKIP sparse problem \"" << it.matname() << "\" (too large)" << std::endl; + } + } } +#else + EIGEN_UNUSED_VARIABLE(maxRealWorldSize); #endif } @@ -330,13 +479,20 @@ template void check_sparse_square_determinant(Solver& solver) typedef typename Solver::MatrixType Mat; typedef typename Mat::Scalar Scalar; typedef Matrix DenseMatrix; - - // generate the problem - Mat A; - DenseMatrix dA; - generate_sparse_square_problem(solver, A, dA, 30); - A.makeCompressed(); + for (int i = 0; i < g_repeat; i++) { + // generate the problem + Mat A; + DenseMatrix dA; + + int size = internal::random(1,30); + dA.setRandom(size,size); + + dA = (dA.array().abs()<0.3).select(0,dA); + dA.diagonal() = (dA.diagonal().array()==0).select(1,dA.diagonal()); + A = dA.sparseView(); + A.makeCompressed(); + check_sparse_determinant(solver, A, dA); } } @@ -347,13 +503,63 @@ template void check_sparse_square_abs_determinant(Solver& solve typedef typename Mat::Scalar Scalar; typedef Matrix DenseMatrix; - // generate the problem - Mat A; - DenseMatrix dA; - generate_sparse_square_problem(solver, A, dA, 30); - A.makeCompressed(); for (int i = 0; i < g_repeat; i++) { + // generate the problem + Mat A; + DenseMatrix dA; + generate_sparse_square_problem(solver, A, dA, 30); + A.makeCompressed(); check_sparse_abs_determinant(solver, A, dA); } } +template +void generate_sparse_leastsquare_problem(Solver&, typename Solver::MatrixType& A, DenseMat& dA, int maxSize = 300, int options = ForceNonZeroDiag) +{ + typedef typename Solver::MatrixType Mat; + typedef typename Mat::Scalar Scalar; + + int rows = internal::random(1,maxSize); + int cols = internal::random(1,rows); + double density = (std::max)(8./(rows*cols), 0.01); + + A.resize(rows,cols); + dA.resize(rows,cols); + + initSparse(density, dA, A, options); +} + +template void check_sparse_leastsquare_solving(Solver& solver) +{ + typedef typename Solver::MatrixType Mat; + typedef typename Mat::Scalar Scalar; + typedef SparseMatrix SpMat; + typedef Matrix DenseMatrix; + typedef Matrix DenseVector; + + int rhsCols = internal::random(1,16); + + Mat A; + DenseMatrix dA; + for (int i = 0; i < g_repeat; i++) { + generate_sparse_leastsquare_problem(solver, A, dA); + + A.makeCompressed(); + DenseVector b = DenseVector::Random(A.rows()); + DenseMatrix dB(A.rows(),rhsCols); + SpMat B(A.rows(),rhsCols); + double density = (std::max)(8./(A.rows()*rhsCols), 0.1); + initSparse(density, dB, B, ForceNonZeroDiag); + B.makeCompressed(); + check_sparse_solving(solver, A, b, dA, b); + check_sparse_solving(solver, A, dB, dA, dB); + check_sparse_solving(solver, A, B, dA, dB); + + // check only once + if(i==0) + { + b = DenseVector::Zero(A.rows()); + check_sparse_solving(solver, A, b, dA, b); + } + } +} diff --git a/testbed/nanogui/ext/eigen/test/sparse_vector.cpp b/testbed/nanogui/ext/eigen/test/sparse_vector.cpp index 0c947680..b3e1dda2 100644 --- a/testbed/nanogui/ext/eigen/test/sparse_vector.cpp +++ b/testbed/nanogui/ext/eigen/test/sparse_vector.cpp @@ -9,22 +9,22 @@ #include "sparse.h" -template void sparse_vector(int rows, int cols) +template void sparse_vector(int rows, int cols) { double densityMat = (std::max)(8./(rows*cols), 0.01); - double densityVec = (std::max)(8./float(rows), 0.1); + double densityVec = (std::max)(8./(rows), 0.1); typedef Matrix DenseMatrix; typedef Matrix DenseVector; - typedef SparseVector SparseVectorType; - typedef SparseMatrix SparseMatrixType; + typedef SparseVector SparseVectorType; + typedef SparseMatrix SparseMatrixType; Scalar eps = 1e-6; SparseMatrixType m1(rows,rows); SparseVectorType v1(rows), v2(rows), v3(rows); DenseMatrix refM1 = DenseMatrix::Zero(rows, rows); DenseVector refV1 = DenseVector::Random(rows), - refV2 = DenseVector::Random(rows), - refV3 = DenseVector::Random(rows); + refV2 = DenseVector::Random(rows), + refV3 = DenseVector::Random(rows); std::vector zerocoords, nonzerocoords; initSparse(densityVec, refV1, v1, &zerocoords, &nonzerocoords); @@ -52,6 +52,20 @@ template void sparse_vector(int rows, int cols) } } VERIFY_IS_APPROX(v1, refV1); + + // test coeffRef with reallocation + { + SparseVectorType v4(rows); + DenseVector v5 = DenseVector::Zero(rows); + for(int k=0; k(0,rows-1); + Scalar v = internal::random(); + v4.coeffRef(i) += v; + v5.coeffRef(i) += v; + } + VERIFY_IS_APPROX(v4,v5); + } v1.coeffRef(nonzerocoords[0]) = Scalar(5); refV1.coeffRef(nonzerocoords[0]) = Scalar(5); @@ -71,9 +85,12 @@ template void sparse_vector(int rows, int cols) VERIFY_IS_APPROX(v1.dot(v2), refV1.dot(refV2)); VERIFY_IS_APPROX(v1.dot(refV2), refV1.dot(refV2)); + VERIFY_IS_APPROX(m1*v2, refM1*refV2); VERIFY_IS_APPROX(v1.dot(m1*v2), refV1.dot(refM1*refV2)); - int i = internal::random(0,rows-1); - VERIFY_IS_APPROX(v1.dot(m1.col(i)), refV1.dot(refM1.col(i))); + { + int i = internal::random(0,rows-1); + VERIFY_IS_APPROX(v1.dot(m1.col(i)), refV1.dot(refM1.col(i))); + } VERIFY_IS_APPROX(v1.squaredNorm(), refV1.squaredNorm()); @@ -96,15 +113,51 @@ template void sparse_vector(int rows, int cols) VERIFY_IS_APPROX(refV3 = v1.transpose(),v1.toDense()); VERIFY_IS_APPROX(DenseVector(v1),v1.toDense()); + // test conservative resize + { + std::vector inc; + if(rows > 3) + inc.push_back(-3); + inc.push_back(0); + inc.push_back(3); + inc.push_back(1); + inc.push_back(10); + + for(std::size_t i = 0; i< inc.size(); i++) { + StorageIndex incRows = inc[i]; + SparseVectorType vec1(rows); + DenseVector refVec1 = DenseVector::Zero(rows); + initSparse(densityVec, refVec1, vec1); + + vec1.conservativeResize(rows+incRows); + refVec1.conservativeResize(rows+incRows); + if (incRows > 0) refVec1.tail(incRows).setZero(); + + VERIFY_IS_APPROX(vec1, refVec1); + + // Insert new values + if (incRows > 0) + vec1.insert(vec1.rows()-1) = refVec1(refVec1.rows()-1) = 1; + + VERIFY_IS_APPROX(vec1, refVec1); + } + } + } void test_sparse_vector() { for(int i = 0; i < g_repeat; i++) { + int r = Eigen::internal::random(1,500), c = Eigen::internal::random(1,500); + if(Eigen::internal::random(0,4) == 0) { + r = c; // check square matrices in 25% of tries + } + EIGEN_UNUSED_VARIABLE(r+c); + CALL_SUBTEST_1(( sparse_vector(8, 8) )); - CALL_SUBTEST_2(( sparse_vector, int>(16, 16) )); - CALL_SUBTEST_1(( sparse_vector(299, 535) )); - CALL_SUBTEST_1(( sparse_vector(299, 535) )); + CALL_SUBTEST_2(( sparse_vector, int>(r, c) )); + CALL_SUBTEST_1(( sparse_vector(r, c) )); + CALL_SUBTEST_1(( sparse_vector(r, c) )); } } diff --git a/testbed/nanogui/ext/eigen/test/sparselu.cpp b/testbed/nanogui/ext/eigen/test/sparselu.cpp index 52371cb1..bd000baf 100644 --- a/testbed/nanogui/ext/eigen/test/sparselu.cpp +++ b/testbed/nanogui/ext/eigen/test/sparselu.cpp @@ -3,25 +3,9 @@ // // Copyright (C) 2012 Désiré Nuentsa-Wakam // -// Eigen is free software; you can redistribute it and/or -// modify it under the terms of the GNU Lesser General Public -// License as published by the Free Software Foundation; either -// version 3 of the License, or (at your option) any later version. -// -// Alternatively, you can redistribute it and/or -// modify it under the terms of the GNU General Public License as -// published by the Free Software Foundation; either version 2 of -// the License, or (at your option) any later version. -// -// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY -// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS -// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the -// GNU General Public License for more details. -// -// You should have received a copy of the GNU Lesser General Public -// License and a copy of the GNU General Public License along with -// Eigen. If not, see . - +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. // SparseLU solve does not accept column major matrices for the destination. // However, as expected, the generic check_sparse_square_solving routines produces row-major @@ -41,12 +25,15 @@ template void test_sparselu_T() SparseLU, AMDOrdering > sparselu_amd; SparseLU, NaturalOrdering > sparselu_natural; - check_sparse_square_solving(sparselu_colamd); - check_sparse_square_solving(sparselu_amd); - check_sparse_square_solving(sparselu_natural); + check_sparse_square_solving(sparselu_colamd, 300, 100000, true); + check_sparse_square_solving(sparselu_amd, 300, 10000, true); + check_sparse_square_solving(sparselu_natural, 300, 2000, true); check_sparse_square_abs_determinant(sparselu_colamd); check_sparse_square_abs_determinant(sparselu_amd); + + check_sparse_square_determinant(sparselu_colamd); + check_sparse_square_determinant(sparselu_amd); } void test_sparselu() diff --git a/testbed/nanogui/ext/eigen/test/sparseqr.cpp b/testbed/nanogui/ext/eigen/test/sparseqr.cpp index 451c0e7f..e8605fd2 100644 --- a/testbed/nanogui/ext/eigen/test/sparseqr.cpp +++ b/testbed/nanogui/ext/eigen/test/sparseqr.cpp @@ -10,11 +10,12 @@ #include template -int generate_sparse_rectangular_problem(MatrixType& A, DenseMat& dA, int maxRows = 300) +int generate_sparse_rectangular_problem(MatrixType& A, DenseMat& dA, int maxRows = 300, int maxCols = 150) { + eigen_assert(maxRows >= maxCols); typedef typename MatrixType::Scalar Scalar; int rows = internal::random(1,maxRows); - int cols = internal::random(1,rows); + int cols = internal::random(1,maxCols); double density = (std::max)(8./(rows*cols), 0.01); A.resize(rows,cols); @@ -53,7 +54,7 @@ template void test_sparseqr_scalar() b = dA * DenseVector::Random(A.cols()); solver.compute(A); - if(internal::random(0,1)>0.5) + if(internal::random(0,1)>0.5f) solver.factorize(A); // this checks that calling analyzePattern is not needed if the pattern do not change. if (solver.info() != Success) { @@ -88,6 +89,11 @@ template void test_sparseqr_scalar() QtQ = Q * Q.adjoint(); idM.resize(Q.rows(), Q.rows()); idM.setIdentity(); VERIFY(idM.isApprox(QtQ)); + + // Q to dense + DenseMat dQ; + dQ = solver.matrixQ(); + VERIFY_IS_APPROX(Q, dQ); } void test_sparseqr() { diff --git a/testbed/nanogui/ext/eigen/test/spqr_support.cpp b/testbed/nanogui/ext/eigen/test/spqr_support.cpp index b8980e08..81e63b6a 100644 --- a/testbed/nanogui/ext/eigen/test/spqr_support.cpp +++ b/testbed/nanogui/ext/eigen/test/spqr_support.cpp @@ -5,6 +5,8 @@ // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed + +#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS #include "sparse.h" #include @@ -18,8 +20,8 @@ int generate_sparse_rectangular_problem(MatrixType& A, DenseMat& dA, int maxRows int cols = internal::random(1,rows); double density = (std::max)(8./(rows*cols), 0.01); - A.resize(rows,rows); - dA.resize(rows,rows); + A.resize(rows,cols); + dA.resize(rows,cols); initSparse(density, dA, A,ForceNonZeroDiag); A.makeCompressed(); return rows; @@ -35,7 +37,7 @@ template void test_spqr_scalar() SPQR solver; generate_sparse_rectangular_problem(A,dA); - int m = A.rows(); + Index m = A.rows(); b = DenseVector::Random(m); solver.compute(A); if (solver.info() != Success) diff --git a/testbed/nanogui/ext/eigen/test/stable_norm.cpp b/testbed/nanogui/ext/eigen/test/stable_norm.cpp index 231dd918..c3eb5ff3 100644 --- a/testbed/nanogui/ext/eigen/test/stable_norm.cpp +++ b/testbed/nanogui/ext/eigen/test/stable_norm.cpp @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2009 Gael Guennebaud +// Copyright (C) 2009-2014 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -9,14 +9,6 @@ #include "main.h" -// workaround aggressive optimization in ICC -template EIGEN_DONT_INLINE T sub(T a, T b) { return a - b; } - -template bool isFinite(const T& x) -{ - return isNotNaN(sub(x,x)); -} - template EIGEN_DONT_INLINE T copy(const T& x) { return x; @@ -32,6 +24,8 @@ template void stable_norm(const MatrixType& m) typedef typename MatrixType::Index Index; typedef typename MatrixType::Scalar Scalar; typedef typename NumTraits::Real RealScalar; + + bool complex_real_product_ok = true; // Check the basic machine-dependent constants. { @@ -44,6 +38,16 @@ template void stable_norm(const MatrixType& m) VERIFY( (!(iemin > 1 - 2*it || 1+it>iemax || (it==2 && ibeta<5) || (it<=4 && ibeta <= 3 ) || it<2)) && "the stable norm algorithm cannot be guaranteed on this computer"); + + Scalar inf = std::numeric_limits::infinity(); + if(NumTraits::IsComplex && (numext::isnan)(inf*RealScalar(1)) ) + { + complex_real_product_ok = false; + static bool first = true; + if(first) + std::cerr << "WARNING: compiler mess up complex*real product, " << inf << " * " << 1.0 << " = " << inf*RealScalar(1) << std::endl; + first = false; + } } @@ -76,19 +80,19 @@ template void stable_norm(const MatrixType& m) RealScalar size = static_cast(m.size()); - // test isFinite - VERIFY(!isFinite( std::numeric_limits::infinity())); - VERIFY(!isFinite(sqrt(-abs(big)))); + // test numext::isfinite + VERIFY(!(numext::isfinite)( std::numeric_limits::infinity())); + VERIFY(!(numext::isfinite)(sqrt(-abs(big)))); // test overflow - VERIFY(isFinite(sqrt(size)*abs(big))); + VERIFY((numext::isfinite)(sqrt(size)*abs(big))); VERIFY_IS_NOT_APPROX(sqrt(copy(vbig.squaredNorm())), abs(sqrt(size)*big)); // here the default norm must fail VERIFY_IS_APPROX(vbig.stableNorm(), sqrt(size)*abs(big)); VERIFY_IS_APPROX(vbig.blueNorm(), sqrt(size)*abs(big)); VERIFY_IS_APPROX(vbig.hypotNorm(), sqrt(size)*abs(big)); // test underflow - VERIFY(isFinite(sqrt(size)*abs(small))); + VERIFY((numext::isfinite)(sqrt(size)*abs(small))); VERIFY_IS_NOT_APPROX(sqrt(copy(vsmall.squaredNorm())), abs(sqrt(size)*small)); // here the default norm must fail VERIFY_IS_APPROX(vsmall.stableNorm(), sqrt(size)*abs(small)); VERIFY_IS_APPROX(vsmall.blueNorm(), sqrt(size)*abs(small)); @@ -101,6 +105,79 @@ template void stable_norm(const MatrixType& m) VERIFY_IS_APPROX(vrand.rowwise().stableNorm(), vrand.rowwise().norm()); VERIFY_IS_APPROX(vrand.rowwise().blueNorm(), vrand.rowwise().norm()); VERIFY_IS_APPROX(vrand.rowwise().hypotNorm(), vrand.rowwise().norm()); + + // test NaN, +inf, -inf + MatrixType v; + Index i = internal::random(0,rows-1); + Index j = internal::random(0,cols-1); + + // NaN + { + v = vrand; + v(i,j) = std::numeric_limits::quiet_NaN(); + VERIFY(!(numext::isfinite)(v.squaredNorm())); VERIFY((numext::isnan)(v.squaredNorm())); + VERIFY(!(numext::isfinite)(v.norm())); VERIFY((numext::isnan)(v.norm())); + VERIFY(!(numext::isfinite)(v.stableNorm())); VERIFY((numext::isnan)(v.stableNorm())); + VERIFY(!(numext::isfinite)(v.blueNorm())); VERIFY((numext::isnan)(v.blueNorm())); + VERIFY(!(numext::isfinite)(v.hypotNorm())); VERIFY((numext::isnan)(v.hypotNorm())); + } + + // +inf + { + v = vrand; + v(i,j) = std::numeric_limits::infinity(); + VERIFY(!(numext::isfinite)(v.squaredNorm())); VERIFY(isPlusInf(v.squaredNorm())); + VERIFY(!(numext::isfinite)(v.norm())); VERIFY(isPlusInf(v.norm())); + VERIFY(!(numext::isfinite)(v.stableNorm())); + if(complex_real_product_ok){ + VERIFY(isPlusInf(v.stableNorm())); + } + VERIFY(!(numext::isfinite)(v.blueNorm())); VERIFY(isPlusInf(v.blueNorm())); + VERIFY(!(numext::isfinite)(v.hypotNorm())); VERIFY(isPlusInf(v.hypotNorm())); + } + + // -inf + { + v = vrand; + v(i,j) = -std::numeric_limits::infinity(); + VERIFY(!(numext::isfinite)(v.squaredNorm())); VERIFY(isPlusInf(v.squaredNorm())); + VERIFY(!(numext::isfinite)(v.norm())); VERIFY(isPlusInf(v.norm())); + VERIFY(!(numext::isfinite)(v.stableNorm())); + if(complex_real_product_ok) { + VERIFY(isPlusInf(v.stableNorm())); + } + VERIFY(!(numext::isfinite)(v.blueNorm())); VERIFY(isPlusInf(v.blueNorm())); + VERIFY(!(numext::isfinite)(v.hypotNorm())); VERIFY(isPlusInf(v.hypotNorm())); + } + + // mix + { + Index i2 = internal::random(0,rows-1); + Index j2 = internal::random(0,cols-1); + v = vrand; + v(i,j) = -std::numeric_limits::infinity(); + v(i2,j2) = std::numeric_limits::quiet_NaN(); + VERIFY(!(numext::isfinite)(v.squaredNorm())); VERIFY((numext::isnan)(v.squaredNorm())); + VERIFY(!(numext::isfinite)(v.norm())); VERIFY((numext::isnan)(v.norm())); + VERIFY(!(numext::isfinite)(v.stableNorm())); VERIFY((numext::isnan)(v.stableNorm())); + VERIFY(!(numext::isfinite)(v.blueNorm())); VERIFY((numext::isnan)(v.blueNorm())); + VERIFY(!(numext::isfinite)(v.hypotNorm())); VERIFY((numext::isnan)(v.hypotNorm())); + } + + // stableNormalize[d] + { + VERIFY_IS_APPROX(vrand.stableNormalized(), vrand.normalized()); + MatrixType vcopy(vrand); + vcopy.stableNormalize(); + VERIFY_IS_APPROX(vcopy, vrand.normalized()); + VERIFY_IS_APPROX((vrand.stableNormalized()).norm(), RealScalar(1)); + VERIFY_IS_APPROX(vcopy.norm(), RealScalar(1)); + VERIFY_IS_APPROX((vbig.stableNormalized()).norm(), RealScalar(1)); + VERIFY_IS_APPROX((vsmall.stableNormalized()).norm(), RealScalar(1)); + RealScalar big_scaling = ((std::numeric_limits::max)() * RealScalar(1e-4)); + VERIFY_IS_APPROX(vbig/big_scaling, (vbig.stableNorm() * vbig.stableNormalized()).eval()/big_scaling); + VERIFY_IS_APPROX(vsmall, vsmall.stableNorm() * vsmall.stableNormalized()); + } } void test_stable_norm() diff --git a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_newstdvector.cpp b/testbed/nanogui/ext/eigen/test/stddeque_overload.cpp similarity index 56% rename from testbed/nanogui/ext/eigen/test/eigen2/eigen2_newstdvector.cpp rename to testbed/nanogui/ext/eigen/test/stddeque_overload.cpp index 5f900990..4da618bb 100644 --- a/testbed/nanogui/ext/eigen/test/eigen2/eigen2_newstdvector.cpp +++ b/testbed/nanogui/ext/eigen/test/stddeque_overload.cpp @@ -2,23 +2,36 @@ // for linear algebra. // // Copyright (C) 2008 Benoit Jacob +// Copyright (C) 2010 Hauke Heibel // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. -#define EIGEN_USE_NEW_STDVECTOR #include "main.h" -#include + +#include #include +EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Vector4f) + +EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Matrix2f) +EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Matrix4f) +EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Matrix4d) + +EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Affine3f) +EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Affine3d) + +EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Quaternionf) +EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Quaterniond) + template -void check_stdvector_matrix(const MatrixType& m) +void check_stddeque_matrix(const MatrixType& m) { - int rows = m.rows(); - int cols = m.cols(); + typename MatrixType::Index rows = m.rows(); + typename MatrixType::Index cols = m.cols(); MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols); - std::vector > v(10, MatrixType(rows,cols)), w(20, y); + std::deque v(10, MatrixType(rows,cols)), w(20, y); v[5] = x; w[6] = v[5]; VERIFY_IS_APPROX(w[6], v[5]); @@ -35,9 +48,8 @@ void check_stdvector_matrix(const MatrixType& m) VERIFY_IS_APPROX(v[21], y); v.push_back(x); VERIFY_IS_APPROX(v[22], x); - VERIFY((std::size_t)&(v[22]) == (std::size_t)&(v[21]) + sizeof(MatrixType)); - // do a lot of push_back such that the vector gets internally resized + // do a lot of push_back such that the deque gets internally resized // (with memory reallocation) MatrixType* ref = &w[0]; for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i) @@ -49,11 +61,11 @@ void check_stdvector_matrix(const MatrixType& m) } template -void check_stdvector_transform(const TransformType&) +void check_stddeque_transform(const TransformType&) { typedef typename TransformType::MatrixType MatrixType; TransformType x(MatrixType::Random()), y(MatrixType::Random()); - std::vector > v(10), w(20, y); + std::deque v(10), w(20, y); v[5] = x; w[6] = v[5]; VERIFY_IS_APPROX(w[6], v[5]); @@ -70,9 +82,8 @@ void check_stdvector_transform(const TransformType&) VERIFY_IS_APPROX(v[21], y); v.push_back(x); VERIFY_IS_APPROX(v[22], x); - VERIFY((std::size_t)&(v[22]) == (std::size_t)&(v[21]) + sizeof(TransformType)); - // do a lot of push_back such that the vector gets internally resized + // do a lot of push_back such that the deque gets internally resized // (with memory reallocation) TransformType* ref = &w[0]; for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i) @@ -84,11 +95,11 @@ void check_stdvector_transform(const TransformType&) } template -void check_stdvector_quaternion(const QuaternionType&) +void check_stddeque_quaternion(const QuaternionType&) { typedef typename QuaternionType::Coefficients Coefficients; QuaternionType x(Coefficients::Random()), y(Coefficients::Random()); - std::vector > v(10), w(20, y); + std::deque v(10), w(20, y); v[5] = x; w[6] = v[5]; VERIFY_IS_APPROX(w[6], v[5]); @@ -105,9 +116,8 @@ void check_stdvector_quaternion(const QuaternionType&) VERIFY_IS_APPROX(v[21], y); v.push_back(x); VERIFY_IS_APPROX(v[22], x); - VERIFY((std::size_t)&(v[22]) == (std::size_t)&(v[21]) + sizeof(QuaternionType)); - // do a lot of push_back such that the vector gets internally resized + // do a lot of push_back such that the deque gets internally resized // (with memory reallocation) QuaternionType* ref = &w[0]; for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i) @@ -118,32 +128,31 @@ void check_stdvector_quaternion(const QuaternionType&) } } -void test_eigen2_newstdvector() +void test_stddeque_overload() { // some non vectorizable fixed sizes - CALL_SUBTEST_1(check_stdvector_matrix(Vector2f())); - CALL_SUBTEST_1(check_stdvector_matrix(Matrix3f())); - CALL_SUBTEST_1(check_stdvector_matrix(Matrix3d())); + CALL_SUBTEST_1(check_stddeque_matrix(Vector2f())); + CALL_SUBTEST_1(check_stddeque_matrix(Matrix3f())); + CALL_SUBTEST_2(check_stddeque_matrix(Matrix3d())); // some vectorizable fixed sizes - CALL_SUBTEST_2(check_stdvector_matrix(Matrix2f())); - CALL_SUBTEST_2(check_stdvector_matrix(Vector4f())); - CALL_SUBTEST_2(check_stdvector_matrix(Matrix4f())); - CALL_SUBTEST_2(check_stdvector_matrix(Matrix4d())); + CALL_SUBTEST_1(check_stddeque_matrix(Matrix2f())); + CALL_SUBTEST_1(check_stddeque_matrix(Vector4f())); + CALL_SUBTEST_1(check_stddeque_matrix(Matrix4f())); + CALL_SUBTEST_2(check_stddeque_matrix(Matrix4d())); // some dynamic sizes - CALL_SUBTEST_3(check_stdvector_matrix(MatrixXd(1,1))); - CALL_SUBTEST_3(check_stdvector_matrix(VectorXd(20))); - CALL_SUBTEST_3(check_stdvector_matrix(RowVectorXf(20))); - CALL_SUBTEST_3(check_stdvector_matrix(MatrixXcf(10,10))); + CALL_SUBTEST_3(check_stddeque_matrix(MatrixXd(1,1))); + CALL_SUBTEST_3(check_stddeque_matrix(VectorXd(20))); + CALL_SUBTEST_3(check_stddeque_matrix(RowVectorXf(20))); + CALL_SUBTEST_3(check_stddeque_matrix(MatrixXcf(10,10))); // some Transform - CALL_SUBTEST_4(check_stdvector_transform(Transform2f())); - CALL_SUBTEST_4(check_stdvector_transform(Transform3f())); - CALL_SUBTEST_4(check_stdvector_transform(Transform3d())); - //CALL_SUBTEST(check_stdvector_transform(Transform4d())); + CALL_SUBTEST_4(check_stddeque_transform(Affine2f())); // does not need the specialization (2+1)^2 = 9 + CALL_SUBTEST_4(check_stddeque_transform(Affine3f())); + CALL_SUBTEST_4(check_stddeque_transform(Affine3d())); // some Quaternion - CALL_SUBTEST_5(check_stdvector_quaternion(Quaternionf())); - CALL_SUBTEST_5(check_stdvector_quaternion(Quaterniond())); + CALL_SUBTEST_5(check_stddeque_quaternion(Quaternionf())); + CALL_SUBTEST_5(check_stddeque_quaternion(Quaterniond())); } diff --git a/testbed/nanogui/ext/eigen/test/stdlist_overload.cpp b/testbed/nanogui/ext/eigen/test/stdlist_overload.cpp new file mode 100644 index 00000000..bb910bd4 --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/stdlist_overload.cpp @@ -0,0 +1,192 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2008 Benoit Jacob +// Copyright (C) 2010 Hauke Heibel +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "main.h" + +#include +#include + +EIGEN_DEFINE_STL_LIST_SPECIALIZATION(Vector4f) + +EIGEN_DEFINE_STL_LIST_SPECIALIZATION(Matrix2f) +EIGEN_DEFINE_STL_LIST_SPECIALIZATION(Matrix4f) +EIGEN_DEFINE_STL_LIST_SPECIALIZATION(Matrix4d) + +EIGEN_DEFINE_STL_LIST_SPECIALIZATION(Affine3f) +EIGEN_DEFINE_STL_LIST_SPECIALIZATION(Affine3d) + +EIGEN_DEFINE_STL_LIST_SPECIALIZATION(Quaternionf) +EIGEN_DEFINE_STL_LIST_SPECIALIZATION(Quaterniond) + +template +typename Container::iterator get(Container & c, Position position) +{ + typename Container::iterator it = c.begin(); + std::advance(it, position); + return it; +} + +template +void set(Container & c, Position position, const Value & value) +{ + typename Container::iterator it = c.begin(); + std::advance(it, position); + *it = value; +} + +template +void check_stdlist_matrix(const MatrixType& m) +{ + typename MatrixType::Index rows = m.rows(); + typename MatrixType::Index cols = m.cols(); + MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols); + std::list v(10, MatrixType(rows,cols)), w(20, y); + typename std::list::iterator itv = get(v, 5); + typename std::list::iterator itw = get(w, 6); + *itv = x; + *itw = *itv; + VERIFY_IS_APPROX(*itw, *itv); + v = w; + itv = v.begin(); + itw = w.begin(); + for(int i = 0; i < 20; i++) + { + VERIFY_IS_APPROX(*itw, *itv); + ++itv; + ++itw; + } + + v.resize(21); + set(v, 20, x); + VERIFY_IS_APPROX(*get(v, 20), x); + v.resize(22,y); + VERIFY_IS_APPROX(*get(v, 21), y); + v.push_back(x); + VERIFY_IS_APPROX(*get(v, 22), x); + + // do a lot of push_back such that the list gets internally resized + // (with memory reallocation) + MatrixType* ref = &(*get(w, 0)); + for(int i=0; i<30 || ((ref==&(*get(w, 0))) && i<300); ++i) + v.push_back(*get(w, i%w.size())); + for(unsigned int i=23; i +void check_stdlist_transform(const TransformType&) +{ + typedef typename TransformType::MatrixType MatrixType; + TransformType x(MatrixType::Random()), y(MatrixType::Random()); + std::list v(10), w(20, y); + typename std::list::iterator itv = get(v, 5); + typename std::list::iterator itw = get(w, 6); + *itv = x; + *itw = *itv; + VERIFY_IS_APPROX(*itw, *itv); + v = w; + itv = v.begin(); + itw = w.begin(); + for(int i = 0; i < 20; i++) + { + VERIFY_IS_APPROX(*itw, *itv); + ++itv; + ++itw; + } + + v.resize(21); + set(v, 20, x); + VERIFY_IS_APPROX(*get(v, 20), x); + v.resize(22,y); + VERIFY_IS_APPROX(*get(v, 21), y); + v.push_back(x); + VERIFY_IS_APPROX(*get(v, 22), x); + + // do a lot of push_back such that the list gets internally resized + // (with memory reallocation) + TransformType* ref = &(*get(w, 0)); + for(int i=0; i<30 || ((ref==&(*get(w, 0))) && i<300); ++i) + v.push_back(*get(w, i%w.size())); + for(unsigned int i=23; imatrix()==get(w, (i-23)%w.size())->matrix()); + } +} + +template +void check_stdlist_quaternion(const QuaternionType&) +{ + typedef typename QuaternionType::Coefficients Coefficients; + QuaternionType x(Coefficients::Random()), y(Coefficients::Random()); + std::list v(10), w(20, y); + typename std::list::iterator itv = get(v, 5); + typename std::list::iterator itw = get(w, 6); + *itv = x; + *itw = *itv; + VERIFY_IS_APPROX(*itw, *itv); + v = w; + itv = v.begin(); + itw = w.begin(); + for(int i = 0; i < 20; i++) + { + VERIFY_IS_APPROX(*itw, *itv); + ++itv; + ++itw; + } + + v.resize(21); + set(v, 20, x); + VERIFY_IS_APPROX(*get(v, 20), x); + v.resize(22,y); + VERIFY_IS_APPROX(*get(v, 21), y); + v.push_back(x); + VERIFY_IS_APPROX(*get(v, 22), x); + + // do a lot of push_back such that the list gets internally resized + // (with memory reallocation) + QuaternionType* ref = &(*get(w, 0)); + for(int i=0; i<30 || ((ref==&(*get(w, 0))) && i<300); ++i) + v.push_back(*get(w, i%w.size())); + for(unsigned int i=23; icoeffs()==get(w, (i-23)%w.size())->coeffs()); + } +} + +void test_stdlist_overload() +{ + // some non vectorizable fixed sizes + CALL_SUBTEST_1(check_stdlist_matrix(Vector2f())); + CALL_SUBTEST_1(check_stdlist_matrix(Matrix3f())); + CALL_SUBTEST_2(check_stdlist_matrix(Matrix3d())); + + // some vectorizable fixed sizes + CALL_SUBTEST_1(check_stdlist_matrix(Matrix2f())); + CALL_SUBTEST_1(check_stdlist_matrix(Vector4f())); + CALL_SUBTEST_1(check_stdlist_matrix(Matrix4f())); + CALL_SUBTEST_2(check_stdlist_matrix(Matrix4d())); + + // some dynamic sizes + CALL_SUBTEST_3(check_stdlist_matrix(MatrixXd(1,1))); + CALL_SUBTEST_3(check_stdlist_matrix(VectorXd(20))); + CALL_SUBTEST_3(check_stdlist_matrix(RowVectorXf(20))); + CALL_SUBTEST_3(check_stdlist_matrix(MatrixXcf(10,10))); + + // some Transform + CALL_SUBTEST_4(check_stdlist_transform(Affine2f())); // does not need the specialization (2+1)^2 = 9 + CALL_SUBTEST_4(check_stdlist_transform(Affine3f())); + CALL_SUBTEST_4(check_stdlist_transform(Affine3d())); + + // some Quaternion + CALL_SUBTEST_5(check_stdlist_quaternion(Quaternionf())); + CALL_SUBTEST_5(check_stdlist_quaternion(Quaterniond())); +} diff --git a/testbed/nanogui/ext/eigen/test/stdvector.cpp b/testbed/nanogui/ext/eigen/test/stdvector.cpp index 6e173c67..50cb3341 100644 --- a/testbed/nanogui/ext/eigen/test/stdvector.cpp +++ b/testbed/nanogui/ext/eigen/test/stdvector.cpp @@ -34,7 +34,7 @@ void check_stdvector_matrix(const MatrixType& m) VERIFY_IS_APPROX(v[21], y); v.push_back(x); VERIFY_IS_APPROX(v[22], x); - VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(MatrixType)); + VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(MatrixType)); // do a lot of push_back such that the vector gets internally resized // (with memory reallocation) @@ -69,7 +69,7 @@ void check_stdvector_transform(const TransformType&) VERIFY_IS_APPROX(v[21], y); v.push_back(x); VERIFY_IS_APPROX(v[22], x); - VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(TransformType)); + VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(TransformType)); // do a lot of push_back such that the vector gets internally resized // (with memory reallocation) @@ -104,7 +104,7 @@ void check_stdvector_quaternion(const QuaternionType&) VERIFY_IS_APPROX(v[21], y); v.push_back(x); VERIFY_IS_APPROX(v[22], x); - VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(QuaternionType)); + VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(QuaternionType)); // do a lot of push_back such that the vector gets internally resized // (with memory reallocation) diff --git a/testbed/nanogui/ext/eigen/test/stdvector_overload.cpp b/testbed/nanogui/ext/eigen/test/stdvector_overload.cpp index 736ff0ee..95966595 100644 --- a/testbed/nanogui/ext/eigen/test/stdvector_overload.cpp +++ b/testbed/nanogui/ext/eigen/test/stdvector_overload.cpp @@ -48,7 +48,7 @@ void check_stdvector_matrix(const MatrixType& m) VERIFY_IS_APPROX(v[21], y); v.push_back(x); VERIFY_IS_APPROX(v[22], x); - VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(MatrixType)); + VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(MatrixType)); // do a lot of push_back such that the vector gets internally resized // (with memory reallocation) @@ -83,7 +83,7 @@ void check_stdvector_transform(const TransformType&) VERIFY_IS_APPROX(v[21], y); v.push_back(x); VERIFY_IS_APPROX(v[22], x); - VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(TransformType)); + VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(TransformType)); // do a lot of push_back such that the vector gets internally resized // (with memory reallocation) @@ -118,7 +118,7 @@ void check_stdvector_quaternion(const QuaternionType&) VERIFY_IS_APPROX(v[21], y); v.push_back(x); VERIFY_IS_APPROX(v[22], x); - VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(QuaternionType)); + VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(QuaternionType)); // do a lot of push_back such that the vector gets internally resized // (with memory reallocation) diff --git a/testbed/nanogui/ext/eigen/test/superlu_support.cpp b/testbed/nanogui/ext/eigen/test/superlu_support.cpp index 3b16135b..98a7bc5c 100644 --- a/testbed/nanogui/ext/eigen/test/superlu_support.cpp +++ b/testbed/nanogui/ext/eigen/test/superlu_support.cpp @@ -7,6 +7,7 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS #include "sparse_solver.h" #include diff --git a/testbed/nanogui/ext/eigen/test/svd_common.h b/testbed/nanogui/ext/eigen/test/svd_common.h new file mode 100644 index 00000000..605d5dfe --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/svd_common.h @@ -0,0 +1,483 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2008-2014 Gael Guennebaud +// Copyright (C) 2009 Benoit Jacob +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef SVD_DEFAULT +#error a macro SVD_DEFAULT(MatrixType) must be defined prior to including svd_common.h +#endif + +#ifndef SVD_FOR_MIN_NORM +#error a macro SVD_FOR_MIN_NORM(MatrixType) must be defined prior to including svd_common.h +#endif + +#include "svd_fill.h" + +// Check that the matrix m is properly reconstructed and that the U and V factors are unitary +// The SVD must have already been computed. +template +void svd_check_full(const MatrixType& m, const SvdType& svd) +{ + typedef typename MatrixType::Index Index; + Index rows = m.rows(); + Index cols = m.cols(); + + enum { + RowsAtCompileTime = MatrixType::RowsAtCompileTime, + ColsAtCompileTime = MatrixType::ColsAtCompileTime + }; + + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + typedef Matrix MatrixUType; + typedef Matrix MatrixVType; + + MatrixType sigma = MatrixType::Zero(rows,cols); + sigma.diagonal() = svd.singularValues().template cast(); + MatrixUType u = svd.matrixU(); + MatrixVType v = svd.matrixV(); + RealScalar scaling = m.cwiseAbs().maxCoeff(); + if(scaling<(std::numeric_limits::min)()) + { + VERIFY(sigma.cwiseAbs().maxCoeff() <= (std::numeric_limits::min)()); + } + else + { + VERIFY_IS_APPROX(m/scaling, u * (sigma/scaling) * v.adjoint()); + } + VERIFY_IS_UNITARY(u); + VERIFY_IS_UNITARY(v); +} + +// Compare partial SVD defined by computationOptions to a full SVD referenceSvd +template +void svd_compare_to_full(const MatrixType& m, + unsigned int computationOptions, + const SvdType& referenceSvd) +{ + typedef typename MatrixType::RealScalar RealScalar; + Index rows = m.rows(); + Index cols = m.cols(); + Index diagSize = (std::min)(rows, cols); + RealScalar prec = test_precision(); + + SvdType svd(m, computationOptions); + + VERIFY_IS_APPROX(svd.singularValues(), referenceSvd.singularValues()); + + if(computationOptions & (ComputeFullV|ComputeThinV)) + { + VERIFY( (svd.matrixV().adjoint()*svd.matrixV()).isIdentity(prec) ); + VERIFY_IS_APPROX( svd.matrixV().leftCols(diagSize) * svd.singularValues().asDiagonal() * svd.matrixV().leftCols(diagSize).adjoint(), + referenceSvd.matrixV().leftCols(diagSize) * referenceSvd.singularValues().asDiagonal() * referenceSvd.matrixV().leftCols(diagSize).adjoint()); + } + + if(computationOptions & (ComputeFullU|ComputeThinU)) + { + VERIFY( (svd.matrixU().adjoint()*svd.matrixU()).isIdentity(prec) ); + VERIFY_IS_APPROX( svd.matrixU().leftCols(diagSize) * svd.singularValues().cwiseAbs2().asDiagonal() * svd.matrixU().leftCols(diagSize).adjoint(), + referenceSvd.matrixU().leftCols(diagSize) * referenceSvd.singularValues().cwiseAbs2().asDiagonal() * referenceSvd.matrixU().leftCols(diagSize).adjoint()); + } + + // The following checks are not critical. + // For instance, with Dived&Conquer SVD, if only the factor 'V' is computedt then different matrix-matrix product implementation will be used + // and the resulting 'V' factor might be significantly different when the SVD decomposition is not unique, especially with single precision float. + ++g_test_level; + if(computationOptions & ComputeFullU) VERIFY_IS_APPROX(svd.matrixU(), referenceSvd.matrixU()); + if(computationOptions & ComputeThinU) VERIFY_IS_APPROX(svd.matrixU(), referenceSvd.matrixU().leftCols(diagSize)); + if(computationOptions & ComputeFullV) VERIFY_IS_APPROX(svd.matrixV().cwiseAbs(), referenceSvd.matrixV().cwiseAbs()); + if(computationOptions & ComputeThinV) VERIFY_IS_APPROX(svd.matrixV(), referenceSvd.matrixV().leftCols(diagSize)); + --g_test_level; +} + +// +template +void svd_least_square(const MatrixType& m, unsigned int computationOptions) +{ + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + typedef typename MatrixType::Index Index; + Index rows = m.rows(); + Index cols = m.cols(); + + enum { + RowsAtCompileTime = MatrixType::RowsAtCompileTime, + ColsAtCompileTime = MatrixType::ColsAtCompileTime + }; + + typedef Matrix RhsType; + typedef Matrix SolutionType; + + RhsType rhs = RhsType::Random(rows, internal::random(1, cols)); + SvdType svd(m, computationOptions); + + if(internal::is_same::value) svd.setThreshold(1e-8); + else if(internal::is_same::value) svd.setThreshold(2e-4); + + SolutionType x = svd.solve(rhs); + + RealScalar residual = (m*x-rhs).norm(); + RealScalar rhs_norm = rhs.norm(); + if(!test_isMuchSmallerThan(residual,rhs.norm())) + { + // ^^^ If the residual is very small, then we have an exact solution, so we are already good. + + // evaluate normal equation which works also for least-squares solutions + if(internal::is_same::value || svd.rank()==m.diagonal().size()) + { + using std::sqrt; + // This test is not stable with single precision. + // This is probably because squaring m signicantly affects the precision. + if(internal::is_same::value) ++g_test_level; + + VERIFY_IS_APPROX(m.adjoint()*(m*x),m.adjoint()*rhs); + + if(internal::is_same::value) --g_test_level; + } + + // Check that there is no significantly better solution in the neighborhood of x + for(Index k=0;k::epsilon())*x.row(k); + RealScalar residual_y = (m*y-rhs).norm(); + VERIFY( test_isMuchSmallerThan(abs(residual_y-residual), rhs_norm) || residual < residual_y ); + if(internal::is_same::value) ++g_test_level; + VERIFY( test_isApprox(residual_y,residual) || residual < residual_y ); + if(internal::is_same::value) --g_test_level; + + y.row(k) = (RealScalar(1)-2*NumTraits::epsilon())*x.row(k); + residual_y = (m*y-rhs).norm(); + VERIFY( test_isMuchSmallerThan(abs(residual_y-residual), rhs_norm) || residual < residual_y ); + if(internal::is_same::value) ++g_test_level; + VERIFY( test_isApprox(residual_y,residual) || residual < residual_y ); + if(internal::is_same::value) --g_test_level; + } + } +} + +// check minimal norm solutions, the inoput matrix m is only used to recover problem size +template +void svd_min_norm(const MatrixType& m, unsigned int computationOptions) +{ + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::Index Index; + Index cols = m.cols(); + + enum { + ColsAtCompileTime = MatrixType::ColsAtCompileTime + }; + + typedef Matrix SolutionType; + + // generate a full-rank m x n problem with m MatrixType2; + typedef Matrix RhsType2; + typedef Matrix MatrixType2T; + Index rank = RankAtCompileTime2==Dynamic ? internal::random(1,cols) : Index(RankAtCompileTime2); + MatrixType2 m2(rank,cols); + int guard = 0; + do { + m2.setRandom(); + } while(SVD_FOR_MIN_NORM(MatrixType2)(m2).setThreshold(test_precision()).rank()!=rank && (++guard)<10); + VERIFY(guard<10); + + RhsType2 rhs2 = RhsType2::Random(rank); + // use QR to find a reference minimal norm solution + HouseholderQR qr(m2.adjoint()); + Matrix tmp = qr.matrixQR().topLeftCorner(rank,rank).template triangularView().adjoint().solve(rhs2); + tmp.conservativeResize(cols); + tmp.tail(cols-rank).setZero(); + SolutionType x21 = qr.householderQ() * tmp; + // now check with SVD + SVD_FOR_MIN_NORM(MatrixType2) svd2(m2, computationOptions); + SolutionType x22 = svd2.solve(rhs2); + VERIFY_IS_APPROX(m2*x21, rhs2); + VERIFY_IS_APPROX(m2*x22, rhs2); + VERIFY_IS_APPROX(x21, x22); + + // Now check with a rank deficient matrix + typedef Matrix MatrixType3; + typedef Matrix RhsType3; + Index rows3 = RowsAtCompileTime3==Dynamic ? internal::random(rank+1,2*cols) : Index(RowsAtCompileTime3); + Matrix C = Matrix::Random(rows3,rank); + MatrixType3 m3 = C * m2; + RhsType3 rhs3 = C * rhs2; + SVD_FOR_MIN_NORM(MatrixType3) svd3(m3, computationOptions); + SolutionType x3 = svd3.solve(rhs3); + VERIFY_IS_APPROX(m3*x3, rhs3); + VERIFY_IS_APPROX(m3*x21, rhs3); + VERIFY_IS_APPROX(m2*x3, rhs2); + VERIFY_IS_APPROX(x21, x3); +} + +// Check full, compare_to_full, least_square, and min_norm for all possible compute-options +template +void svd_test_all_computation_options(const MatrixType& m, bool full_only) +{ +// if (QRPreconditioner == NoQRPreconditioner && m.rows() != m.cols()) +// return; + SvdType fullSvd(m, ComputeFullU|ComputeFullV); + CALL_SUBTEST(( svd_check_full(m, fullSvd) )); + CALL_SUBTEST(( svd_least_square(m, ComputeFullU | ComputeFullV) )); + CALL_SUBTEST(( svd_min_norm(m, ComputeFullU | ComputeFullV) )); + + #if defined __INTEL_COMPILER + // remark #111: statement is unreachable + #pragma warning disable 111 + #endif + if(full_only) + return; + + CALL_SUBTEST(( svd_compare_to_full(m, ComputeFullU, fullSvd) )); + CALL_SUBTEST(( svd_compare_to_full(m, ComputeFullV, fullSvd) )); + CALL_SUBTEST(( svd_compare_to_full(m, 0, fullSvd) )); + + if (MatrixType::ColsAtCompileTime == Dynamic) { + // thin U/V are only available with dynamic number of columns + CALL_SUBTEST(( svd_compare_to_full(m, ComputeFullU|ComputeThinV, fullSvd) )); + CALL_SUBTEST(( svd_compare_to_full(m, ComputeThinV, fullSvd) )); + CALL_SUBTEST(( svd_compare_to_full(m, ComputeThinU|ComputeFullV, fullSvd) )); + CALL_SUBTEST(( svd_compare_to_full(m, ComputeThinU , fullSvd) )); + CALL_SUBTEST(( svd_compare_to_full(m, ComputeThinU|ComputeThinV, fullSvd) )); + + CALL_SUBTEST(( svd_least_square(m, ComputeFullU | ComputeThinV) )); + CALL_SUBTEST(( svd_least_square(m, ComputeThinU | ComputeFullV) )); + CALL_SUBTEST(( svd_least_square(m, ComputeThinU | ComputeThinV) )); + + CALL_SUBTEST(( svd_min_norm(m, ComputeFullU | ComputeThinV) )); + CALL_SUBTEST(( svd_min_norm(m, ComputeThinU | ComputeFullV) )); + CALL_SUBTEST(( svd_min_norm(m, ComputeThinU | ComputeThinV) )); + + // test reconstruction + typedef typename MatrixType::Index Index; + Index diagSize = (std::min)(m.rows(), m.cols()); + SvdType svd(m, ComputeThinU | ComputeThinV); + VERIFY_IS_APPROX(m, svd.matrixU().leftCols(diagSize) * svd.singularValues().asDiagonal() * svd.matrixV().leftCols(diagSize).adjoint()); + } +} + + +// work around stupid msvc error when constructing at compile time an expression that involves +// a division by zero, even if the numeric type has floating point +template +EIGEN_DONT_INLINE Scalar zero() { return Scalar(0); } + +// workaround aggressive optimization in ICC +template EIGEN_DONT_INLINE T sub(T a, T b) { return a - b; } + +// all this function does is verify we don't iterate infinitely on nan/inf values +template +void svd_inf_nan() +{ + SvdType svd; + typedef typename MatrixType::Scalar Scalar; + Scalar some_inf = Scalar(1) / zero(); + VERIFY(sub(some_inf, some_inf) != sub(some_inf, some_inf)); + svd.compute(MatrixType::Constant(10,10,some_inf), ComputeFullU | ComputeFullV); + + Scalar nan = std::numeric_limits::quiet_NaN(); + VERIFY(nan != nan); + svd.compute(MatrixType::Constant(10,10,nan), ComputeFullU | ComputeFullV); + + MatrixType m = MatrixType::Zero(10,10); + m(internal::random(0,9), internal::random(0,9)) = some_inf; + svd.compute(m, ComputeFullU | ComputeFullV); + + m = MatrixType::Zero(10,10); + m(internal::random(0,9), internal::random(0,9)) = nan; + svd.compute(m, ComputeFullU | ComputeFullV); + + // regression test for bug 791 + m.resize(3,3); + m << 0, 2*NumTraits::epsilon(), 0.5, + 0, -0.5, 0, + nan, 0, 0; + svd.compute(m, ComputeFullU | ComputeFullV); + + m.resize(4,4); + m << 1, 0, 0, 0, + 0, 3, 1, 2e-308, + 1, 0, 1, nan, + 0, nan, nan, 0; + svd.compute(m, ComputeFullU | ComputeFullV); +} + +// Regression test for bug 286: JacobiSVD loops indefinitely with some +// matrices containing denormal numbers. +template +void svd_underoverflow() +{ +#if defined __INTEL_COMPILER +// shut up warning #239: floating point underflow +#pragma warning push +#pragma warning disable 239 +#endif + Matrix2d M; + M << -7.90884e-313, -4.94e-324, + 0, 5.60844e-313; + SVD_DEFAULT(Matrix2d) svd; + svd.compute(M,ComputeFullU|ComputeFullV); + CALL_SUBTEST( svd_check_full(M,svd) ); + + // Check all 2x2 matrices made with the following coefficients: + VectorXd value_set(9); + value_set << 0, 1, -1, 5.60844e-313, -5.60844e-313, 4.94e-324, -4.94e-324, -4.94e-223, 4.94e-223; + Array4i id(0,0,0,0); + int k = 0; + do + { + M << value_set(id(0)), value_set(id(1)), value_set(id(2)), value_set(id(3)); + svd.compute(M,ComputeFullU|ComputeFullV); + CALL_SUBTEST( svd_check_full(M,svd) ); + + id(k)++; + if(id(k)>=value_set.size()) + { + while(k<3 && id(k)>=value_set.size()) id(++k)++; + id.head(k).setZero(); + k=0; + } + + } while((id +void svd_all_trivial_2x2( void (*cb)(const MatrixType&,bool) ) +{ + MatrixType M; + VectorXd value_set(3); + value_set << 0, 1, -1; + Array4i id(0,0,0,0); + int k = 0; + do + { + M << value_set(id(0)), value_set(id(1)), value_set(id(2)), value_set(id(3)); + + cb(M,false); + + id(k)++; + if(id(k)>=value_set.size()) + { + while(k<3 && id(k)>=value_set.size()) id(++k)++; + id.head(k).setZero(); + k=0; + } + + } while((id +void svd_preallocate() +{ + Vector3f v(3.f, 2.f, 1.f); + MatrixXf m = v.asDiagonal(); + + internal::set_is_malloc_allowed(false); + VERIFY_RAISES_ASSERT(VectorXf tmp(10);) + SVD_DEFAULT(MatrixXf) svd; + internal::set_is_malloc_allowed(true); + svd.compute(m); + VERIFY_IS_APPROX(svd.singularValues(), v); + + SVD_DEFAULT(MatrixXf) svd2(3,3); + internal::set_is_malloc_allowed(false); + svd2.compute(m); + internal::set_is_malloc_allowed(true); + VERIFY_IS_APPROX(svd2.singularValues(), v); + VERIFY_RAISES_ASSERT(svd2.matrixU()); + VERIFY_RAISES_ASSERT(svd2.matrixV()); + svd2.compute(m, ComputeFullU | ComputeFullV); + VERIFY_IS_APPROX(svd2.matrixU(), Matrix3f::Identity()); + VERIFY_IS_APPROX(svd2.matrixV(), Matrix3f::Identity()); + internal::set_is_malloc_allowed(false); + svd2.compute(m); + internal::set_is_malloc_allowed(true); + + SVD_DEFAULT(MatrixXf) svd3(3,3,ComputeFullU|ComputeFullV); + internal::set_is_malloc_allowed(false); + svd2.compute(m); + internal::set_is_malloc_allowed(true); + VERIFY_IS_APPROX(svd2.singularValues(), v); + VERIFY_IS_APPROX(svd2.matrixU(), Matrix3f::Identity()); + VERIFY_IS_APPROX(svd2.matrixV(), Matrix3f::Identity()); + internal::set_is_malloc_allowed(false); + svd2.compute(m, ComputeFullU|ComputeFullV); + internal::set_is_malloc_allowed(true); +} + +template +void svd_verify_assert(const MatrixType& m) +{ + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::Index Index; + Index rows = m.rows(); + Index cols = m.cols(); + + enum { + RowsAtCompileTime = MatrixType::RowsAtCompileTime, + ColsAtCompileTime = MatrixType::ColsAtCompileTime + }; + + typedef Matrix RhsType; + RhsType rhs(rows); + SvdType svd; + VERIFY_RAISES_ASSERT(svd.matrixU()) + VERIFY_RAISES_ASSERT(svd.singularValues()) + VERIFY_RAISES_ASSERT(svd.matrixV()) + VERIFY_RAISES_ASSERT(svd.solve(rhs)) + MatrixType a = MatrixType::Zero(rows, cols); + a.setZero(); + svd.compute(a, 0); + VERIFY_RAISES_ASSERT(svd.matrixU()) + VERIFY_RAISES_ASSERT(svd.matrixV()) + svd.singularValues(); + VERIFY_RAISES_ASSERT(svd.solve(rhs)) + + if (ColsAtCompileTime == Dynamic) + { + svd.compute(a, ComputeThinU); + svd.matrixU(); + VERIFY_RAISES_ASSERT(svd.matrixV()) + VERIFY_RAISES_ASSERT(svd.solve(rhs)) + svd.compute(a, ComputeThinV); + svd.matrixV(); + VERIFY_RAISES_ASSERT(svd.matrixU()) + VERIFY_RAISES_ASSERT(svd.solve(rhs)) + } + else + { + VERIFY_RAISES_ASSERT(svd.compute(a, ComputeThinU)) + VERIFY_RAISES_ASSERT(svd.compute(a, ComputeThinV)) + } +} + +#undef SVD_DEFAULT +#undef SVD_FOR_MIN_NORM diff --git a/testbed/nanogui/ext/eigen/test/svd_fill.h b/testbed/nanogui/ext/eigen/test/svd_fill.h new file mode 100644 index 00000000..3877c0c7 --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/svd_fill.h @@ -0,0 +1,119 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014-2015 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +template +Array four_denorms(); + +template<> +Array4f four_denorms() { return Array4f(5.60844e-39f, -5.60844e-39f, 4.94e-44f, -4.94e-44f); } +template<> +Array4d four_denorms() { return Array4d(5.60844e-313, -5.60844e-313, 4.94e-324, -4.94e-324); } +template +Array four_denorms() { return four_denorms().cast(); } + +template +void svd_fill_random(MatrixType &m, int Option = 0) +{ + using std::pow; + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + typedef typename MatrixType::Index Index; + Index diagSize = (std::min)(m.rows(), m.cols()); + RealScalar s = std::numeric_limits::max_exponent10/4; + s = internal::random(1,s); + Matrix d = Matrix::Random(diagSize); + for(Index k=0; k(-s,s)); + + bool dup = internal::random(0,10) < 3; + bool unit_uv = internal::random(0,10) < (dup?7:3); // if we duplicate some diagonal entries, then increase the chance to preserve them using unitary U and V factors + + // duplicate some singular values + if(dup) + { + Index n = internal::random(0,d.size()-1); + for(Index i=0; i(0,d.size()-1)) = d(internal::random(0,d.size()-1)); + } + + Matrix U(m.rows(),diagSize); + Matrix VT(diagSize,m.cols()); + if(unit_uv) + { + // in very rare cases let's try with a pure diagonal matrix + if(internal::random(0,10) < 1) + { + U.setIdentity(); + VT.setIdentity(); + } + else + { + createRandomPIMatrixOfRank(diagSize,U.rows(), U.cols(), U); + createRandomPIMatrixOfRank(diagSize,VT.rows(), VT.cols(), VT); + } + } + else + { + U.setRandom(); + VT.setRandom(); + } + + Matrix samples(9); + samples << 0, four_denorms(), + -RealScalar(1)/NumTraits::highest(), RealScalar(1)/NumTraits::highest(), (std::numeric_limits::min)(), pow((std::numeric_limits::min)(),0.8); + + if(Option==Symmetric) + { + m = U * d.asDiagonal() * U.transpose(); + + // randomly nullify some rows/columns + { + Index count = internal::random(-diagSize,diagSize); + for(Index k=0; k(0,diagSize-1); + m.row(i).setZero(); + m.col(i).setZero(); + } + if(count<0) + // (partly) cancel some coeffs + if(!(dup && unit_uv)) + { + + Index n = internal::random(0,m.size()-1); + for(Index k=0; k(0,m.rows()-1); + Index j = internal::random(0,m.cols()-1); + m(j,i) = m(i,j) = samples(internal::random(0,samples.size()-1)); + if(NumTraits::IsComplex) + *(&numext::real_ref(m(j,i))+1) = *(&numext::real_ref(m(i,j))+1) = samples.real()(internal::random(0,samples.size()-1)); + } + } + } + } + else + { + m = U * d.asDiagonal() * VT; + // (partly) cancel some coeffs + if(!(dup && unit_uv)) + { + Index n = internal::random(0,m.size()-1); + for(Index k=0; k(0,m.rows()-1); + Index j = internal::random(0,m.cols()-1); + m(i,j) = samples(internal::random(0,samples.size()-1)); + if(NumTraits::IsComplex) + *(&numext::real_ref(m(i,j))+1) = samples.real()(internal::random(0,samples.size()-1)); + } + } + } +} + diff --git a/testbed/nanogui/ext/eigen/test/swap.cpp b/testbed/nanogui/ext/eigen/test/swap.cpp index 36b35314..f76e3624 100644 --- a/testbed/nanogui/ext/eigen/test/swap.cpp +++ b/testbed/nanogui/ext/eigen/test/swap.cpp @@ -41,9 +41,15 @@ template void swap(const MatrixType& m) OtherMatrixType m3_copy = m3; // test swapping 2 matrices of same type + Scalar *d1=m1.data(), *d2=m2.data(); m1.swap(m2); VERIFY_IS_APPROX(m1,m2_copy); VERIFY_IS_APPROX(m2,m1_copy); + if(MatrixType::SizeAtCompileTime==Dynamic) + { + VERIFY(m1.data()==d2); + VERIFY(m2.data()==d1); + } m1 = m1_copy; m2 = m2_copy; @@ -68,16 +74,21 @@ template void swap(const MatrixType& m) m1 = m1_copy; m3 = m3_copy; - // test assertion on mismatching size -- matrix case - VERIFY_RAISES_ASSERT(m1.swap(m1.row(0))); - // test assertion on mismatching size -- xpr case - VERIFY_RAISES_ASSERT(m1.row(0).swap(m1)); + if(m1.rows()>1) + { + // test assertion on mismatching size -- matrix case + VERIFY_RAISES_ASSERT(m1.swap(m1.row(0))); + // test assertion on mismatching size -- xpr case + VERIFY_RAISES_ASSERT(m1.row(0).swap(m1)); + } } void test_swap() { + int s = internal::random(1,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_1( swap(Matrix3f()) ); // fixed size, no vectorization CALL_SUBTEST_2( swap(Matrix4d()) ); // fixed size, possible vectorization - CALL_SUBTEST_3( swap(MatrixXd(3,3)) ); // dyn size, no vectorization - CALL_SUBTEST_4( swap(MatrixXf(30,30)) ); // dyn size, possible vectorization + CALL_SUBTEST_3( swap(MatrixXd(s,s)) ); // dyn size, no vectorization + CALL_SUBTEST_4( swap(MatrixXf(s,s)) ); // dyn size, possible vectorization + TEST_SET_BUT_UNUSED_VARIABLE(s) } diff --git a/testbed/nanogui/ext/eigen/test/symbolic_index.cpp b/testbed/nanogui/ext/eigen/test/symbolic_index.cpp new file mode 100644 index 00000000..1db85144 --- /dev/null +++ b/testbed/nanogui/ext/eigen/test/symbolic_index.cpp @@ -0,0 +1,104 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2017 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifdef EIGEN_TEST_PART_2 +#define EIGEN_MAX_CPP_VER 03 +#endif + +#include "main.h" + +template +bool match(const T& xpr, std::string ref, std::string str_xpr = "") { + EIGEN_UNUSED_VARIABLE(str_xpr); + std::stringstream str; + str << xpr; + if(!(str.str() == ref)) + std::cout << str_xpr << "\n" << xpr << "\n\n"; + return str.str() == ref; +} + +#define MATCH(X,R) match(X, R, #X) + +template +typename internal::enable_if::value,bool>::type +is_same_fixed(const T1& a, const T2& b) +{ + return (Index(a) == Index(b)); +} + +template +bool is_same_seq(const T1& a, const T2& b) +{ + bool ok = a.first()==b.first() && a.size() == b.size() && Index(a.incrObject())==Index(b.incrObject());; + if(!ok) + { + std::cerr << "seqN(" << a.first() << ", " << a.size() << ", " << Index(a.incrObject()) << ") != "; + std::cerr << "seqN(" << b.first() << ", " << b.size() << ", " << Index(b.incrObject()) << ")\n"; + } + return ok; +} + +template +typename internal::enable_if::value,bool>::type +is_same_type(const T1&, const T2&) +{ + return true; +} + +template +bool is_same_symb(const T1& a, const T2& b, Index size) +{ + using Eigen::placeholders::last; + return a.eval(last=size-1) == b.eval(last=size-1); +} + + +#define VERIFY_EQ_INT(A,B) VERIFY_IS_APPROX(int(A),int(B)) + +void check_symbolic_index() +{ + using Eigen::placeholders::last; + using Eigen::placeholders::end; + + Index size=100; + + // First, let's check FixedInt arithmetic: + VERIFY( is_same_type( (fix<5>()-fix<3>())*fix<9>()/(-fix<3>()), fix<-(5-3)*9/3>() ) ); + VERIFY( is_same_type( (fix<5>()-fix<3>())*fix<9>()/fix<2>(), fix<(5-3)*9/2>() ) ); + VERIFY( is_same_type( fix<9>()/fix<2>(), fix<9/2>() ) ); + VERIFY( is_same_type( fix<9>()%fix<2>(), fix<9%2>() ) ); + VERIFY( is_same_type( fix<9>()&fix<2>(), fix<9&2>() ) ); + VERIFY( is_same_type( fix<9>()|fix<2>(), fix<9|2>() ) ); + VERIFY( is_same_type( fix<9>()/2, int(9/2) ) ); + + VERIFY( is_same_symb( end-1, last, size) ); + VERIFY( is_same_symb( end-fix<1>, last, size) ); + + VERIFY_IS_EQUAL( ( (last*5-2)/3 ).eval(last=size-1), ((size-1)*5-2)/3 ); + VERIFY_IS_EQUAL( ( (last*fix<5>-fix<2>)/fix<3> ).eval(last=size-1), ((size-1)*5-2)/3 ); + VERIFY_IS_EQUAL( ( -last*end ).eval(last=size-1), -(size-1)*size ); + VERIFY_IS_EQUAL( ( end-3*last ).eval(last=size-1), size- 3*(size-1) ); + VERIFY_IS_EQUAL( ( (end-3*last)/end ).eval(last=size-1), (size- 3*(size-1))/size ); + +#if EIGEN_HAS_CXX14 + { + struct x_tag {}; static const Symbolic::SymbolExpr x; + struct y_tag {}; static const Symbolic::SymbolExpr y; + struct z_tag {}; static const Symbolic::SymbolExpr z; + + VERIFY_IS_APPROX( int(((x+3)/y+z).eval(x=6,y=3,z=-13)), (6+3)/3+(-13) ); + } +#endif +} + +void test_symbolic_index() +{ + CALL_SUBTEST_1( check_symbolic_index() ); + CALL_SUBTEST_2( check_symbolic_index() ); +} diff --git a/testbed/nanogui/ext/eigen/test/testsuite.cmake b/testbed/nanogui/ext/eigen/test/testsuite.cmake deleted file mode 100644 index 3bec56b3..00000000 --- a/testbed/nanogui/ext/eigen/test/testsuite.cmake +++ /dev/null @@ -1,229 +0,0 @@ - -#################################################################### -# -# Usage: -# - create a new folder, let's call it cdash -# - in that folder, do: -# ctest -S path/to/eigen/test/testsuite.cmake[,option1=value1[,option2=value2]] -# -# Options: -# - EIGEN_CXX: compiler, eg.: g++-4.2 -# default: default c++ compiler -# - EIGEN_SITE: eg, INRIA-Bdx_pc-gael, or the name of the contributor, etc. -# default: hostname -# - EIGEN_BUILD_STRING: a string which identify the system/compiler. It should be formed like that: -# --- -# with: -# = opensuse, debian, osx, windows, cygwin, freebsd, solaris, etc. -# = 11.1, XP, vista, leopard, etc. -# = i386, x86_64, ia64, powerpc, etc. -# = gcc-4.3.2, icc-11.0, MSVC-2008, etc. -# - EIGEN_EXPLICIT_VECTORIZATION: novec, SSE2, Altivec -# default: SSE2 for x86_64 systems, novec otherwise -# Its value is automatically appended to EIGEN_BUILD_STRING -# - EIGEN_CMAKE_DIR: path to cmake executable -# - EIGEN_MODE: dashboard model, can be Experimental, Nightly, or Continuous -# default: Nightly -# - EIGEN_WORK_DIR: directory used to download the source files and make the builds -# default: folder which contains this script -# - EIGEN_CMAKE_ARGS: additional arguments passed to cmake -# - EIGEN_GENERATOR_TYPE: allows to overwrite the generator type -# default: nmake (windows -# See http://www.cmake.org/cmake/help/cmake2.6docs.html#section_Generators for a complete -# list of supported generators. -# - EIGEN_NO_UPDATE: allows to submit dash boards from local repositories -# This might be interesting in case you want to submit dashboards -# including local changes. -# - CTEST_SOURCE_DIRECTORY: path to eigen's src (use a new and empty folder, not the one you are working on) -# default: /src -# - CTEST_BINARY_DIRECTORY: build directory -# default: /nightly- -# -# Here is an example running several compilers on a linux system: -# #!/bin/bash -# ARCH=`uname -m` -# SITE=`hostname` -# VERSION=opensuse-11.1 -# WORK_DIR=/home/gael/Coding/eigen/cdash -# # get the last version of the script -# wget http://bitbucket.org/eigen/eigen/raw/tip/test/testsuite.cmake -o $WORK_DIR/testsuite.cmake -# COMMON="ctest -S $WORK_DIR/testsuite.cmake,EIGEN_WORK_DIR=$WORK_DIR,EIGEN_SITE=$SITE,EIGEN_MODE=$1,EIGEN_BUILD_STRING=$OS_VERSION-$ARCH" -# $COMMON-gcc-3.4.6,EIGEN_CXX=g++-3.4 -# $COMMON-gcc-4.0.1,EIGEN_CXX=g++-4.0.1 -# $COMMON-gcc-4.3.2,EIGEN_CXX=g++-4.3,EIGEN_EXPLICIT_VECTORIZATION=novec -# $COMMON-gcc-4.3.2,EIGEN_CXX=g++-4.3,EIGEN_EXPLICIT_VECTORIZATION=SSE2 -# $COMMON-icc-11.0,EIGEN_CXX=icpc -# -#################################################################### - -# process the arguments - -set(ARGLIST ${CTEST_SCRIPT_ARG}) -while(${ARGLIST} MATCHES ".+.*") - - # pick first - string(REGEX MATCH "([^,]*)(,.*)?" DUMMY ${ARGLIST}) - SET(TOP ${CMAKE_MATCH_1}) - - # remove first - string(REGEX MATCHALL "[^,]*,(.*)" DUMMY ${ARGLIST}) - SET(ARGLIST ${CMAKE_MATCH_1}) - - # decompose as a pair key=value - string(REGEX MATCH "([^=]*)(=.*)?" DUMMY ${TOP}) - SET(KEY ${CMAKE_MATCH_1}) - - string(REGEX MATCH "[^=]*=(.*)" DUMMY ${TOP}) - SET(VALUE ${CMAKE_MATCH_1}) - - # set the variable to the specified value - if(VALUE) - SET(${KEY} ${VALUE}) - else(VALUE) - SET(${KEY} ON) - endif(VALUE) - -endwhile(${ARGLIST} MATCHES ".+.*") - -#################################################################### -# Automatically set some user variables if they have not been defined manually -#################################################################### -cmake_minimum_required(VERSION 2.6 FATAL_ERROR) - -if(NOT EIGEN_SITE) - site_name(EIGEN_SITE) -endif(NOT EIGEN_SITE) - -if(NOT EIGEN_CMAKE_DIR) - SET(EIGEN_CMAKE_DIR "") -endif(NOT EIGEN_CMAKE_DIR) - -if(NOT EIGEN_BUILD_STRING) - - # let's try to find all information we need to make the build string ourself - - # OS - build_name(EIGEN_OS_VERSION) - - # arch - set(EIGEN_ARCH ${CMAKE_SYSTEM_PROCESSOR}) - if(WIN32) - set(EIGEN_ARCH $ENV{PROCESSOR_ARCHITECTURE}) - else(WIN32) - execute_process(COMMAND uname -m OUTPUT_VARIABLE EIGEN_ARCH OUTPUT_STRIP_TRAILING_WHITESPACE) - endif(WIN32) - - set(EIGEN_BUILD_STRING ${EIGEN_OS_VERSION}${EIGEN_ARCH}-${EIGEN_CXX}) - -endif(NOT EIGEN_BUILD_STRING) - -if(DEFINED EIGEN_EXPLICIT_VECTORIZATION) - set(EIGEN_BUILD_STRING ${EIGEN_BUILD_STRING}-${EIGEN_EXPLICIT_VECTORIZATION}) -endif(DEFINED EIGEN_EXPLICIT_VECTORIZATION) - -if(NOT EIGEN_WORK_DIR) - set(EIGEN_WORK_DIR ${CTEST_SCRIPT_DIRECTORY}) -endif(NOT EIGEN_WORK_DIR) - -if(NOT CTEST_SOURCE_DIRECTORY) - SET (CTEST_SOURCE_DIRECTORY "${EIGEN_WORK_DIR}/src") -endif(NOT CTEST_SOURCE_DIRECTORY) - -if(NOT CTEST_BINARY_DIRECTORY) - SET (CTEST_BINARY_DIRECTORY "${EIGEN_WORK_DIR}/nightly_${EIGEN_CXX}") -endif(NOT CTEST_BINARY_DIRECTORY) - -if(NOT EIGEN_MODE) - set(EIGEN_MODE Nightly) -endif(NOT EIGEN_MODE) - -## mandatory variables (the default should be ok in most cases): - -if(NOT EIGEN_NO_UPDATE) - SET (CTEST_CVS_COMMAND "hg") - SET (CTEST_CVS_CHECKOUT "${CTEST_CVS_COMMAND} clone http://bitbucket.org/eigen/eigen \"${CTEST_SOURCE_DIRECTORY}\"") - SET(CTEST_BACKUP_AND_RESTORE TRUE) # the backup is CVS related ... -endif(NOT EIGEN_NO_UPDATE) - -# which ctest command to use for running the dashboard -SET (CTEST_COMMAND "${EIGEN_CMAKE_DIR}ctest -D ${EIGEN_MODE} --no-compress-output") -if($ENV{EIGEN_CTEST_ARGS}) -SET (CTEST_COMMAND "${CTEST_COMMAND} $ENV{EIGEN_CTEST_ARGS}") -endif($ENV{EIGEN_CTEST_ARGS}) -# what cmake command to use for configuring this dashboard -SET (CTEST_CMAKE_COMMAND "${EIGEN_CMAKE_DIR}cmake -DEIGEN_LEAVE_TEST_IN_ALL_TARGET=ON") - -#################################################################### -# The values in this section are optional you can either -# have them or leave them commented out -#################################################################### - -# this make sure we get consistent outputs -SET($ENV{LC_MESSAGES} "en_EN") - -# should ctest wipe the binary tree before running -SET(CTEST_START_WITH_EMPTY_BINARY_DIRECTORY TRUE) - -# raise the warning/error limit -set(CTEST_CUSTOM_MAXIMUM_NUMBER_OF_WARNINGS "33331") -set(CTEST_CUSTOM_MAXIMUM_NUMBER_OF_ERRORS "33331") - -# this is the initial cache to use for the binary tree, be careful to escape -# any quotes inside of this string if you use it -if(WIN32 AND NOT UNIX) - #message(SEND_ERROR "win32") - if(EIGEN_GENERATOR_TYPE) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -G \"${EIGEN_GENERATOR_TYPE}\"") - SET (CTEST_INITIAL_CACHE " - CMAKE_BUILD_TYPE:STRING=Release - BUILDNAME:STRING=${EIGEN_BUILD_STRING} - SITE:STRING=${EIGEN_SITE} - ") - else(EIGEN_GENERATOR_TYPE) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -G \"NMake Makefiles\" -DCMAKE_MAKE_PROGRAM=nmake") - SET (CTEST_INITIAL_CACHE " - MAKECOMMAND:STRING=nmake /i - CMAKE_MAKE_PROGRAM:FILEPATH=nmake - CMAKE_GENERATOR:INTERNAL=NMake Makefiles - CMAKE_BUILD_TYPE:STRING=Release - BUILDNAME:STRING=${EIGEN_BUILD_STRING} - SITE:STRING=${EIGEN_SITE} - ") - endif(EIGEN_GENERATOR_TYPE) -else(WIN32 AND NOT UNIX) - SET (CTEST_INITIAL_CACHE " - BUILDNAME:STRING=${EIGEN_BUILD_STRING} - SITE:STRING=${EIGEN_SITE} - ") -endif(WIN32 AND NOT UNIX) - -# set any extra environment variables to use during the execution of the script here: -# setting this variable on windows machines causes trouble ... - -if(EIGEN_CXX AND NOT WIN32) - set(CTEST_ENVIRONMENT "CXX=${EIGEN_CXX}") -endif(EIGEN_CXX AND NOT WIN32) - -if(DEFINED EIGEN_EXPLICIT_VECTORIZATION) - if(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSE2) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_SSE2=ON") - elseif(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSE3) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_SSE2=ON -DEIGEN_TEST_SSE3=ON") - elseif(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSSE3) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_SSE2=ON -DEIGEN_TEST_SSE3=ON -DEIGEN_TEST_SSSE3=ON") - elseif(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSE4_1) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_SSE2=ON -DEIGEN_TEST_SSE3=ON -DEIGEN_TEST_SSSE3=ON -DEIGEN_TEST_SSE4_1=ON") - elseif(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSE4_2) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_SSE2=ON -DEIGEN_TEST_SSE3=ON -DEIGEN_TEST_SSSE3=ON -DEIGEN_TEST_SSE4_1=ON -DEIGEN_TEST_SSE4_2=ON") - elseif(EIGEN_EXPLICIT_VECTORIZATION MATCHES Altivec) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_ALTIVEC=ON") - elseif(EIGEN_EXPLICIT_VECTORIZATION MATCHES novec) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_NO_EXPLICIT_VECTORIZATION=ON") - else(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSE2) - message(FATAL_ERROR "Invalid value for EIGEN_EXPLICIT_VECTORIZATION (${EIGEN_EXPLICIT_VECTORIZATION}), must be: novec, SSE2, SSE3, Altivec") - endif(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSE2) -endif(DEFINED EIGEN_EXPLICIT_VECTORIZATION) - -if(DEFINED EIGEN_CMAKE_ARGS) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} ${EIGEN_CMAKE_ARGS}") -endif(DEFINED EIGEN_CMAKE_ARGS) diff --git a/testbed/nanogui/ext/eigen/test/triangular.cpp b/testbed/nanogui/ext/eigen/test/triangular.cpp index 54320390..b9685648 100644 --- a/testbed/nanogui/ext/eigen/test/triangular.cpp +++ b/testbed/nanogui/ext/eigen/test/triangular.cpp @@ -65,7 +65,7 @@ template void triangular_square(const MatrixType& m) m1 = MatrixType::Random(rows, cols); for (int i=0; i(); + while (numext::abs2(m1(i,i))(); Transpose trm4(m4); // test back and forward subsitution with a vector as the rhs @@ -78,7 +78,7 @@ template void triangular_square(const MatrixType& m) m3 = m1.template triangularView(); VERIFY(v2.isApprox(m3.conjugate() * (m1.conjugate().template triangularView().solve(v2)), largerEps)); - // test back and forward subsitution with a matrix as the rhs + // test back and forward substitution with a matrix as the rhs m3 = m1.template triangularView(); VERIFY(m2.isApprox(m3.adjoint() * (m1.adjoint().template triangularView().solve(m2)), largerEps)); m3 = m1.template triangularView(); @@ -113,6 +113,21 @@ template void triangular_square(const MatrixType& m) m3.setZero(); m3.template triangularView().setOnes(); VERIFY_IS_APPROX(m2,m3); + + m1.setRandom(); + m3 = m1.template triangularView(); + Matrix m5(cols, internal::random(1,20)); m5.setRandom(); + Matrix m6(internal::random(1,20), rows); m6.setRandom(); + VERIFY_IS_APPROX(m1.template triangularView() * m5, m3*m5); + VERIFY_IS_APPROX(m6*m1.template triangularView(), m6*m3); + + m1up = m1.template triangularView(); + VERIFY_IS_APPROX(m1.template selfadjointView().template triangularView().toDenseMatrix(), m1up); + VERIFY_IS_APPROX(m1up.template selfadjointView().template triangularView().toDenseMatrix(), m1up); + VERIFY_IS_APPROX(m1.template selfadjointView().template triangularView().toDenseMatrix(), m1up.adjoint()); + VERIFY_IS_APPROX(m1up.template selfadjointView().template triangularView().toDenseMatrix(), m1up.adjoint()); + + VERIFY_IS_APPROX(m1.template selfadjointView().diagonal(), m1.diagonal()); } diff --git a/testbed/nanogui/ext/eigen/test/umfpack_support.cpp b/testbed/nanogui/ext/eigen/test/umfpack_support.cpp index 9eb84c14..37ab11f0 100644 --- a/testbed/nanogui/ext/eigen/test/umfpack_support.cpp +++ b/testbed/nanogui/ext/eigen/test/umfpack_support.cpp @@ -7,6 +7,7 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS #include "sparse_solver.h" #include diff --git a/testbed/nanogui/ext/eigen/test/unalignedassert.cpp b/testbed/nanogui/ext/eigen/test/unalignedassert.cpp index 601dbf21..731a0897 100644 --- a/testbed/nanogui/ext/eigen/test/unalignedassert.cpp +++ b/testbed/nanogui/ext/eigen/test/unalignedassert.cpp @@ -2,13 +2,39 @@ // for linear algebra. // // Copyright (C) 2008 Benoit Jacob +// Copyright (C) 2015 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +#if defined(EIGEN_TEST_PART_1) + // default +#elif defined(EIGEN_TEST_PART_2) + #define EIGEN_MAX_STATIC_ALIGN_BYTES 16 + #define EIGEN_MAX_ALIGN_BYTES 16 +#elif defined(EIGEN_TEST_PART_3) + #define EIGEN_MAX_STATIC_ALIGN_BYTES 32 + #define EIGEN_MAX_ALIGN_BYTES 32 +#elif defined(EIGEN_TEST_PART_4) + #define EIGEN_MAX_STATIC_ALIGN_BYTES 64 + #define EIGEN_MAX_ALIGN_BYTES 64 +#endif + #include "main.h" +typedef Matrix Vector6f; +typedef Matrix Vector8f; +typedef Matrix Vector12f; + +typedef Matrix Vector5d; +typedef Matrix Vector6d; +typedef Matrix Vector7d; +typedef Matrix Vector8d; +typedef Matrix Vector9d; +typedef Matrix Vector10d; +typedef Matrix Vector12d; + struct TestNew1 { MatrixXd m; // good: m will allocate its own array, taking care of alignment. @@ -36,7 +62,7 @@ struct TestNew4 struct TestNew5 { EIGEN_MAKE_ALIGNED_OPERATOR_NEW - float f; // try the f at first -- the EIGEN_ALIGN16 attribute of m should make that still work + float f; // try the f at first -- the EIGEN_ALIGN_MAX attribute of m should make that still work Matrix4f m; }; @@ -63,13 +89,13 @@ void check_unalignedassert_good() delete[] y; } -#if EIGEN_ALIGN_STATICALLY +#if EIGEN_MAX_STATIC_ALIGN_BYTES>0 template void construct_at_boundary(int boundary) { char buf[sizeof(T)+256]; - size_t _buf = reinterpret_cast(buf); - _buf += (16 - (_buf % 16)); // make 16-byte aligned + size_t _buf = reinterpret_cast(buf); + _buf += (EIGEN_MAX_ALIGN_BYTES - (_buf % EIGEN_MAX_ALIGN_BYTES)); // make 16/32/...-byte aligned _buf += boundary; // make exact boundary-aligned T *x = ::new(reinterpret_cast(_buf)) T; x[0].setZero(); // just in order to silence warnings @@ -79,26 +105,36 @@ void construct_at_boundary(int boundary) void unalignedassert() { - #if EIGEN_ALIGN_STATICALLY +#if EIGEN_MAX_STATIC_ALIGN_BYTES>0 construct_at_boundary(4); construct_at_boundary(4); construct_at_boundary(16); + construct_at_boundary(4); + construct_at_boundary(EIGEN_MAX_ALIGN_BYTES); + construct_at_boundary(16); construct_at_boundary(16); construct_at_boundary(4); - construct_at_boundary(16); + construct_at_boundary(EIGEN_MAX_ALIGN_BYTES); construct_at_boundary(16); construct_at_boundary(4); - construct_at_boundary(16); - construct_at_boundary(16); + construct_at_boundary(EIGEN_MAX_ALIGN_BYTES); + construct_at_boundary(4); + construct_at_boundary(16); + construct_at_boundary(4); + construct_at_boundary(EIGEN_MAX_ALIGN_BYTES); + construct_at_boundary(4); + construct_at_boundary(16); + construct_at_boundary(EIGEN_MAX_ALIGN_BYTES); + construct_at_boundary(EIGEN_MAX_ALIGN_BYTES); construct_at_boundary(4); - construct_at_boundary(16); + construct_at_boundary(EIGEN_MAX_ALIGN_BYTES); construct_at_boundary(16); construct_at_boundary(4); - construct_at_boundary(16); + construct_at_boundary(EIGEN_MAX_ALIGN_BYTES); construct_at_boundary(16); - #endif +#endif check_unalignedassert_good(); check_unalignedassert_good(); @@ -109,15 +145,32 @@ void unalignedassert() check_unalignedassert_good(); check_unalignedassert_good >(); -#if EIGEN_ALIGN_STATICALLY - VERIFY_RAISES_ASSERT(construct_at_boundary(8)); - VERIFY_RAISES_ASSERT(construct_at_boundary(8)); - VERIFY_RAISES_ASSERT(construct_at_boundary(8)); - VERIFY_RAISES_ASSERT(construct_at_boundary(8)); - VERIFY_RAISES_ASSERT(construct_at_boundary(8)); - VERIFY_RAISES_ASSERT(construct_at_boundary(8)); - VERIFY_RAISES_ASSERT(construct_at_boundary(8)); - VERIFY_RAISES_ASSERT(construct_at_boundary(8)); +#if EIGEN_MAX_STATIC_ALIGN_BYTES>0 + if(EIGEN_MAX_ALIGN_BYTES>=16) + { + VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + // Complexes are disabled because the compiler might aggressively vectorize + // the initialization of complex coeffs to 0 before we can check for alignedness + //VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + } + for(int b=8; b(b)); + if(b<64) VERIFY_RAISES_ASSERT(construct_at_boundary(b)); + if(b<32) VERIFY_RAISES_ASSERT(construct_at_boundary(b)); + if(b<32) VERIFY_RAISES_ASSERT(construct_at_boundary(b)); + if(b<128) VERIFY_RAISES_ASSERT(construct_at_boundary(b)); + //if(b<32) VERIFY_RAISES_ASSERT(construct_at_boundary(b)); + } #endif } diff --git a/testbed/nanogui/ext/eigen/test/unalignedcount.cpp b/testbed/nanogui/ext/eigen/test/unalignedcount.cpp index ca7e159f..d6ffeafd 100644 --- a/testbed/nanogui/ext/eigen/test/unalignedcount.cpp +++ b/testbed/nanogui/ext/eigen/test/unalignedcount.cpp @@ -30,7 +30,14 @@ static int nb_storeu; void test_unalignedcount() { - #ifdef EIGEN_VECTORIZE_SSE + #if defined(EIGEN_VECTORIZE_AVX) + VectorXf a(40), b(40); + VERIFY_ALIGNED_UNALIGNED_COUNT(a += b, 10, 0, 5, 0); + VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) += b.segment(0,40), 5, 5, 5, 0); + VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) -= b.segment(0,40), 5, 5, 5, 0); + VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) *= 3.5, 5, 0, 5, 0); + VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) /= 3.5, 5, 0, 5, 0); + #elif defined(EIGEN_VECTORIZE_SSE) VectorXf a(40), b(40); VERIFY_ALIGNED_UNALIGNED_COUNT(a += b, 20, 0, 10, 0); VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) += b.segment(0,40), 10, 10, 10, 0); diff --git a/testbed/nanogui/ext/eigen/test/upperbidiagonalization.cpp b/testbed/nanogui/ext/eigen/test/upperbidiagonalization.cpp index d15bf588..847b34b5 100644 --- a/testbed/nanogui/ext/eigen/test/upperbidiagonalization.cpp +++ b/testbed/nanogui/ext/eigen/test/upperbidiagonalization.cpp @@ -35,7 +35,7 @@ void test_upperbidiagonalization() CALL_SUBTEST_1( upperbidiag(MatrixXf(3,3)) ); CALL_SUBTEST_2( upperbidiag(MatrixXd(17,12)) ); CALL_SUBTEST_3( upperbidiag(MatrixXcf(20,20)) ); - CALL_SUBTEST_4( upperbidiag(MatrixXcd(16,15)) ); + CALL_SUBTEST_4( upperbidiag(Matrix,Dynamic,Dynamic,RowMajor>(16,15)) ); CALL_SUBTEST_5( upperbidiag(Matrix()) ); CALL_SUBTEST_6( upperbidiag(Matrix()) ); CALL_SUBTEST_7( upperbidiag(Matrix()) ); diff --git a/testbed/nanogui/ext/eigen/test/vectorization_logic.cpp b/testbed/nanogui/ext/eigen/test/vectorization_logic.cpp index aee68a87..83c1439a 100644 --- a/testbed/nanogui/ext/eigen/test/vectorization_logic.cpp +++ b/testbed/nanogui/ext/eigen/test/vectorization_logic.cpp @@ -1,72 +1,47 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2008 Gael Guennebaud +// Copyright (C) 2015 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +#ifdef EIGEN_TEST_PART_1 +#define EIGEN_UNALIGNED_VECTORIZE 1 +#endif + +#ifdef EIGEN_TEST_PART_2 +#define EIGEN_UNALIGNED_VECTORIZE 0 +#endif + +#ifdef EIGEN_DEFAULT_TO_ROW_MAJOR +#undef EIGEN_DEFAULT_TO_ROW_MAJOR +#endif #define EIGEN_DEBUG_ASSIGN #include "main.h" #include -std::string demangle_traversal(int t) -{ - if(t==DefaultTraversal) return "DefaultTraversal"; - if(t==LinearTraversal) return "LinearTraversal"; - if(t==InnerVectorizedTraversal) return "InnerVectorizedTraversal"; - if(t==LinearVectorizedTraversal) return "LinearVectorizedTraversal"; - if(t==SliceVectorizedTraversal) return "SliceVectorizedTraversal"; - return "?"; -} -std::string demangle_unrolling(int t) -{ - if(t==NoUnrolling) return "NoUnrolling"; - if(t==InnerUnrolling) return "InnerUnrolling"; - if(t==CompleteUnrolling) return "CompleteUnrolling"; - return "?"; -} +using internal::demangle_flags; +using internal::demangle_traversal; +using internal::demangle_unrolling; template bool test_assign(const Dst&, const Src&, int traversal, int unrolling) { - internal::assign_traits::debug(); - bool res = internal::assign_traits::Traversal==traversal - && internal::assign_traits::Unrolling==unrolling; - if(!res) - { - std::cerr << " Expected Traversal == " << demangle_traversal(traversal) - << " got " << demangle_traversal(internal::assign_traits::Traversal) << "\n"; - std::cerr << " Expected Unrolling == " << demangle_unrolling(unrolling) - << " got " << demangle_unrolling(internal::assign_traits::Unrolling) << "\n"; - } - return res; -} - -template -bool test_assign(int traversal, int unrolling) -{ - internal::assign_traits::debug(); - bool res = internal::assign_traits::Traversal==traversal - && internal::assign_traits::Unrolling==unrolling; - if(!res) - { - std::cerr << " Expected Traversal == " << demangle_traversal(traversal) - << " got " << demangle_traversal(internal::assign_traits::Traversal) << "\n"; - std::cerr << " Expected Unrolling == " << demangle_unrolling(unrolling) - << " got " << demangle_unrolling(internal::assign_traits::Unrolling) << "\n"; - } - return res; -} - -template -bool test_redux(const Xpr&, int traversal, int unrolling) -{ - typedef internal::redux_traits,Xpr> traits; - bool res = traits::Traversal==traversal && traits::Unrolling==unrolling; + typedef internal::copy_using_evaluator_traits,internal::evaluator, internal::assign_op > traits; + bool res = traits::Traversal==traversal; + if(unrolling==InnerUnrolling+CompleteUnrolling) + res = res && (int(traits::Unrolling)==InnerUnrolling || int(traits::Unrolling)==CompleteUnrolling); + else + res = res && int(traits::Unrolling)==unrolling; if(!res) { + std::cerr << "Src: " << demangle_flags(Src::Flags) << std::endl; + std::cerr << " " << demangle_flags(internal::evaluator::Flags) << std::endl; + std::cerr << "Dst: " << demangle_flags(Dst::Flags) << std::endl; + std::cerr << " " << demangle_flags(internal::evaluator::Flags) << std::endl; + traits::debug(); std::cerr << " Expected Traversal == " << demangle_traversal(traversal) << " got " << demangle_traversal(traits::Traversal) << "\n"; std::cerr << " Expected Unrolling == " << demangle_unrolling(unrolling) @@ -75,10 +50,57 @@ bool test_redux(const Xpr&, int traversal, int unrolling) return res; } -template::Vectorizable> struct vectorization_logic +template +bool test_assign(int traversal, int unrolling) { + typedef internal::copy_using_evaluator_traits,internal::evaluator, internal::assign_op > traits; + bool res = traits::Traversal==traversal && traits::Unrolling==unrolling; + if(!res) + { + std::cerr << "Src: " << demangle_flags(Src::Flags) << std::endl; + std::cerr << " " << demangle_flags(internal::evaluator::Flags) << std::endl; + std::cerr << "Dst: " << demangle_flags(Dst::Flags) << std::endl; + std::cerr << " " << demangle_flags(internal::evaluator::Flags) << std::endl; + traits::debug(); + std::cerr << " Expected Traversal == " << demangle_traversal(traversal) + << " got " << demangle_traversal(traits::Traversal) << "\n"; + std::cerr << " Expected Unrolling == " << demangle_unrolling(unrolling) + << " got " << demangle_unrolling(traits::Unrolling) << "\n"; + } + return res; +} + +template +bool test_redux(const Xpr&, int traversal, int unrolling) +{ + typedef typename Xpr::Scalar Scalar; + typedef internal::redux_traits,internal::redux_evaluator > traits; + + bool res = traits::Traversal==traversal && traits::Unrolling==unrolling; + if(!res) + { + std::cerr << demangle_flags(Xpr::Flags) << std::endl; + std::cerr << demangle_flags(internal::evaluator::Flags) << std::endl; + traits::debug(); + + std::cerr << " Expected Traversal == " << demangle_traversal(traversal) + << " got " << demangle_traversal(traits::Traversal) << "\n"; + std::cerr << " Expected Unrolling == " << demangle_unrolling(unrolling) + << " got " << demangle_unrolling(traits::Unrolling) << "\n"; + } + return res; +} + +template::Vectorizable> +struct vectorization_logic +{ + typedef internal::packet_traits PacketTraits; + + typedef typename internal::packet_traits::type PacketType; + typedef typename internal::unpacket_traits::half HalfPacketType; enum { - PacketSize = internal::packet_traits::size + PacketSize = internal::unpacket_traits::size, + HalfPacketSize = internal::unpacket_traits::size }; static void run() { @@ -90,8 +112,8 @@ template::Vectori typedef Matrix Matrix22; typedef Matrix Matrix44; typedef Matrix Matrix44u; - typedef Matrix Matrix44c; - typedef Matrix Matrix44r; + typedef Matrix Matrix44c; + typedef Matrix Matrix44r; typedef Matrix::Vectori InnerVectorizedTraversal,InnerUnrolling)); VERIFY(test_assign(Matrix44u(),Matrix44()+Matrix44(), - LinearTraversal,NoUnrolling)); + EIGEN_UNALIGNED_VECTORIZE ? InnerVectorizedTraversal : LinearTraversal, + EIGEN_UNALIGNED_VECTORIZE ? InnerUnrolling : NoUnrolling)); + + VERIFY(test_assign(Matrix1(),Matrix1()+Matrix1(), + (Matrix1::InnerSizeAtCompileTime % PacketSize)==0 ? InnerVectorizedTraversal : LinearVectorizedTraversal, + CompleteUnrolling)); VERIFY(test_assign(Matrix1u(),Matrix1()+Matrix1(), - LinearTraversal,CompleteUnrolling)); + EIGEN_UNALIGNED_VECTORIZE ? ((Matrix1::InnerSizeAtCompileTime % PacketSize)==0 ? InnerVectorizedTraversal : LinearVectorizedTraversal) + : LinearTraversal, CompleteUnrolling)); VERIFY(test_assign(Matrix44c().col(1),Matrix44c().col(2)+Matrix44c().col(3), InnerVectorizedTraversal,CompleteUnrolling)); - + VERIFY(test_assign(Matrix44r().row(2),Matrix44r().row(1)+Matrix44r().row(1), InnerVectorizedTraversal,CompleteUnrolling)); - + if(PacketSize>1) { typedef Matrix Matrix33c; + typedef Matrix Vector3; VERIFY(test_assign(Matrix33c().row(2),Matrix33c().row(1)+Matrix33c().row(1), LinearTraversal,CompleteUnrolling)); + VERIFY(test_assign(Vector3(),Vector3()+Vector3(), + EIGEN_UNALIGNED_VECTORIZE ? (HalfPacketSize==1 ? InnerVectorizedTraversal : LinearVectorizedTraversal) : (HalfPacketSize==1 ? InnerVectorizedTraversal : LinearTraversal), CompleteUnrolling)); VERIFY(test_assign(Matrix33c().col(0),Matrix33c().col(1)+Matrix33c().col(1), - LinearTraversal,CompleteUnrolling)); - - VERIFY(test_assign(Matrix3(),Matrix3().cwiseQuotient(Matrix3()), + EIGEN_UNALIGNED_VECTORIZE ? (HalfPacketSize==1 ? InnerVectorizedTraversal : LinearVectorizedTraversal) : (HalfPacketSize==1 ? SliceVectorizedTraversal : LinearTraversal), + ((!EIGEN_UNALIGNED_VECTORIZE) && HalfPacketSize==1) ? NoUnrolling : CompleteUnrolling)); + + VERIFY(test_assign(Matrix3(),Matrix3().cwiseProduct(Matrix3()), LinearVectorizedTraversal,CompleteUnrolling)); VERIFY(test_assign(Matrix(),Matrix()+Matrix(), - LinearTraversal,NoUnrolling)); + HalfPacketSize==1 ? InnerVectorizedTraversal : + EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : + LinearTraversal, + NoUnrolling)); - VERIFY(test_assign(Matrix11(),Matrix().template block(2,3)+Matrix().template block(10,4), - DefaultTraversal,CompleteUnrolling)); + VERIFY(test_assign(Matrix11(), Matrix11()+Matrix11(),InnerVectorizedTraversal,CompleteUnrolling)); + + + VERIFY(test_assign(Matrix11(),Matrix().template block(2,3)+Matrix().template block(8,4), + (EIGEN_UNALIGNED_VECTORIZE) ? InnerVectorizedTraversal : DefaultTraversal, CompleteUnrolling|InnerUnrolling)); + + VERIFY(test_assign(Vector1(),Matrix11()*Vector1(), + InnerVectorizedTraversal,CompleteUnrolling)); + + VERIFY(test_assign(Matrix11(),Matrix11().lazyProduct(Matrix11()), + InnerVectorizedTraversal,InnerUnrolling+CompleteUnrolling)); } - + + VERIFY(test_redux(Vector1(), + LinearVectorizedTraversal,CompleteUnrolling)); + + VERIFY(test_redux(Matrix(), + LinearVectorizedTraversal,CompleteUnrolling)); + VERIFY(test_redux(Matrix3(), LinearVectorizedTraversal,CompleteUnrolling)); @@ -174,18 +224,19 @@ template::Vectori VERIFY(test_redux(Matrix44r().template block<1,2*PacketSize>(2,1), LinearVectorizedTraversal,CompleteUnrolling)); - + VERIFY((test_assign< - Map >, + Map >, Matrix22 >(InnerVectorizedTraversal,CompleteUnrolling))); VERIFY((test_assign< - Map >, - Matrix22 - >(DefaultTraversal,CompleteUnrolling))); + Map, AlignedMax, InnerStride<3*PacketSize> >, + Matrix + >(DefaultTraversal,PacketSize>=8?InnerUnrolling:CompleteUnrolling))); - VERIFY((test_assign(Matrix11(), Matrix11()*Matrix11(), InnerVectorizedTraversal, CompleteUnrolling))); + VERIFY((test_assign(Matrix11(), Matrix()*Matrix(), + InnerVectorizedTraversal, CompleteUnrolling))); #endif VERIFY(test_assign(MatrixXX(10,10),MatrixXX(20,20).block(10,10,2,3), @@ -193,8 +244,6 @@ template::Vectori VERIFY(test_redux(VectorX(10), LinearVectorizedTraversal,NoUnrolling)); - - } }; @@ -203,32 +252,167 @@ template struct vectorization_logic static void run() {} }; +template::type>::half, + typename internal::packet_traits::type>::value > +struct vectorization_logic_half +{ + typedef internal::packet_traits PacketTraits; + typedef typename internal::unpacket_traits::type>::half PacketType; + enum { + PacketSize = internal::unpacket_traits::size + }; + static void run() + { + + typedef Matrix Vector1; + typedef Matrix Matrix11; + typedef Matrix Matrix57; + typedef Matrix Matrix35; + typedef Matrix Matrix57u; +// typedef Matrix Matrix44; +// typedef Matrix Matrix44u; +// typedef Matrix Matrix44c; +// typedef Matrix Matrix44r; + + typedef Matrix Matrix1; + + typedef Matrix Matrix1u; + + // this type is made such that it can only be vectorized when viewed as a linear 1D vector + typedef Matrix Matrix3; + + #if !EIGEN_GCC_AND_ARCH_DOESNT_WANT_STACK_ALIGNMENT + VERIFY(test_assign(Vector1(),Vector1(), + InnerVectorizedTraversal,CompleteUnrolling)); + VERIFY(test_assign(Vector1(),Vector1()+Vector1(), + InnerVectorizedTraversal,CompleteUnrolling)); + VERIFY(test_assign(Vector1(),Vector1().template segment(0).derived(), + EIGEN_UNALIGNED_VECTORIZE ? InnerVectorizedTraversal : LinearVectorizedTraversal,CompleteUnrolling)); + VERIFY(test_assign(Vector1(),Scalar(2.1)*Vector1()-Vector1(), + InnerVectorizedTraversal,CompleteUnrolling)); + VERIFY(test_assign(Vector1(),(Scalar(2.1)*Vector1().template segment(0)-Vector1().template segment(0)).derived(), + EIGEN_UNALIGNED_VECTORIZE ? InnerVectorizedTraversal : LinearVectorizedTraversal,CompleteUnrolling)); + VERIFY(test_assign(Vector1(),Vector1().cwiseProduct(Vector1()), + InnerVectorizedTraversal,CompleteUnrolling)); + VERIFY(test_assign(Vector1(),Vector1().template cast(), + InnerVectorizedTraversal,CompleteUnrolling)); + + + VERIFY(test_assign(Vector1(),Vector1(), + InnerVectorizedTraversal,CompleteUnrolling)); + VERIFY(test_assign(Vector1(),Vector1()+Vector1(), + InnerVectorizedTraversal,CompleteUnrolling)); + VERIFY(test_assign(Vector1(),Vector1().cwiseProduct(Vector1()), + InnerVectorizedTraversal,CompleteUnrolling)); + + VERIFY(test_assign(Matrix57(),Matrix57()+Matrix57(), + InnerVectorizedTraversal,InnerUnrolling)); + + VERIFY(test_assign(Matrix57u(),Matrix57()+Matrix57(), + EIGEN_UNALIGNED_VECTORIZE ? InnerVectorizedTraversal : LinearTraversal, + EIGEN_UNALIGNED_VECTORIZE ? InnerUnrolling : NoUnrolling)); + + VERIFY(test_assign(Matrix1u(),Matrix1()+Matrix1(), + EIGEN_UNALIGNED_VECTORIZE ? ((Matrix1::InnerSizeAtCompileTime % PacketSize)==0 ? InnerVectorizedTraversal : LinearVectorizedTraversal) : LinearTraversal,CompleteUnrolling)); + + if(PacketSize>1) + { + typedef Matrix Matrix33c; + VERIFY(test_assign(Matrix33c().row(2),Matrix33c().row(1)+Matrix33c().row(1), + LinearTraversal,CompleteUnrolling)); + VERIFY(test_assign(Matrix33c().col(0),Matrix33c().col(1)+Matrix33c().col(1), + EIGEN_UNALIGNED_VECTORIZE ? (PacketSize==1 ? InnerVectorizedTraversal : LinearVectorizedTraversal) : LinearTraversal,CompleteUnrolling)); + + VERIFY(test_assign(Matrix3(),Matrix3().cwiseQuotient(Matrix3()), + PacketTraits::HasDiv ? LinearVectorizedTraversal : LinearTraversal,CompleteUnrolling)); + + VERIFY(test_assign(Matrix(),Matrix()+Matrix(), + EIGEN_UNALIGNED_VECTORIZE ? (PacketSize==1 ? InnerVectorizedTraversal : LinearVectorizedTraversal) : LinearTraversal, + NoUnrolling)); + + VERIFY(test_assign(Matrix11(),Matrix().template block(2,3)+Matrix().template block(8,4), + EIGEN_UNALIGNED_VECTORIZE ? InnerVectorizedTraversal : DefaultTraversal,PacketSize>4?InnerUnrolling:CompleteUnrolling)); + + VERIFY(test_assign(Vector1(),Matrix11()*Vector1(), + InnerVectorizedTraversal,CompleteUnrolling)); + + VERIFY(test_assign(Matrix11(),Matrix11().lazyProduct(Matrix11()), + InnerVectorizedTraversal,InnerUnrolling+CompleteUnrolling)); + } + + VERIFY(test_redux(Vector1(), + LinearVectorizedTraversal,CompleteUnrolling)); + + VERIFY(test_redux(Matrix(), + LinearVectorizedTraversal,CompleteUnrolling)); + + VERIFY(test_redux(Matrix3(), + LinearVectorizedTraversal,CompleteUnrolling)); + + VERIFY(test_redux(Matrix35(), + LinearVectorizedTraversal,CompleteUnrolling)); + + VERIFY(test_redux(Matrix57().template block(1,0), + DefaultTraversal,CompleteUnrolling)); + + VERIFY((test_assign< + Map, AlignedMax, InnerStride<3*PacketSize> >, + Matrix + >(DefaultTraversal,CompleteUnrolling))); + + VERIFY((test_assign(Matrix57(), Matrix()*Matrix(), + InnerVectorizedTraversal, InnerUnrolling|CompleteUnrolling))); + #endif + } +}; + +template struct vectorization_logic_half +{ + static void run() {} +}; + void test_vectorization_logic() { #ifdef EIGEN_VECTORIZE + CALL_SUBTEST( vectorization_logic::run() ); CALL_SUBTEST( vectorization_logic::run() ); CALL_SUBTEST( vectorization_logic::run() ); CALL_SUBTEST( vectorization_logic >::run() ); CALL_SUBTEST( vectorization_logic >::run() ); + CALL_SUBTEST( vectorization_logic_half::run() ); + CALL_SUBTEST( vectorization_logic_half::run() ); + CALL_SUBTEST( vectorization_logic_half::run() ); + CALL_SUBTEST( vectorization_logic_half >::run() ); + CALL_SUBTEST( vectorization_logic_half >::run() ); + if(internal::packet_traits::Vectorizable) { VERIFY(test_assign(Matrix(),Matrix()+Matrix(), - LinearTraversal,CompleteUnrolling)); + EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : LinearTraversal,CompleteUnrolling)); VERIFY(test_redux(Matrix(), - DefaultTraversal,CompleteUnrolling)); + EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : DefaultTraversal,CompleteUnrolling)); } if(internal::packet_traits::Vectorizable) { VERIFY(test_assign(Matrix(),Matrix()+Matrix(), - LinearTraversal,CompleteUnrolling)); + EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : LinearTraversal,CompleteUnrolling)); VERIFY(test_redux(Matrix(), - DefaultTraversal,CompleteUnrolling)); + EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : DefaultTraversal,CompleteUnrolling)); } #endif // EIGEN_VECTORIZE diff --git a/testbed/nanogui/ext/eigen/test/vectorwiseop.cpp b/testbed/nanogui/ext/eigen/test/vectorwiseop.cpp index 6cd1acdd..f3ab561e 100644 --- a/testbed/nanogui/ext/eigen/test/vectorwiseop.cpp +++ b/testbed/nanogui/ext/eigen/test/vectorwiseop.cpp @@ -2,11 +2,13 @@ // for linear algebra. // // Copyright (C) 2011 Benoit Jacob +// Copyright (C) 2015 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +#define TEST_ENABLE_TEMPORARY_TRACKING #define EIGEN_NO_STATIC_ASSERT #include "main.h" @@ -101,16 +103,28 @@ template void vectorwiseop_array(const ArrayType& m) VERIFY_RAISES_ASSERT(m2.rowwise() /= rowvec.transpose()); VERIFY_RAISES_ASSERT(m1.rowwise() / rowvec.transpose()); - + m2 = m1; // yes, there might be an aliasing issue there but ".rowwise() /=" - // is suppposed to evaluate " m2.colwise().sum()" into to temporary to avoid - // evaluating the reducions multiple times + // is supposed to evaluate " m2.colwise().sum()" into a temporary to avoid + // evaluating the reduction multiple times if(ArrayType::RowsAtCompileTime>2 || ArrayType::RowsAtCompileTime==Dynamic) { m2.rowwise() /= m2.colwise().sum(); VERIFY_IS_APPROX(m2, m1.rowwise() / m1.colwise().sum()); } + + // all/any + Array mb(rows,cols); + mb = (m1.real()<=0.7).colwise().all(); + VERIFY( (mb.col(c) == (m1.real().col(c)<=0.7).all()).all() ); + mb = (m1.real()<=0.7).rowwise().all(); + VERIFY( (mb.row(r) == (m1.real().row(r)<=0.7).all()).all() ); + + mb = (m1.real()>=0.7).colwise().any(); + VERIFY( (mb.col(c) == (m1.real().col(c)>=0.7).any()).all() ); + mb = (m1.real()>=0.7).rowwise().any(); + VERIFY( (mb.row(r) == (m1.real().row(r)>=0.7).any()).all() ); } template void vectorwiseop_matrix(const MatrixType& m) @@ -144,16 +158,22 @@ template void vectorwiseop_matrix(const MatrixType& m) VERIFY_IS_APPROX(m2, m1.colwise() + colvec); VERIFY_IS_APPROX(m2.col(c), m1.col(c) + colvec); - VERIFY_RAISES_ASSERT(m2.colwise() += colvec.transpose()); - VERIFY_RAISES_ASSERT(m1.colwise() + colvec.transpose()); + if(rows>1) + { + VERIFY_RAISES_ASSERT(m2.colwise() += colvec.transpose()); + VERIFY_RAISES_ASSERT(m1.colwise() + colvec.transpose()); + } m2 = m1; m2.rowwise() += rowvec; VERIFY_IS_APPROX(m2, m1.rowwise() + rowvec); VERIFY_IS_APPROX(m2.row(r), m1.row(r) + rowvec); - VERIFY_RAISES_ASSERT(m2.rowwise() += rowvec.transpose()); - VERIFY_RAISES_ASSERT(m1.rowwise() + rowvec.transpose()); + if(cols>1) + { + VERIFY_RAISES_ASSERT(m2.rowwise() += rowvec.transpose()); + VERIFY_RAISES_ASSERT(m1.rowwise() + rowvec.transpose()); + } // test substraction @@ -162,29 +182,43 @@ template void vectorwiseop_matrix(const MatrixType& m) VERIFY_IS_APPROX(m2, m1.colwise() - colvec); VERIFY_IS_APPROX(m2.col(c), m1.col(c) - colvec); - VERIFY_RAISES_ASSERT(m2.colwise() -= colvec.transpose()); - VERIFY_RAISES_ASSERT(m1.colwise() - colvec.transpose()); + if(rows>1) + { + VERIFY_RAISES_ASSERT(m2.colwise() -= colvec.transpose()); + VERIFY_RAISES_ASSERT(m1.colwise() - colvec.transpose()); + } m2 = m1; m2.rowwise() -= rowvec; VERIFY_IS_APPROX(m2, m1.rowwise() - rowvec); VERIFY_IS_APPROX(m2.row(r), m1.row(r) - rowvec); - VERIFY_RAISES_ASSERT(m2.rowwise() -= rowvec.transpose()); - VERIFY_RAISES_ASSERT(m1.rowwise() - rowvec.transpose()); - + if(cols>1) + { + VERIFY_RAISES_ASSERT(m2.rowwise() -= rowvec.transpose()); + VERIFY_RAISES_ASSERT(m1.rowwise() - rowvec.transpose()); + } + // test norm rrres = m1.colwise().norm(); VERIFY_IS_APPROX(rrres(c), m1.col(c).norm()); rcres = m1.rowwise().norm(); VERIFY_IS_APPROX(rcres(r), m1.row(r).norm()); - + + VERIFY_IS_APPROX(m1.cwiseAbs().colwise().sum(), m1.colwise().template lpNorm<1>()); + VERIFY_IS_APPROX(m1.cwiseAbs().rowwise().sum(), m1.rowwise().template lpNorm<1>()); + VERIFY_IS_APPROX(m1.cwiseAbs().colwise().maxCoeff(), m1.colwise().template lpNorm()); + VERIFY_IS_APPROX(m1.cwiseAbs().rowwise().maxCoeff(), m1.rowwise().template lpNorm()); + + // regression for bug 1158 + VERIFY_IS_APPROX(m1.cwiseAbs().colwise().sum().x(), m1.col(0).cwiseAbs().sum()); + // test normalized m2 = m1.colwise().normalized(); VERIFY_IS_APPROX(m2.col(c), m1.col(c).normalized()); m2 = m1.rowwise().normalized(); VERIFY_IS_APPROX(m2.row(r), m1.row(r).normalized()); - + // test normalize m2 = m1; m2.colwise().normalize(); @@ -192,14 +226,27 @@ template void vectorwiseop_matrix(const MatrixType& m) m2 = m1; m2.rowwise().normalize(); VERIFY_IS_APPROX(m2.row(r), m1.row(r).normalized()); + + // test with partial reduction of products + Matrix m1m1 = m1 * m1.transpose(); + VERIFY_IS_APPROX( (m1 * m1.transpose()).colwise().sum(), m1m1.colwise().sum()); + Matrix tmp(rows); + VERIFY_EVALUATION_COUNT( tmp = (m1 * m1.transpose()).colwise().sum(), 1); + + m2 = m1.rowwise() - (m1.colwise().sum()/RealScalar(m1.rows())).eval(); + m1 = m1.rowwise() - (m1.colwise().sum()/RealScalar(m1.rows())); + VERIFY_IS_APPROX( m1, m2 ); + VERIFY_EVALUATION_COUNT( m2 = (m1.rowwise() - m1.colwise().sum()/RealScalar(m1.rows())), (MatrixType::RowsAtCompileTime!=1 ? 1 : 0) ); } void test_vectorwiseop() { - CALL_SUBTEST_1(vectorwiseop_array(Array22cd())); - CALL_SUBTEST_2(vectorwiseop_array(Array())); - CALL_SUBTEST_3(vectorwiseop_array(ArrayXXf(3, 4))); - CALL_SUBTEST_4(vectorwiseop_matrix(Matrix4cf())); - CALL_SUBTEST_5(vectorwiseop_matrix(Matrix())); - CALL_SUBTEST_6(vectorwiseop_matrix(MatrixXd(7,2))); + CALL_SUBTEST_1( vectorwiseop_array(Array22cd()) ); + CALL_SUBTEST_2( vectorwiseop_array(Array()) ); + CALL_SUBTEST_3( vectorwiseop_array(ArrayXXf(3, 4)) ); + CALL_SUBTEST_4( vectorwiseop_matrix(Matrix4cf()) ); + CALL_SUBTEST_5( vectorwiseop_matrix(Matrix()) ); + CALL_SUBTEST_6( vectorwiseop_matrix(MatrixXd(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_7( vectorwiseop_matrix(VectorXd(internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_7( vectorwiseop_matrix(RowVectorXd(internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } diff --git a/testbed/nanogui/ext/eigen/test/visitor.cpp b/testbed/nanogui/ext/eigen/test/visitor.cpp index 39a5d6b5..844170ec 100644 --- a/testbed/nanogui/ext/eigen/test/visitor.cpp +++ b/testbed/nanogui/ext/eigen/test/visitor.cpp @@ -55,6 +55,11 @@ template void matrixVisitor(const MatrixType& p) VERIFY_IS_APPROX(maxc, eigen_maxc); VERIFY_IS_APPROX(minc, m.minCoeff()); VERIFY_IS_APPROX(maxc, m.maxCoeff()); + + eigen_maxc = (m.adjoint()*m).maxCoeff(&eigen_maxrow,&eigen_maxcol); + eigen_maxc = (m.adjoint()*m).eval().maxCoeff(&maxrow,&maxcol); + VERIFY(maxrow == eigen_maxrow); + VERIFY(maxcol == eigen_maxcol); } template void vectorVisitor(const VectorType& w) diff --git a/testbed/nanogui/ext/eigen/test/zerosized.cpp b/testbed/nanogui/ext/eigen/test/zerosized.cpp index da7dd048..477ff007 100644 --- a/testbed/nanogui/ext/eigen/test/zerosized.cpp +++ b/testbed/nanogui/ext/eigen/test/zerosized.cpp @@ -25,6 +25,7 @@ template void zeroReduction(const MatrixType& m) { template void zeroSizedMatrix() { MatrixType t1; + typedef typename MatrixType::Scalar Scalar; if (MatrixType::SizeAtCompileTime == Dynamic || MatrixType::SizeAtCompileTime == 0) { @@ -37,7 +38,7 @@ template void zeroSizedMatrix() if (MatrixType::RowsAtCompileTime == Dynamic && MatrixType::ColsAtCompileTime == Dynamic) { - MatrixType t2(0, 0); + MatrixType t2(0, 0), t3(t1); VERIFY(t2.rows() == 0); VERIFY(t2.cols() == 0); @@ -45,6 +46,23 @@ template void zeroSizedMatrix() VERIFY(t1==t2); } } + + if(MatrixType::MaxColsAtCompileTime!=0 && MatrixType::MaxRowsAtCompileTime!=0) + { + Index rows = MatrixType::RowsAtCompileTime==Dynamic ? internal::random(1,10) : Index(MatrixType::RowsAtCompileTime); + Index cols = MatrixType::ColsAtCompileTime==Dynamic ? internal::random(1,10) : Index(MatrixType::ColsAtCompileTime); + MatrixType m(rows,cols); + zeroReduction(m.template block<0,MatrixType::ColsAtCompileTime>(0,0,0,cols)); + zeroReduction(m.template block(0,0,rows,0)); + zeroReduction(m.template block<0,1>(0,0)); + zeroReduction(m.template block<1,0>(0,0)); + Matrix prod = m.template block(0,0,rows,0) * m.template block<0,MatrixType::ColsAtCompileTime>(0,0,0,cols); + VERIFY(prod.rows()==rows && prod.cols()==cols); + VERIFY(prod.isZero()); + prod = m.template block<1,0>(0,0) * m.template block<0,1>(0,0); + VERIFY(prod.size()==1); + VERIFY(prod.isZero()); + } } template void zeroSizedVector() diff --git a/testbed/nanogui/ext/eigen/unsupported/CMakeLists.txt b/testbed/nanogui/ext/eigen/unsupported/CMakeLists.txt index 4fef40a8..9a566610 100644 --- a/testbed/nanogui/ext/eigen/unsupported/CMakeLists.txt +++ b/testbed/nanogui/ext/eigen/unsupported/CMakeLists.txt @@ -1,7 +1,9 @@ add_subdirectory(Eigen) add_subdirectory(doc EXCLUDE_FROM_ALL) -if(EIGEN_LEAVE_TEST_IN_ALL_TARGET) - add_subdirectory(test) # can't do EXCLUDE_FROM_ALL here, breaks CTest -else() - add_subdirectory(test EXCLUDE_FROM_ALL) +if(BUILD_TESTING) + if(EIGEN_LEAVE_TEST_IN_ALL_TARGET) + add_subdirectory(test) # can't do EXCLUDE_FROM_ALL here, breaks CTest + else() + add_subdirectory(test EXCLUDE_FROM_ALL) + endif() endif() diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/AdolcForward b/testbed/nanogui/ext/eigen/unsupported/Eigen/AdolcForward index 2627decd..15f5f073 100644 --- a/testbed/nanogui/ext/eigen/unsupported/Eigen/AdolcForward +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/AdolcForward @@ -25,7 +25,7 @@ #ifndef NUMBER_DIRECTIONS # define NUMBER_DIRECTIONS 2 #endif -#include +#include // adolc defines some very stupid macros: #if defined(malloc) diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/AlignedVector3 b/testbed/nanogui/ext/eigen/unsupported/Eigen/AlignedVector3 index 7b45e6cc..47a86d4c 100644 --- a/testbed/nanogui/ext/eigen/unsupported/Eigen/AlignedVector3 +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/AlignedVector3 @@ -57,6 +57,11 @@ template class AlignedVector3 inline Index rows() const { return 3; } inline Index cols() const { return 1; } + + Scalar* data() { return m_coeffs.data(); } + const Scalar* data() const { return m_coeffs.data(); } + Index innerStride() const { return 1; } + Index outerStride() const { return 3; } inline const Scalar& coeff(Index row, Index col) const { return m_coeffs.coeff(row, col); } @@ -100,7 +105,7 @@ template class AlignedVector3 }; template - inline explicit AlignedVector3(const MatrixBase& other) + inline AlignedVector3(const MatrixBase& other) { generic_assign_selector::run(*this,other.derived()); } @@ -108,6 +113,12 @@ template class AlignedVector3 inline AlignedVector3& operator=(const AlignedVector3& other) { m_coeffs = other.m_coeffs; return *this; } + template + inline AlignedVector3& operator=(const MatrixBase& other) + { + generic_assign_selector::run(*this,other.derived()); + return *this; + } inline AlignedVector3 operator+(const AlignedVector3& other) const { return AlignedVector3(m_coeffs + other.m_coeffs); } @@ -148,7 +159,7 @@ template class AlignedVector3 m_coeffs /= norm(); } - inline AlignedVector3 normalized() + inline AlignedVector3 normalized() const { return AlignedVector3(m_coeffs / norm()); } @@ -177,12 +188,35 @@ template class AlignedVector3 } template - inline bool isApprox(const MatrixBase& other, RealScalar eps=NumTraits::dummy_precision()) const + inline bool isApprox(const MatrixBase& other, const RealScalar& eps=NumTraits::dummy_precision()) const { return m_coeffs.template head<3>().isApprox(other,eps); } + + CoeffType& coeffs() { return m_coeffs; } + const CoeffType& coeffs() const { return m_coeffs; } }; +namespace internal { + +template +struct eval, Dense> +{ + typedef const AlignedVector3<_Scalar>& type; +}; + +template +struct evaluator > + : evaluator > +{ + typedef AlignedVector3 XprType; + typedef evaluator > Base; + + evaluator(const XprType &m) : Base(m.coeffs()) {} +}; + +} + //@} } diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CMakeLists.txt b/testbed/nanogui/ext/eigen/unsupported/Eigen/CMakeLists.txt index e06f1238..631a0601 100644 --- a/testbed/nanogui/ext/eigen/unsupported/Eigen/CMakeLists.txt +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CMakeLists.txt @@ -1,11 +1,32 @@ -set(Eigen_HEADERS AdolcForward BVH IterativeSolvers MatrixFunctions MoreVectorization AutoDiff AlignedVector3 Polynomials - FFT NonLinearOptimization SparseExtra IterativeSolvers - NumericalDiff Skyline MPRealSupport OpenGLSupport KroneckerProduct Splines LevenbergMarquardt - ) +set(Eigen_HEADERS + AdolcForward + AlignedVector3 + ArpackSupport + AutoDiff + BVH + EulerAngles + FFT + IterativeSolvers + KroneckerProduct + LevenbergMarquardt + MatrixFunctions + MoreVectorization + MPRealSupport + NonLinearOptimization + NumericalDiff + OpenGLSupport + Polynomials + Skyline + SparseExtra + SpecialFunctions + Splines + ) install(FILES ${Eigen_HEADERS} DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen COMPONENT Devel ) -add_subdirectory(src) +install(DIRECTORY src DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen COMPONENT Devel FILES_MATCHING PATTERN "*.h") + +add_subdirectory(CXX11) diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/CMakeLists.txt b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/CMakeLists.txt new file mode 100644 index 00000000..385ed240 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/CMakeLists.txt @@ -0,0 +1,8 @@ +set(Eigen_CXX11_HEADERS Tensor TensorSymmetry ThreadPool) + +install(FILES + ${Eigen_CXX11_HEADERS} + DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen/CXX11 COMPONENT Devel + ) + +install(DIRECTORY src DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen/CXX11 COMPONENT Devel FILES_MATCHING PATTERN "*.h") diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/Tensor b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/Tensor new file mode 100644 index 00000000..39916092 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/Tensor @@ -0,0 +1,159 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// Copyright (C) 2013 Christian Seiler +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +//#ifndef EIGEN_CXX11_TENSOR_MODULE +//#define EIGEN_CXX11_TENSOR_MODULE + +#include "../../../Eigen/Core" + +#if defined(EIGEN_USE_SYCL) +#undef min +#undef max +#undef isnan +#undef isinf +#undef isfinite +#include +#include +#include +#include +#include +#endif + +#include + +#include "../SpecialFunctions" +#include "src/util/CXX11Meta.h" +#include "src/util/MaxSizeVector.h" + +/** \defgroup CXX11_Tensor_Module Tensor Module + * + * This module provides a Tensor class for storing arbitrarily indexed + * objects. + * + * \code + * #include + * \endcode + */ + +#include +#include +#include + +#ifdef _WIN32 +typedef __int16 int16_t; +typedef unsigned __int16 uint16_t; +typedef __int32 int32_t; +typedef unsigned __int32 uint32_t; +typedef __int64 int64_t; +typedef unsigned __int64 uint64_t; +#include +#else +#include +#include +#endif + +#if __cplusplus > 199711 || EIGEN_COMP_MSVC >= 1900 +#include +#endif + +#ifdef _WIN32 +#include +#elif defined(__APPLE__) +#include +#else +#include +#endif + +#if defined(EIGEN_USE_LIBXSMM) +#include "libxsmm.h" +#endif + +#ifdef EIGEN_USE_THREADS +#include "ThreadPool" +#endif + +#ifdef EIGEN_USE_GPU +#include +#include +#if __cplusplus >= 201103L +#include +#include +#endif +#endif + +#include "src/Tensor/TensorMacros.h" +#include "src/Tensor/TensorForwardDeclarations.h" +#include "src/Tensor/TensorMeta.h" +#include "src/Tensor/TensorFunctors.h" +#include "src/Tensor/TensorCostModel.h" +#include "src/Tensor/TensorDeviceDefault.h" +#include "src/Tensor/TensorDeviceThreadPool.h" +#include "src/Tensor/TensorDeviceCuda.h" +#include "src/Tensor/TensorDeviceSycl.h" +#include "src/Tensor/TensorIndexList.h" +#include "src/Tensor/TensorDimensionList.h" +#include "src/Tensor/TensorDimensions.h" +#include "src/Tensor/TensorInitializer.h" +#include "src/Tensor/TensorTraits.h" +#include "src/Tensor/TensorRandom.h" +#include "src/Tensor/TensorUInt128.h" +#include "src/Tensor/TensorIntDiv.h" +#include "src/Tensor/TensorGlobalFunctions.h" + +#include "src/Tensor/TensorBase.h" + +#include "src/Tensor/TensorEvaluator.h" +#include "src/Tensor/TensorExpr.h" +#include "src/Tensor/TensorReduction.h" +#include "src/Tensor/TensorReductionCuda.h" +#include "src/Tensor/TensorArgMax.h" +#include "src/Tensor/TensorConcatenation.h" +#include "src/Tensor/TensorContractionMapper.h" +#include "src/Tensor/TensorContractionBlocking.h" +#include "src/Tensor/TensorContraction.h" +#include "src/Tensor/TensorContractionThreadPool.h" +#include "src/Tensor/TensorContractionCuda.h" +#include "src/Tensor/TensorConversion.h" +#include "src/Tensor/TensorConvolution.h" +#include "src/Tensor/TensorFFT.h" +#include "src/Tensor/TensorPatch.h" +#include "src/Tensor/TensorImagePatch.h" +#include "src/Tensor/TensorVolumePatch.h" +#include "src/Tensor/TensorBroadcasting.h" +#include "src/Tensor/TensorChipping.h" +#include "src/Tensor/TensorInflation.h" +#include "src/Tensor/TensorLayoutSwap.h" +#include "src/Tensor/TensorMorphing.h" +#include "src/Tensor/TensorPadding.h" +#include "src/Tensor/TensorReverse.h" +#include "src/Tensor/TensorShuffling.h" +#include "src/Tensor/TensorStriding.h" +#include "src/Tensor/TensorCustomOp.h" +#include "src/Tensor/TensorEvalTo.h" +#include "src/Tensor/TensorForcedEval.h" +#include "src/Tensor/TensorGenerator.h" +#include "src/Tensor/TensorAssign.h" +#include "src/Tensor/TensorScan.h" + +#include "src/Tensor/TensorSycl.h" +#include "src/Tensor/TensorExecutor.h" +#include "src/Tensor/TensorDevice.h" + +#include "src/Tensor/TensorStorage.h" +#include "src/Tensor/Tensor.h" +#include "src/Tensor/TensorFixedSize.h" +#include "src/Tensor/TensorMap.h" +#include "src/Tensor/TensorRef.h" + +#include "src/Tensor/TensorIO.h" + +#include + +//#endif // EIGEN_CXX11_TENSOR_MODULE diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/TensorSymmetry b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/TensorSymmetry new file mode 100644 index 00000000..fb1b0c0f --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/TensorSymmetry @@ -0,0 +1,42 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2013 Christian Seiler +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSORSYMMETRY_MODULE +#define EIGEN_CXX11_TENSORSYMMETRY_MODULE + +#include + +#include + +#include "src/util/CXX11Meta.h" + +/** \defgroup CXX11_TensorSymmetry_Module Tensor Symmetry Module + * + * This module provides a classes that allow for the definition of + * symmetries w.r.t. tensor indices. + * + * Including this module will implicitly include the Tensor module. + * + * \code + * #include + * \endcode + */ + +#include "src/TensorSymmetry/util/TemplateGroupTheory.h" +#include "src/TensorSymmetry/Symmetry.h" +#include "src/TensorSymmetry/StaticSymmetry.h" +#include "src/TensorSymmetry/DynamicSymmetry.h" + +#include + +#endif // EIGEN_CXX11_TENSORSYMMETRY_MODULE + +/* + * kate: space-indent on; indent-width 2; mixedindent off; indent-mode cstyle; + */ diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/ThreadPool b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/ThreadPool new file mode 100644 index 00000000..c3461419 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/ThreadPool @@ -0,0 +1,78 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2016 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_THREADPOOL_MODULE +#define EIGEN_CXX11_THREADPOOL_MODULE + +#include "../../../Eigen/Core" + +#include + +/** \defgroup CXX11_ThreadPool_Module C++11 ThreadPool Module + * + * This module provides 2 threadpool implementations + * - a simple reference implementation + * - a faster non blocking implementation + * + * This module requires C++11. + * + * \code + * #include + * \endcode + */ + + +// The code depends on CXX11, so only include the module if the +// compiler supports it. +#if __cplusplus > 199711L || EIGEN_COMP_MSVC >= 1900 +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "src/util/CXX11Meta.h" +#include "src/util/MaxSizeVector.h" + +#include "src/ThreadPool/ThreadLocal.h" +#include "src/ThreadPool/ThreadYield.h" +#include "src/ThreadPool/ThreadCancel.h" +#include "src/ThreadPool/EventCount.h" +#include "src/ThreadPool/RunQueue.h" +#include "src/ThreadPool/ThreadPoolInterface.h" +#include "src/ThreadPool/ThreadEnvironment.h" +#include "src/ThreadPool/SimpleThreadPool.h" +#include "src/ThreadPool/NonBlockingThreadPool.h" + + +// Use the more efficient NonBlockingThreadPool by default. +namespace Eigen { +#ifndef EIGEN_USE_SIMPLE_THREAD_POOL +template using ThreadPoolTempl = NonBlockingThreadPoolTempl; +typedef NonBlockingThreadPool ThreadPool; +#else +template using ThreadPoolTempl = SimpleThreadPoolTempl; +typedef SimpleThreadPool ThreadPool; +#endif +} // namespace Eigen + +#endif + +#include + +#endif // EIGEN_CXX11_THREADPOOL_MODULE + diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/README.md b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/README.md new file mode 100644 index 00000000..38cdb9c6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/README.md @@ -0,0 +1,1755 @@ +# Eigen Tensors + +Tensors are multidimensional arrays of elements. Elements are typically scalars, +but more complex types such as strings are also supported. + +[TOC] + +## Tensor Classes + +You can manipulate a tensor with one of the following classes. They all are in +the namespace ```::Eigen.``` + + +### Class Tensor + +This is the class to use to create a tensor and allocate memory for it. The +class is templatized with the tensor datatype, such as float or int, and the +tensor rank. The rank is the number of dimensions, for example rank 2 is a +matrix. + +Tensors of this class are resizable. For example, if you assign a tensor of a +different size to a Tensor, that tensor is resized to match its new value. + +#### Constructor Tensor(size0, size1, ...) + +Constructor for a Tensor. The constructor must be passed ```rank``` integers +indicating the sizes of the instance along each of the the ```rank``` +dimensions. + + // Create a tensor of rank 3 of sizes 2, 3, 4. This tensor owns + // memory to hold 24 floating point values (24 = 2 x 3 x 4). + Tensor t_3d(2, 3, 4); + + // Resize t_3d by assigning a tensor of different sizes, but same rank. + t_3d = Tensor(3, 4, 3); + +#### Constructor Tensor(size_array) + +Constructor where the sizes for the constructor are specified as an array of +values instead of an explicitly list of parameters. The array type to use is +```Eigen::array```. The array can be constructed automatically +from an initializer list. + + // Create a tensor of strings of rank 2 with sizes 5, 7. + Tensor t_2d({5, 7}); + + +### Class TensorFixedSize> + +Class to use for tensors of fixed size, where the size is known at compile +time. Fixed sized tensors can provide very fast computations because all their +dimensions are known by the compiler. FixedSize tensors are not resizable. + +If the total number of elements in a fixed size tensor is small enough the +tensor data is held onto the stack and does not cause heap allocation and free. + + // Create a 4 x 3 tensor of floats. + TensorFixedSize> t_4x3; + +### Class TensorMap> + +This is the class to use to create a tensor on top of memory allocated and +owned by another part of your code. It allows to view any piece of allocated +memory as a Tensor. Instances of this class do not own the memory where the +data are stored. + +A TensorMap is not resizable because it does not own the memory where its data +are stored. + +#### Constructor TensorMap>(data, size0, size1, ...) + +Constructor for a Tensor. The constructor must be passed a pointer to the +storage for the data, and "rank" size attributes. The storage has to be +large enough to hold all the data. + + // Map a tensor of ints on top of stack-allocated storage. + int storage[128]; // 2 x 4 x 2 x 8 = 128 + TensorMap> t_4d(storage, 2, 4, 2, 8); + + // The same storage can be viewed as a different tensor. + // You can also pass the sizes as an array. + TensorMap> t_2d(storage, 16, 8); + + // You can also map fixed-size tensors. Here we get a 1d view of + // the 2d fixed-size tensor. + Tensor> t_4x3; + TensorMap> t_12(t_4x3, 12); + + +#### Class TensorRef + +See Assigning to a TensorRef below. + +## Accessing Tensor Elements + +#### tensor(index0, index1...) + +Return the element at position ```(index0, index1...)``` in tensor +```tensor```. You must pass as many parameters as the rank of ```tensor```. +The expression can be used as an l-value to set the value of the element at the +specified position. The value returned is of the datatype of the tensor. + + // Set the value of the element at position (0, 1, 0); + Tensor t_3d(2, 3, 4); + t_3d(0, 1, 0) = 12.0f; + + // Initialize all elements to random values. + for (int i = 0; i < 2; ++i) { + for (int j = 0; j < 3; ++j) { + for (int k = 0; k < 4; ++k) { + t_3d(i, j, k) = ...some random value...; + } + } + } + + // Print elements of a tensor. + for (int i = 0; i < 2; ++i) { + LOG(INFO) << t_3d(i, 0, 0); + } + + +## TensorLayout + +The tensor library supports 2 layouts: ```ColMajor``` (the default) and +```RowMajor```. Only the default column major layout is currently fully +supported, and it is therefore not recommended to attempt to use the row major +layout at the moment. + +The layout of a tensor is optionally specified as part of its type. If not +specified explicitly column major is assumed. + + Tensor col_major; // equivalent to Tensor + TensorMap > row_major(data, ...); + +All the arguments to an expression must use the same layout. Attempting to mix +different layouts will result in a compilation error. + +It is possible to change the layout of a tensor or an expression using the +```swap_layout()``` method. Note that this will also reverse the order of the +dimensions. + + Tensor col_major(2, 4); + Tensor row_major(2, 4); + + Tensor col_major_result = col_major; // ok, layouts match + Tensor col_major_result = row_major; // will not compile + + // Simple layout swap + col_major_result = row_major.swap_layout(); + eigen_assert(col_major_result.dimension(0) == 4); + eigen_assert(col_major_result.dimension(1) == 2); + + // Swap the layout and preserve the order of the dimensions + array shuffle(1, 0); + col_major_result = row_major.swap_layout().shuffle(shuffle); + eigen_assert(col_major_result.dimension(0) == 2); + eigen_assert(col_major_result.dimension(1) == 4); + + +## Tensor Operations + +The Eigen Tensor library provides a vast library of operations on Tensors: +numerical operations such as addition and multiplication, geometry operations +such as slicing and shuffling, etc. These operations are available as methods +of the Tensor classes, and in some cases as operator overloads. For example +the following code computes the elementwise addition of two tensors: + + Tensor t1(2, 3, 4); + ...set some values in t1... + Tensor t2(2, 3, 4); + ...set some values in t2... + // Set t3 to the element wise sum of t1 and t2 + Tensor t3 = t1 + t2; + +While the code above looks easy enough, it is important to understand that the +expression ```t1 + t2``` is not actually adding the values of the tensors. The +expression instead constructs a "tensor operator" object of the class +TensorCwiseBinaryOp, which has references to the tensors +```t1``` and ```t2```. This is a small C++ object that knows how to add +```t1``` and ```t2```. It is only when the value of the expression is assigned +to the tensor ```t3``` that the addition is actually performed. Technically, +this happens through the overloading of ```operator=()``` in the Tensor class. + +This mechanism for computing tensor expressions allows for lazy evaluation and +optimizations which are what make the tensor library very fast. + +Of course, the tensor operators do nest, and the expression ```t1 + t2 * +0.3f``` is actually represented with the (approximate) tree of operators: + + TensorCwiseBinaryOp(t1, TensorCwiseUnaryOp(t2, 0.3f)) + + +### Tensor Operations and C++ "auto" + +Because Tensor operations create tensor operators, the C++ ```auto``` keyword +does not have its intuitive meaning. Consider these 2 lines of code: + + Tensor t3 = t1 + t2; + auto t4 = t1 + t2; + +In the first line we allocate the tensor ```t3``` and it will contain the +result of the addition of ```t1``` and ```t2```. In the second line, ```t4``` +is actually the tree of tensor operators that will compute the addition of +```t1``` and ```t2```. In fact, ```t4``` is *not* a tensor and you cannot get +the values of its elements: + + Tensor t3 = t1 + t2; + cout << t3(0, 0, 0); // OK prints the value of t1(0, 0, 0) + t2(0, 0, 0) + + auto t4 = t1 + t2; + cout << t4(0, 0, 0); // Compilation error! + +When you use ```auto``` you do not get a Tensor as a result but instead a +non-evaluated expression. So only use ```auto``` to delay evaluation. + +Unfortunately, there is no single underlying concrete type for holding +non-evaluated expressions, hence you have to use auto in the case when you do +want to hold non-evaluated expressions. + +When you need the results of set of tensor computations you have to assign the +result to a Tensor that will be capable of holding onto them. This can be +either a normal Tensor, a fixed size Tensor, or a TensorMap on an existing +piece of memory. All the following will work: + + auto t4 = t1 + t2; + + Tensor result = t4; // Could also be: result(t4); + cout << result(0, 0, 0); + + TensorMap result(, , ...) = t4; + cout << result(0, 0, 0); + + TensorFixedSize> result = t4; + cout << result(0, 0, 0); + +Until you need the results, you can keep the operation around, and even reuse +it for additional operations. As long as you keep the expression as an +operation, no computation is performed. + + // One way to compute exp((t1 + t2) * 0.2f); + auto t3 = t1 + t2; + auto t4 = t3 * 0.2f; + auto t5 = t4.exp(); + Tensor result = t5; + + // Another way, exactly as efficient as the previous one: + Tensor result = ((t1 + t2) * 0.2f).exp(); + +### Controlling When Expression are Evaluated + +There are several ways to control when expressions are evaluated: + +* Assignment to a Tensor, TensorFixedSize, or TensorMap. +* Use of the eval() method. +* Assignment to a TensorRef. + +#### Assigning to a Tensor, TensorFixedSize, or TensorMap. + +The most common way to evaluate an expression is to assign it to a Tensor. In +the example below, the ```auto``` declarations make the intermediate values +"Operations", not Tensors, and do not cause the expressions to be evaluated. +The assignment to the Tensor ```result``` causes the evaluation of all the +operations. + + auto t3 = t1 + t2; // t3 is an Operation. + auto t4 = t3 * 0.2f; // t4 is an Operation. + auto t5 = t4.exp(); // t5 is an Operation. + Tensor result = t5; // The operations are evaluated. + +If you know the ranks and sizes of the Operation value you can assign the +Operation to a TensorFixedSize instead of a Tensor, which is a bit more +efficient. + + // We know that the result is a 4x4x2 tensor! + TensorFixedSize result = t5; + +Simiarly, assigning an expression to a TensorMap causes its evaluation. Like +tensors of type TensorFixedSize, TensorMaps cannot be resized so they have to +have the rank and sizes of the expression that are assigned to them. + +#### Calling eval(). + +When you compute large composite expressions, you sometimes want to tell Eigen +that an intermediate value in the expression tree is worth evaluating ahead of +time. This is done by inserting a call to the ```eval()``` method of the +expression Operation. + + // The previous example could have been written: + Tensor result = ((t1 + t2) * 0.2f).exp(); + + // If you want to compute (t1 + t2) once ahead of time you can write: + Tensor result = ((t1 + t2).eval() * 0.2f).exp(); + +Semantically, calling ```eval()``` is equivalent to materializing the value of +the expression in a temporary Tensor of the right size. The code above in +effect does: + + // .eval() knows the size! + TensorFixedSize tmp = t1 + t2; + Tensor result = (tmp * 0.2f).exp(); + +Note that the return value of ```eval()``` is itself an Operation, so the +following code does not do what you may think: + + // Here t3 is an evaluation Operation. t3 has not been evaluated yet. + auto t3 = (t1 + t2).eval(); + + // You can use t3 in another expression. Still no evaluation. + auto t4 = (t3 * 0.2f).exp(); + + // The value is evaluated when you assign the Operation to a Tensor, using + // an intermediate tensor to represent t3.x + Tensor result = t4; + +While in the examples above calling ```eval()``` does not make a difference in +performance, in other cases it can make a huge difference. In the expression +below the ```broadcast()``` expression causes the ```X.maximum()``` expression +to be evaluated many times: + + Tensor<...> X ...; + Tensor<...> Y = ((X - X.maximum(depth_dim).reshape(dims2d).broadcast(bcast)) + * beta).exp(); + +Inserting a call to ```eval()``` between the ```maximum()``` and +```reshape()``` calls guarantees that maximum() is only computed once and +greatly speeds-up execution: + + Tensor<...> Y = + ((X - X.maximum(depth_dim).eval().reshape(dims2d).broadcast(bcast)) + * beta).exp(); + +In the other example below, the tensor ```Y``` is both used in the expression +and its assignment. This is an aliasing problem and if the evaluation is not +done in the right order Y will be updated incrementally during the evaluation +resulting in bogus results: + + Tensor<...> Y ...; + Y = Y / (Y.sum(depth_dim).reshape(dims2d).broadcast(bcast)); + +Inserting a call to ```eval()``` between the ```sum()``` and ```reshape()``` +expressions ensures that the sum is computed before any updates to ```Y``` are +done. + + Y = Y / (Y.sum(depth_dim).eval().reshape(dims2d).broadcast(bcast)); + +Note that an eval around the full right hand side expression is not needed +because the generated has to compute the i-th value of the right hand side +before assigning it to the left hand side. + +However, if you were assigning the expression value to a shuffle of ```Y``` +then you would need to force an eval for correctness by adding an ```eval()``` +call for the right hand side: + + Y.shuffle(...) = + (Y / (Y.sum(depth_dim).eval().reshape(dims2d).broadcast(bcast))).eval(); + + +#### Assigning to a TensorRef. + +If you need to access only a few elements from the value of an expression you +can avoid materializing the value in a full tensor by using a TensorRef. + +A TensorRef is a small wrapper class for any Eigen Operation. It provides +overloads for the ```()``` operator that let you access individual values in +the expression. TensorRef is convenient, because the Operation themselves do +not provide a way to access individual elements. + + // Create a TensorRef for the expression. The expression is not + // evaluated yet. + TensorRef > ref = ((t1 + t2) * 0.2f).exp(); + + // Use "ref" to access individual elements. The expression is evaluated + // on the fly. + float at_0 = ref(0, 0, 0); + cout << ref(0, 1, 0); + +Only use TensorRef when you need a subset of the values of the expression. +TensorRef only computes the values you access. However note that if you are +going to access all the values it will be much faster to materialize the +results in a Tensor first. + +In some cases, if the full Tensor result would be very large, you may save +memory by accessing it as a TensorRef. But not always. So don't count on it. + + +### Controlling How Expressions Are Evaluated + +The tensor library provides several implementations of the various operations +such as contractions and convolutions. The implementations are optimized for +different environments: single threaded on CPU, multi threaded on CPU, or on a +GPU using cuda. Additional implementations may be added later. + +You can choose which implementation to use with the ```device()``` call. If +you do not choose an implementation explicitly the default implementation that +uses a single thread on the CPU is used. + +The default implementation has been optimized for recent Intel CPUs, taking +advantage of SSE, AVX, and FMA instructions. Work is ongoing to tune the +library on ARM CPUs. Note that you need to pass compiler-dependent flags +to enable the use of SSE, AVX, and other instructions. + +For example, the following code adds two tensors using the default +single-threaded CPU implementation: + + Tensor a(30, 40); + Tensor b(30, 40); + Tensor c = a + b; + +To choose a different implementation you have to insert a ```device()``` call +before the assignment of the result. For technical C++ reasons this requires +that the Tensor for the result be declared on its own. This means that you +have to know the size of the result. + + Eigen::Tensor c(30, 40); + c.device(...) = a + b; + +The call to ```device()``` must be the last call on the left of the operator=. + +You must pass to the ```device()``` call an Eigen device object. There are +presently three devices you can use: DefaultDevice, ThreadPoolDevice and +GpuDevice. + + +#### Evaluating With the DefaultDevice + +This is exactly the same as not inserting a ```device()``` call. + + DefaultDevice my_device; + c.device(my_device) = a + b; + +#### Evaluating with a Thread Pool + + // Create the Eigen ThreadPoolDevice. + Eigen::ThreadPoolDevice my_device(4 /* number of threads to use */); + + // Now just use the device when evaluating expressions. + Eigen::Tensor c(30, 50); + c.device(my_device) = a.contract(b, dot_product_dims); + + +#### Evaluating On GPU + +This is presently a bit more complicated than just using a thread pool device. +You need to create a GPU device but you also need to explicitly allocate the +memory for tensors with cuda. + + +## API Reference + +### Datatypes + +In the documentation of the tensor methods and Operation we mention datatypes +that are tensor-type specific: + +#### ::Dimensions + +Acts like an array of ints. Has an ```int size``` attribute, and can be +indexed like an array to access individual values. Used to represent the +dimensions of a tensor. See ```dimensions()```. + +#### ::Index + +Acts like an ```int```. Used for indexing tensors along their dimensions. See +```operator()```, ```dimension()```, and ```size()```. + +#### ::Scalar + +Represents the datatype of individual tensor elements. For example, for a +```Tensor```, ```Scalar``` is the type ```float```. See +```setConstant()```. + +#### + +We use this pseudo type to indicate that a tensor Operation is returned by a +method. We indicate in the text the type and dimensions of the tensor that the +Operation returns after evaluation. + +The Operation will have to be evaluated, for example by assigning it to a +tensor, before you can access the values of the resulting tensor. You can also +access the values through a TensorRef. + + +## Built-in Tensor Methods + +These are usual C++ methods that act on tensors immediately. They are not +Operations which provide delayed evaluation of their results. Unless specified +otherwise, all the methods listed below are available on all tensor classes: +Tensor, TensorFixedSize, and TensorMap. + +## Metadata + +### int NumDimensions + +Constant value indicating the number of dimensions of a Tensor. This is also +known as the tensor "rank". + + Eigen::Tensor a(3, 4); + cout << "Dims " << a.NumDimensions; + => Dims 2 + +### Dimensions dimensions() + +Returns an array-like object representing the dimensions of the tensor. +The actual type of the dimensions() result is ::Dimensions. + + Eigen::Tensor a(3, 4); + const Eigen::Tensor::Dimensions& d = a.dimensions(); + cout << "Dim size: " << d.size << ", dim 0: " << d[0] + << ", dim 1: " << d[1]; + => Dim size: 2, dim 0: 3, dim 1: 4 + +If you use a C++11 compiler, you can use ```auto``` to simplify the code: + + const auto& d = a.dimensions(); + cout << "Dim size: " << d.size << ", dim 0: " << d[0] + << ", dim 1: " << d[1]; + => Dim size: 2, dim 0: 3, dim 1: 4 + +### Index dimension(Index n) + +Returns the n-th dimension of the tensor. The actual type of the +```dimension()``` result is ```::Index```, but you can +always use it like an int. + + Eigen::Tensor a(3, 4); + int dim1 = a.dimension(1); + cout << "Dim 1: " << dim1; + => Dim 1: 4 + +### Index size() + +Returns the total number of elements in the tensor. This is the product of all +the tensor dimensions. The actual type of the ```size()``` result is +```::Index```, but you can always use it like an int. + + Eigen::Tensor a(3, 4); + cout << "Size: " << a.size(); + => Size: 12 + + +### Getting Dimensions From An Operation + +A few operations provide ```dimensions()``` directly, +e.g. ```TensorReslicingOp```. Most operations defer calculating dimensions +until the operation is being evaluated. If you need access to the dimensions +of a deferred operation, you can wrap it in a TensorRef (see Assigning to a +TensorRef above), which provides ```dimensions()``` and ```dimension()``` as +above. + +TensorRef can also wrap the plain Tensor types, so this is a useful idiom in +templated contexts where the underlying object could be either a raw Tensor +or some deferred operation (e.g. a slice of a Tensor). In this case, the +template code can wrap the object in a TensorRef and reason about its +dimensionality while remaining agnostic to the underlying type. + + +## Constructors + +### Tensor + +Creates a tensor of the specified size. The number of arguments must be equal +to the rank of the tensor. The content of the tensor is not initialized. + + Eigen::Tensor a(3, 4); + cout << "NumRows: " << a.dimension(0) << " NumCols: " << a.dimension(1) << endl; + => NumRows: 3 NumCols: 4 + +### TensorFixedSize + +Creates a tensor of the specified size. The number of arguments in the Size<> +template parameter determines the rank of the tensor. The content of the tensor +is not initialized. + + Eigen::TensorFixedSize> a; + cout << "Rank: " << a.rank() << endl; + => Rank: 2 + cout << "NumRows: " << a.dimension(0) << " NumCols: " << a.dimension(1) << endl; + => NumRows: 3 NumCols: 4 + +### TensorMap + +Creates a tensor mapping an existing array of data. The data must not be freed +until the TensorMap is discarded, and the size of the data must be large enough +to accomodate of the coefficients of the tensor. + + float data[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11}; + Eigen::TensorMap a(data, 3, 4); + cout << "NumRows: " << a.dimension(0) << " NumCols: " << a.dimension(1) << endl; + => NumRows: 3 NumCols: 4 + cout << "a(1, 2): " << a(1, 2) << endl; + => a(1, 2): 9 + + +## Contents Initialization + +When a new Tensor or a new TensorFixedSize are created, memory is allocated to +hold all the tensor elements, but the memory is not initialized. Similarly, +when a new TensorMap is created on top of non-initialized memory the memory its +contents are not initialized. + +You can use one of the methods below to initialize the tensor memory. These +have an immediate effect on the tensor and return the tensor itself as a +result. These are not tensor Operations which delay evaluation. + +### setConstant(const Scalar& val) + +Sets all elements of the tensor to the constant value ```val```. ```Scalar``` +is the type of data stored in the tensor. You can pass any value that is +convertible to that type. + +Returns the tensor itself in case you want to chain another call. + + a.setConstant(12.3f); + cout << "Constant: " << endl << a << endl << endl; + => + Constant: + 12.3 12.3 12.3 12.3 + 12.3 12.3 12.3 12.3 + 12.3 12.3 12.3 12.3 + +Note that ```setConstant()``` can be used on any tensor where the element type +has a copy constructor and an ```operator=()```: + + Eigen::Tensor a(2, 3); + a.setConstant("yolo"); + cout << "String tensor: " << endl << a << endl << endl; + => + String tensor: + yolo yolo yolo + yolo yolo yolo + + +### setZero() + +Fills the tensor with zeros. Equivalent to ```setConstant(Scalar(0))```. +Returns the tensor itself in case you want to chain another call. + + a.setZero(); + cout << "Zeros: " << endl << a << endl << endl; + => + Zeros: + 0 0 0 0 + 0 0 0 0 + 0 0 0 0 + + +### setValues({..initializer_list}) + +Fills the tensor with explicit values specified in a std::initializer_list. +The type of the initializer list depends on the type and rank of the tensor. + +If the tensor has rank N, the initializer list must be nested N times. The +most deeply nested lists must contains P scalars of the Tensor type where P is +the size of the last dimension of the Tensor. + +For example, for a ```TensorFixedSize``` the initializer list must +contains 2 lists of 3 floats each. + +```setValues()``` returns the tensor itself in case you want to chain another +call. + + Eigen::Tensor a(2, 3); + a.setValues({{0.0f, 1.0f, 2.0f}, {3.0f, 4.0f, 5.0f}}); + cout << "a" << endl << a << endl << endl; + => + a + 0 1 2 + 3 4 5 + +If a list is too short, the corresponding elements of the tensor will not be +changed. This is valid at each level of nesting. For example the following +code only sets the values of the first row of the tensor. + + Eigen::Tensor a(2, 3); + a.setConstant(1000); + a.setValues({{10, 20, 30}}); + cout << "a" << endl << a << endl << endl; + => + a + 10 20 30 + 1000 1000 1000 + +### setRandom() + +Fills the tensor with random values. Returns the tensor itself in case you +want to chain another call. + + a.setRandom(); + cout << "Random: " << endl << a << endl << endl; + => + Random: + 0.680375 0.59688 -0.329554 0.10794 + -0.211234 0.823295 0.536459 -0.0452059 + 0.566198 -0.604897 -0.444451 0.257742 + +You can customize ```setRandom()``` by providing your own random number +generator as a template argument: + + a.setRandom(); + +Here, ```MyRandomGenerator``` must be a struct with the following member +functions, where Scalar and Index are the same as ```::Scalar``` +and ```::Index```. + +See ```struct UniformRandomGenerator``` in TensorFunctors.h for an example. + + // Custom number generator for use with setRandom(). + struct MyRandomGenerator { + // Default and copy constructors. Both are needed + MyRandomGenerator() { } + MyRandomGenerator(const MyRandomGenerator& ) { } + + // Return a random value to be used. "element_location" is the + // location of the entry to set in the tensor, it can typically + // be ignored. + Scalar operator()(Eigen::DenseIndex element_location, + Eigen::DenseIndex /*unused*/ = 0) const { + return ; + } + + // Same as above but generates several numbers at a time. + typename internal::packet_traits::type packetOp( + Eigen::DenseIndex packet_location, Eigen::DenseIndex /*unused*/ = 0) const { + return ; + } + }; + +You can also use one of the 2 random number generators that are part of the +tensor library: +* UniformRandomGenerator +* NormalRandomGenerator + + +## Data Access + +The Tensor, TensorFixedSize, and TensorRef classes provide the following +accessors to access the tensor coefficients: + + const Scalar& operator()(const array& indices) + const Scalar& operator()(Index firstIndex, IndexTypes... otherIndices) + Scalar& operator()(const array& indices) + Scalar& operator()(Index firstIndex, IndexTypes... otherIndices) + +The number of indices must be equal to the rank of the tensor. Moreover, these +accessors are not available on tensor expressions. In order to access the +values of a tensor expression, the expression must either be evaluated or +wrapped in a TensorRef. + + +### Scalar* data() and const Scalar* data() const + +Returns a pointer to the storage for the tensor. The pointer is const if the +tensor was const. This allows direct access to the data. The layout of the +data depends on the tensor layout: RowMajor or ColMajor. + +This access is usually only needed for special cases, for example when mixing +Eigen Tensor code with other libraries. + +Scalar is the type of data stored in the tensor. + + Eigen::Tensor a(3, 4); + float* a_data = a.data(); + a_data[0] = 123.45f; + cout << "a(0, 0): " << a(0, 0); + => a(0, 0): 123.45 + + +## Tensor Operations + +All the methods documented below return non evaluated tensor ```Operations```. +These can be chained: you can apply another Tensor Operation to the value +returned by the method. + +The chain of Operation is evaluated lazily, typically when it is assigned to a +tensor. See "Controlling when Expression are Evaluated" for more details about +their evaluation. + +### constant(const Scalar& val) + +Returns a tensor of the same type and dimensions as the original tensor but +where all elements have the value ```val```. + +This is useful, for example, when you want to add or subtract a constant from a +tensor, or multiply every element of a tensor by a scalar. + + Eigen::Tensor a(2, 3); + a.setConstant(1.0f); + Eigen::Tensor b = a + a.constant(2.0f); + Eigen::Tensor c = b * b.constant(0.2f); + cout << "a" << endl << a << endl << endl; + cout << "b" << endl << b << endl << endl; + cout << "c" << endl << c << endl << endl; + => + a + 1 1 1 + 1 1 1 + + b + 3 3 3 + 3 3 3 + + c + 0.6 0.6 0.6 + 0.6 0.6 0.6 + +### random() + +Returns a tensor of the same type and dimensions as the current tensor +but where all elements have random values. + +This is for example useful to add random values to an existing tensor. +The generation of random values can be customized in the same manner +as for ```setRandom()```. + + Eigen::Tensor a(2, 3); + a.setConstant(1.0f); + Eigen::Tensor b = a + a.random(); + cout << "a" << endl << a << endl << endl; + cout << "b" << endl << b << endl << endl; + => + a + 1 1 1 + 1 1 1 + + b + 1.68038 1.5662 1.82329 + 0.788766 1.59688 0.395103 + + +## Unary Element Wise Operations + +All these operations take a single input tensor as argument and return a tensor +of the same type and dimensions as the tensor to which they are applied. The +requested operations are applied to each element independently. + +### operator-() + +Returns a tensor of the same type and dimensions as the original tensor +containing the opposite values of the original tensor. + + Eigen::Tensor a(2, 3); + a.setConstant(1.0f); + Eigen::Tensor b = -a; + cout << "a" << endl << a << endl << endl; + cout << "b" << endl << b << endl << endl; + => + a + 1 1 1 + 1 1 1 + + b + -1 -1 -1 + -1 -1 -1 + +### sqrt() + +Returns a tensor of the same type and dimensions as the original tensor +containing the square roots of the original tensor. + +### rsqrt() + +Returns a tensor of the same type and dimensions as the original tensor +containing the inverse square roots of the original tensor. + +### square() + +Returns a tensor of the same type and dimensions as the original tensor +containing the squares of the original tensor values. + +### inverse() + +Returns a tensor of the same type and dimensions as the original tensor +containing the inverse of the original tensor values. + +### exp() + +Returns a tensor of the same type and dimensions as the original tensor +containing the exponential of the original tensor. + +### log() + +Returns a tensor of the same type and dimensions as the original tensor +containing the natural logarithms of the original tensor. + +### abs() + +Returns a tensor of the same type and dimensions as the original tensor +containing the absolute values of the original tensor. + +### pow(Scalar exponent) + +Returns a tensor of the same type and dimensions as the original tensor +containing the coefficients of the original tensor to the power of the +exponent. + +The type of the exponent, Scalar, is always the same as the type of the +tensor coefficients. For example, only integer exponents can be used in +conjuntion with tensors of integer values. + +You can use cast() to lift this restriction. For example this computes +cubic roots of an int Tensor: + + Eigen::Tensor a(2, 3); + a.setValues({{0, 1, 8}, {27, 64, 125}}); + Eigen::Tensor b = a.cast().pow(1.0 / 3.0); + cout << "a" << endl << a << endl << endl; + cout << "b" << endl << b << endl << endl; + => + a + 0 1 8 + 27 64 125 + + b + 0 1 2 + 3 4 5 + +### operator * (Scalar scale) + +Multiplies all the coefficients of the input tensor by the provided scale. + +### cwiseMax(Scalar threshold) +TODO + +### cwiseMin(Scalar threshold) +TODO + +### unaryExpr(const CustomUnaryOp& func) +TODO + + +## Binary Element Wise Operations + +These operations take two input tensors as arguments. The 2 input tensors should +be of the same type and dimensions. The result is a tensor of the same +dimensions as the tensors to which they are applied, and unless otherwise +specified it is also of the same type. The requested operations are applied to +each pair of elements independently. + +### operator+(const OtherDerived& other) + +Returns a tensor of the same type and dimensions as the input tensors +containing the coefficient wise sums of the inputs. + +### operator-(const OtherDerived& other) + +Returns a tensor of the same type and dimensions as the input tensors +containing the coefficient wise differences of the inputs. + +### operator*(const OtherDerived& other) + +Returns a tensor of the same type and dimensions as the input tensors +containing the coefficient wise products of the inputs. + +### operator/(const OtherDerived& other) + +Returns a tensor of the same type and dimensions as the input tensors +containing the coefficient wise quotients of the inputs. + +This operator is not supported for integer types. + +### cwiseMax(const OtherDerived& other) + +Returns a tensor of the same type and dimensions as the input tensors +containing the coefficient wise maximums of the inputs. + +### cwiseMin(const OtherDerived& other) + +Returns a tensor of the same type and dimensions as the input tensors +containing the coefficient wise mimimums of the inputs. + +### Logical operators + +The following logical operators are supported as well: + +* operator&&(const OtherDerived& other) +* operator||(const OtherDerived& other) +* operator<(const OtherDerived& other) +* operator<=(const OtherDerived& other) +* operator>(const OtherDerived& other) +* operator>=(const OtherDerived& other) +* operator==(const OtherDerived& other) +* operator!=(const OtherDerived& other) + +They all return a tensor of boolean values. + + +## Selection (select(const ThenDerived& thenTensor, const ElseDerived& elseTensor) + +Selection is a coefficient-wise ternary operator that is the tensor equivalent +to the if-then-else operation. + + Tensor if = ...; + Tensor then = ...; + Tensor else = ...; + Tensor result = if.select(then, else); + +The 3 arguments must be of the same dimensions, which will also be the dimension +of the result. The 'if' tensor must be of type boolean, the 'then' and the +'else' tensor must be of the same type, which will also be the type of the +result. + +Each coefficient in the result is equal to the corresponding coefficient in the +'then' tensor if the corresponding value in the 'if' tensor is true. If not, the +resulting coefficient will come from the 'else' tensor. + + +## Contraction + +Tensor *contractions* are a generalization of the matrix product to the +multidimensional case. + + // Create 2 matrices using tensors of rank 2 + Eigen::Tensor a(2, 3); + a.setValues({{1, 2, 3}, {6, 5, 4}}); + Eigen::Tensor b(3, 2); + a.setValues({{1, 2}, {4, 5}, {5, 6}}); + + // Compute the traditional matrix product + array, 1> product_dims = { IndexPair(1, 0) }; + Eigen::Tensor AB = a.contract(b, product_dims); + + // Compute the product of the transpose of the matrices + array, 1> transpose_product_dims = { IndexPair(0, 1) }; + Eigen::Tensor AtBt = a.contract(b, transposed_product_dims); + + +## Reduction Operations + +A *Reduction* operation returns a tensor with fewer dimensions than the +original tensor. The values in the returned tensor are computed by applying a +*reduction operator* to slices of values from the original tensor. You specify +the dimensions along which the slices are made. + +The Eigen Tensor library provides a set of predefined reduction operators such +as ```maximum()``` and ```sum()``` and lets you define additional operators by +implementing a few methods from a reductor template. + +### Reduction Dimensions + +All reduction operations take a single parameter of type +```::Dimensions``` which can always be specified as an array of +ints. These are called the "reduction dimensions." The values are the indices +of the dimensions of the input tensor over which the reduction is done. The +parameter can have at most as many element as the rank of the input tensor; +each element must be less than the tensor rank, as it indicates one of the +dimensions to reduce. + +Each dimension of the input tensor should occur at most once in the reduction +dimensions as the implementation does not remove duplicates. + +The order of the values in the reduction dimensions does not affect the +results, but the code may execute faster if you list the dimensions in +increasing order. + +Example: Reduction along one dimension. + + // Create a tensor of 2 dimensions + Eigen::Tensor a(2, 3); + a.setValues({{1, 2, 3}, {6, 5, 4}}); + // Reduce it along the second dimension (1)... + Eigen::array dims({1 /* dimension to reduce */}); + // ...using the "maximum" operator. + // The result is a tensor with one dimension. The size of + // that dimension is the same as the first (non-reduced) dimension of a. + Eigen::Tensor b = a.maximum(dims); + cout << "a" << endl << a << endl << endl; + cout << "b" << endl << b << endl << endl; + => + a + 1 2 3 + 6 5 4 + + b + 3 + 6 + +Example: Reduction along two dimensions. + + Eigen::Tensor a(2, 3, 4); + a.setValues({{{0.0f, 1.0f, 2.0f, 3.0f}, + {7.0f, 6.0f, 5.0f, 4.0f}, + {8.0f, 9.0f, 10.0f, 11.0f}}, + {{12.0f, 13.0f, 14.0f, 15.0f}, + {19.0f, 18.0f, 17.0f, 16.0f}, + {20.0f, 21.0f, 22.0f, 23.0f}}}); + // The tensor a has 3 dimensions. We reduce along the + // first 2, resulting in a tensor with a single dimension + // of size 4 (the last dimension of a.) + // Note that we pass the array of reduction dimensions + // directly to the maximum() call. + Eigen::Tensor b = + a.maximum(Eigen::array({0, 1})); + cout << "b" << endl << b << endl << endl; + => + b + 20 + 21 + 22 + 23 + +#### Reduction along all dimensions + +As a special case, if you pass no parameter to a reduction operation the +original tensor is reduced along *all* its dimensions. The result is a +scalar, represented as a zero-dimension tensor. + + Eigen::Tensor a(2, 3, 4); + a.setValues({{{0.0f, 1.0f, 2.0f, 3.0f}, + {7.0f, 6.0f, 5.0f, 4.0f}, + {8.0f, 9.0f, 10.0f, 11.0f}}, + {{12.0f, 13.0f, 14.0f, 15.0f}, + {19.0f, 18.0f, 17.0f, 16.0f}, + {20.0f, 21.0f, 22.0f, 23.0f}}}); + // Reduce along all dimensions using the sum() operator. + Eigen::Tensor b = a.sum(); + cout << "b" << endl << b << endl << endl; + => + b + 276 + + +### sum(const Dimensions& new_dims) +### sum() + +Reduce a tensor using the sum() operator. The resulting values +are the sum of the reduced values. + +### mean(const Dimensions& new_dims) +### mean() + +Reduce a tensor using the mean() operator. The resulting values +are the mean of the reduced values. + +### maximum(const Dimensions& new_dims) +### maximum() + +Reduce a tensor using the maximum() operator. The resulting values are the +largest of the reduced values. + +### minimum(const Dimensions& new_dims) +### minimum() + +Reduce a tensor using the minimum() operator. The resulting values +are the smallest of the reduced values. + +### prod(const Dimensions& new_dims) +### prod() + +Reduce a tensor using the prod() operator. The resulting values +are the product of the reduced values. + +### all(const Dimensions& new_dims) +### all() +Reduce a tensor using the all() operator. Casts tensor to bool and then checks +whether all elements are true. Runs through all elements rather than +short-circuiting, so may be significantly inefficient. + +### any(const Dimensions& new_dims) +### any() +Reduce a tensor using the any() operator. Casts tensor to bool and then checks +whether any element is true. Runs through all elements rather than +short-circuiting, so may be significantly inefficient. + + +### reduce(const Dimensions& new_dims, const Reducer& reducer) + +Reduce a tensor using a user-defined reduction operator. See ```SumReducer``` +in TensorFunctors.h for information on how to implement a reduction operator. + + +## Scan Operations + +A *Scan* operation returns a tensor with the same dimensions as the original +tensor. The operation performs an inclusive scan along the specified +axis, which means it computes a running total along the axis for a given +reduction operation. +If the reduction operation corresponds to summation, then this computes the +prefix sum of the tensor along the given axis. + +Example: +dd a comment to this line + + // Create a tensor of 2 dimensions + Eigen::Tensor a(2, 3); + a.setValues({{1, 2, 3}, {4, 5, 6}}); + // Scan it along the second dimension (1) using summation + Eigen::Tensor b = a.cumsum(1); + // The result is a tensor with the same size as the input + cout << "a" << endl << a << endl << endl; + cout << "b" << endl << b << endl << endl; + => + a + 1 2 3 + 6 5 4 + + b + 1 3 6 + 4 9 15 + +### cumsum(const Index& axis) + +Perform a scan by summing consecutive entries. + +### cumprod(const Index& axis) + +Perform a scan by multiplying consecutive entries. + + +## Convolutions + +### convolve(const Kernel& kernel, const Dimensions& dims) + +Returns a tensor that is the output of the convolution of the input tensor with the kernel, +along the specified dimensions of the input tensor. The dimension size for dimensions of the output tensor +which were part of the convolution will be reduced by the formula: +output_dim_size = input_dim_size - kernel_dim_size + 1 (requires: input_dim_size >= kernel_dim_size). +The dimension sizes for dimensions that were not part of the convolution will remain the same. +Performance of the convolution can depend on the length of the stride(s) of the input tensor dimension(s) along which the +convolution is computed (the first dimension has the shortest stride for ColMajor, whereas RowMajor's shortest stride is +for the last dimension). + + // Compute convolution along the second and third dimension. + Tensor input(3, 3, 7, 11); + Tensor kernel(2, 2); + Tensor output(3, 2, 6, 11); + input.setRandom(); + kernel.setRandom(); + + Eigen::array dims({1, 2}); // Specify second and third dimension for convolution. + output = input.convolve(kernel, dims); + + for (int i = 0; i < 3; ++i) { + for (int j = 0; j < 2; ++j) { + for (int k = 0; k < 6; ++k) { + for (int l = 0; l < 11; ++l) { + const float result = output(i,j,k,l); + const float expected = input(i,j+0,k+0,l) * kernel(0,0) + + input(i,j+1,k+0,l) * kernel(1,0) + + input(i,j+0,k+1,l) * kernel(0,1) + + input(i,j+1,k+1,l) * kernel(1,1); + VERIFY_IS_APPROX(result, expected); + } + } + } + } + + +## Geometrical Operations + +These operations return a Tensor with different dimensions than the original +Tensor. They can be used to access slices of tensors, see them with different +dimensions, or pad tensors with additional data. + +### reshape(const Dimensions& new_dims) + +Returns a view of the input tensor that has been reshaped to the specified +new dimensions. The argument new_dims is an array of Index values. The +rank of the resulting tensor is equal to the number of elements in new_dims. + +The product of all the sizes in the new dimension array must be equal to +the number of elements in the input tensor. + + // Increase the rank of the input tensor by introducing a new dimension + // of size 1. + Tensor input(7, 11); + array three_dims{{7, 11, 1}}; + Tensor result = input.reshape(three_dims); + + // Decrease the rank of the input tensor by merging 2 dimensions; + array one_dim{{7 * 11}}; + Tensor result = input.reshape(one_dim); + +This operation does not move any data in the input tensor, so the resulting +contents of a reshaped Tensor depend on the data layout of the original Tensor. + +For example this is what happens when you ```reshape()``` a 2D ColMajor tensor +to one dimension: + + Eigen::Tensor a(2, 3); + a.setValues({{0.0f, 100.0f, 200.0f}, {300.0f, 400.0f, 500.0f}}); + Eigen::array one_dim({3 * 2}); + Eigen::Tensor b = a.reshape(one_dim); + cout << "b" << endl << b << endl; + => + b + 0 + 300 + 100 + 400 + 200 + 500 + +This is what happens when the 2D Tensor is RowMajor: + + Eigen::Tensor a(2, 3); + a.setValues({{0.0f, 100.0f, 200.0f}, {300.0f, 400.0f, 500.0f}}); + Eigen::array one_dim({3 * 2}); + Eigen::Tensor b = a.reshape(one_dim); + cout << "b" << endl << b << endl; + => + b + 0 + 100 + 200 + 300 + 400 + 500 + +The reshape operation is a lvalue. In other words, it can be used on the left +side of the assignment operator. + +The previous example can be rewritten as follow: + + Eigen::Tensor a(2, 3); + a.setValues({{0.0f, 100.0f, 200.0f}, {300.0f, 400.0f, 500.0f}}); + Eigen::array two_dim({2, 3}); + Eigen::Tensor b; + b.reshape(two_dim) = a; + cout << "b" << endl << b << endl; + => + b + 0 + 300 + 100 + 400 + 200 + 500 + +Note that "b" itself was not reshaped but that instead the assignment is done to +the reshape view of b. + + +### shuffle(const Shuffle& shuffle) + +Returns a copy of the input tensor whose dimensions have been +reordered according to the specified permutation. The argument shuffle +is an array of Index values. Its size is the rank of the input +tensor. It must contain a permutation of 0, 1, ..., rank - 1. The i-th +dimension of the output tensor equals to the size of the shuffle[i]-th +dimension of the input tensor. For example: + + // Shuffle all dimensions to the left by 1. + Tensor input(20, 30, 50); + // ... set some values in input. + Tensor output = input.shuffle({1, 2, 0}) + + eigen_assert(output.dimension(0) == 30); + eigen_assert(output.dimension(1) == 50); + eigen_assert(output.dimension(2) == 20); + +Indices into the output tensor are shuffled accordingly to formulate +indices into the input tensor. For example, one can assert in the above +code snippet that: + + eigen_assert(output(3, 7, 11) == input(11, 3, 7)); + +In general, one can assert that + + eigen_assert(output(..., indices[shuffle[i]], ...) == + input(..., indices[i], ...)) + +The shuffle operation results in a lvalue, which means that it can be assigned +to. In other words, it can be used on the left side of the assignment operator. + +Let's rewrite the previous example to take advantage of this feature: + + // Shuffle all dimensions to the left by 1. + Tensor input(20, 30, 50); + // ... set some values in input. + Tensor output(30, 50, 20); + output.shuffle({2, 0, 1}) = input; + + +### stride(const Strides& strides) + +Returns a view of the input tensor that strides (skips stride-1 +elements) along each of the dimensions. The argument strides is an +array of Index values. The dimensions of the resulting tensor are +ceil(input_dimensions[i] / strides[i]). + +For example this is what happens when you ```stride()``` a 2D tensor: + + Eigen::Tensor a(4, 3); + a.setValues({{0, 100, 200}, {300, 400, 500}, {600, 700, 800}, {900, 1000, 1100}}); + Eigen::array strides({3, 2}); + Eigen::Tensor b = a.stride(strides); + cout << "b" << endl << b << endl; + => + b + 0 200 + 900 1100 + +It is possible to assign a tensor to a stride: + Tensor input(20, 30, 50); + // ... set some values in input. + Tensor output(40, 90, 200); + output.stride({2, 3, 4}) = input; + + +### slice(const StartIndices& offsets, const Sizes& extents) + +Returns a sub-tensor of the given tensor. For each dimension i, the slice is +made of the coefficients stored between offset[i] and offset[i] + extents[i] in +the input tensor. + + Eigen::Tensor a(4, 3); + a.setValues({{0, 100, 200}, {300, 400, 500}, + {600, 700, 800}, {900, 1000, 1100}}); + Eigen::array offsets = {1, 0}; + Eigen::array extents = {2, 2}; + Eigen::Tensor slice = a.slice(offsets, extents); + cout << "a" << endl << a << endl; + => + a + 0 100 200 + 300 400 500 + 600 700 800 + 900 1000 1100 + cout << "slice" << endl << slice << endl; + => + slice + 300 400 + 600 700 + + +### chip(const Index offset, const Index dim) + +A chip is a special kind of slice. It is the subtensor at the given offset in +the dimension dim. The returned tensor has one fewer dimension than the input +tensor: the dimension dim is removed. + +For example, a matrix chip would be either a row or a column of the input +matrix. + + Eigen::Tensor a(4, 3); + a.setValues({{0, 100, 200}, {300, 400, 500}, + {600, 700, 800}, {900, 1000, 1100}}); + Eigen::Tensor row_3 = a.chip(2, 0); + Eigen::Tensor col_2 = a.chip(1, 1); + cout << "a" << endl << a << endl; + => + a + 0 100 200 + 300 400 500 + 600 700 800 + 900 1000 1100 + cout << "row_3" << endl << row_3 << endl; + => + row_3 + 600 700 800 + cout << "col_2" << endl << col_2 << endl; + => + col_2 + 100 400 700 1000 + +It is possible to assign values to a tensor chip since the chip operation is a +lvalue. For example: + + Eigen::Tensor a(3); + a.setValues({{100, 200, 300}}); + Eigen::Tensor b(2, 3); + b.setZero(); + b.chip(0, 0) = a; + cout << "a" << endl << a << endl; + => + a + 100 + 200 + 300 + cout << "b" << endl << b << endl; + => + b + 100 200 300 + 0 0 0 + + +### reverse(const ReverseDimensions& reverse) + +Returns a view of the input tensor that reverses the order of the coefficients +along a subset of the dimensions. The argument reverse is an array of boolean +values that indicates whether or not the order of the coefficients should be +reversed along each of the dimensions. This operation preserves the dimensions +of the input tensor. + +For example this is what happens when you ```reverse()``` the first dimension +of a 2D tensor: + + Eigen::Tensor a(4, 3); + a.setValues({{0, 100, 200}, {300, 400, 500}, + {600, 700, 800}, {900, 1000, 1100}}); + Eigen::array reverse({true, false}); + Eigen::Tensor b = a.reverse(reverse); + cout << "a" << endl << a << endl << "b" << endl << b << endl; + => + a + 0 100 200 + 300 400 500 + 600 700 800 + 900 1000 1100 + b + 900 1000 1100 + 600 700 800 + 300 400 500 + 0 100 200 + + +### broadcast(const Broadcast& broadcast) + +Returns a view of the input tensor in which the input is replicated one to many +times. +The broadcast argument specifies how many copies of the input tensor need to be +made in each of the dimensions. + + Eigen::Tensor a(2, 3); + a.setValues({{0, 100, 200}, {300, 400, 500}}); + Eigen::array bcast({3, 2}); + Eigen::Tensor b = a.broadcast(bcast); + cout << "a" << endl << a << endl << "b" << endl << b << endl; + => + a + 0 100 200 + 300 400 500 + b + 0 100 200 0 100 200 + 300 400 500 300 400 500 + 0 100 200 0 100 200 + 300 400 500 300 400 500 + 0 100 200 0 100 200 + 300 400 500 300 400 500 + +### concatenate(const OtherDerived& other, Axis axis) + +TODO + +### pad(const PaddingDimensions& padding) + +Returns a view of the input tensor in which the input is padded with zeros. + + Eigen::Tensor a(2, 3); + a.setValues({{0, 100, 200}, {300, 400, 500}}); + Eigen::array, 2> paddings; + paddings[0] = make_pair(0, 1); + paddings[1] = make_pair(2, 3); + Eigen::Tensor b = a.pad(paddings); + cout << "a" << endl << a << endl << "b" << endl << b << endl; + => + a + 0 100 200 + 300 400 500 + b + 0 0 0 0 + 0 0 0 0 + 0 100 200 0 + 300 400 500 0 + 0 0 0 0 + 0 0 0 0 + 0 0 0 0 + + +### extract_patches(const PatchDims& patch_dims) + +Returns a tensor of coefficient patches extracted from the input tensor, where +each patch is of dimension specified by 'patch_dims'. The returned tensor has +one greater dimension than the input tensor, which is used to index each patch. +The patch index in the output tensor depends on the data layout of the input +tensor: the patch index is the last dimension ColMajor layout, and the first +dimension in RowMajor layout. + +For example, given the following input tensor: + + Eigen::Tensor tensor(3,4); + tensor.setValues({{0.0f, 1.0f, 2.0f, 3.0f}, + {4.0f, 5.0f, 6.0f, 7.0f}, + {8.0f, 9.0f, 10.0f, 11.0f}}); + + cout << "tensor: " << endl << tensor << endl; +=> +tensor: + 0 1 2 3 + 4 5 6 7 + 8 9 10 11 + +Six 2x2 patches can be extracted and indexed using the following code: + + Eigen::Tensor patch; + Eigen::array patch_dims; + patch_dims[0] = 2; + patch_dims[1] = 2; + patch = tensor.extract_patches(patch_dims); + for (int k = 0; k < 6; ++k) { + cout << "patch index: " << k << endl; + for (int i = 0; i < 2; ++i) { + for (int j = 0; j < 2; ++j) { + if (DataLayout == ColMajor) { + cout << patch(i, j, k) << " "; + } else { + cout << patch(k, i, j) << " "; + } + } + cout << endl; + } + } + +This code results in the following output when the data layout is ColMajor: + +patch index: 0 +0 1 +4 5 +patch index: 1 +4 5 +8 9 +patch index: 2 +1 2 +5 6 +patch index: 3 +5 6 +9 10 +patch index: 4 +2 3 +6 7 +patch index: 5 +6 7 +10 11 + +This code results in the following output when the data layout is RowMajor: +(NOTE: the set of patches is the same as in ColMajor, but are indexed differently). + +patch index: 0 +0 1 +4 5 +patch index: 1 +1 2 +5 6 +patch index: 2 +2 3 +6 7 +patch index: 3 +4 5 +8 9 +patch index: 4 +5 6 +9 10 +patch index: 5 +6 7 +10 11 + +### extract_image_patches(const Index patch_rows, const Index patch_cols, + const Index row_stride, const Index col_stride, + const PaddingType padding_type) + +Returns a tensor of coefficient image patches extracted from the input tensor, +which is expected to have dimensions ordered as follows (depending on the data +layout of the input tensor, and the number of additional dimensions 'N'): + +*) ColMajor +1st dimension: channels (of size d) +2nd dimension: rows (of size r) +3rd dimension: columns (of size c) +4th-Nth dimension: time (for video) or batch (for bulk processing). + +*) RowMajor (reverse order of ColMajor) +1st-Nth dimension: time (for video) or batch (for bulk processing). +N+1'th dimension: columns (of size c) +N+2'th dimension: rows (of size r) +N+3'th dimension: channels (of size d) + +The returned tensor has one greater dimension than the input tensor, which is +used to index each patch. The patch index in the output tensor depends on the +data layout of the input tensor: the patch index is the 4'th dimension in +ColMajor layout, and the 4'th from the last dimension in RowMajor layout. + +For example, given the following input tensor with the following dimension +sizes: + *) depth: 2 + *) rows: 3 + *) columns: 5 + *) batch: 7 + + Tensor tensor(2,3,5,7); + Tensor tensor_row_major = tensor.swap_layout(); + +2x2 image patches can be extracted and indexed using the following code: + +*) 2D patch: ColMajor (patch indexed by second-to-last dimension) + Tensor twod_patch; + twod_patch = tensor.extract_image_patches<2, 2>(); + // twod_patch.dimension(0) == 2 + // twod_patch.dimension(1) == 2 + // twod_patch.dimension(2) == 2 + // twod_patch.dimension(3) == 3*5 + // twod_patch.dimension(4) == 7 + +*) 2D patch: RowMajor (patch indexed by the second dimension) + Tensor twod_patch_row_major; + twod_patch_row_major = tensor_row_major.extract_image_patches<2, 2>(); + // twod_patch_row_major.dimension(0) == 7 + // twod_patch_row_major.dimension(1) == 3*5 + // twod_patch_row_major.dimension(2) == 2 + // twod_patch_row_major.dimension(3) == 2 + // twod_patch_row_major.dimension(4) == 2 + +## Special Operations + +### cast() + +Returns a tensor of type T with the same dimensions as the original tensor. +The returned tensor contains the values of the original tensor converted to +type T. + + Eigen::Tensor a(2, 3); + Eigen::Tensor b = a.cast(); + +This can be useful for example if you need to do element-wise division of +Tensors of integers. This is not currently supported by the Tensor library +but you can easily cast the tensors to floats to do the division: + + Eigen::Tensor a(2, 3); + a.setValues({{0, 1, 2}, {3, 4, 5}}); + Eigen::Tensor b = + (a.cast() / a.constant(2).cast()).cast(); + cout << "a" << endl << a << endl << endl; + cout << "b" << endl << b << endl << endl; + => + a + 0 1 2 + 3 4 5 + + b + 0 0 1 + 1 2 2 + + +### eval() + +TODO + + +## Representation of scalar values + +Scalar values are often represented by tensors of size 1 and rank 0.For example +Tensor::maximum() currently returns a Tensor. Similarly, the inner +product of 2 1d tensors (through contractions) returns a 0d tensor. + +## Limitations + +* The number of tensor dimensions is currently limited to 250 when using a + compiler that supports cxx11. It is limited to only 5 for older compilers. +* The IndexList class requires a cxx11 compliant compiler. You can use an + array of indices instead if you don't have access to a modern compiler. +* On GPUs only floating point values are properly tested and optimized for. +* Complex and integer values are known to be broken on GPUs. If you try to use + them you'll most likely end up triggering a static assertion failure such as + EIGEN_STATIC_ASSERT(packetSize > 1, YOU_MADE_A_PROGRAMMING_MISTAKE) + + diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/Tensor.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/Tensor.h new file mode 100644 index 00000000..1940a969 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/Tensor.h @@ -0,0 +1,527 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// Copyright (C) 2013 Christian Seiler +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_H +#define EIGEN_CXX11_TENSOR_TENSOR_H + +namespace Eigen { + +/** \class Tensor + * \ingroup CXX11_Tensor_Module + * + * \brief The tensor class. + * + * The %Tensor class is the work-horse for all \em dense tensors within Eigen. + * + * The %Tensor class encompasses only dynamic-size objects so far. + * + * The first two template parameters are required: + * \tparam Scalar_ \anchor tensor_tparam_scalar Numeric type, e.g. float, double, int or std::complex. + * User defined scalar types are supported as well (see \ref user_defined_scalars "here"). + * \tparam NumIndices_ Number of indices (i.e. rank of the tensor) + * + * The remaining template parameters are optional -- in most cases you don't have to worry about them. + * \tparam Options_ \anchor tensor_tparam_options A combination of either \b #RowMajor or \b #ColMajor, and of either + * \b #AutoAlign or \b #DontAlign. + * The former controls \ref TopicStorageOrders "storage order", and defaults to column-major. The latter controls alignment, which is required + * for vectorization. It defaults to aligning tensors. Note that tensors currently do not support any operations that profit from vectorization. + * Support for such operations (i.e. adding two tensors etc.) is planned. + * + * You can access elements of tensors using normal subscripting: + * + * \code + * Eigen::Tensor t(10, 10, 10, 10); + * t(0, 1, 2, 3) = 42.0; + * \endcode + * + * This class can be extended with the help of the plugin mechanism described on the page + * \ref TopicCustomizingEigen by defining the preprocessor symbol \c EIGEN_TENSOR_PLUGIN. + * + * Some notes: + * + *
+ *
Relation to other parts of Eigen:
+ *
The midterm developement goal for this class is to have a similar hierarchy as Eigen uses for matrices, so that + * taking blocks or using tensors in expressions is easily possible, including an interface with the vector/matrix code + * by providing .asMatrix() and .asVector() (or similar) methods for rank 2 and 1 tensors. However, currently, the %Tensor + * class does not provide any of these features and is only available as a stand-alone class that just allows for + * coefficient access. Also, when fixed-size tensors are implemented, the number of template arguments is likely to + * change dramatically.
+ *
+ * + * \ref TopicStorageOrders + */ + +template +class Tensor : public TensorBase > +{ + public: + typedef Tensor Self; + typedef TensorBase > Base; + typedef typename Eigen::internal::nested::type Nested; + typedef typename internal::traits::StorageKind StorageKind; + typedef typename internal::traits::Index Index; + typedef Scalar_ Scalar; + typedef typename NumTraits::Real RealScalar; + typedef typename Base::CoeffReturnType CoeffReturnType; + + enum { + IsAligned = bool(EIGEN_MAX_ALIGN_BYTES>0) & !(Options_&DontAlign), + Layout = Options_ & RowMajor ? RowMajor : ColMajor, + CoordAccess = true, + RawAccess = true + }; + + static const int Options = Options_; + static const int NumIndices = NumIndices_; + typedef DSizes Dimensions; + + protected: + TensorStorage m_storage; + +#ifdef EIGEN_HAS_SFINAE + template + struct isOfNormalIndex{ + static const bool is_array = internal::is_base_of, CustomIndices>::value; + static const bool is_int = NumTraits::IsInteger; + static const bool value = is_array | is_int; + }; +#endif + + public: + // Metadata + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rank() const { return NumIndices; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index dimension(std::size_t n) const { return m_storage.dimensions()[n]; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_storage.dimensions(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index size() const { return m_storage.size(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar *data() { return m_storage.data(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar *data() const { return m_storage.data(); } + + // This makes EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED + // work, because that uses base().coeffRef() - and we don't yet + // implement a similar class hierarchy + inline Self& base() { return *this; } + inline const Self& base() const { return *this; } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template + EIGEN_DEVICE_FUNC inline const Scalar& coeff(Index firstIndex, Index secondIndex, IndexTypes... otherIndices) const + { + // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + return coeff(array{{firstIndex, secondIndex, otherIndices...}}); + } +#endif + + // normal indices + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(const array& indices) const + { + eigen_internal_assert(checkIndexRange(indices)); + return m_storage.data()[linearizedIndex(indices)]; + } + + // custom indices +#ifdef EIGEN_HAS_SFINAE + template::value) ) + > + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(CustomIndices& indices) const + { + return coeff(internal::customIndices2Array(indices)); + } +#endif + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff() const + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE); + return m_storage.data()[0]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(Index index) const + { + eigen_internal_assert(index >= 0 && index < size()); + return m_storage.data()[index]; + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template + inline Scalar& coeffRef(Index firstIndex, Index secondIndex, IndexTypes... otherIndices) + { + // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + return coeffRef(array{{firstIndex, secondIndex, otherIndices...}}); + } +#endif + + // normal indices + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(const array& indices) + { + eigen_internal_assert(checkIndexRange(indices)); + return m_storage.data()[linearizedIndex(indices)]; + } + + // custom indices +#ifdef EIGEN_HAS_SFINAE + template::value) ) + > + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(CustomIndices& indices) + { + return coeffRef(internal::customIndices2Array(indices)); + } +#endif + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef() + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE); + return m_storage.data()[0]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index index) + { + eigen_internal_assert(index >= 0 && index < size()); + return m_storage.data()[index]; + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template + inline const Scalar& operator()(Index firstIndex, Index secondIndex, IndexTypes... otherIndices) const + { + // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + return this->operator()(array{{firstIndex, secondIndex, otherIndices...}}); + } +#else + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1) const + { + return coeff(array(i0, i1)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2) const + { + return coeff(array(i0, i1, i2)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2, Index i3) const + { + return coeff(array(i0, i1, i2, i3)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2, Index i3, Index i4) const + { + return coeff(array(i0, i1, i2, i3, i4)); + } +#endif + + // custom indices +#ifdef EIGEN_HAS_SFINAE + template::value) ) + > + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator()(CustomIndices& indices) const + { + return coeff(internal::customIndices2Array(indices)); + } +#endif + + // normal indices + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator()(const array& indices) const + { + return coeff(indices); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator()(Index index) const + { + eigen_internal_assert(index >= 0 && index < size()); + return coeff(index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator()() const + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE); + return coeff(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator[](Index index) const + { + // The bracket operator is only for vectors, use the parenthesis operator instead. + EIGEN_STATIC_ASSERT(NumIndices == 1, YOU_MADE_A_PROGRAMMING_MISTAKE); + return coeff(index); + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template + inline Scalar& operator()(Index firstIndex, Index secondIndex, IndexTypes... otherIndices) + { + // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + return operator()(array{{firstIndex, secondIndex, otherIndices...}}); + } +#else + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1) + { + return coeffRef(array(i0, i1)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2) + { + return coeffRef(array(i0, i1, i2)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3) + { + return coeffRef(array(i0, i1, i2, i3)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3, Index i4) + { + return coeffRef(array(i0, i1, i2, i3, i4)); + } +#endif + + // normal indices + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator()(const array& indices) + { + return coeffRef(indices); + } + + // custom indices +#ifdef EIGEN_HAS_SFINAE + template::value) ) + > + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator()(CustomIndices& indices) + { + return coeffRef(internal::customIndices2Array(indices)); + } +#endif + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator()(Index index) + { + eigen_assert(index >= 0 && index < size()); + return coeffRef(index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator()() + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE); + return coeffRef(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator[](Index index) + { + // The bracket operator is only for vectors, use the parenthesis operator instead + EIGEN_STATIC_ASSERT(NumIndices == 1, YOU_MADE_A_PROGRAMMING_MISTAKE) + return coeffRef(index); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Tensor() + : m_storage() + { + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Tensor(const Self& other) + : m_storage(other.m_storage) + { + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Tensor(Index firstDimension, IndexTypes... otherDimensions) + : m_storage(firstDimension, otherDimensions...) + { + // The number of dimensions used to construct a tensor must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT(sizeof...(otherDimensions) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + } +#else + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE explicit Tensor(Index dim1) + : m_storage(dim1, array(dim1)) + { + EIGEN_STATIC_ASSERT(1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Tensor(Index dim1, Index dim2) + : m_storage(dim1*dim2, array(dim1, dim2)) + { + EIGEN_STATIC_ASSERT(2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Tensor(Index dim1, Index dim2, Index dim3) + : m_storage(dim1*dim2*dim3, array(dim1, dim2, dim3)) + { + EIGEN_STATIC_ASSERT(3 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Tensor(Index dim1, Index dim2, Index dim3, Index dim4) + : m_storage(dim1*dim2*dim3*dim4, array(dim1, dim2, dim3, dim4)) + { + EIGEN_STATIC_ASSERT(4 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Tensor(Index dim1, Index dim2, Index dim3, Index dim4, Index dim5) + : m_storage(dim1*dim2*dim3*dim4*dim5, array(dim1, dim2, dim3, dim4, dim5)) + { + EIGEN_STATIC_ASSERT(5 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + } +#endif + + /** Normal Dimension */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE explicit Tensor(const array& dimensions) + : m_storage(internal::array_prod(dimensions), dimensions) + { + EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Tensor(const TensorBase& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other.derived()); + resize(TensorEvaluator(assign, DefaultDevice()).dimensions()); + internal::TensorExecutor::run(assign, DefaultDevice()); + } + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Tensor(const TensorBase& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other.derived()); + resize(TensorEvaluator(assign, DefaultDevice()).dimensions()); + internal::TensorExecutor::run(assign, DefaultDevice()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Tensor& operator=(const Tensor& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + resize(TensorEvaluator(assign, DefaultDevice()).dimensions()); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Tensor& operator=(const OtherDerived& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + resize(TensorEvaluator(assign, DefaultDevice()).dimensions()); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template EIGEN_DEVICE_FUNC + void resize(Index firstDimension, IndexTypes... otherDimensions) + { + // The number of dimensions used to resize a tensor must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT(sizeof...(otherDimensions) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + resize(array{{firstDimension, otherDimensions...}}); + } +#endif + + /** Normal Dimension */ + EIGEN_DEVICE_FUNC void resize(const array& dimensions) + { + int i; + Index size = Index(1); + for (i = 0; i < NumIndices; i++) { + internal::check_rows_cols_for_overflow::run(size, dimensions[i]); + size *= dimensions[i]; + } + #ifdef EIGEN_INITIALIZE_COEFFS + bool size_changed = size != this->size(); + m_storage.resize(size, dimensions); + if(size_changed) EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED + #else + m_storage.resize(size, dimensions); + #endif + } + + // Why this overload, DSizes is derived from array ??? // + EIGEN_DEVICE_FUNC void resize(const DSizes& dimensions) { + array dims; + for (int i = 0; i < NumIndices; ++i) { + dims[i] = dimensions[i]; + } + resize(dims); + } + + EIGEN_DEVICE_FUNC + void resize() + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE); + // Nothing to do: rank 0 tensors have fixed size + } + + /** Custom Dimension */ +#ifdef EIGEN_HAS_SFINAE + template::value) ) + > + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(CustomDimension& dimensions) + { + resize(internal::customIndices2Array(dimensions)); + } +#endif + +#ifndef EIGEN_EMULATE_CXX11_META_H + template + EIGEN_DEVICE_FUNC + void resize(const Sizes& dimensions) { + array dims; + for (int i = 0; i < NumIndices; ++i) { + dims[i] = static_cast(dimensions[i]); + } + resize(dims); + } +#else + template + EIGEN_DEVICE_FUNC + void resize(const Sizes& dimensions) { + array dims; + for (int i = 0; i < NumIndices; ++i) { + dims[i] = static_cast(dimensions[i]); + } + resize(dims); + } +#endif + + protected: + + bool checkIndexRange(const array& indices) const + { + using internal::array_apply_and_reduce; + using internal::array_zip_and_reduce; + using internal::greater_equal_zero_op; + using internal::logical_and_op; + using internal::lesser_op; + + return + // check whether the indices are all >= 0 + array_apply_and_reduce(indices) && + // check whether the indices fit in the dimensions + array_zip_and_reduce(indices, m_storage.dimensions()); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index linearizedIndex(const array& indices) const + { + if (Options&RowMajor) { + return m_storage.dimensions().IndexOfRowMajor(indices); + } else { + return m_storage.dimensions().IndexOfColMajor(indices); + } + } +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorArgMax.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorArgMax.h new file mode 100644 index 00000000..d06f40cd --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorArgMax.h @@ -0,0 +1,299 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Eugene Brevdo +// Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_ARG_MAX_H +#define EIGEN_CXX11_TENSOR_TENSOR_ARG_MAX_H + +namespace Eigen { +namespace internal { + +/** \class TensorIndexTuple + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor + Index Tuple class. + * + * + */ +template +struct traits > : public traits +{ + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef Tuple Scalar; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorIndexTupleOp& type; +}; + +template +struct nested, 1, + typename eval >::type> +{ + typedef TensorIndexTupleOp type; +}; + +} // end namespace internal + +template +class TensorIndexTupleOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + typedef Tuple CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorIndexTupleOp(const XprType& expr) + : m_xpr(expr) {} + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + protected: + typename XprType::Nested m_xpr; +}; + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorIndexTupleOp XprType; + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + + typedef typename TensorEvaluator::Dimensions Dimensions; + static const int NumDims = internal::array_size::value; + + enum { + IsAligned = /*TensorEvaluator::IsAligned*/ false, + PacketAccess = /*TensorEvaluator::PacketAccess*/ false, + BlockAccess = false, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device) { } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { + return m_impl.dimensions(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* /*data*/) { + m_impl.evalSubExprsIfNeeded(NULL); + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + return CoeffReturnType(index, m_impl.coeff(index)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + return m_impl.costPerCoeff(vectorized) + TensorOpCost(0, 0, 1); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + protected: + TensorEvaluator m_impl; +}; + +namespace internal { + +/** \class TensorTupleIndex + * \ingroup CXX11_Tensor_Module + * + * \brief Converts to Tensor > and reduces to Tensor. + * + */ +template +struct traits > : public traits +{ + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef Index Scalar; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions - array_size::value; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorTupleReducerOp& type; +}; + +template +struct nested, 1, + typename eval >::type> +{ + typedef TensorTupleReducerOp type; +}; + +} // end namespace internal + +template +class TensorTupleReducerOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + typedef Index CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorTupleReducerOp(const XprType& expr, + const ReduceOp& reduce_op, + const int return_dim, + const Dims& reduce_dims) + : m_xpr(expr), m_reduce_op(reduce_op), m_return_dim(return_dim), m_reduce_dims(reduce_dims) {} + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + EIGEN_DEVICE_FUNC + const ReduceOp& reduce_op() const { return m_reduce_op; } + + EIGEN_DEVICE_FUNC + const Dims& reduce_dims() const { return m_reduce_dims; } + + EIGEN_DEVICE_FUNC + int return_dim() const { return m_return_dim; } + + protected: + typename XprType::Nested m_xpr; + const ReduceOp m_reduce_op; + const int m_return_dim; + const Dims m_reduce_dims; +}; + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorTupleReducerOp XprType; + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename TensorIndexTupleOp::CoeffReturnType TupleType; + typedef typename TensorEvaluator >, Device>::Dimensions Dimensions; + typedef typename TensorEvaluator , Device>::Dimensions InputDimensions; + static const int NumDims = internal::array_size::value; + typedef array StrideDims; + + enum { + IsAligned = /*TensorEvaluator::IsAligned*/ false, + PacketAccess = /*TensorEvaluator::PacketAccess*/ false, + BlockAccess = false, + Layout = TensorEvaluator >, Device>::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_orig_impl(op.expression(), device), + m_impl(op.expression().index_tuples().reduce(op.reduce_dims(), op.reduce_op()), device), + m_return_dim(op.return_dim()) { + + gen_strides(m_orig_impl.dimensions(), m_strides); + if (Layout == static_cast(ColMajor)) { + const Index total_size = internal::array_prod(m_orig_impl.dimensions()); + m_stride_mod = (m_return_dim < NumDims - 1) ? m_strides[m_return_dim + 1] : total_size; + } else { + const Index total_size = internal::array_prod(m_orig_impl.dimensions()); + m_stride_mod = (m_return_dim > 0) ? m_strides[m_return_dim - 1] : total_size; + } + m_stride_div = m_strides[m_return_dim]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { + return m_impl.dimensions(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* /*data*/) { + m_impl.evalSubExprsIfNeeded(NULL); + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const { + const TupleType v = m_impl.coeff(index); + return (m_return_dim < 0) ? v.first : (v.first % m_stride_mod) / m_stride_div; + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + const double compute_cost = 1.0 + + (m_return_dim < 0 ? 0.0 : (TensorOpCost::ModCost() + TensorOpCost::DivCost())); + return m_orig_impl.costPerCoeff(vectorized) + + m_impl.costPerCoeff(vectorized) + TensorOpCost(0, 0, compute_cost); + } + + private: + EIGEN_DEVICE_FUNC void gen_strides(const InputDimensions& dims, StrideDims& strides) { + if (m_return_dim < 0) { + return; // Won't be using the strides. + } + eigen_assert(m_return_dim < NumDims && + "Asking to convert index to a dimension outside of the rank"); + + // Calculate m_stride_div and m_stride_mod, which are used to + // calculate the value of an index w.r.t. the m_return_dim. + if (Layout == static_cast(ColMajor)) { + strides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + strides[i] = strides[i-1] * dims[i-1]; + } + } else { + strides[NumDims-1] = 1; + for (int i = NumDims - 2; i >= 0; --i) { + strides[i] = strides[i+1] * dims[i+1]; + } + } + } + + protected: + TensorEvaluator, Device> m_orig_impl; + TensorEvaluator >, Device> m_impl; + const int m_return_dim; + StrideDims m_strides; + Index m_stride_mod; + Index m_stride_div; +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_ARG_MAX_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorAssign.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorAssign.h new file mode 100644 index 00000000..166be200 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorAssign.h @@ -0,0 +1,181 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_ASSIGN_H +#define EIGEN_CXX11_TENSOR_TENSOR_ASSIGN_H + +namespace Eigen { + +/** \class TensorAssign + * \ingroup CXX11_Tensor_Module + * + * \brief The tensor assignment class. + * + * This class is represents the assignment of the values resulting from the evaluation of + * the rhs expression to the memory locations denoted by the lhs expression. + */ +namespace internal { +template +struct traits > +{ + typedef typename LhsXprType::Scalar Scalar; + typedef typename traits::StorageKind StorageKind; + typedef typename promote_index_type::Index, + typename traits::Index>::type Index; + typedef typename LhsXprType::Nested LhsNested; + typedef typename RhsXprType::Nested RhsNested; + typedef typename remove_reference::type _LhsNested; + typedef typename remove_reference::type _RhsNested; + static const std::size_t NumDimensions = internal::traits::NumDimensions; + static const int Layout = internal::traits::Layout; + + enum { + Flags = 0 + }; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorAssignOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorAssignOp type; +}; + +} // end namespace internal + + + +template +class TensorAssignOp : public TensorBase > +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename LhsXprType::CoeffReturnType CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorAssignOp(LhsXprType& lhs, const RhsXprType& rhs) + : m_lhs_xpr(lhs), m_rhs_xpr(rhs) {} + + /** \returns the nested expressions */ + EIGEN_DEVICE_FUNC + typename internal::remove_all::type& + lhsExpression() const { return *((typename internal::remove_all::type*)&m_lhs_xpr); } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + rhsExpression() const { return m_rhs_xpr; } + + protected: + typename internal::remove_all::type& m_lhs_xpr; + const typename internal::remove_all::type& m_rhs_xpr; +}; + + +template +struct TensorEvaluator, Device> +{ + typedef TensorAssignOp XprType; + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + typedef typename TensorEvaluator::Dimensions Dimensions; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = TensorEvaluator::IsAligned & TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess & TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + RawAccess = TensorEvaluator::RawAccess + }; + + EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device) : + m_leftImpl(op.lhsExpression(), device), + m_rightImpl(op.rhsExpression(), device) + { + EIGEN_STATIC_ASSERT((static_cast(TensorEvaluator::Layout) == static_cast(TensorEvaluator::Layout)), YOU_MADE_A_PROGRAMMING_MISTAKE); + } + + EIGEN_DEVICE_FUNC const Dimensions& dimensions() const + { + // The dimensions of the lhs and the rhs tensors should be equal to prevent + // overflows and ensure the result is fully initialized. + // TODO: use left impl instead if right impl dimensions are known at compile time. + return m_rightImpl.dimensions(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar*) { + eigen_assert(dimensions_match(m_leftImpl.dimensions(), m_rightImpl.dimensions())); + m_leftImpl.evalSubExprsIfNeeded(NULL); + // If the lhs provides raw access to its storage area (i.e. if m_leftImpl.data() returns a non + // null value), attempt to evaluate the rhs expression in place. Returns true iff in place + // evaluation isn't supported and the caller still needs to manually assign the values generated + // by the rhs to the lhs. + return m_rightImpl.evalSubExprsIfNeeded(m_leftImpl.data()); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_leftImpl.cleanup(); + m_rightImpl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalScalar(Index i) { + m_leftImpl.coeffRef(i) = m_rightImpl.coeff(i); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalPacket(Index i) { + const int LhsStoreMode = TensorEvaluator::IsAligned ? Aligned : Unaligned; + const int RhsLoadMode = TensorEvaluator::IsAligned ? Aligned : Unaligned; + m_leftImpl.template writePacket(i, m_rightImpl.template packet(i)); + } + EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const + { + return m_leftImpl.coeff(index); + } + template + EIGEN_DEVICE_FUNC PacketReturnType packet(Index index) const + { + return m_leftImpl.template packet(index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + // We assume that evalPacket or evalScalar is called to perform the + // assignment and account for the cost of the write here, but reduce left + // cost by one load because we are using m_leftImpl.coeffRef. + TensorOpCost left = m_leftImpl.costPerCoeff(vectorized); + return m_rightImpl.costPerCoeff(vectorized) + + TensorOpCost( + numext::maxi(0.0, left.bytes_loaded() - sizeof(CoeffReturnType)), + left.bytes_stored(), left.compute_cycles()) + + TensorOpCost(0, sizeof(CoeffReturnType), 0, vectorized, PacketSize); + } + + /// required by sycl in order to extract the accessor + const TensorEvaluator& left_impl() const { return m_leftImpl; } + /// required by sycl in order to extract the accessor + const TensorEvaluator& right_impl() const { return m_rightImpl; } + + EIGEN_DEVICE_FUNC CoeffReturnType* data() const { return m_leftImpl.data(); } + + private: + TensorEvaluator m_leftImpl; + TensorEvaluator m_rightImpl; +}; + +} + + +#endif // EIGEN_CXX11_TENSOR_TENSOR_ASSIGN_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBase.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBase.h new file mode 100644 index 00000000..fbe34082 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBase.h @@ -0,0 +1,1016 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_BASE_H +#define EIGEN_CXX11_TENSOR_TENSOR_BASE_H + +// clang-format off + +namespace Eigen { + +/** \class TensorBase + * \ingroup CXX11_Tensor_Module + * + * \brief The tensor base class. + * + * This class is the common parent of the Tensor and TensorMap class, thus + * making it possible to use either class interchangably in expressions. + */ + +template +class TensorBase +{ + public: + typedef internal::traits DerivedTraits; + typedef typename DerivedTraits::Scalar Scalar; + typedef typename DerivedTraits::Index Index; + typedef typename internal::remove_const::type CoeffReturnType; + static const int NumDimensions = DerivedTraits::NumDimensions; + + // Generic nullary operation support. + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseNullaryOp + nullaryExpr(const CustomNullaryOp& func) const { + return TensorCwiseNullaryOp(derived(), func); + } + + // Coefficient-wise nullary operators + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseNullaryOp, const Derived> + constant(const Scalar& value) const { + return nullaryExpr(internal::scalar_constant_op(value)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseNullaryOp, const Derived> + random() const { + return nullaryExpr(internal::UniformRandomGenerator()); + } + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseNullaryOp + random(const RandomGenerator& gen = RandomGenerator()) const { + return nullaryExpr(gen); + } + + // Tensor generation + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorGeneratorOp + generate(const Generator& generator) const { + return TensorGeneratorOp(derived(), generator); + } + + // Generic unary operation support. + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp + unaryExpr(const CustomUnaryOp& func) const { + return TensorCwiseUnaryOp(derived(), func); + } + + // Coefficient-wise unary operators + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + operator-() const { + return unaryExpr(internal::scalar_opposite_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + sqrt() const { + return unaryExpr(internal::scalar_sqrt_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + sign() const { + return unaryExpr(internal::scalar_sign_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + rsqrt() const { + return unaryExpr(internal::scalar_rsqrt_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + square() const { + return unaryExpr(internal::scalar_square_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + cube() const { + return unaryExpr(internal::scalar_cube_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + inverse() const { + return unaryExpr(internal::scalar_inverse_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + tanh() const { + return unaryExpr(internal::scalar_tanh_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + lgamma() const { + return unaryExpr(internal::scalar_lgamma_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + digamma() const { + return unaryExpr(internal::scalar_digamma_op()); + } + + // igamma(a = this, x = other) + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + igamma(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_igamma_op()); + } + + // igammac(a = this, x = other) + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + igammac(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_igammac_op()); + } + + // zeta(x = this, q = other) + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + zeta(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_zeta_op()); + } + + // polygamma(n = this, x = other) + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + polygamma(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_polygamma_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + erf() const { + return unaryExpr(internal::scalar_erf_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + erfc() const { + return unaryExpr(internal::scalar_erfc_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + sigmoid() const { + return unaryExpr(internal::scalar_sigmoid_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + exp() const { + return unaryExpr(internal::scalar_exp_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + expm1() const { + return unaryExpr(internal::scalar_expm1_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + log() const { + return unaryExpr(internal::scalar_log_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + log1p() const { + return unaryExpr(internal::scalar_log1p_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + abs() const { + return unaryExpr(internal::scalar_abs_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + conjugate() const { + return unaryExpr(internal::scalar_conjugate_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp >, const Derived> + pow(Scalar exponent) const { + return unaryExpr(internal::bind2nd_op >(exponent)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + real() const { + return unaryExpr(internal::scalar_real_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + imag() const { + return unaryExpr(internal::scalar_imag_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp >, const Derived> + operator+ (Scalar rhs) const { + return unaryExpr(internal::bind2nd_op >(rhs)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE friend + const TensorCwiseUnaryOp >, const Derived> + operator+ (Scalar lhs, const Derived& rhs) { + return rhs.unaryExpr(internal::bind1st_op >(lhs)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp >, const Derived> + operator- (Scalar rhs) const { + EIGEN_STATIC_ASSERT((NumTraits::IsSigned || internal::is_same >::value), YOU_MADE_A_PROGRAMMING_MISTAKE); + return unaryExpr(internal::bind2nd_op >(rhs)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE friend + const TensorCwiseUnaryOp >, const Derived> + operator- (Scalar lhs, const Derived& rhs) { + return rhs.unaryExpr(internal::bind1st_op >(lhs)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp >, const Derived> + operator* (Scalar rhs) const { + return unaryExpr(internal::bind2nd_op >(rhs)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE friend + const TensorCwiseUnaryOp >, const Derived> + operator* (Scalar lhs, const Derived& rhs) { + return rhs.unaryExpr(internal::bind1st_op >(lhs)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp >, const Derived> + operator/ (Scalar rhs) const { + return unaryExpr(internal::bind2nd_op >(rhs)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE friend + const TensorCwiseUnaryOp >, const Derived> + operator/ (Scalar lhs, const Derived& rhs) { + return rhs.unaryExpr(internal::bind1st_op >(lhs)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + operator% (Scalar rhs) const { + EIGEN_STATIC_ASSERT(NumTraits::IsInteger, YOU_MADE_A_PROGRAMMING_MISTAKE_TRY_MOD); + return unaryExpr(internal::scalar_mod_op(rhs)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseBinaryOp, const Derived, const TensorCwiseNullaryOp, const Derived> > + cwiseMax(Scalar threshold) const { + return cwiseMax(constant(threshold)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseBinaryOp, const Derived, const TensorCwiseNullaryOp, const Derived> > + cwiseMin(Scalar threshold) const { + return cwiseMin(constant(threshold)); + } + + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorConversionOp + cast() const { + return TensorConversionOp(derived()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + round() const { + return unaryExpr(internal::scalar_round_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + ceil() const { + return unaryExpr(internal::scalar_ceil_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + floor() const { + return unaryExpr(internal::scalar_floor_op()); + } + + // Generic binary operation support. + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseBinaryOp + binaryExpr(const OtherDerived& other, const CustomBinaryOp& func) const { + return TensorCwiseBinaryOp(derived(), other, func); + } + + // Coefficient-wise binary operators. + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + operator+(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_sum_op()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + operator-(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_difference_op()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + operator*(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_product_op()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + operator/(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_quotient_op()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + cwiseMax(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_max_op()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + cwiseMin(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_min_op()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp + operator&&(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_boolean_and_op()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp + operator||(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_boolean_or_op()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp + operator^(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_boolean_xor_op()); + } + + // Comparisons and tests. + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + operator<(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_cmp_op()); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + operator<=(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_cmp_op()); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + operator>(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_cmp_op()); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + operator>=(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_cmp_op()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + operator==(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_cmp_op()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + operator!=(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_cmp_op()); + } + + // comparisons and tests for Scalars + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseBinaryOp, const Derived, const TensorCwiseNullaryOp, const Derived> > + operator<(Scalar threshold) const { + return operator<(constant(threshold)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseBinaryOp, const Derived, const TensorCwiseNullaryOp, const Derived> > + operator<=(Scalar threshold) const { + return operator<=(constant(threshold)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseBinaryOp, const Derived, const TensorCwiseNullaryOp, const Derived> > + operator>(Scalar threshold) const { + return operator>(constant(threshold)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseBinaryOp, const Derived, const TensorCwiseNullaryOp, const Derived> > + operator>=(Scalar threshold) const { + return operator>=(constant(threshold)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseBinaryOp, const Derived, const TensorCwiseNullaryOp, const Derived> > + operator==(Scalar threshold) const { + return operator==(constant(threshold)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseBinaryOp, const Derived, const TensorCwiseNullaryOp, const Derived> > + operator!=(Scalar threshold) const { + return operator!=(constant(threshold)); + } + + // Checks + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + (isnan)() const { + return unaryExpr(internal::scalar_isnan_op()); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + (isinf)() const { + return unaryExpr(internal::scalar_isinf_op()); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + (isfinite)() const { + return unaryExpr(internal::scalar_isfinite_op()); + } + + // Coefficient-wise ternary operators. + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorSelectOp + select(const ThenDerived& thenTensor, const ElseDerived& elseTensor) const { + return TensorSelectOp(derived(), thenTensor.derived(), elseTensor.derived()); + } + + // Contractions. + typedef Eigen::IndexPair DimensionPair; + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorContractionOp + contract(const OtherDerived& other, const Dimensions& dims) const { + return TensorContractionOp(derived(), other.derived(), dims); + } + + // Convolutions. + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorConvolutionOp + convolve(const KernelDerived& kernel, const Dimensions& dims) const { + return TensorConvolutionOp(derived(), kernel.derived(), dims); + } + + // Fourier transforms + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorFFTOp + fft(const FFT& fft) const { + return TensorFFTOp(derived(), fft); + } + + // Scan. + typedef TensorScanOp, const Derived> TensorScanSumOp; + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorScanSumOp + cumsum(const Index& axis, bool exclusive = false) const { + return TensorScanSumOp(derived(), axis, exclusive); + } + + typedef TensorScanOp, const Derived> TensorScanProdOp; + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorScanProdOp + cumprod(const Index& axis, bool exclusive = false) const { + return TensorScanProdOp(derived(), axis, exclusive); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorScanOp + scan(const Index& axis, const Reducer& reducer, bool exclusive = false) const { + return TensorScanOp(derived(), axis, exclusive, reducer); + } + + // Reductions. + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReductionOp, const Dims, const Derived> + sum(const Dims& dims) const { + return TensorReductionOp, const Dims, const Derived>(derived(), dims, internal::SumReducer()); + } + + const TensorReductionOp, const DimensionList, const Derived> + sum() const { + DimensionList in_dims; + return TensorReductionOp, const DimensionList, const Derived>(derived(), in_dims, internal::SumReducer()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReductionOp, const Dims, const Derived> + mean(const Dims& dims) const { + return TensorReductionOp, const Dims, const Derived>(derived(), dims, internal::MeanReducer()); + } + + const TensorReductionOp, const DimensionList, const Derived> + mean() const { + DimensionList in_dims; + return TensorReductionOp, const DimensionList, const Derived>(derived(), in_dims, internal::MeanReducer()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReductionOp, const Dims, const Derived> + prod(const Dims& dims) const { + return TensorReductionOp, const Dims, const Derived>(derived(), dims, internal::ProdReducer()); + } + + const TensorReductionOp, const DimensionList, const Derived> + prod() const { + DimensionList in_dims; + return TensorReductionOp, const DimensionList, const Derived>(derived(), in_dims, internal::ProdReducer()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReductionOp, const Dims, const Derived> + maximum(const Dims& dims) const { + return TensorReductionOp, const Dims, const Derived>(derived(), dims, internal::MaxReducer()); + } + + const TensorReductionOp, const DimensionList, const Derived> + maximum() const { + DimensionList in_dims; + return TensorReductionOp, const DimensionList, const Derived>(derived(), in_dims, internal::MaxReducer()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReductionOp, const Dims, const Derived> + minimum(const Dims& dims) const { + return TensorReductionOp, const Dims, const Derived>(derived(), dims, internal::MinReducer()); + } + + const TensorReductionOp, const DimensionList, const Derived> + minimum() const { + DimensionList in_dims; + return TensorReductionOp, const DimensionList, const Derived>(derived(), in_dims, internal::MinReducer()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReductionOp > + all(const Dims& dims) const { + return cast().reduce(dims, internal::AndReducer()); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReductionOp, const TensorConversionOp > + all() const { + DimensionList in_dims; + return cast().reduce(in_dims, internal::AndReducer()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReductionOp > + any(const Dims& dims) const { + return cast().reduce(dims, internal::OrReducer()); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReductionOp, const TensorConversionOp > + any() const { + DimensionList in_dims; + return cast().reduce(in_dims, internal::OrReducer()); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorTupleReducerOp< + internal::ArgMaxTupleReducer >, + const array, const Derived> + argmax() const { + array in_dims; + for (int d = 0; d < NumDimensions; ++d) in_dims[d] = d; + return TensorTupleReducerOp< + internal::ArgMaxTupleReducer >, + const array, + const Derived>(derived(), internal::ArgMaxTupleReducer >(), -1, in_dims); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorTupleReducerOp< + internal::ArgMinTupleReducer >, + const array, const Derived> + argmin() const { + array in_dims; + for (int d = 0; d < NumDimensions; ++d) in_dims[d] = d; + return TensorTupleReducerOp< + internal::ArgMinTupleReducer >, + const array, + const Derived>(derived(), internal::ArgMinTupleReducer >(), -1, in_dims); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorTupleReducerOp< + internal::ArgMaxTupleReducer >, + const array, const Derived> + argmax(const int return_dim) const { + array in_dims; + in_dims[0] = return_dim; + return TensorTupleReducerOp< + internal::ArgMaxTupleReducer >, + const array, + const Derived>(derived(), internal::ArgMaxTupleReducer >(), return_dim, in_dims); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorTupleReducerOp< + internal::ArgMinTupleReducer >, + const array, const Derived> + argmin(const int return_dim) const { + array in_dims; + in_dims[0] = return_dim; + return TensorTupleReducerOp< + internal::ArgMinTupleReducer >, + const array, + const Derived>(derived(), internal::ArgMinTupleReducer >(), return_dim, in_dims); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReductionOp + reduce(const Dims& dims, const Reducer& reducer) const { + return TensorReductionOp(derived(), dims, reducer); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorBroadcastingOp + broadcast(const Broadcast& broadcast) const { + return TensorBroadcastingOp(derived(), broadcast); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorConcatenationOp + concatenate(const OtherDerived& other, Axis axis) const { + return TensorConcatenationOp(derived(), other.derived(), axis); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorPatchOp + extract_patches(const PatchDims& patch_dims) const { + return TensorPatchOp(derived(), patch_dims); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorImagePatchOp + extract_image_patches(const Index patch_rows = 1, const Index patch_cols = 1, + const Index row_stride = 1, const Index col_stride = 1, + const Index in_row_stride = 1, const Index in_col_stride = 1, + const PaddingType padding_type = PADDING_SAME, const Scalar padding_value = Scalar(0)) const { + return TensorImagePatchOp(derived(), patch_rows, patch_cols, row_stride, col_stride, + in_row_stride, in_col_stride, 1, 1, padding_type, padding_value); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorImagePatchOp + extract_image_patches(const Index patch_rows, const Index patch_cols, + const Index row_stride, const Index col_stride, + const Index in_row_stride, const Index in_col_stride, + const Index row_inflate_stride, const Index col_inflate_stride, + const Index padding_top, const Index padding_bottom, + const Index padding_left,const Index padding_right, + const Scalar padding_value) const { + return TensorImagePatchOp(derived(), patch_rows, patch_cols, row_stride, col_stride, + in_row_stride, in_col_stride, row_inflate_stride, col_inflate_stride, + padding_top, padding_bottom, padding_left, padding_right, padding_value); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorVolumePatchOp + extract_volume_patches(const Index patch_planes, const Index patch_rows, const Index patch_cols, + const Index plane_stride = 1, const Index row_stride = 1, const Index col_stride = 1, + const PaddingType padding_type = PADDING_SAME, const Scalar padding_value = Scalar(0)) const { + return TensorVolumePatchOp(derived(), patch_planes, patch_rows, patch_cols, plane_stride, row_stride, col_stride, 1, 1, 1, 1, 1, 1, padding_type, padding_value); + } + + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorVolumePatchOp + extract_volume_patches(const Index patch_planes, const Index patch_rows, const Index patch_cols, + const Index plane_stride, const Index row_stride, const Index col_stride, + const Index plane_inflate_stride, const Index row_inflate_stride, const Index col_inflate_stride, + const Index padding_top_z, const Index padding_bottom_z, + const Index padding_top, const Index padding_bottom, + const Index padding_left, const Index padding_right, const Scalar padding_value = Scalar(0)) const { + return TensorVolumePatchOp(derived(), patch_planes, patch_rows, patch_cols, plane_stride, row_stride, col_stride, 1, 1, 1, plane_inflate_stride, row_inflate_stride, col_inflate_stride, padding_top_z, padding_bottom_z, padding_top, padding_bottom, padding_left, padding_right, padding_value); + } + + // Morphing operators. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorLayoutSwapOp + swap_layout() const { + return TensorLayoutSwapOp(derived()); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReshapingOp + reshape(const NewDimensions& newDimensions) const { + return TensorReshapingOp(derived(), newDimensions); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorSlicingOp + slice(const StartIndices& startIndices, const Sizes& sizes) const { + return TensorSlicingOp(derived(), startIndices, sizes); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorStridingSlicingOp + stridedSlice(const StartIndices& startIndices, const StopIndices& stopIndices, const Strides& strides) const { + return TensorStridingSlicingOp(derived(), startIndices, stopIndices, strides); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorChippingOp + chip(const Index offset) const { + return TensorChippingOp(derived(), offset, DimId); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorChippingOp + chip(const Index offset, const Index dim) const { + return TensorChippingOp(derived(), offset, dim); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReverseOp + reverse(const ReverseDimensions& rev) const { + return TensorReverseOp(derived(), rev); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorPaddingOp + pad(const PaddingDimensions& padding) const { + return TensorPaddingOp(derived(), padding, internal::scalar_cast_op()(0)); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorPaddingOp + pad(const PaddingDimensions& padding, const Scalar padding_value) const { + return TensorPaddingOp(derived(), padding, padding_value); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorShufflingOp + shuffle(const Shuffle& shuffle) const { + return TensorShufflingOp(derived(), shuffle); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorStridingOp + stride(const Strides& strides) const { + return TensorStridingOp(derived(), strides); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorInflationOp + inflate(const Strides& strides) const { + return TensorInflationOp(derived(), strides); + } + + // Returns a tensor containing index/value tuples + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorIndexTupleOp + index_tuples() const { + return TensorIndexTupleOp(derived()); + } + + // Support for custom unary and binary operations + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCustomUnaryOp customOp(const CustomUnaryFunc& op) const { + return TensorCustomUnaryOp(derived(), op); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCustomBinaryOp customOp(const OtherDerived& other, const CustomBinaryFunc& op) const { + return TensorCustomBinaryOp(derived(), other, op); + } + + // Force the evaluation of the expression. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorForcedEvalOp eval() const { + return TensorForcedEvalOp(derived()); + } + + protected: + template friend class Tensor; + template friend class TensorFixedSize; + template friend class TensorBase; + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Derived& derived() const { return *static_cast(this); } +}; + +template::value> +class TensorBase : public TensorBase { + public: + typedef internal::traits DerivedTraits; + typedef typename DerivedTraits::Scalar Scalar; + typedef typename DerivedTraits::Index Index; + typedef Scalar CoeffReturnType; + static const int NumDimensions = DerivedTraits::NumDimensions; + + template friend class Tensor; + template friend class TensorFixedSize; + template friend class TensorBase; + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Derived& setZero() { + return setConstant(Scalar(0)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Derived& setConstant(const Scalar& val) { + return derived() = this->constant(val); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Derived& setRandom() { + return derived() = this->random(); + } + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Derived& setRandom() { + return derived() = this->template random(); + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Derived& setValues( + const typename internal::Initializer::InitList& vals) { + TensorEvaluator eval(derived(), DefaultDevice()); + internal::initialize_tensor(eval, vals); + return derived(); + } +#endif // EIGEN_HAS_VARIADIC_TEMPLATES + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Derived& operator+=(const OtherDerived& other) { + return derived() = derived() + other.derived(); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Derived& operator-=(const OtherDerived& other) { + return derived() = derived() - other.derived(); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Derived& operator*=(const OtherDerived& other) { + return derived() = derived() * other.derived(); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Derived& operator/=(const OtherDerived& other) { + return derived() = derived() / other.derived(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorLayoutSwapOp + swap_layout() const { + return TensorLayoutSwapOp(derived()); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorLayoutSwapOp + swap_layout() { + return TensorLayoutSwapOp(derived()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorConcatenationOp + concatenate(const OtherDerived& other, const Axis& axis) const { + return TensorConcatenationOp(derived(), other, axis); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorConcatenationOp + concatenate(const OtherDerived& other, const Axis& axis) { + return TensorConcatenationOp(derived(), other, axis); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReshapingOp + reshape(const NewDimensions& newDimensions) const { + return TensorReshapingOp(derived(), newDimensions); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorReshapingOp + reshape(const NewDimensions& newDimensions) { + return TensorReshapingOp(derived(), newDimensions); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorSlicingOp + slice(const StartIndices& startIndices, const Sizes& sizes) const { + return TensorSlicingOp(derived(), startIndices, sizes); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorSlicingOp + slice(const StartIndices& startIndices, const Sizes& sizes) { + return TensorSlicingOp(derived(), startIndices, sizes); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorStridingSlicingOp + stridedSlice(const StartIndices& startIndices, const StopIndices& stopIndices, const Strides& strides) const { + return TensorStridingSlicingOp(derived(), startIndices, stopIndices, strides); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorStridingSlicingOp + stridedSlice(const StartIndices& startIndices, const StopIndices& stopIndices, const Strides& strides) { + return TensorStridingSlicingOp(derived(), startIndices, stopIndices, strides); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorChippingOp + chip(const Index offset) const { + return TensorChippingOp(derived(), offset, DimId); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorChippingOp + chip(const Index offset) { + return TensorChippingOp(derived(), offset, DimId); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorChippingOp + chip(const Index offset, const Index dim) const { + return TensorChippingOp(derived(), offset, dim); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorChippingOp + chip(const Index offset, const Index dim) { + return TensorChippingOp(derived(), offset, dim); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReverseOp + reverse(const ReverseDimensions& rev) const { + return TensorReverseOp(derived(), rev); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorReverseOp + reverse(const ReverseDimensions& rev) { + return TensorReverseOp(derived(), rev); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorShufflingOp + shuffle(const Shuffle& shuffle) const { + return TensorShufflingOp(derived(), shuffle); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorShufflingOp + shuffle(const Shuffle& shuffle) { + return TensorShufflingOp(derived(), shuffle); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorStridingOp + stride(const Strides& strides) const { + return TensorStridingOp(derived(), strides); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorStridingOp + stride(const Strides& strides) { + return TensorStridingOp(derived(), strides); + } + + // Select the device on which to evaluate the expression. + template + TensorDevice device(const DeviceType& device) { + return TensorDevice(device, derived()); + } + + protected: + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Derived& derived() { return *static_cast(this); } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Derived& derived() const { return *static_cast(this); } +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_BASE_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBroadcasting.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBroadcasting.h new file mode 100644 index 00000000..23a74460 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBroadcasting.h @@ -0,0 +1,392 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_BROADCASTING_H +#define EIGEN_CXX11_TENSOR_TENSOR_BROADCASTING_H + +namespace Eigen { + +/** \class TensorBroadcasting + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor broadcasting class. + * + * + */ +namespace internal { +template +struct traits > : public traits +{ + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorBroadcastingOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorBroadcastingOp type; +}; + +template +struct is_input_scalar { + static const bool value = false; +}; +template <> +struct is_input_scalar > { + static const bool value = true; +}; +#ifndef EIGEN_EMULATE_CXX11_META_H +template +struct is_input_scalar > { + static const bool value = (Sizes::total_size == 1); +}; +#endif + +} // end namespace internal + + + +template +class TensorBroadcastingOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBroadcastingOp(const XprType& expr, const Broadcast& broadcast) + : m_xpr(expr), m_broadcast(broadcast) {} + + EIGEN_DEVICE_FUNC + const Broadcast& broadcast() const { return m_broadcast; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + protected: + typename XprType::Nested m_xpr; + const Broadcast m_broadcast; +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorBroadcastingOp XprType; + typedef typename XprType::Index Index; + static const int NumDims = internal::array_size::Dimensions>::value; + typedef DSizes Dimensions; + typedef typename XprType::Scalar Scalar; + typedef typename TensorEvaluator::Dimensions InputDimensions; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = true, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_broadcast(op.broadcast()),m_impl(op.expression(), device) + { + // The broadcasting op doesn't change the rank of the tensor. One can't broadcast a scalar + // and store the result in a scalar. Instead one should reshape the scalar into a a N-D + // tensor with N >= 1 of 1 element first and then broadcast. + EIGEN_STATIC_ASSERT((NumDims > 0), YOU_MADE_A_PROGRAMMING_MISTAKE); + const InputDimensions& input_dims = m_impl.dimensions(); + const Broadcast& broadcast = op.broadcast(); + for (int i = 0; i < NumDims; ++i) { + eigen_assert(input_dims[i] > 0); + m_dimensions[i] = input_dims[i] * broadcast[i]; + } + + if (static_cast(Layout) == static_cast(ColMajor)) { + m_inputStrides[0] = 1; + m_outputStrides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1]; + m_outputStrides[i] = m_outputStrides[i-1] * m_dimensions[i-1]; + } + } else { + m_inputStrides[NumDims-1] = 1; + m_outputStrides[NumDims-1] = 1; + for (int i = NumDims-2; i >= 0; --i) { + m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1]; + m_outputStrides[i] = m_outputStrides[i+1] * m_dimensions[i+1]; + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* /*data*/) { + m_impl.evalSubExprsIfNeeded(NULL); + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE CoeffReturnType coeff(Index index) const + { + if (internal::is_input_scalar::type>::value) { + return m_impl.coeff(0); + } + + if (static_cast(Layout) == static_cast(ColMajor)) { + return coeffColMajor(index); + } else { + return coeffRowMajor(index); + } + } + + // TODO: attempt to speed this up. The integer divisions and modulo are slow + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeffColMajor(Index index) const + { + Index inputIndex = 0; + for (int i = NumDims - 1; i > 0; --i) { + const Index idx = index / m_outputStrides[i]; + if (internal::index_statically_eq(i, 1)) { + eigen_assert(idx < m_impl.dimensions()[i]); + inputIndex += idx * m_inputStrides[i]; + } else { + if (internal::index_statically_eq(i, 1)) { + eigen_assert(idx % m_impl.dimensions()[i] == 0); + } else { + inputIndex += (idx % m_impl.dimensions()[i]) * m_inputStrides[i]; + } + } + index -= idx * m_outputStrides[i]; + } + if (internal::index_statically_eq(0, 1)) { + eigen_assert(index < m_impl.dimensions()[0]); + inputIndex += index; + } else { + if (internal::index_statically_eq(0, 1)) { + eigen_assert(index % m_impl.dimensions()[0] == 0); + } else { + inputIndex += (index % m_impl.dimensions()[0]); + } + } + return m_impl.coeff(inputIndex); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeffRowMajor(Index index) const + { + Index inputIndex = 0; + for (int i = 0; i < NumDims - 1; ++i) { + const Index idx = index / m_outputStrides[i]; + if (internal::index_statically_eq(i, 1)) { + eigen_assert(idx < m_impl.dimensions()[i]); + inputIndex += idx * m_inputStrides[i]; + } else { + if (internal::index_statically_eq(i, 1)) { + eigen_assert(idx % m_impl.dimensions()[i] == 0); + } else { + inputIndex += (idx % m_impl.dimensions()[i]) * m_inputStrides[i]; + } + } + index -= idx * m_outputStrides[i]; + } + if (internal::index_statically_eq(NumDims-1, 1)) { + eigen_assert(index < m_impl.dimensions()[NumDims-1]); + inputIndex += index; + } else { + if (internal::index_statically_eq(NumDims-1, 1)) { + eigen_assert(index % m_impl.dimensions()[NumDims-1] == 0); + } else { + inputIndex += (index % m_impl.dimensions()[NumDims-1]); + } + } + return m_impl.coeff(inputIndex); + } + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketReturnType packet(Index index) const + { + if (internal::is_input_scalar::type>::value) { + return internal::pset1(m_impl.coeff(0)); + } + + if (static_cast(Layout) == static_cast(ColMajor)) { + return packetColMajor(index); + } else { + return packetRowMajor(index); + } + } + + // Ignore the LoadMode and always use unaligned loads since we can't guarantee + // the alignment at compile time. + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetColMajor(Index index) const + { + EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index+PacketSize-1 < dimensions().TotalSize()); + + const Index originalIndex = index; + + Index inputIndex = 0; + for (int i = NumDims - 1; i > 0; --i) { + const Index idx = index / m_outputStrides[i]; + if (internal::index_statically_eq(i, 1)) { + eigen_assert(idx < m_impl.dimensions()[i]); + inputIndex += idx * m_inputStrides[i]; + } else { + if (internal::index_statically_eq(i, 1)) { + eigen_assert(idx % m_impl.dimensions()[i] == 0); + } else { + inputIndex += (idx % m_impl.dimensions()[i]) * m_inputStrides[i]; + } + } + index -= idx * m_outputStrides[i]; + } + Index innermostLoc; + if (internal::index_statically_eq(0, 1)) { + eigen_assert(index < m_impl.dimensions()[0]); + innermostLoc = index; + } else { + if (internal::index_statically_eq(0, 1)) { + eigen_assert(index % m_impl.dimensions()[0] == 0); + innermostLoc = 0; + } else { + innermostLoc = index % m_impl.dimensions()[0]; + } + } + inputIndex += innermostLoc; + + // Todo: this could be extended to the second dimension if we're not + // broadcasting alongside the first dimension, and so on. + if (innermostLoc + PacketSize <= m_impl.dimensions()[0]) { + return m_impl.template packet(inputIndex); + } else { + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + values[0] = m_impl.coeff(inputIndex); + for (int i = 1; i < PacketSize; ++i) { + values[i] = coeffColMajor(originalIndex+i); + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetRowMajor(Index index) const + { + EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index+PacketSize-1 < dimensions().TotalSize()); + + const Index originalIndex = index; + + Index inputIndex = 0; + for (int i = 0; i < NumDims - 1; ++i) { + const Index idx = index / m_outputStrides[i]; + if (internal::index_statically_eq(i, 1)) { + eigen_assert(idx < m_impl.dimensions()[i]); + inputIndex += idx * m_inputStrides[i]; + } else { + if (internal::index_statically_eq(i, 1)) { + eigen_assert(idx % m_impl.dimensions()[i] == 0); + } else { + inputIndex += (idx % m_impl.dimensions()[i]) * m_inputStrides[i]; + } + } + index -= idx * m_outputStrides[i]; + } + Index innermostLoc; + if (internal::index_statically_eq(NumDims-1, 1)) { + eigen_assert(index < m_impl.dimensions()[NumDims-1]); + innermostLoc = index; + } else { + if (internal::index_statically_eq(NumDims-1, 1)) { + eigen_assert(index % m_impl.dimensions()[NumDims-1] == 0); + innermostLoc = 0; + } else { + innermostLoc = index % m_impl.dimensions()[NumDims-1]; + } + } + inputIndex += innermostLoc; + + // Todo: this could be extended to the second dimension if we're not + // broadcasting alongside the first dimension, and so on. + if (innermostLoc + PacketSize <= m_impl.dimensions()[NumDims-1]) { + return m_impl.template packet(inputIndex); + } else { + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + values[0] = m_impl.coeff(inputIndex); + for (int i = 1; i < PacketSize; ++i) { + values[i] = coeffRowMajor(originalIndex+i); + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + double compute_cost = TensorOpCost::AddCost(); + if (NumDims > 0) { + for (int i = NumDims - 1; i > 0; --i) { + compute_cost += TensorOpCost::DivCost(); + if (internal::index_statically_eq(i, 1)) { + compute_cost += + TensorOpCost::MulCost() + TensorOpCost::AddCost(); + } else { + if (!internal::index_statically_eq(i, 1)) { + compute_cost += TensorOpCost::MulCost() + + TensorOpCost::ModCost() + + TensorOpCost::AddCost(); + } + } + compute_cost += + TensorOpCost::MulCost() + TensorOpCost::AddCost(); + } + } + return m_impl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, compute_cost, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + const TensorEvaluator& impl() const { return m_impl; } + + Broadcast functor() const { return m_broadcast; } + + protected: + const Broadcast m_broadcast; + Dimensions m_dimensions; + array m_outputStrides; + array m_inputStrides; + TensorEvaluator m_impl; +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_BROADCASTING_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorChipping.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorChipping.h new file mode 100644 index 00000000..c46a778b --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorChipping.h @@ -0,0 +1,400 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CHIPPING_H +#define EIGEN_CXX11_TENSOR_TENSOR_CHIPPING_H + +namespace Eigen { + +/** \class TensorKChippingReshaping + * \ingroup CXX11_Tensor_Module + * + * \brief A chip is a thin slice, corresponding to a column or a row in a 2-d tensor. + * + * + */ + +namespace internal { +template +struct traits > : public traits +{ + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions - 1; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorChippingOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorChippingOp type; +}; + +template +struct DimensionId +{ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DimensionId(DenseIndex dim) { + EIGEN_UNUSED_VARIABLE(dim); + eigen_assert(dim == DimId); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex actualDim() const { + return DimId; + } +}; +template <> +struct DimensionId +{ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DimensionId(DenseIndex dim) : actual_dim(dim) { + eigen_assert(dim >= 0); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex actualDim() const { + return actual_dim; + } + private: + const DenseIndex actual_dim; +}; + + +} // end namespace internal + + + +template +class TensorChippingOp : public TensorBase > +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorChippingOp(const XprType& expr, const Index offset, const Index dim) + : m_xpr(expr), m_offset(offset), m_dim(dim) { + } + + EIGEN_DEVICE_FUNC + const Index offset() const { return m_offset; } + EIGEN_DEVICE_FUNC + const Index dim() const { return m_dim.actualDim(); } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorChippingOp& operator = (const TensorChippingOp& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorChippingOp& operator = (const OtherDerived& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + protected: + typename XprType::Nested m_xpr; + const Index m_offset; + const internal::DimensionId m_dim; +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorChippingOp XprType; + static const int NumInputDims = internal::array_size::Dimensions>::value; + static const int NumDims = NumInputDims-1; + typedef typename XprType::Index Index; + typedef DSizes Dimensions; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + + enum { + // Alignment can't be guaranteed at compile time since it depends on the + // slice offsets. + IsAligned = false, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device), m_dim(op.dim()), m_device(device), m_offset(op.offset()) + { + EIGEN_STATIC_ASSERT((NumInputDims >= 1), YOU_MADE_A_PROGRAMMING_MISTAKE); + eigen_assert(NumInputDims > m_dim.actualDim()); + + const typename TensorEvaluator::Dimensions& input_dims = m_impl.dimensions(); + eigen_assert(op.offset() < input_dims[m_dim.actualDim()]); + + int j = 0; + for (int i = 0; i < NumInputDims; ++i) { + if (i != m_dim.actualDim()) { + m_dimensions[j] = input_dims[i]; + ++j; + } + } + + m_stride = 1; + m_inputStride = 1; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = 0; i < m_dim.actualDim(); ++i) { + m_stride *= input_dims[i]; + m_inputStride *= input_dims[i]; + } + } else { + for (int i = NumInputDims-1; i > m_dim.actualDim(); --i) { + m_stride *= input_dims[i]; + m_inputStride *= input_dims[i]; + } + } + m_inputStride *= input_dims[m_dim.actualDim()]; + m_inputOffset = m_stride * op.offset(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* /*data*/) { + m_impl.evalSubExprsIfNeeded(NULL); + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + return m_impl.coeff(srcCoeff(index)); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index+PacketSize-1 < dimensions().TotalSize()); + + if ((static_cast(Layout) == static_cast(ColMajor) && m_dim.actualDim() == 0) || + (static_cast(Layout) == static_cast(RowMajor) && m_dim.actualDim() == NumInputDims-1)) { + // m_stride is equal to 1, so let's avoid the integer division. + eigen_assert(m_stride == 1); + Index inputIndex = index * m_inputStride + m_inputOffset; + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + for (int i = 0; i < PacketSize; ++i) { + values[i] = m_impl.coeff(inputIndex); + inputIndex += m_inputStride; + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } else if ((static_cast(Layout) == static_cast(ColMajor) && m_dim.actualDim() == NumInputDims - 1) || + (static_cast(Layout) == static_cast(RowMajor) && m_dim.actualDim() == 0)) { + // m_stride is aways greater than index, so let's avoid the integer division. + eigen_assert(m_stride > index); + return m_impl.template packet(index + m_inputOffset); + } else { + const Index idx = index / m_stride; + const Index rem = index - idx * m_stride; + if (rem + PacketSize <= m_stride) { + Index inputIndex = idx * m_inputStride + m_inputOffset + rem; + return m_impl.template packet(inputIndex); + } else { + // Cross the stride boundary. Fallback to slow path. + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + for (int i = 0; i < PacketSize; ++i) { + values[i] = coeff(index); + ++index; + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + double cost = 0; + if ((static_cast(Layout) == static_cast(ColMajor) && + m_dim.actualDim() == 0) || + (static_cast(Layout) == static_cast(RowMajor) && + m_dim.actualDim() == NumInputDims - 1)) { + cost += TensorOpCost::MulCost() + TensorOpCost::AddCost(); + } else if ((static_cast(Layout) == static_cast(ColMajor) && + m_dim.actualDim() == NumInputDims - 1) || + (static_cast(Layout) == static_cast(RowMajor) && + m_dim.actualDim() == 0)) { + cost += TensorOpCost::AddCost(); + } else { + cost += 3 * TensorOpCost::MulCost() + TensorOpCost::DivCost() + + 3 * TensorOpCost::AddCost(); + } + + return m_impl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, cost, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType* data() const { + CoeffReturnType* result = const_cast(m_impl.data()); + if (((static_cast(Layout) == static_cast(ColMajor) && m_dim.actualDim() == NumDims) || + (static_cast(Layout) == static_cast(RowMajor) && m_dim.actualDim() == 0)) && + result) { + return result + m_inputOffset; + } else { + return NULL; + } + } + + /// used by sycl + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex dimId() const { + return m_dim.actualDim(); + } + + /// used by sycl + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const DenseIndex& offset() const { + return m_offset; + } + /// required by sycl in order to extract the accessor + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const TensorEvaluator& impl() const { return m_impl; } + + protected: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index srcCoeff(Index index) const + { + Index inputIndex; + if ((static_cast(Layout) == static_cast(ColMajor) && m_dim.actualDim() == 0) || + (static_cast(Layout) == static_cast(RowMajor) && m_dim.actualDim() == NumInputDims-1)) { + // m_stride is equal to 1, so let's avoid the integer division. + eigen_assert(m_stride == 1); + inputIndex = index * m_inputStride + m_inputOffset; + } else if ((static_cast(Layout) == static_cast(ColMajor) && m_dim.actualDim() == NumInputDims-1) || + (static_cast(Layout) == static_cast(RowMajor) && m_dim.actualDim() == 0)) { + // m_stride is aways greater than index, so let's avoid the integer division. + eigen_assert(m_stride > index); + inputIndex = index + m_inputOffset; + } else { + const Index idx = index / m_stride; + inputIndex = idx * m_inputStride + m_inputOffset; + index -= idx * m_stride; + inputIndex += index; + } + return inputIndex; + } + + Dimensions m_dimensions; + Index m_stride; + Index m_inputOffset; + Index m_inputStride; + TensorEvaluator m_impl; + const internal::DimensionId m_dim; + const Device& m_device; +// required by sycl + const DenseIndex m_offset; + +}; + + +// Eval as lvalue +template +struct TensorEvaluator, Device> + : public TensorEvaluator, Device> +{ + typedef TensorEvaluator, Device> Base; + typedef TensorChippingOp XprType; + static const int NumInputDims = internal::array_size::Dimensions>::value; + static const int NumDims = NumInputDims-1; + typedef typename XprType::Index Index; + typedef DSizes Dimensions; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = false, + PacketAccess = TensorEvaluator::PacketAccess, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : Base(op, device) + { } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index) + { + return this->m_impl.coeffRef(this->srcCoeff(index)); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketReturnType& x) + { + EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + + if ((static_cast(this->Layout) == static_cast(ColMajor) && this->m_dim.actualDim() == 0) || + (static_cast(this->Layout) == static_cast(RowMajor) && this->m_dim.actualDim() == NumInputDims-1)) { + // m_stride is equal to 1, so let's avoid the integer division. + eigen_assert(this->m_stride == 1); + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + internal::pstore(values, x); + Index inputIndex = index * this->m_inputStride + this->m_inputOffset; + for (int i = 0; i < PacketSize; ++i) { + this->m_impl.coeffRef(inputIndex) = values[i]; + inputIndex += this->m_inputStride; + } + } else if ((static_cast(this->Layout) == static_cast(ColMajor) && this->m_dim.actualDim() == NumInputDims-1) || + (static_cast(this->Layout) == static_cast(RowMajor) && this->m_dim.actualDim() == 0)) { + // m_stride is aways greater than index, so let's avoid the integer division. + eigen_assert(this->m_stride > index); + this->m_impl.template writePacket(index + this->m_inputOffset, x); + } else { + const Index idx = index / this->m_stride; + const Index rem = index - idx * this->m_stride; + if (rem + PacketSize <= this->m_stride) { + const Index inputIndex = idx * this->m_inputStride + this->m_inputOffset + rem; + this->m_impl.template writePacket(inputIndex, x); + } else { + // Cross stride boundary. Fallback to slow path. + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + internal::pstore(values, x); + for (int i = 0; i < PacketSize; ++i) { + this->coeffRef(index) = values[i]; + ++index; + } + } + } + } +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_CHIPPING_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConcatenation.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConcatenation.h new file mode 100644 index 00000000..2c7ba961 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConcatenation.h @@ -0,0 +1,367 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONCATENATION_H +#define EIGEN_CXX11_TENSOR_TENSOR_CONCATENATION_H + +namespace Eigen { + +/** \class TensorConcatenationOp + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor concatenation class. + * + * + */ +namespace internal { +template +struct traits > +{ + // Type promotion to handle the case where the types of the lhs and the rhs are different. + typedef typename promote_storage_type::ret Scalar; + typedef typename promote_storage_type::StorageKind, + typename traits::StorageKind>::ret StorageKind; + typedef typename promote_index_type::Index, + typename traits::Index>::type Index; + typedef typename LhsXprType::Nested LhsNested; + typedef typename RhsXprType::Nested RhsNested; + typedef typename remove_reference::type _LhsNested; + typedef typename remove_reference::type _RhsNested; + static const int NumDimensions = traits::NumDimensions; + static const int Layout = traits::Layout; + enum { Flags = 0 }; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorConcatenationOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorConcatenationOp type; +}; + +} // end namespace internal + + +template +class TensorConcatenationOp : public TensorBase, WriteAccessors> +{ + public: + typedef typename internal::traits::Scalar Scalar; + typedef typename internal::traits::StorageKind StorageKind; + typedef typename internal::traits::Index Index; + typedef typename internal::nested::type Nested; + typedef typename internal::promote_storage_type::ret CoeffReturnType; + typedef typename NumTraits::Real RealScalar; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorConcatenationOp(const LhsXprType& lhs, const RhsXprType& rhs, Axis axis) + : m_lhs_xpr(lhs), m_rhs_xpr(rhs), m_axis(axis) {} + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + lhsExpression() const { return m_lhs_xpr; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + rhsExpression() const { return m_rhs_xpr; } + + EIGEN_DEVICE_FUNC const Axis& axis() const { return m_axis; } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorConcatenationOp& operator = (const TensorConcatenationOp& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorConcatenationOp& operator = (const OtherDerived& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + protected: + typename LhsXprType::Nested m_lhs_xpr; + typename RhsXprType::Nested m_rhs_xpr; + const Axis m_axis; +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorConcatenationOp XprType; + typedef typename XprType::Index Index; + static const int NumDims = internal::array_size::Dimensions>::value; + static const int RightNumDims = internal::array_size::Dimensions>::value; + typedef DSizes Dimensions; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + enum { + IsAligned = false, + PacketAccess = TensorEvaluator::PacketAccess & TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_leftImpl(op.lhsExpression(), device), m_rightImpl(op.rhsExpression(), device), m_axis(op.axis()) + { + EIGEN_STATIC_ASSERT((static_cast(TensorEvaluator::Layout) == static_cast(TensorEvaluator::Layout) || NumDims == 1), YOU_MADE_A_PROGRAMMING_MISTAKE); + EIGEN_STATIC_ASSERT((NumDims == RightNumDims), YOU_MADE_A_PROGRAMMING_MISTAKE); + EIGEN_STATIC_ASSERT((NumDims > 0), YOU_MADE_A_PROGRAMMING_MISTAKE); + + eigen_assert(0 <= m_axis && m_axis < NumDims); + const Dimensions& lhs_dims = m_leftImpl.dimensions(); + const Dimensions& rhs_dims = m_rightImpl.dimensions(); + { + int i = 0; + for (; i < m_axis; ++i) { + eigen_assert(lhs_dims[i] > 0); + eigen_assert(lhs_dims[i] == rhs_dims[i]); + m_dimensions[i] = lhs_dims[i]; + } + eigen_assert(lhs_dims[i] > 0); // Now i == m_axis. + eigen_assert(rhs_dims[i] > 0); + m_dimensions[i] = lhs_dims[i] + rhs_dims[i]; + for (++i; i < NumDims; ++i) { + eigen_assert(lhs_dims[i] > 0); + eigen_assert(lhs_dims[i] == rhs_dims[i]); + m_dimensions[i] = lhs_dims[i]; + } + } + + if (static_cast(Layout) == static_cast(ColMajor)) { + m_leftStrides[0] = 1; + m_rightStrides[0] = 1; + m_outputStrides[0] = 1; + + for (int j = 1; j < NumDims; ++j) { + m_leftStrides[j] = m_leftStrides[j-1] * lhs_dims[j-1]; + m_rightStrides[j] = m_rightStrides[j-1] * rhs_dims[j-1]; + m_outputStrides[j] = m_outputStrides[j-1] * m_dimensions[j-1]; + } + } else { + m_leftStrides[NumDims - 1] = 1; + m_rightStrides[NumDims - 1] = 1; + m_outputStrides[NumDims - 1] = 1; + + for (int j = NumDims - 2; j >= 0; --j) { + m_leftStrides[j] = m_leftStrides[j+1] * lhs_dims[j+1]; + m_rightStrides[j] = m_rightStrides[j+1] * rhs_dims[j+1]; + m_outputStrides[j] = m_outputStrides[j+1] * m_dimensions[j+1]; + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + // TODO(phli): Add short-circuit memcpy evaluation if underlying data are linear? + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* /*data*/) + { + m_leftImpl.evalSubExprsIfNeeded(NULL); + m_rightImpl.evalSubExprsIfNeeded(NULL); + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() + { + m_leftImpl.cleanup(); + m_rightImpl.cleanup(); + } + + // TODO(phli): attempt to speed this up. The integer divisions and modulo are slow. + // See CL/76180724 comments for more ideas. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + // Collect dimension-wise indices (subs). + array subs; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i > 0; --i) { + subs[i] = index / m_outputStrides[i]; + index -= subs[i] * m_outputStrides[i]; + } + subs[0] = index; + } else { + for (int i = 0; i < NumDims - 1; ++i) { + subs[i] = index / m_outputStrides[i]; + index -= subs[i] * m_outputStrides[i]; + } + subs[NumDims - 1] = index; + } + + const Dimensions& left_dims = m_leftImpl.dimensions(); + if (subs[m_axis] < left_dims[m_axis]) { + Index left_index; + if (static_cast(Layout) == static_cast(ColMajor)) { + left_index = subs[0]; + for (int i = 1; i < NumDims; ++i) { + left_index += (subs[i] % left_dims[i]) * m_leftStrides[i]; + } + } else { + left_index = subs[NumDims - 1]; + for (int i = NumDims - 2; i >= 0; --i) { + left_index += (subs[i] % left_dims[i]) * m_leftStrides[i]; + } + } + return m_leftImpl.coeff(left_index); + } else { + subs[m_axis] -= left_dims[m_axis]; + const Dimensions& right_dims = m_rightImpl.dimensions(); + Index right_index; + if (static_cast(Layout) == static_cast(ColMajor)) { + right_index = subs[0]; + for (int i = 1; i < NumDims; ++i) { + right_index += (subs[i] % right_dims[i]) * m_rightStrides[i]; + } + } else { + right_index = subs[NumDims - 1]; + for (int i = NumDims - 2; i >= 0; --i) { + right_index += (subs[i] % right_dims[i]) * m_rightStrides[i]; + } + } + return m_rightImpl.coeff(right_index); + } + } + + // TODO(phli): Add a real vectorization. + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + const int packetSize = internal::unpacket_traits::size; + EIGEN_STATIC_ASSERT((packetSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index + packetSize - 1 < dimensions().TotalSize()); + + EIGEN_ALIGN_MAX CoeffReturnType values[packetSize]; + for (int i = 0; i < packetSize; ++i) { + values[i] = coeff(index+i); + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + const double compute_cost = NumDims * (2 * TensorOpCost::AddCost() + + 2 * TensorOpCost::MulCost() + + TensorOpCost::DivCost() + + TensorOpCost::ModCost()); + const double lhs_size = m_leftImpl.dimensions().TotalSize(); + const double rhs_size = m_rightImpl.dimensions().TotalSize(); + return (lhs_size / (lhs_size + rhs_size)) * + m_leftImpl.costPerCoeff(vectorized) + + (rhs_size / (lhs_size + rhs_size)) * + m_rightImpl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, compute_cost); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + /// required by sycl in order to extract the accessor + const TensorEvaluator& left_impl() const { return m_leftImpl; } + /// required by sycl in order to extract the accessor + const TensorEvaluator& right_impl() const { return m_rightImpl; } + /// required by sycl in order to extract the accessor + const Axis& axis() const { return m_axis; } + + protected: + Dimensions m_dimensions; + array m_outputStrides; + array m_leftStrides; + array m_rightStrides; + TensorEvaluator m_leftImpl; + TensorEvaluator m_rightImpl; + const Axis m_axis; +}; + +// Eval as lvalue +template + struct TensorEvaluator, Device> + : public TensorEvaluator, Device> +{ + typedef TensorEvaluator, Device> Base; + typedef TensorConcatenationOp XprType; + typedef typename Base::Dimensions Dimensions; + enum { + IsAligned = false, + PacketAccess = TensorEvaluator::PacketAccess & TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(XprType& op, const Device& device) + : Base(op, device) + { + EIGEN_STATIC_ASSERT((static_cast(Layout) == static_cast(ColMajor)), YOU_MADE_A_PROGRAMMING_MISTAKE); + } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index) + { + // Collect dimension-wise indices (subs). + array subs; + for (int i = Base::NumDims - 1; i > 0; --i) { + subs[i] = index / this->m_outputStrides[i]; + index -= subs[i] * this->m_outputStrides[i]; + } + subs[0] = index; + + const Dimensions& left_dims = this->m_leftImpl.dimensions(); + if (subs[this->m_axis] < left_dims[this->m_axis]) { + Index left_index = subs[0]; + for (int i = 1; i < Base::NumDims; ++i) { + left_index += (subs[i] % left_dims[i]) * this->m_leftStrides[i]; + } + return this->m_leftImpl.coeffRef(left_index); + } else { + subs[this->m_axis] -= left_dims[this->m_axis]; + const Dimensions& right_dims = this->m_rightImpl.dimensions(); + Index right_index = subs[0]; + for (int i = 1; i < Base::NumDims; ++i) { + right_index += (subs[i] % right_dims[i]) * this->m_rightStrides[i]; + } + return this->m_rightImpl.coeffRef(right_index); + } + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketReturnType& x) + { + const int packetSize = internal::unpacket_traits::size; + EIGEN_STATIC_ASSERT((packetSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index + packetSize - 1 < this->dimensions().TotalSize()); + + EIGEN_ALIGN_MAX CoeffReturnType values[packetSize]; + internal::pstore(values, x); + for (int i = 0; i < packetSize; ++i) { + coeffRef(index+i) = values[i]; + } + } +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_CONCATENATION_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContraction.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContraction.h new file mode 100644 index 00000000..bf4a476d --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContraction.h @@ -0,0 +1,909 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_H +#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_H + +namespace Eigen { + +/** \class TensorContraction + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor contraction class. + * + * + */ +namespace internal { +#if defined(EIGEN_VECTORIZE_AVX) && defined(EIGEN_USE_LIBXSMM) +template +void pack_simple(Scalar * dst, const Scalar * src, Index cols, Index rows, Index lddst, Index ldsrc) { + size_t psize = packet_traits::size; // Packet size + typedef typename packet_traits::type Packet; // Packet type + size_t alignment = psize*sizeof(Scalar); // Needed alignment + if (rows % psize == 0 && (lddst*sizeof(Scalar)) % alignment == 0 && + (ldsrc*sizeof(Scalar)) % alignment == 0 && + reinterpret_cast(src) % alignment == 0 && + reinterpret_cast(dst) % alignment == 0) { + // Optimized version using packets + size_t num_packets = rows / psize; + for (Index col = 0; col < cols; ++col) { + EIGEN_ASM_COMMENT("begin pack_simple inner copy"); + // Unrolled manually 4 times. + for (size_t i=0; i < num_packets/4; ++i) { + internal::pstore(dst, internal::pload(src)); + dst += psize; src += psize; + internal::pstore(dst, internal::pload(src)); + dst += psize; src += psize; + internal::pstore(dst, internal::pload(src)); + dst += psize; src += psize; + internal::pstore(dst, internal::pload(src)); + dst += psize; src += psize; + } + for (size_t i=0; i < num_packets%4; ++i) { + internal::pstore(dst, internal::pload(src)); + dst += psize; src += psize; + } + dst += lddst - num_packets*psize; + src += ldsrc - num_packets*psize; + EIGEN_ASM_COMMENT("end pack_simple inner copy"); + } + } else { + // Naive memcpy calls + for (Index col = 0; col < cols; ++col) { + memcpy(dst + col*lddst, src + col*ldsrc, rows*sizeof(Scalar)); + } + } +} + +template + struct libxsmm_wrapper { + libxsmm_wrapper() {} + libxsmm_wrapper(int, int, int, int, int, int, int, float, float, int) {} + void operator()(const LhsScalar*, const RhsScalar*, Scalar*) {} + void operator()(const LhsScalar*, const RhsScalar*, Scalar*, const LhsScalar*, const RhsScalar*, const Scalar*) {} + }; + + template<> + struct libxsmm_wrapper: public libxsmm_mmfunction { + libxsmm_wrapper(): libxsmm_mmfunction() {} + libxsmm_wrapper(int flags, int m, int n, int k, int lda, int ldb, int ldc, float alpha, float beta, int prefetch) : + libxsmm_mmfunction(flags, m, n, k, lda, ldb, ldc, alpha, beta, prefetch) {} + }; + + template<> + struct libxsmm_wrapper: public libxsmm_mmfunction { + libxsmm_wrapper(): libxsmm_mmfunction() {} + libxsmm_wrapper(int flags, int m, int n, int k, int lda, int ldb, int ldc, float alpha, float beta, int prefetch) : + libxsmm_mmfunction(flags, m, n, k, lda, ldb, ldc, alpha, beta, prefetch) {} + }; +#endif + + +template +struct traits > +{ + // Type promotion to handle the case where the types of the lhs and the rhs are different. + typedef typename gebp_traits::type, + typename remove_const::type>::ResScalar Scalar; + + typedef typename promote_storage_type::StorageKind, + typename traits::StorageKind>::ret StorageKind; + typedef typename promote_index_type::Index, + typename traits::Index>::type Index; + typedef typename LhsXprType::Nested LhsNested; + typedef typename RhsXprType::Nested RhsNested; + typedef typename remove_reference::type _LhsNested; + typedef typename remove_reference::type _RhsNested; + + // From NumDims below. + static const int NumDimensions = traits::NumDimensions + traits::NumDimensions - 2 * array_size::value; + static const int Layout = traits::Layout; + + enum { + Flags = 0 + }; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorContractionOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorContractionOp type; +}; + +template +struct traits, Device_> > { + typedef Indices_ Indices; + typedef LeftArgType_ LeftArgType; + typedef RightArgType_ RightArgType; + typedef Device_ Device; + + // From NumDims below. + static const int NumDimensions = traits::NumDimensions + traits::NumDimensions - 2 * array_size::value; +}; + +} // end namespace internal + +template +class TensorContractionOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename internal::gebp_traits::ResScalar CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorContractionOp( + const LhsXprType& lhs, const RhsXprType& rhs, const Indices& dims) + : m_lhs_xpr(lhs), m_rhs_xpr(rhs), m_indices(dims) {} + + EIGEN_DEVICE_FUNC + const Indices& indices() const { return m_indices; } + + /** \returns the nested expressions */ + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + lhsExpression() const { return m_lhs_xpr; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + rhsExpression() const { return m_rhs_xpr; } + + protected: + typename LhsXprType::Nested m_lhs_xpr; + typename RhsXprType::Nested m_rhs_xpr; + const Indices m_indices; +}; + + +template +struct TensorContractionEvaluatorBase +{ + typedef typename internal::traits::Indices Indices; + typedef typename internal::traits::LeftArgType LeftArgType; + typedef typename internal::traits::RightArgType RightArgType; + typedef typename internal::traits::Device Device; + + typedef TensorContractionOp XprType; + typedef typename internal::remove_const::type Scalar; + typedef typename XprType::Index Index; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + + enum { + IsAligned = true, + PacketAccess = (internal::unpacket_traits::size > 1), + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = true + }; + + // Most of the code is assuming that both input tensors are ColMajor. If the + // inputs are RowMajor, we will "cheat" by swapping the LHS and RHS: + // If we want to compute A * B = C, where A is LHS and B is RHS, the code + // will pretend B is LHS and A is RHS. + typedef typename internal::conditional< + static_cast(Layout) == static_cast(ColMajor), LeftArgType, RightArgType>::type EvalLeftArgType; + typedef typename internal::conditional< + static_cast(Layout) == static_cast(ColMajor), RightArgType, LeftArgType>::type EvalRightArgType; + + static const int LDims = + internal::array_size::Dimensions>::value; + static const int RDims = + internal::array_size::Dimensions>::value; + static const int ContractDims = internal::array_size::value; + static const int NumDims = LDims + RDims - 2 * ContractDims; + + typedef array contract_t; + typedef array left_nocontract_t; + typedef array right_nocontract_t; + + typedef DSizes Dimensions; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorContractionEvaluatorBase(const XprType& op, const Device& device) + : m_leftImpl(choose(Cond(Layout) == static_cast(ColMajor)>(), + op.lhsExpression(), op.rhsExpression()), device), + m_rightImpl(choose(Cond(Layout) == static_cast(ColMajor)>(), + op.rhsExpression(), op.lhsExpression()), device), + m_device(device), + m_result(NULL) { + EIGEN_STATIC_ASSERT((static_cast(TensorEvaluator::Layout) == + static_cast(TensorEvaluator::Layout)), + YOU_MADE_A_PROGRAMMING_MISTAKE); + + + DSizes eval_left_dims; + DSizes eval_right_dims; + array, ContractDims> eval_op_indices; + if (static_cast(Layout) == static_cast(ColMajor)) { + // For ColMajor, we keep using the existing dimensions + for (int i = 0; i < LDims; i++) { + eval_left_dims[i] = m_leftImpl.dimensions()[i]; + } + for (int i = 0; i < RDims; i++) { + eval_right_dims[i] = m_rightImpl.dimensions()[i]; + } + // We keep the pairs of contracting indices. + for (int i = 0; i < ContractDims; i++) { + eval_op_indices[i].first = op.indices()[i].first; + eval_op_indices[i].second = op.indices()[i].second; + } + } else { + // For RowMajor, we need to reverse the existing dimensions + for (int i = 0; i < LDims; i++) { + eval_left_dims[i] = m_leftImpl.dimensions()[LDims - i - 1]; + } + for (int i = 0; i < RDims; i++) { + eval_right_dims[i] = m_rightImpl.dimensions()[RDims - i - 1]; + } + // We need to flip all the pairs of contracting indices as well as + // reversing the dimensions. + for (int i = 0; i < ContractDims; i++) { + eval_op_indices[i].first = LDims - 1 - op.indices()[ContractDims - 1 - i].second; + eval_op_indices[i].second = RDims - 1 - op.indices()[ContractDims - 1 - i].first; + } + } + + // Check for duplicate axes and make sure the first index in eval_op_indices + // is increasing. Using O(n^2) sorting is OK since ContractDims is small + for (int i = 0; i < ContractDims; i++) { + for (int j = i + 1; j < ContractDims; j++) { + eigen_assert(eval_op_indices[j].first != eval_op_indices[i].first && + eval_op_indices[j].second != eval_op_indices[i].second && + "contraction axes should be unique"); + if (eval_op_indices[j].first < eval_op_indices[i].first) { + numext::swap(eval_op_indices[j], eval_op_indices[i]); + } + } + } + + array lhs_strides; + lhs_strides[0] = 1; + for (int i = 0; i < LDims-1; ++i) { + lhs_strides[i+1] = lhs_strides[i] * eval_left_dims[i]; + } + + array rhs_strides; + rhs_strides[0] = 1; + for (int i = 0; i < RDims-1; ++i) { + rhs_strides[i+1] = rhs_strides[i] * eval_right_dims[i]; + } + + if (m_i_strides.size() > 0) m_i_strides[0] = 1; + if (m_j_strides.size() > 0) m_j_strides[0] = 1; + if (m_k_strides.size() > 0) m_k_strides[0] = 1; + + m_i_size = 1; + m_j_size = 1; + m_k_size = 1; + + // To compute the dimension, we simply concatenate the non-contracting + // dimensions of the left and then the right tensor. Additionally, we also + // compute the strides corresponding to the left non-contracting + // dimensions and right non-contracting dimensions. + m_lhs_inner_dim_contiguous = true; + int dim_idx = 0; + unsigned int nocontract_idx = 0; + + for (int i = 0; i < LDims; i++) { + // find if we are contracting on index i of left tensor + bool contracting = false; + for (int j = 0; j < ContractDims; j++) { + if (eval_op_indices[j].first == i) { + contracting = true; + break; + } + } + if (!contracting) { + // add dimension size to output dimensions + m_dimensions[dim_idx] = eval_left_dims[i]; + m_left_nocontract_strides[nocontract_idx] = lhs_strides[i]; + if (dim_idx != i) { + m_lhs_inner_dim_contiguous = false; + } + if (nocontract_idx+1 < internal::array_size::value) { + m_i_strides[nocontract_idx+1] = + m_i_strides[nocontract_idx] * eval_left_dims[i]; + } else { + m_i_size = m_i_strides[nocontract_idx] * eval_left_dims[i]; + } + dim_idx++; + nocontract_idx++; + } + } + + nocontract_idx = 0; + for (int i = 0; i < RDims; i++) { + bool contracting = false; + // find if we are contracting on index i of right tensor + for (int j = 0; j < ContractDims; j++) { + if (eval_op_indices[j].second == i) { + contracting = true; + break; + } + } + if (!contracting) { + m_dimensions[dim_idx] = eval_right_dims[i]; + if (nocontract_idx+1 < internal::array_size::value) { + m_j_strides[nocontract_idx+1] = + m_j_strides[nocontract_idx] * eval_right_dims[i]; + } else { + m_j_size = m_j_strides[nocontract_idx] * eval_right_dims[i]; + } + m_right_nocontract_strides[nocontract_idx] = rhs_strides[i]; + dim_idx++; + nocontract_idx++; + } + } + + // Now compute the strides corresponding to the contracting dimensions. We + // assumed above that non-contracting axes are represented in the same order + // in the matrix as they are in the tensor. This is not the case for + // contracting axes. As the contracting axes must be of the same size in + // each tensor, we'll only look at the first tensor here. + m_rhs_inner_dim_contiguous = true; + m_rhs_inner_dim_reordered = false; + for (int i = 0; i < ContractDims; i++) { + Index left = eval_op_indices[i].first; + Index right = eval_op_indices[i].second; + + Index size = eval_left_dims[left]; + eigen_assert(size == eval_right_dims[right] && + "Contraction axes must be same size"); + + if (i+1 < static_cast(internal::array_size::value)) { + m_k_strides[i+1] = m_k_strides[i] * size; + } else { + m_k_size = m_k_strides[i] * size; + } + m_left_contracting_strides[i] = lhs_strides[left]; + m_right_contracting_strides[i] = rhs_strides[right]; + + if (i > 0 && right < eval_op_indices[i-1].second) { + m_rhs_inner_dim_reordered = true; + } + if (right != i) { + m_rhs_inner_dim_contiguous = false; + } + } + + EnableXSMMIfPossible(eval_op_indices); + + // If the layout is RowMajor, we need to reverse the m_dimensions + if (static_cast(Layout) == static_cast(RowMajor)) { + for (int i = 0, j = NumDims - 1; i < j; i++, j--) { + numext::swap(m_dimensions[i], m_dimensions[j]); + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar * data) { + m_leftImpl.evalSubExprsIfNeeded(NULL); + m_rightImpl.evalSubExprsIfNeeded(NULL); + if (data) { + evalTo(data); + return false; + } else { + m_result = static_cast(m_device.allocate(dimensions().TotalSize() * sizeof(Scalar))); + evalTo(m_result); + return true; + } + } + + EIGEN_DEVICE_FUNC void evalTo(Scalar* buffer) const { + if (this->m_lhs_inner_dim_contiguous) { + if (this->m_rhs_inner_dim_contiguous) { + if (this->m_rhs_inner_dim_reordered) { + static_cast(this)->template evalProduct(buffer); + } + else { + static_cast(this)->template evalProduct(buffer); + } + } + else { + if (this->m_rhs_inner_dim_reordered) { + static_cast(this)->template evalProduct(buffer); + } + else { + static_cast(this)->template evalProduct(buffer); + } + } + } + else { + if (this->m_rhs_inner_dim_contiguous) { + if (this->m_rhs_inner_dim_reordered) { + static_cast(this)->template evalProduct(buffer); + } + else { + static_cast(this)->template evalProduct(buffer); + } + } + else { + if (this->m_rhs_inner_dim_reordered) { + static_cast(this)->template evalProduct(buffer); + } + else { + static_cast(this)->template evalProduct(buffer); + } + } + } + } + + template + EIGEN_DEVICE_FUNC void evalGemv(Scalar* buffer) const { + const Index rows = m_i_size; + const Index cols = m_k_size; + + typedef typename internal::remove_const::type LhsScalar; + typedef typename internal::remove_const::type RhsScalar; + typedef TensorEvaluator LeftEvaluator; + typedef TensorEvaluator RightEvaluator; + const Index lhs_packet_size = internal::unpacket_traits::size; + const Index rhs_packet_size = internal::unpacket_traits::size; + const int lhs_alignment = LeftEvaluator::IsAligned ? Aligned : Unaligned; + const int rhs_alignment = RightEvaluator::IsAligned ? Aligned : Unaligned; + typedef internal::TensorContractionInputMapper LhsMapper; + + typedef internal::TensorContractionInputMapper RhsMapper; + + LhsMapper lhs(m_leftImpl, m_left_nocontract_strides, m_i_strides, + m_left_contracting_strides, m_k_strides); + RhsMapper rhs(m_rightImpl, m_right_nocontract_strides, m_j_strides, + m_right_contracting_strides, m_k_strides); + + const Scalar alpha(1); + const Index resIncr(1); + + // zero out the result buffer (which must be of size at least rows * sizeof(Scalar) + m_device.memset(buffer, 0, rows * sizeof(Scalar)); + + internal::general_matrix_vector_product::run( + rows, cols, lhs, rhs, + buffer, resIncr, alpha); + } + + template + EIGEN_DEVICE_FUNC void evalGemm(Scalar* buffer) const { + #if defined(EIGEN_VECTORIZE_AVX) && defined(EIGEN_USE_LIBXSMM) + if (m_can_use_xsmm) { + evalGemmXSMM(buffer); + return; + } + #endif + + // columns in left side, rows in right side + const Index k = this->m_k_size; + + // rows in left side + const Index m = this->m_i_size; + + // columns in right side + const Index n = this->m_j_size; + + // zero out the result buffer (which must be of size at least m * n * sizeof(Scalar) + this->m_device.memset(buffer, 0, m * n * sizeof(Scalar)); + + // define mr, nr, and all of my data mapper types + typedef typename internal::remove_const::type LhsScalar; + typedef typename internal::remove_const::type RhsScalar; + typedef typename internal::gebp_traits Traits; + + const Index nr = Traits::nr; + const Index mr = Traits::mr; + + typedef TensorEvaluator LeftEvaluator; + typedef TensorEvaluator RightEvaluator; + + const Index lhs_packet_size = internal::unpacket_traits::size; + const Index rhs_packet_size = internal::unpacket_traits::size; + + typedef internal::TensorContractionInputMapper LhsMapper; + + typedef internal::TensorContractionInputMapper RhsMapper; + + typedef internal::blas_data_mapper OutputMapper; + + // Declare GEBP packing and kernel structs + internal::gemm_pack_lhs pack_lhs; + internal::gemm_pack_rhs pack_rhs; + + internal::gebp_kernel gebp; + + // initialize data mappers + LhsMapper lhs(this->m_leftImpl, this->m_left_nocontract_strides, this->m_i_strides, + this->m_left_contracting_strides, this->m_k_strides); + + RhsMapper rhs(this->m_rightImpl, this->m_right_nocontract_strides, this->m_j_strides, + this->m_right_contracting_strides, this->m_k_strides); + + OutputMapper output(buffer, m); + + // Sizes of the blocks to load in cache. See the Goto paper for details. + internal::TensorContractionBlocking blocking(k, m, n, 1); + const Index kc = blocking.kc(); + const Index mc = numext::mini(m, blocking.mc()); + const Index nc = numext::mini(n, blocking.nc()); + const Index sizeA = mc * kc; + const Index sizeB = kc * nc; + + LhsScalar* blockA = static_cast(this->m_device.allocate(sizeA * sizeof(LhsScalar))); + RhsScalar* blockB = static_cast(this->m_device.allocate(sizeB * sizeof(RhsScalar))); + + for(Index i2=0; i2m_device.deallocate(blockA); + this->m_device.deallocate(blockB); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_leftImpl.cleanup(); + m_rightImpl.cleanup(); + + if (m_result != NULL) { + m_device.deallocate(m_result); + m_result = NULL; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const { + return m_result[index]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool) const { + return TensorOpCost(sizeof(CoeffReturnType), 0, 0); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const { + return internal::ploadt(m_result + index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar* data() const { return m_result; } + +protected: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void EnableXSMMIfPossible(const array, ContractDims>& eval_op_indices) { + m_can_use_xsmm = false; + +#if defined(EIGEN_VECTORIZE_AVX) && defined(EIGEN_USE_LIBXSMM) + typedef typename internal::remove_const::type LhsScalar; + typedef typename internal::remove_const::type RhsScalar; + if (!std::is_same::value || + !std::is_same::value || + !(std::is_same::value || + std::is_same::value) || + m_leftImpl.data() == NULL || + m_rightImpl.data() == NULL) { + return; + } + + // Check if we can use faster matmul algorithms. For contraction to be + // equivalent to matmul, we need both lhs and rhs contracting dims sequences + // to be either a prefix or suffix of all dims. Also, the order of both + // must be the same, so we don't have to do reordering. + // For example: + // * OK: lhs 4D, rhs 4D, contraction: [(0, 2), (1, 3)] + // * BAD: lhs 3D, rhs 3D, contraction: [(1,1)] + // * BAD: lhs 3D, rhs 3D, contraction: [(0, 0), (2, 2)] + // * BAD: lhs 3D, rhs 3D, contraction: [(0, 2), (1, 1)] + // Depending if contraction dims are prefix or suffix of all dims we need to + // pre-transpose matrices in matmul algorithm: + // lhs: prefix -> transpose, suffix -> no transpose + // rhs: prefix -> no transpose, suffix -> transpose + // For example, for lhs 2D, rhs 2D, contraction [(1, 0)] is regular, + // non-transposed matmul. + if (ContractDims == 0) { + // This case is totally uninteresting, filter it out to avoid problems + // with iterations in further tests. + return; + } + + // Check if RHS dims list is increasing. LHS already is, so if not, the + // order is different and we cannot do matmul. + for (int i = 1; i < ContractDims; i++) { + if (eval_op_indices[i].second < eval_op_indices[i-1].second) { + return; + } + } + + // Check if no holes. + int diff; + for (int i = 1; i < ContractDims; i++) { + // LHS contract dims are sorted to form an increasing seq. + diff = eval_op_indices[i].first - eval_op_indices[i-1].first; + if (diff != 1) { + return; + } + // Now we may already assume RHS contract dims seq is increasing too. + diff = eval_op_indices[i].second - eval_op_indices[i-1].second; + if (diff != 1) { + return; + } + } + + // Check if suffix or prefix. + if (eval_op_indices[0].first != 0 && + eval_op_indices[ContractDims-1].first != LDims-1) { + return; + } + if (eval_op_indices[0].second != 0 && + eval_op_indices[ContractDims-1].second != RDims-1) { + return; + } + + m_can_use_xsmm = true; +#else + EIGEN_UNUSED_VARIABLE(eval_op_indices); +#endif + } + +#if defined(EIGEN_VECTORIZE_AVX) && defined(EIGEN_USE_LIBXSMM) + EIGEN_DEVICE_FUNC void evalGemmXSMM(Scalar* buffer) const { + // columns in left side, rows in right side + const Index k = this->m_k_size; + + // rows in left side + const Index m = this->m_i_size; + + // columns in right side + const Index n = this->m_j_size; + + const bool transposeA = !m_lhs_inner_dim_contiguous; + const bool transposeB = !m_rhs_inner_dim_contiguous; + + typedef typename internal::remove_const::type LhsScalar; + typedef typename internal::remove_const::type RhsScalar; + + internal::TensorXsmmContractionBlocking blocking( + k, m, n, 1, transposeA, transposeB); + + // Outer blocks sizes + const Index mc_outer = blocking.outer_m(); + const Index nc_outer = blocking.outer_n(); + const Index kc_outer = blocking.outer_k(); + // Inner blocks sizes + const Index mc = blocking.mc(); + const Index nc = blocking.nc(); + const Index kc = blocking.kc(); + // Decisions whether we should copy parts of matrices + const bool copyA = blocking.copyA(); + const bool copyB = blocking.copyB(); + + const LhsScalar* leftData = m_leftImpl.data(); + const RhsScalar* rightData = m_rightImpl.data(); + + const libxsmm_blasint stride_A = static_cast(transposeA ? k : m); + const libxsmm_blasint stride_B = static_cast(transposeB ? n : k); + const libxsmm_blasint stride_C = static_cast(m); + + const libxsmm_blasint stride_blockA = static_cast(mc); + // Use bigger stride to avoid hitting same cache line too often. + // This consistently gives +~0.5 Gflops. + const libxsmm_blasint stride_panelB = static_cast( + kc % 32 == 0 ? kc + 16 : kc + ); + + // Kernel for the general case (not edges) + internal::libxsmm_wrapper kernel; + + LhsScalar* blockA = NULL; + RhsScalar* panelB = NULL; + + if (copyA) { + blockA = static_cast(this->m_device.allocate(mc * kc * sizeof(LhsScalar))); + } + if (copyB) { + panelB = static_cast(this->m_device.allocate(nc_outer * stride_panelB * sizeof(RhsScalar))); + } + + const Index kernel_stride_A = copyA ? stride_blockA : stride_A; + const Index kernel_stride_B = copyB ? stride_panelB : stride_B; + kernel = internal::libxsmm_wrapper(0, mc, nc, kc, kernel_stride_A, kernel_stride_B, stride_C, 1, 1, blocking.prefetch()); + + // Outer blocking + for (Index ki_outer = 0; ki_outer < k; ki_outer += kc_outer) { + for (Index mi_outer = 0; mi_outer < m; mi_outer += mc_outer) { + for (Index ni_outer = 0; ni_outer < n; ni_outer += nc_outer) { + using numext::mini; + + Index actual_nc_outer = mini(ni_outer+nc_outer, n) - ni_outer; + + // Inner blocking + for (Index ki = ki_outer; ki < mini(ki_outer+kc_outer, k); ki += kc) { + const Index actual_kc = mini(ki_outer+kc_outer, mini(ki+kc, k)) - ki; + const float beta = ki == 0 ? 0 : 1; + + if (copyB) { + if (transposeB) { + libxsmm_otrans(panelB, rightData + ki*stride_B + ni_outer, sizeof(RhsScalar), actual_nc_outer, actual_kc, stride_B, stride_panelB); + } else { + internal::pack_simple(panelB, rightData + ni_outer*stride_B + ki, actual_nc_outer, actual_kc, stride_panelB, stride_B); + } + } + + for (Index mi = mi_outer; mi < mini(mi_outer+mc_outer, m); mi += mc) { + const Index actual_mc = mini(mi_outer+mc_outer, mini(mi+mc, m)) - mi; + + const LhsScalar* a = transposeA ? leftData + mi*stride_A + ki : + leftData + ki*stride_A + mi; + + if (copyA) { + if (transposeA) { + libxsmm_otrans(blockA, a, sizeof(LhsScalar), actual_kc, actual_mc, stride_A, stride_blockA); + } else { + internal::pack_simple(blockA, a, actual_kc, actual_mc, stride_blockA, stride_A); + } + } + const LhsScalar* actual_a = copyA ? blockA : a; + + for (Index ni = ni_outer; ni < mini(ni_outer+nc_outer, n); ni += nc) { + const Index actual_nc = mini(ni_outer+nc_outer, mini(ni+nc, n)) - ni; + + const RhsScalar* b = rightData + ni*stride_B + ki; + Scalar* c = buffer + ni*stride_C + mi; + const Scalar* cp = c + nc*stride_C; + + const RhsScalar* actual_b = copyB ? panelB + (ni-ni_outer)*stride_panelB : b; + const RhsScalar* bp = copyB ? panelB + nc*stride_panelB : b + nc*stride_B; + + if (actual_mc == mc && actual_kc == kc && actual_nc == nc && beta == 1) { + // Most used, cached kernel. + kernel(actual_a, actual_b, c, actual_a, bp, cp); + } else { + // Edges - use libxsmm kernel cache. + internal::libxsmm_wrapper(0, actual_mc, actual_nc, actual_kc, kernel_stride_A, kernel_stride_B, stride_C, 1, beta, blocking.prefetch())(actual_a, actual_b, c, actual_a, bp, cp); + } + } + } + } + } + } + } + + if (copyA) { + this->m_device.deallocate(blockA); + } + if (copyB) { + this->m_device.deallocate(panelB); + } + } +#endif + + // Prevent assignment + TensorContractionEvaluatorBase& operator = (const TensorContractionEvaluatorBase&); + Dimensions m_dimensions; + + contract_t m_k_strides; + contract_t m_left_contracting_strides; + contract_t m_right_contracting_strides; + + bool m_lhs_inner_dim_contiguous; + bool m_rhs_inner_dim_contiguous; + bool m_rhs_inner_dim_reordered; + + left_nocontract_t m_i_strides; + right_nocontract_t m_j_strides; + left_nocontract_t m_left_nocontract_strides; + right_nocontract_t m_right_nocontract_strides; + + Index m_i_size; + Index m_j_size; + Index m_k_size; + + TensorEvaluator m_leftImpl; + TensorEvaluator m_rightImpl; + const Device& m_device; + Scalar* m_result; + bool m_can_use_xsmm; +}; + + +// evaluator for default device +template +struct TensorEvaluator, Device> : + public TensorContractionEvaluatorBase< + TensorEvaluator, Device> > { + typedef TensorEvaluator, Device> Self; + typedef TensorContractionEvaluatorBase Base; + + typedef TensorContractionOp XprType; + typedef typename internal::remove_const::type Scalar; + typedef typename XprType::Index Index; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + + enum { + Layout = TensorEvaluator::Layout + }; + + // Most of the code is assuming that both input tensors are ColMajor. If the + // inputs are RowMajor, we will "cheat" by swapping the LHS and RHS: + // If we want to compute A * B = C, where A is LHS and B is RHS, the code + // will pretend B is LHS and A is RHS. + typedef typename internal::conditional< + static_cast(Layout) == static_cast(ColMajor), LeftArgType, RightArgType>::type EvalLeftArgType; + typedef typename internal::conditional< + static_cast(Layout) == static_cast(ColMajor), RightArgType, LeftArgType>::type EvalRightArgType; + + static const int LDims = + internal::array_size::Dimensions>::value; + static const int RDims = + internal::array_size::Dimensions>::value; + static const int ContractDims = internal::array_size::value; + + typedef array contract_t; + typedef array left_nocontract_t; + typedef array right_nocontract_t; + + static const int NumDims = LDims + RDims - 2 * ContractDims; + + // Could we use NumDimensions here? + typedef DSizes Dimensions; + + EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device) : + Base(op, device) { } + + template + EIGEN_DEVICE_FUNC void evalProduct(Scalar* buffer) const { + if (this->m_j_size == 1) { + this->template evalGemv(buffer); + return; + } + + this->template evalGemm(buffer); + } +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionBlocking.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionBlocking.h new file mode 100644 index 00000000..d34f9cae --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionBlocking.h @@ -0,0 +1,190 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_BLOCKING_H +#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_BLOCKING_H + + +namespace Eigen { +namespace internal { + +enum { + ShardByRow = 0, + ShardByCol = 1 +}; + + +// Default Blocking Strategy +template +class TensorContractionBlocking { + public: + + typedef typename LhsMapper::Scalar LhsScalar; + typedef typename RhsMapper::Scalar RhsScalar; + + EIGEN_DEVICE_FUNC TensorContractionBlocking(Index k, Index m, Index n, Index num_threads = 1) : + kc_(k), mc_(m), nc_(n) + { + if (ShardingType == ShardByCol) { + computeProductBlockingSizes(kc_, mc_, nc_, num_threads); + } + else { + computeProductBlockingSizes(kc_, nc_, mc_, num_threads); + } + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Index kc() const { return kc_; } + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Index mc() const { return mc_; } + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Index nc() const { return nc_; } + + private: + Index kc_; + Index mc_; + Index nc_; +}; + + + +#if defined(EIGEN_USE_LIBXSMM) +template +class TensorXsmmContractionBlocking { + public: + TensorXsmmContractionBlocking(Index k, Index m, Index n, + size_t max_num_threads = 1, bool transposeA = false, + bool transposeB = false): + k_(k), m_(m), n_(n), transposeA_(transposeA), + transposeB_(transposeB), num_threads_(max_num_threads) { +#ifdef EIGEN_TEST_SPECIFIC_BLOCKING_SIZES + if (EIGEN_TEST_SPECIFIC_BLOCKING_SIZES) { + mc_ = EIGEN_TEST_SPECIFIC_BLOCKING_SIZE_M; + kc_ = EIGEN_TEST_SPECIFIC_BLOCKING_SIZE_K; + nc_ = EIGEN_TEST_SPECIFIC_BLOCKING_SIZE_N; + outer_m_ = EIGEN_TEST_SPECIFIC_OUTER_BLOCKING_SIZE_M; + outer_k_ = EIGEN_TEST_SPECIFIC_OUTER_BLOCKING_SIZE_K; + outer_n_ = EIGEN_TEST_SPECIFIC_OUTER_BLOCKING_SIZE_N; + copyA_ = EIGEN_TEST_SPECIFIC_BLOCKING_COPY_A; + copyB_ = EIGEN_TEST_SPECIFIC_BLOCKING_COPY_B; + outer_m_ = outer_m_ != 0 ? outer_m_ : m; + outer_k_ = outer_k_ != 0 ? outer_k_ : k; + outer_n_ = outer_n_ != 0 ? outer_n_ : n; + } +#else + // Defaults, possibly overriden per-platform. + copyA_ = true; + copyB_ = false; + + // If the matrix is small enough, don't do blocking, just call single xsmm + // kernel. + if (static_cast(m)*k*n <= LIBXSMM_THRESHOLD) { + mc_ = m; kc_ = k; nc_ = n; + outer_m_ = m; outer_k_ = k; outer_n_ = n; + copyA_ = false; copyB_ = false; + } else { + int arch = libxsmm_cpuid_x86(); + + if (arch == LIBXSMM_X86_AVX512_CORE) { + // skylake + mc_ = 64; kc_ = 64; nc_ = 24; + outer_m_ = 512; outer_k_ = 512; outer_n_ = 24*22; + // Hack to use this kernel architecture as the other one has performance + // issues (no hardware prefetching). + // TODO(nishantpatil): This should be removed if the issues are fixed, + // or this one becomes the default. + setenv("LIBXSMM_AVX512_CLASSIC_GEMM", "1", 1); + } else if (arch == LIBXSMM_X86_AVX2) { + // haswell + mc_ = 32; kc_ = 192; nc_ = 33; + outer_m_ = 512; outer_k_ = 3*192; outer_n_ = 33*16; + } else if (arch == LIBXSMM_X86_AVX) { + // ivybridge + mc_ = 32; kc_ = 192; nc_ = 48; + outer_m_ = 512; outer_k_ = 3*192; outer_n_ = 48*11; + } else { + // generic kernel size, usually performing well + mc_ = 32; kc_ = 128; nc_ = 32; + outer_m_ = 512; outer_k_ = 512; outer_n_ = 512; + } + + // Only copy if it makes the stride smaller. + copyA_ = copyA_ && (m > mc_); + copyB_ = copyB_ && (k > kc_); + } + + // We need to copy anyway if transposing + copyA_ = copyA_ || transposeA; + copyB_ = copyB_ || transposeB; + + // See libxsmm_gemm_prefetch_type definition in libxsmm_typedefs.h + prefetch_ = LIBXSMM_PREFETCH_AL2CL2BL2_VIA_C; + +#endif + + mc_ = mc_ > m ? m : mc_; + nc_ = nc_ > n ? n : nc_; + kc_ = kc_ > k ? k : kc_; + + size_t compute_parallelism = (m / mc_) * (n / nc_); + size_t pack_parallelism = 0; + if (copyA_) { + pack_parallelism += (m / mc_) * (k / kc_); + } + if (copyB_) { + pack_parallelism += (n / nc_) * (k / kc_); + } + size_t parallelism = numext::maxi(compute_parallelism, pack_parallelism); + + num_threads_ = numext::mini(num_threads_, + parallelism / MIN_JOBS_PER_THREAD); + num_threads_ = numext::maxi(num_threads_, 1); + + // For optimal performance outer block sizes should be multiplies of kernel + // sizes, or bigger than matrix size (=no outer blocking). + eigen_assert(outer_m_ % mc_ == 0 || outer_m_ >= m); + eigen_assert(outer_k_ % kc_ == 0 || outer_k_ >= k); + eigen_assert(outer_n_ % nc_ == 0 || outer_n_ >= n); + } + + EIGEN_ALWAYS_INLINE Index kc() const { return kc_; } + EIGEN_ALWAYS_INLINE Index mc() const { return mc_; } + EIGEN_ALWAYS_INLINE Index nc() const { return nc_; } + EIGEN_ALWAYS_INLINE Index outer_k() const { return outer_k_; } + EIGEN_ALWAYS_INLINE Index outer_m() const { return outer_m_; } + EIGEN_ALWAYS_INLINE Index outer_n() const { return outer_n_; } + EIGEN_ALWAYS_INLINE bool copyA() const { return copyA_; } + EIGEN_ALWAYS_INLINE bool copyB() const { return copyB_; } + EIGEN_ALWAYS_INLINE bool transposeA() const { return transposeA_; } + EIGEN_ALWAYS_INLINE bool transposeB() const { return transposeB_; } + EIGEN_ALWAYS_INLINE int num_threads() const { return num_threads_; } + EIGEN_ALWAYS_INLINE Index blocks_m() const { return divup(m_, mc_); } + EIGEN_ALWAYS_INLINE Index blocks_k() const { return divup(k_, kc_); } + EIGEN_ALWAYS_INLINE Index blocks_n() const { return divup(n_, nc_); } + EIGEN_ALWAYS_INLINE libxsmm_gemm_prefetch_type prefetch() const { + return prefetch_; + } + + private: + Index k_, m_, n_; + Index kc_, mc_, nc_; + Index outer_k_, outer_m_, outer_n_; + bool copyA_, copyB_, transposeA_, transposeB_; + size_t num_threads_; + + // Threshold for m*k*n to skip blocking and just call libxsmm + const double LIBXSMM_THRESHOLD = 80*80*80; + // For computing optimal number of threads - so that each thread gets at least + // that many jobs. + const double MIN_JOBS_PER_THREAD = 3; + libxsmm_gemm_prefetch_type prefetch_; +}; +#endif // EIGEN_USE_LIBXSMM + +} // end namespace internal +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_BLOCKING_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionCuda.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionCuda.h new file mode 100644 index 00000000..c04b784a --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionCuda.h @@ -0,0 +1,1386 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014-2015 Benoit Steiner +// Copyright (C) 2015 Navdeep Jaitly +// Copyright (C) 2014 Eric Martin +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_CUDA_H +#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_CUDA_H + +#if defined(EIGEN_USE_GPU) && defined(__CUDACC__) + +namespace Eigen { + +template +__device__ EIGEN_STRONG_INLINE void +EigenContractionKernelInternal(const LhsMapper lhs, const RhsMapper rhs, + const OutputMapper output, Scalar* lhs_shmem, Scalar* rhs_shmem, + const Index m_size, const Index n_size, const Index k_size) { + + const Index m_block_idx = blockIdx.x; + const Index n_block_idx = blockIdx.y; + + const Index base_m = 64 * m_block_idx; + const Index base_n = 64 * n_block_idx; + + // declare and initialize 64 registers for output 8x8 block + + // prefetch registers + Scalar lhs_pf0; + Scalar lhs_pf1; + Scalar lhs_pf2; + Scalar lhs_pf3; + Scalar lhs_pf4; + Scalar lhs_pf5; + Scalar lhs_pf6; + Scalar lhs_pf7; + + Scalar rhs_pf0; + Scalar rhs_pf1; + Scalar rhs_pf2; + Scalar rhs_pf3; + Scalar rhs_pf4; + Scalar rhs_pf5; + Scalar rhs_pf6; + Scalar rhs_pf7; + + // shared memory is formatted + // (contract idx in block, nocontract idx in block, block idx) + // where block idx is column major. This transposition limits the number of + // bank conflicts when reading the LHS. The core idea is that since the contracting + // index is shared by both sides, then the contracting index should be in threadIdx.x. + + // On the LHS, we pad each row inside of each block with an extra element. This makes + // each block 8 rows of 9 elements, which is 72 elements. This gives no bank conflicts + // on writes and very few 2-way conflicts on reads. There is an 8x8 grid of these blocks. + + // On the RHS we just add 8 padding elements to the end of each block. This gives no bank + // conflicts on writes and also none on reads. + + // storage indices + const Index lhs_store_idx_base = threadIdx.y * 72 + threadIdx.x * 9 + threadIdx.z; + const Index rhs_store_idx_base = threadIdx.y * 72 + threadIdx.z * 8 + threadIdx.x; + + const Index lhs_store_idx_0 = lhs_store_idx_base + 576 * 0; + const Index lhs_store_idx_1 = lhs_store_idx_base + 576 * 1; + const Index lhs_store_idx_2 = lhs_store_idx_base + 576 * 2; + const Index lhs_store_idx_3 = lhs_store_idx_base + 576 * 3; + const Index lhs_store_idx_4 = lhs_store_idx_base + 576 * 4; + const Index lhs_store_idx_5 = lhs_store_idx_base + 576 * 5; + const Index lhs_store_idx_6 = lhs_store_idx_base + 576 * 6; + const Index lhs_store_idx_7 = lhs_store_idx_base + 576 * 7; + + const Index rhs_store_idx_0 = rhs_store_idx_base + 576 * 0; + const Index rhs_store_idx_1 = rhs_store_idx_base + 576 * 1; + const Index rhs_store_idx_2 = rhs_store_idx_base + 576 * 2; + const Index rhs_store_idx_3 = rhs_store_idx_base + 576 * 3; + const Index rhs_store_idx_4 = rhs_store_idx_base + 576 * 4; + const Index rhs_store_idx_5 = rhs_store_idx_base + 576 * 5; + const Index rhs_store_idx_6 = rhs_store_idx_base + 576 * 6; + const Index rhs_store_idx_7 = rhs_store_idx_base + 576 * 7; + + // in the loading code, the following variables are important: + // threadIdx.x: the vertical position in an 8x8 block + // threadIdx.y: the vertical index of the 8x8 block in the grid + // threadIdx.z: the horizontal position in an 8x8 block + // k: the horizontal index of the 8x8 block in the grid + // + // The k parameter is implicit (it was the loop counter for a loop that went + // from 0 to <8, but now that loop is unrolled in the below code. + + const Index load_idx_vert = threadIdx.x + 8 * threadIdx.y; + const Index lhs_vert = base_m + load_idx_vert; + +#define prefetchIntoRegisters(base_k) \ + { \ + lhs_pf0 = conv(0); \ + lhs_pf1 = conv(0); \ + lhs_pf2 = conv(0); \ + lhs_pf3 = conv(0); \ + lhs_pf4 = conv(0); \ + lhs_pf5 = conv(0); \ + lhs_pf6 = conv(0); \ + lhs_pf7 = conv(0); \ + \ + rhs_pf0 = conv(0); \ + rhs_pf1 = conv(0); \ + rhs_pf2 = conv(0); \ + rhs_pf3 = conv(0); \ + rhs_pf4 = conv(0); \ + rhs_pf5 = conv(0); \ + rhs_pf6 = conv(0); \ + rhs_pf7 = conv(0); \ + \ + if (!needs_edge_check || lhs_vert < m_size) { \ + const Index lhs_horiz_0 = base_k + threadIdx.z + 0 * 8; \ + const Index lhs_horiz_1 = base_k + threadIdx.z + 1 * 8; \ + const Index lhs_horiz_2 = base_k + threadIdx.z + 2 * 8; \ + const Index lhs_horiz_3 = base_k + threadIdx.z + 3 * 8; \ + const Index lhs_horiz_4 = base_k + threadIdx.z + 4 * 8; \ + const Index lhs_horiz_5 = base_k + threadIdx.z + 5 * 8; \ + const Index lhs_horiz_6 = base_k + threadIdx.z + 6 * 8; \ + const Index lhs_horiz_7 = base_k + threadIdx.z + 7 * 8; \ + \ + if (!needs_edge_check || lhs_horiz_7 < k_size) { \ + lhs_pf0 = lhs(lhs_vert, lhs_horiz_0); \ + lhs_pf1 = lhs(lhs_vert, lhs_horiz_1); \ + lhs_pf2 = lhs(lhs_vert, lhs_horiz_2); \ + lhs_pf3 = lhs(lhs_vert, lhs_horiz_3); \ + lhs_pf4 = lhs(lhs_vert, lhs_horiz_4); \ + lhs_pf5 = lhs(lhs_vert, lhs_horiz_5); \ + lhs_pf6 = lhs(lhs_vert, lhs_horiz_6); \ + lhs_pf7 = lhs(lhs_vert, lhs_horiz_7); \ + } else if (lhs_horiz_6 < k_size) { \ + lhs_pf0 = lhs(lhs_vert, lhs_horiz_0); \ + lhs_pf1 = lhs(lhs_vert, lhs_horiz_1); \ + lhs_pf2 = lhs(lhs_vert, lhs_horiz_2); \ + lhs_pf3 = lhs(lhs_vert, lhs_horiz_3); \ + lhs_pf4 = lhs(lhs_vert, lhs_horiz_4); \ + lhs_pf5 = lhs(lhs_vert, lhs_horiz_5); \ + lhs_pf6 = lhs(lhs_vert, lhs_horiz_6); \ + } else if (lhs_horiz_5 < k_size) { \ + lhs_pf0 = lhs(lhs_vert, lhs_horiz_0); \ + lhs_pf1 = lhs(lhs_vert, lhs_horiz_1); \ + lhs_pf2 = lhs(lhs_vert, lhs_horiz_2); \ + lhs_pf3 = lhs(lhs_vert, lhs_horiz_3); \ + lhs_pf4 = lhs(lhs_vert, lhs_horiz_4); \ + lhs_pf5 = lhs(lhs_vert, lhs_horiz_5); \ + } else if (lhs_horiz_4 < k_size) { \ + lhs_pf0 = lhs(lhs_vert, lhs_horiz_0); \ + lhs_pf1 = lhs(lhs_vert, lhs_horiz_1); \ + lhs_pf2 = lhs(lhs_vert, lhs_horiz_2); \ + lhs_pf3 = lhs(lhs_vert, lhs_horiz_3); \ + lhs_pf4 = lhs(lhs_vert, lhs_horiz_4); \ + } else if (lhs_horiz_3 < k_size) { \ + lhs_pf0 = lhs(lhs_vert, lhs_horiz_0); \ + lhs_pf1 = lhs(lhs_vert, lhs_horiz_1); \ + lhs_pf2 = lhs(lhs_vert, lhs_horiz_2); \ + lhs_pf3 = lhs(lhs_vert, lhs_horiz_3); \ + } else if (lhs_horiz_2 < k_size) { \ + lhs_pf0 = lhs(lhs_vert, lhs_horiz_0); \ + lhs_pf1 = lhs(lhs_vert, lhs_horiz_1); \ + lhs_pf2 = lhs(lhs_vert, lhs_horiz_2); \ + } else if (lhs_horiz_1 < k_size) { \ + lhs_pf0 = lhs(lhs_vert, lhs_horiz_0); \ + lhs_pf1 = lhs(lhs_vert, lhs_horiz_1); \ + } else if (lhs_horiz_0 < k_size) { \ + lhs_pf0 = lhs(lhs_vert, lhs_horiz_0); \ + } \ + } \ + \ + const Index rhs_vert = base_k + load_idx_vert; \ + if (!needs_edge_check || rhs_vert < k_size) { \ + const Index rhs_horiz_0 = base_n + threadIdx.z + 0 * 8; \ + const Index rhs_horiz_1 = base_n + threadIdx.z + 1 * 8; \ + const Index rhs_horiz_2 = base_n + threadIdx.z + 2 * 8; \ + const Index rhs_horiz_3 = base_n + threadIdx.z + 3 * 8; \ + const Index rhs_horiz_4 = base_n + threadIdx.z + 4 * 8; \ + const Index rhs_horiz_5 = base_n + threadIdx.z + 5 * 8; \ + const Index rhs_horiz_6 = base_n + threadIdx.z + 6 * 8; \ + const Index rhs_horiz_7 = base_n + threadIdx.z + 7 * 8; \ + \ + if (rhs_horiz_7 < n_size) { \ + rhs_pf0 = rhs(rhs_vert, rhs_horiz_0); \ + rhs_pf1 = rhs(rhs_vert, rhs_horiz_1); \ + rhs_pf2 = rhs(rhs_vert, rhs_horiz_2); \ + rhs_pf3 = rhs(rhs_vert, rhs_horiz_3); \ + rhs_pf4 = rhs(rhs_vert, rhs_horiz_4); \ + rhs_pf5 = rhs(rhs_vert, rhs_horiz_5); \ + rhs_pf6 = rhs(rhs_vert, rhs_horiz_6); \ + rhs_pf7 = rhs(rhs_vert, rhs_horiz_7); \ + } else if (rhs_horiz_6 < n_size) { \ + rhs_pf0 = rhs(rhs_vert, rhs_horiz_0); \ + rhs_pf1 = rhs(rhs_vert, rhs_horiz_1); \ + rhs_pf2 = rhs(rhs_vert, rhs_horiz_2); \ + rhs_pf3 = rhs(rhs_vert, rhs_horiz_3); \ + rhs_pf4 = rhs(rhs_vert, rhs_horiz_4); \ + rhs_pf5 = rhs(rhs_vert, rhs_horiz_5); \ + rhs_pf6 = rhs(rhs_vert, rhs_horiz_6); \ + } else if (rhs_horiz_5 < n_size) { \ + rhs_pf0 = rhs(rhs_vert, rhs_horiz_0); \ + rhs_pf1 = rhs(rhs_vert, rhs_horiz_1); \ + rhs_pf2 = rhs(rhs_vert, rhs_horiz_2); \ + rhs_pf3 = rhs(rhs_vert, rhs_horiz_3); \ + rhs_pf4 = rhs(rhs_vert, rhs_horiz_4); \ + rhs_pf5 = rhs(rhs_vert, rhs_horiz_5); \ + } else if (rhs_horiz_4 < n_size) { \ + rhs_pf0 = rhs(rhs_vert, rhs_horiz_0); \ + rhs_pf1 = rhs(rhs_vert, rhs_horiz_1); \ + rhs_pf2 = rhs(rhs_vert, rhs_horiz_2); \ + rhs_pf3 = rhs(rhs_vert, rhs_horiz_3); \ + rhs_pf4 = rhs(rhs_vert, rhs_horiz_4); \ + } else if (rhs_horiz_3 < n_size) { \ + rhs_pf0 = rhs(rhs_vert, rhs_horiz_0); \ + rhs_pf1 = rhs(rhs_vert, rhs_horiz_1); \ + rhs_pf2 = rhs(rhs_vert, rhs_horiz_2); \ + rhs_pf3 = rhs(rhs_vert, rhs_horiz_3); \ + } else if (rhs_horiz_2 < n_size) { \ + rhs_pf0 = rhs(rhs_vert, rhs_horiz_0); \ + rhs_pf1 = rhs(rhs_vert, rhs_horiz_1); \ + rhs_pf2 = rhs(rhs_vert, rhs_horiz_2); \ + } else if (rhs_horiz_1 < n_size) { \ + rhs_pf0 = rhs(rhs_vert, rhs_horiz_0); \ + rhs_pf1 = rhs(rhs_vert, rhs_horiz_1); \ + } else if (rhs_horiz_0 < n_size) { \ + rhs_pf0 = rhs(rhs_vert, rhs_horiz_0); \ + } \ + } \ + } \ + +#define writeRegToShmem(_) \ + lhs_shmem[lhs_store_idx_0] = lhs_pf0; \ + rhs_shmem[rhs_store_idx_0] = rhs_pf0; \ + \ + lhs_shmem[lhs_store_idx_1] = lhs_pf1; \ + rhs_shmem[rhs_store_idx_1] = rhs_pf1; \ + \ + lhs_shmem[lhs_store_idx_2] = lhs_pf2; \ + rhs_shmem[rhs_store_idx_2] = rhs_pf2; \ + \ + lhs_shmem[lhs_store_idx_3] = lhs_pf3; \ + rhs_shmem[rhs_store_idx_3] = rhs_pf3; \ + \ + lhs_shmem[lhs_store_idx_4] = lhs_pf4; \ + rhs_shmem[rhs_store_idx_4] = rhs_pf4; \ + \ + lhs_shmem[lhs_store_idx_5] = lhs_pf5; \ + rhs_shmem[rhs_store_idx_5] = rhs_pf5; \ + \ + lhs_shmem[lhs_store_idx_6] = lhs_pf6; \ + rhs_shmem[rhs_store_idx_6] = rhs_pf6; \ + \ + lhs_shmem[lhs_store_idx_7] = lhs_pf7; \ + rhs_shmem[rhs_store_idx_7] = rhs_pf7; \ + + // declare and initialize result array +#define res(i, j) _res_##i##j +#define initResultRow(i) \ + Scalar res(i, 0) = conv(0); \ + Scalar res(i, 1) = conv(0); \ + Scalar res(i, 2) = conv(0); \ + Scalar res(i, 3) = conv(0); \ + Scalar res(i, 4) = conv(0); \ + Scalar res(i, 5) = conv(0); \ + Scalar res(i, 6) = conv(0); \ + Scalar res(i, 7) = conv(0); \ + + internal::scalar_cast_op conv; + initResultRow(0); + initResultRow(1); + initResultRow(2); + initResultRow(3); + initResultRow(4); + initResultRow(5); + initResultRow(6); + initResultRow(7); +#undef initResultRow + + for (Index base_k = 0; base_k < k_size; base_k += 64) { + // wait for previous iteration to finish with shmem. Despite common sense, + // the code is a bit faster with this here then at bottom of loop + __syncthreads(); + + prefetchIntoRegisters(base_k); + writeRegToShmem(); + + #undef prefetchIntoRegisters + #undef writeRegToShmem + + // wait for shared mem packing to be done before starting computation + __syncthreads(); + + // compute 8x8 matrix product by outer product. This involves packing one column + // of LHS and one row of RHS into registers (takes 16 registers). + +#define lcol(i) _lcol##i + Scalar lcol(0); + Scalar lcol(1); + Scalar lcol(2); + Scalar lcol(3); + Scalar lcol(4); + Scalar lcol(5); + Scalar lcol(6); + Scalar lcol(7); + +#define rrow(j) _rrow##j + Scalar rrow(0); + Scalar rrow(1); + Scalar rrow(2); + Scalar rrow(3); + Scalar rrow(4); + Scalar rrow(5); + Scalar rrow(6); + Scalar rrow(7); + + // Now x corresponds to k, y to m, and z to n + const Scalar* lhs_block = &lhs_shmem[threadIdx.x + 9 * threadIdx.y]; + const Scalar* rhs_block = &rhs_shmem[threadIdx.x + 8 * threadIdx.z]; + +#define lhs_element(i, j) lhs_block[72 * ((i) + 8 * (j))] +#define rhs_element(i, j) rhs_block[72 * ((i) + 8 * (j))] + +#define loadData(i, j) \ + lcol(0) = lhs_element(0, j); \ + rrow(0) = rhs_element(i, 0); \ + lcol(1) = lhs_element(1, j); \ + rrow(1) = rhs_element(i, 1); \ + lcol(2) = lhs_element(2, j); \ + rrow(2) = rhs_element(i, 2); \ + lcol(3) = lhs_element(3, j); \ + rrow(3) = rhs_element(i, 3); \ + lcol(4) = lhs_element(4, j); \ + rrow(4) = rhs_element(i, 4); \ + lcol(5) = lhs_element(5, j); \ + rrow(5) = rhs_element(i, 5); \ + lcol(6) = lhs_element(6, j); \ + rrow(6) = rhs_element(i, 6); \ + lcol(7) = lhs_element(7, j); \ + rrow(7) = rhs_element(i, 7); \ + +#define computeCol(j) \ + res(0, j) += lcol(0) * rrow(j); \ + res(1, j) += lcol(1) * rrow(j); \ + res(2, j) += lcol(2) * rrow(j); \ + res(3, j) += lcol(3) * rrow(j); \ + res(4, j) += lcol(4) * rrow(j); \ + res(5, j) += lcol(5) * rrow(j); \ + res(6, j) += lcol(6) * rrow(j); \ + res(7, j) += lcol(7) * rrow(j); \ + +#define computePass(i) \ + loadData(i, i); \ + \ + computeCol(0); \ + computeCol(1); \ + computeCol(2); \ + computeCol(3); \ + computeCol(4); \ + computeCol(5); \ + computeCol(6); \ + computeCol(7); \ + + computePass(0); + computePass(1); + computePass(2); + computePass(3); + computePass(4); + computePass(5); + computePass(6); + computePass(7); + +#undef lcol +#undef rrow +#undef lhs_element +#undef rhs_element +#undef loadData +#undef computeCol +#undef computePass + } // end loop over k + + // we've now iterated over all of the large (ie width 64) k blocks and + // accumulated results in registers. At this point thread (x, y, z) contains + // the sum across all big k blocks of the product of little k block of index (x, y) + // with block of index (y, z). To compute the final output, we need to reduce + // the 8 threads over y by summation. +#define shuffleInc(i, j, mask) res(i, j) += __shfl_xor(res(i, j), mask) + +#define reduceRow(i, mask) \ + shuffleInc(i, 0, mask); \ + shuffleInc(i, 1, mask); \ + shuffleInc(i, 2, mask); \ + shuffleInc(i, 3, mask); \ + shuffleInc(i, 4, mask); \ + shuffleInc(i, 5, mask); \ + shuffleInc(i, 6, mask); \ + shuffleInc(i, 7, mask); \ + +#define reduceMatrix(mask) \ + reduceRow(0, mask); \ + reduceRow(1, mask); \ + reduceRow(2, mask); \ + reduceRow(3, mask); \ + reduceRow(4, mask); \ + reduceRow(5, mask); \ + reduceRow(6, mask); \ + reduceRow(7, mask); \ + + // actually perform the reduction, now each thread of index (_, y, z) + // contains the correct values in its registers that belong in the output + // block + reduceMatrix(1); + reduceMatrix(2); + reduceMatrix(4); + +#undef shuffleInc +#undef reduceRow +#undef reduceMatrix + + // now we need to copy the 64 values into main memory. We can't split work + // among threads because all variables are in registers. There's 2 ways + // to do this: + // (1) have 1 thread do 64 writes from registers into global memory + // (2) have 1 thread do 64 writes into shared memory, and then 8 threads + // each do 8 writes into global memory. We can just overwrite the shared + // memory from the problem we just solved. + // (2) is slightly faster than (1) due to less branching and more ILP + + // TODO: won't yield much gain, but could just use currently unused shared mem + // and then we won't have to sync + // wait for shared mem to be out of use + __syncthreads(); + +#define writeResultShmem(i, j) \ + lhs_shmem[i + 8 * threadIdx.y + 64 * threadIdx.z + 512 * j] = res(i, j); \ + +#define writeRow(i) \ + writeResultShmem(i, 0); \ + writeResultShmem(i, 1); \ + writeResultShmem(i, 2); \ + writeResultShmem(i, 3); \ + writeResultShmem(i, 4); \ + writeResultShmem(i, 5); \ + writeResultShmem(i, 6); \ + writeResultShmem(i, 7); \ + + if (threadIdx.x == 0) { + writeRow(0); + writeRow(1); + writeRow(2); + writeRow(3); + writeRow(4); + writeRow(5); + writeRow(6); + writeRow(7); + } +#undef writeResultShmem +#undef writeRow + + const int max_i_write = numext::mini((int)((m_size - base_m - threadIdx.y + 7) / 8), 8); + const int max_j_write = numext::mini((int)((n_size - base_n - threadIdx.z + 7) / 8), 8); + + if (threadIdx.x < max_i_write) { + if (max_j_write == 8) { + // TODO: can i trade bank conflicts for coalesced writes? + Scalar val0 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 0]; + Scalar val1 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 1]; + Scalar val2 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 2]; + Scalar val3 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 3]; + Scalar val4 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 4]; + Scalar val5 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 5]; + Scalar val6 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 6]; + Scalar val7 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 7]; + + output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 0) = val0; + output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 1) = val1; + output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 2) = val2; + output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 3) = val3; + output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 4) = val4; + output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 5) = val5; + output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 6) = val6; + output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 7) = val7; + } else { +#pragma unroll 7 + for (int j = 0; j < max_j_write; j++) { + Scalar val = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * j]; + output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * j) = val; + } + } + } +#undef res +} + + +template +__global__ void +__launch_bounds__(512) +EigenContractionKernel(const LhsMapper lhs, const RhsMapper rhs, + const OutputMapper output, + const Index m_size, const Index n_size, const Index k_size) { + __shared__ Scalar lhs_shmem[72 * 64]; + __shared__ Scalar rhs_shmem[72 * 64]; + + const Index m_block_idx = blockIdx.x; + const Index n_block_idx = blockIdx.y; + + const Index base_m = 64 * m_block_idx; + const Index base_n = 64 * n_block_idx; + + if (base_m + 63 < m_size && base_n + 63 < n_size) { + EigenContractionKernelInternal(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size); + } else { + EigenContractionKernelInternal(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size); + } +} + + +template +__device__ EIGEN_STRONG_INLINE void +EigenFloatContractionKernelInternal16x16(const LhsMapper lhs, const RhsMapper rhs, + const OutputMapper output, float2 lhs_shmem2[][16], + float2 rhs_shmem2[][8], const Index m_size, + const Index n_size, const Index k_size, + const Index base_m, const Index base_n) { + + // prefetch registers + float4 lhs_pf0, rhs_pf0; + + float4 results[4]; + for (int i=0; i < 4; i++) { + results[i].x = results[i].y = results[i].z = results[i].w = 0; + } + + +#define prefetch_lhs(reg, row, col) \ + if (!CHECK_LHS_BOUNDARY) { \ + if (col < k_size) { \ + reg =lhs.template loadPacket(row, col); \ + } \ + } else { \ + if (col < k_size) { \ + if (row + 3 < m_size) { \ + reg =lhs.template loadPacket(row, col); \ + } else if (row + 2 < m_size) { \ + reg.x =lhs(row + 0, col); \ + reg.y =lhs(row + 1, col); \ + reg.z =lhs(row + 2, col); \ + } else if (row + 1 < m_size) { \ + reg.x =lhs(row + 0, col); \ + reg.y =lhs(row + 1, col); \ + } else if (row < m_size) { \ + reg.x =lhs(row + 0, col); \ + } \ + } \ + } \ + + + Index lhs_vert = base_m+threadIdx.x*4; + + for (Index k = 0; k < k_size; k += 16) { + lhs_pf0 = internal::pset1(0); + rhs_pf0 = internal::pset1(0); + + Index lhs_horiz = threadIdx.y+k; + prefetch_lhs(lhs_pf0, lhs_vert, lhs_horiz) + + Index rhs_vert = k+(threadIdx.x%4)*4; + Index rhs_horiz0 = (threadIdx.x>>2)+threadIdx.y*4+base_n; + + if (!CHECK_RHS_BOUNDARY) { + if ((rhs_vert + 3) < k_size) { + // just CHECK_RHS_BOUNDARY + rhs_pf0 = rhs.template loadPacket(rhs_vert, rhs_horiz0); + } else if (rhs_vert + 2 < k_size) { + // just CHECK_RHS_BOUNDARY + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0); + rhs_pf0.z = rhs(rhs_vert + 2, rhs_horiz0); + } else if (rhs_vert + 1 < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0); + } else if (rhs_vert < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + } + } else { + if (rhs_horiz0 < n_size) { + if ((rhs_vert + 3) < k_size) { + rhs_pf0 = rhs.template loadPacket(rhs_vert, rhs_horiz0); + } else if ((rhs_vert + 2) < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0); + rhs_pf0.z = rhs(rhs_vert + 2, rhs_horiz0); + } else if ((rhs_vert + 1) < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0); + } else if (rhs_vert < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + } + } + } + float x1, x2 ; + // the following can be a bitwise operation..... some day. + if((threadIdx.x%8) < 4) { + x1 = rhs_pf0.y; + x2 = rhs_pf0.w; + } else { + x1 = rhs_pf0.x; + x2 = rhs_pf0.z; + } + x1 = __shfl_xor(x1, 4); + x2 = __shfl_xor(x2, 4); + if((threadIdx.x%8) < 4) { + rhs_pf0.y = x1; + rhs_pf0.w = x2; + } else { + rhs_pf0.x = x1; + rhs_pf0.z = x2; + } + + // We have 64 features. + // Row 0 -> times (0, 4, 8, 12, 1, 5, 9, 13) for features 0, 1. + // Row 1 -> times (0, 4, 8, 12, 1, 5, 9, 13) for features 2, 3. + // ... + // Row 31 -> times (0, 4, 8, 12, 1, 5, 9, 13) for features 62, 63 + // Row 32 -> times (2, 6, 10, 14, 3, 7, 11, 15) for features 0, 1 + // ... + rhs_shmem2[(threadIdx.x>>3)+ threadIdx.y*2][threadIdx.x%8] = make_float2(rhs_pf0.x, rhs_pf0.y); + rhs_shmem2[(threadIdx.x>>3)+ threadIdx.y*2+32][threadIdx.x%8] = make_float2(rhs_pf0.z, rhs_pf0.w); + + // Row 0 (time 0) -> features (0, 1), (4, 5), .. (28, 29), (32, 33), .. (60, 61) + // Row 1 (time 1) -> features (0, 1), (4, 5), .. (28, 29), (32, 33), .. (60, 61) + // ... + // Row 15 (time 15) -> features (0, 1), (4, 5), .. (28, 29), (32, 33), .. (60, 61) + // Row 16 (time 0) -> features (2, 3), (6, 7), .. (30, 31), (34, 35), .. (62, 63) + // ... + + lhs_shmem2[threadIdx.y][threadIdx.x] = make_float2(lhs_pf0.x, lhs_pf0.y); + lhs_shmem2[threadIdx.y+16][threadIdx.x] = make_float2(lhs_pf0.z, lhs_pf0.w); + + +#define add_vals(fl1, fl2, fr1, fr2)\ + results[0].x += fl1.x * fr1.x;\ + results[0].y += fl1.y * fr1.x;\ + results[0].z += fl2.x * fr1.x;\ + results[0].w += fl2.y * fr1.x;\ +\ + results[1].x += fl1.x * fr1.y;\ + results[1].y += fl1.y * fr1.y;\ + results[1].z += fl2.x * fr1.y;\ + results[1].w += fl2.y * fr1.y;\ +\ + results[2].x += fl1.x * fr2.x;\ + results[2].y += fl1.y * fr2.x;\ + results[2].z += fl2.x * fr2.x;\ + results[2].w += fl2.y * fr2.x;\ +\ + results[3].x += fl1.x * fr2.y;\ + results[3].y += fl1.y * fr2.y;\ + results[3].z += fl2.x * fr2.y;\ + results[3].w += fl2.y * fr2.y;\ + + __syncthreads(); + + // Do the multiplies. + #pragma unroll + for (int koff = 0; koff < 16; koff ++) { + // 32 x threads. + float2 fl1 = lhs_shmem2[koff][threadIdx.x]; + float2 fl2 = lhs_shmem2[koff + 16][threadIdx.x]; + + int start_feature = threadIdx.y * 4; + float2 fr1 = rhs_shmem2[(start_feature>>1) + 32*((koff%4)/2)][koff/4 + (koff%2)*4]; + float2 fr2 = rhs_shmem2[(start_feature>>1) + 1 + 32*((koff%4)/2)][koff/4 + (koff%2)*4]; + + add_vals(fl1, fl2, fr1, fr2) + } + __syncthreads(); + } + +#undef prefetch_lhs +#undef add_vals + + Index horiz_base = threadIdx.y*4+base_n; + if (!CHECK_LHS_BOUNDARY && !CHECK_RHS_BOUNDARY) { + for (int i = 0; i < 4; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + output(lhs_vert + 2, horiz_base + i) = results[i].z; + output(lhs_vert + 3, horiz_base + i) = results[i].w; + } + } else if (!CHECK_RHS_BOUNDARY) { + // CHECK LHS + if (lhs_vert + 3 < m_size) { + for (int i = 0; i < 4; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + output(lhs_vert + 2, horiz_base + i) = results[i].z; + output(lhs_vert + 3, horiz_base + i) = results[i].w; + } + } else if (lhs_vert + 2 < m_size) { + for (int i = 0; i < 4; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + output(lhs_vert + 2, horiz_base + i) = results[i].z; + } + } else if (lhs_vert + 1 < m_size) { + for (int i = 0; i < 4; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + } + } else if (lhs_vert < m_size) { + for (int i = 0; i < 4; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + } + } + } else if (!CHECK_LHS_BOUNDARY) { + // CHECK RHS + /* + int ncols_rem = fminf(n_size- horiz_base, 4); + for (int i = 0; i < ncols_rem; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + output(lhs_vert + 2, horiz_base + i) = results[i].z; + output(lhs_vert + 3, horiz_base + i) = results[i].w; + }*/ + for (int i = 0; i < 4; i++) { + if (horiz_base+i < n_size) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + output(lhs_vert + 2, horiz_base + i) = results[i].z; + output(lhs_vert + 3, horiz_base + i) = results[i].w; + } + } + } else { + // CHECK both boundaries. + for (int i = 0; i < 4; i++) { + if (horiz_base+i < n_size) { + if (lhs_vert < m_size) + output(lhs_vert, horiz_base + i) = results[i].x; + if (lhs_vert + 1 < m_size) + output(lhs_vert + 1, horiz_base + i) = results[i].y; + if (lhs_vert + 2 < m_size) + output(lhs_vert + 2, horiz_base + i) = results[i].z; + if (lhs_vert + 3 < m_size) + output(lhs_vert + 3, horiz_base + i) = results[i].w; + } + } + } +} + + +template +__device__ EIGEN_STRONG_INLINE void +EigenFloatContractionKernelInternal(const LhsMapper lhs, const RhsMapper rhs, + const OutputMapper output, float2 lhs_shmem2[][32], + float2 rhs_shmem2[][8], const Index m_size, + const Index n_size, const Index k_size, + const Index base_m, const Index base_n) { + + // prefetch registers + float4 lhs_pf0, lhs_pf1, lhs_pf2, lhs_pf3; + float4 rhs_pf0, rhs_pf1; + + float4 results[8]; + for (int i=0; i < 8; i++) { + results[i].x = results[i].y = results[i].z = results[i].w = 0; + } + + + Index lhs_vert = base_m+threadIdx.x*4+(threadIdx.y%4)*32; + for (Index k = 0; k < k_size; k += 32) { + lhs_pf0 = internal::pset1(0); + lhs_pf1 = internal::pset1(0); + lhs_pf2 = internal::pset1(0); + lhs_pf3 = internal::pset1(0); + + rhs_pf0 = internal::pset1(0); + rhs_pf1 = internal::pset1(0); + + if (!CHECK_LHS_BOUNDARY) { + if ((threadIdx.y/4+k+24) < k_size) { + lhs_pf0 =lhs.template loadPacket(lhs_vert, (threadIdx.y/4+k)); + lhs_pf1 =lhs.template loadPacket(lhs_vert, (threadIdx.y/4+k+8)); + lhs_pf2 =lhs.template loadPacket(lhs_vert, (threadIdx.y/4+k+16)); + lhs_pf3 =lhs.template loadPacket(lhs_vert, (threadIdx.y/4+k+24)); + } else if ((threadIdx.y/4+k+16) < k_size) { + lhs_pf0 =lhs.template loadPacket(lhs_vert, (threadIdx.y/4+k)); + lhs_pf1 =lhs.template loadPacket(lhs_vert, (threadIdx.y/4+k+8)); + lhs_pf2 =lhs.template loadPacket(lhs_vert, (threadIdx.y/4+k+16)); + } else if ((threadIdx.y/4+k+8) < k_size) { + lhs_pf0 =lhs.template loadPacket(lhs_vert, (threadIdx.y/4+k)); + lhs_pf1 =lhs.template loadPacket(lhs_vert, (threadIdx.y/4+k+8)); + } else if ((threadIdx.y/4+k) < k_size) { + lhs_pf0 =lhs.template loadPacket(lhs_vert, (threadIdx.y/4+k)); + } + } else { + // just CHECK_LHS_BOUNDARY + if (lhs_vert + 3 < m_size) { + if ((threadIdx.y/4+k+24) < k_size) { + lhs_pf0 =lhs.template loadPacket(lhs_vert, (threadIdx.y/4+k)); + lhs_pf1 =lhs.template loadPacket(lhs_vert, (threadIdx.y/4+k+8)); + lhs_pf2 =lhs.template loadPacket(lhs_vert, (threadIdx.y/4+k+16)); + lhs_pf3 =lhs.template loadPacket(lhs_vert, (threadIdx.y/4+k+24)); + } else if ((threadIdx.y/4+k+16) < k_size) { + lhs_pf0 =lhs.template loadPacket(lhs_vert, (threadIdx.y/4+k)); + lhs_pf1 =lhs.template loadPacket(lhs_vert, (threadIdx.y/4+k+8)); + lhs_pf2 =lhs.template loadPacket(lhs_vert, (threadIdx.y/4+k+16)); + } else if ((threadIdx.y/4+k+8) < k_size) { + lhs_pf0 =lhs.template loadPacket(lhs_vert, (threadIdx.y/4+k)); + lhs_pf1 =lhs.template loadPacket(lhs_vert, (threadIdx.y/4+k+8)); + } else if ((threadIdx.y/4+k) < k_size) { + lhs_pf0 =lhs.template loadPacket(lhs_vert, (threadIdx.y/4+k)); + } + } else if (lhs_vert + 2 < m_size) { + if ((threadIdx.y/4+k+24) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k)); + lhs_pf0.z =lhs(lhs_vert + 2, (threadIdx.y/4+k)); + lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8)); + lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8)); + lhs_pf1.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+8)); + lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16)); + lhs_pf2.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+16)); + lhs_pf2.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+16)); + lhs_pf3.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+24)); + lhs_pf3.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+24)); + lhs_pf3.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+24)); + } else if ((threadIdx.y/4+k+16) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k)); + lhs_pf0.z =lhs(lhs_vert + 2, (threadIdx.y/4+k)); + lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8)); + lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8)); + lhs_pf1.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+8)); + lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16)); + lhs_pf2.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+16)); + lhs_pf2.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+16)); + } else if ((threadIdx.y/4+k+8) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k)); + lhs_pf0.z =lhs(lhs_vert + 2, (threadIdx.y/4+k)); + lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8)); + lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8)); + lhs_pf1.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+8)); + } else if ((threadIdx.y/4+k) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k)); + lhs_pf0.z =lhs(lhs_vert + 2, (threadIdx.y/4+k)); + } + } else if (lhs_vert + 1 < m_size) { + if ((threadIdx.y/4+k+24) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k)); + lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8)); + lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8)); + lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16)); + lhs_pf2.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+16)); + lhs_pf3.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+24)); + lhs_pf3.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+24)); + } else if ((threadIdx.y/4+k+16) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k)); + lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8)); + lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8)); + lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16)); + lhs_pf2.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+16)); + } else if ((threadIdx.y/4+k+8) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k)); + lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8)); + lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8)); + } else if ((threadIdx.y/4+k) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k)); + } + } else if (lhs_vert < m_size) { + if ((threadIdx.y/4+k+24) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8)); + lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16)); + lhs_pf3.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+24)); + } else if ((threadIdx.y/4+k+16) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8)); + lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16)); + } else if ((threadIdx.y/4+k+8) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8)); + } else if ((threadIdx.y/4+k) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + } + } + } + __syncthreads(); + Index rhs_vert = k+threadIdx.x*4; + Index rhs_horiz0 = threadIdx.y*2+base_n; + Index rhs_horiz1 = threadIdx.y*2+1+base_n; + if (!CHECK_RHS_BOUNDARY) { + if ((rhs_vert + 3) < k_size) { + // just CHECK_RHS_BOUNDARY + rhs_pf0 = rhs.template loadPacket(rhs_vert, rhs_horiz0); + rhs_pf1 = rhs.template loadPacket(rhs_vert, rhs_horiz1); + } else if (rhs_vert + 2 < k_size) { + // just CHECK_RHS_BOUNDARY + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0); + rhs_pf0.z = rhs(rhs_vert + 2, rhs_horiz0); + rhs_pf1.x = rhs(rhs_vert, rhs_horiz1); + rhs_pf1.y = rhs(rhs_vert + 1, rhs_horiz1); + rhs_pf1.z = rhs(rhs_vert + 2, rhs_horiz1); + } else if (rhs_vert + 1 < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0); + rhs_pf1.x = rhs(rhs_vert, rhs_horiz1); + rhs_pf1.y = rhs(rhs_vert + 1, rhs_horiz1); + } else if (rhs_vert < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf1.x = rhs(rhs_vert, rhs_horiz1); + } + } else { + if (rhs_horiz1 < n_size) { + if ((rhs_vert + 3) < k_size) { + // just CHECK_RHS_BOUNDARY + rhs_pf0 = rhs.template loadPacket(rhs_vert, rhs_horiz0); + rhs_pf1 = rhs.template loadPacket(rhs_vert, rhs_horiz1); + } else if (rhs_vert + 2 < k_size) { + // just CHECK_RHS_BOUNDARY + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0); + rhs_pf0.z = rhs(rhs_vert + 2, rhs_horiz0); + rhs_pf1.x = rhs(rhs_vert, rhs_horiz1); + rhs_pf1.y = rhs(rhs_vert + 1, rhs_horiz1); + rhs_pf1.z = rhs(rhs_vert + 2, rhs_horiz1); + } else if (k+threadIdx.x*4 + 1 < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0); + rhs_pf1.x = rhs(rhs_vert, rhs_horiz1); + rhs_pf1.y = rhs(rhs_vert + 1, rhs_horiz1); + } else if (k+threadIdx.x*4 < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf1.x = rhs(rhs_vert, rhs_horiz1); + } + } else if (rhs_horiz0 < n_size) { + if ((rhs_vert + 3) < k_size) { + // just CHECK_RHS_BOUNDARY + rhs_pf0 = rhs.template loadPacket(rhs_vert, rhs_horiz0); + } else if ((rhs_vert + 2) < k_size) { + // just CHECK_RHS_BOUNDARY + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0); + rhs_pf0.z = rhs(rhs_vert + 2, rhs_horiz0); + } else if ((rhs_vert + 1) < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0); + } else if (rhs_vert < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + } + } + } + __syncthreads(); + // Loaded. Do computation + // Row 0 -> times (0, 4, 8, .. 28) for features 0, 1. + // Row 1 -> times (0, 4, 8, .. 28) for features 2, 3. + // .. + // Row 31 -> times (0, 4, 8, .. 28) for features 62, 63 + rhs_shmem2[threadIdx.y][threadIdx.x] = make_float2(rhs_pf0.x, rhs_pf1.x); + // Row 32 -> times (1, 5, 9, .. 29) for features 0, 1. + // Row 33 -> times (1, 5, 9, .. 29) for features 2, 3. + // .. + rhs_shmem2[threadIdx.y+32][threadIdx.x] = make_float2(rhs_pf0.y, rhs_pf1.y); + // Row 64 -> times (2, 6, 10, .. 30) for features 0, 1. + // Row 65 -> times (2, 6, 10, .. 30) for features 2, 3. + rhs_shmem2[threadIdx.y+64][threadIdx.x] = make_float2(rhs_pf0.z, rhs_pf1.z); + // Row 96 -> times (3, 7, 11, .. 31) for features 0, 1. + // Row 97 -> times (3, 7, 11, .. 31) for features 2, 3. + rhs_shmem2[threadIdx.y+96][threadIdx.x] = make_float2(rhs_pf0.w, rhs_pf1.w); + + // LHS. + // Row 0 (time 0) -> features (0, 1), (4, 5), .. (28, 29), (32, 33), .. (60, 61) .. (124, 125) + // Row 1 (time 1) -> features (0, 1), (4, 5), .. (28, 29), (32, 33), .. (60, 61) .. (124, 125) + // ... + // Row 8 (time 0) -> features (2, 3), (6, 7), .. (30, 31), (34, 35), .. (62, 63) .. (126, 127) + // Row 15 (time 7) -> features (2, 3), (6, 7), .. (30, 31), (34, 35), .. (62, 63) .. (126, 127) + + +#define add_vals(a_feat1, a_feat2, f1, f2, f3, f4)\ + results[0].x += a_feat1.x * f1.x;\ + results[1].x += a_feat1.x * f1.y;\ + results[2].x += a_feat1.x * f2.x;\ + results[3].x += a_feat1.x * f2.y;\ + results[4].x += a_feat1.x * f3.x;\ + results[5].x += a_feat1.x * f3.y;\ + results[6].x += a_feat1.x * f4.x;\ + results[7].x += a_feat1.x * f4.y;\ +\ + results[0].y += a_feat1.y * f1.x;\ + results[1].y += a_feat1.y * f1.y;\ + results[2].y += a_feat1.y * f2.x;\ + results[3].y += a_feat1.y * f2.y;\ + results[4].y += a_feat1.y * f3.x;\ + results[5].y += a_feat1.y * f3.y;\ + results[6].y += a_feat1.y * f4.x;\ + results[7].y += a_feat1.y * f4.y;\ +\ + results[0].z += a_feat2.x * f1.x;\ + results[1].z += a_feat2.x * f1.y;\ + results[2].z += a_feat2.x * f2.x;\ + results[3].z += a_feat2.x * f2.y;\ + results[4].z += a_feat2.x * f3.x;\ + results[5].z += a_feat2.x * f3.y;\ + results[6].z += a_feat2.x * f4.x;\ + results[7].z += a_feat2.x * f4.y;\ +\ + results[0].w += a_feat2.y * f1.x;\ + results[1].w += a_feat2.y * f1.y;\ + results[2].w += a_feat2.y * f2.x;\ + results[3].w += a_feat2.y * f2.y;\ + results[4].w += a_feat2.y * f3.x;\ + results[5].w += a_feat2.y * f3.y;\ + results[6].w += a_feat2.y * f4.x;\ + results[7].w += a_feat2.y * f4.y;\ + + lhs_shmem2[threadIdx.y/4][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf0.x, lhs_pf0.y); + lhs_shmem2[threadIdx.y/4+8][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf1.x, lhs_pf1.y); + lhs_shmem2[threadIdx.y/4+16][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf2.x, lhs_pf2.y); + lhs_shmem2[threadIdx.y/4+24][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf3.x, lhs_pf3.y); + + lhs_shmem2[threadIdx.y/4 + 32][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf0.z, lhs_pf0.w); + lhs_shmem2[threadIdx.y/4 + 40][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf1.z, lhs_pf1.w); + lhs_shmem2[threadIdx.y/4 + 48][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf2.z, lhs_pf2.w); + lhs_shmem2[threadIdx.y/4 + 56][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf3.z, lhs_pf3.w); + + __syncthreads(); + + // Do the multiplies. + #pragma unroll + for (int koff = 0; koff < 32; koff ++) { + float2 a3 = lhs_shmem2[koff][threadIdx.x + (threadIdx.y % 4) * 8]; + float2 a4 = lhs_shmem2[koff + 32][threadIdx.x + (threadIdx.y % 4) * 8]; + + // first feature is at (threadIdx.y/4) * 8 last is at start + 8. + int start_feature = (threadIdx.y / 4) * 8; + + float2 br1 = rhs_shmem2[start_feature/2 + (koff % 4) * 32][koff/4]; + float2 br2 = rhs_shmem2[start_feature/2 + 1 + (koff % 4) * 32][koff/4]; + float2 br3 = rhs_shmem2[start_feature/2 + 2 + (koff % 4) * 32][koff/4]; + float2 br4 = rhs_shmem2[start_feature/2 + 3 + (koff % 4) * 32][koff/4]; + + add_vals(a3, a4, br1, br2, br3, br4) + } + __syncthreads(); + } // end loop over k + + + __syncthreads(); + Index horiz_base = (threadIdx.y/4)*8+base_n; + if (!CHECK_LHS_BOUNDARY && !CHECK_RHS_BOUNDARY) { + for (int i = 0; i < 8; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + output(lhs_vert + 2, horiz_base + i) = results[i].z; + output(lhs_vert + 3, horiz_base + i) = results[i].w; + } + } else if (!CHECK_RHS_BOUNDARY) { + if (lhs_vert + 3 < m_size) { + for (int i = 0; i < 8; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + output(lhs_vert + 2, horiz_base + i) = results[i].z; + output(lhs_vert + 3, horiz_base + i) = results[i].w; + } + } else if (lhs_vert + 2 < m_size) { + for (int i = 0; i < 8; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + output(lhs_vert + 2, horiz_base + i) = results[i].z; + } + } else if (lhs_vert + 1 < m_size) { + for (int i = 0; i < 8; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + } + } else if (lhs_vert < m_size) { + for (int i = 0; i < 8; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + } + } + } else if (!CHECK_LHS_BOUNDARY) { + // CHECK BOUNDARY_B + for (int i = 0; i < 8; i++) { + if (horiz_base + i < n_size) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + output(lhs_vert + 2, horiz_base + i) = results[i].z; + output(lhs_vert + 3, horiz_base + i) = results[i].w; + } + } + } else { + // CHECK both boundaries. + for (int i = 0; i < 8; i++) { + if (horiz_base + i < n_size) { + if (lhs_vert < m_size) + output(lhs_vert, horiz_base + i) = results[i].x; + if (lhs_vert + 1 < m_size) + output(lhs_vert + 1, horiz_base + i) = results[i].y; + if (lhs_vert + 2 < m_size) + output(lhs_vert + 2, horiz_base + i) = results[i].z; + if (lhs_vert + 3 < m_size) + output(lhs_vert + 3, horiz_base + i) = results[i].w; + } + } + } +} + + +template +__global__ void +__launch_bounds__(256) +EigenFloatContractionKernel(const LhsMapper lhs, const RhsMapper rhs, + const OutputMapper output, + const Index m_size, const Index n_size, const Index k_size) { + __shared__ float2 lhs_shmem[64*32]; + __shared__ float2 rhs_shmem[128*8]; + + typedef float2 LHS_MEM[64][32]; + typedef float2 RHS_MEM[128][8]; + + const Index m_block_idx = blockIdx.x; + const Index n_block_idx = blockIdx.y; + + const Index base_m = 128 * m_block_idx; + const Index base_n = 64 * n_block_idx; + + bool check_rhs = (base_n + 63) >= n_size; + bool check_lhs128 = (base_m + 127) >= m_size; + + if (!check_rhs) { + if (!check_lhs128) { + // >= 128 rows left + EigenFloatContractionKernelInternal( + lhs, rhs, output, *((LHS_MEM *) lhs_shmem), *((RHS_MEM *) rhs_shmem), m_size, n_size, k_size, base_m, base_n); + } else { + EigenFloatContractionKernelInternal( + lhs, rhs, output, *((LHS_MEM *) lhs_shmem), *((RHS_MEM *) rhs_shmem), m_size, n_size, k_size, base_m, base_n); + } + } else { + if (!check_lhs128) { + // >= 128 rows left + EigenFloatContractionKernelInternal( + lhs, rhs, output, *((LHS_MEM *) lhs_shmem), *((RHS_MEM *) rhs_shmem), m_size, n_size, k_size, base_m, base_n); + } else { + EigenFloatContractionKernelInternal( + lhs, rhs, output, *((LHS_MEM *) lhs_shmem), *((RHS_MEM *) rhs_shmem), m_size, n_size, k_size, base_m, base_n); + } + } +} + +template +__global__ void +__launch_bounds__(256) +EigenFloatContractionKernel16x16(const LhsMapper lhs, const RhsMapper rhs, + const OutputMapper output, + const Index m_size, const Index n_size, const Index k_size) { + __shared__ float2 lhs_shmem[32][16]; + __shared__ float2 rhs_shmem[64][8]; + + const Index m_block_idx = blockIdx.x; + const Index n_block_idx = blockIdx.y; + + const Index base_m = 64 * m_block_idx; + const Index base_n = 64 * n_block_idx; + + if (base_m + 63 < m_size) { + if (base_n + 63 < n_size) { + EigenFloatContractionKernelInternal16x16(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size, base_m, base_n); + } else { + EigenFloatContractionKernelInternal16x16(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size, base_m, base_n); + } + } else { + if (base_n + 63 < n_size) { + EigenFloatContractionKernelInternal16x16(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size, base_m, base_n); + } else { + EigenFloatContractionKernelInternal16x16(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size, base_m, base_n); + } + } +} + + +template +struct TensorEvaluator, GpuDevice> : + public TensorContractionEvaluatorBase, GpuDevice> > { + + typedef GpuDevice Device; + + typedef TensorEvaluator, Device> Self; + typedef TensorContractionEvaluatorBase Base; + + typedef TensorContractionOp XprType; + typedef typename internal::remove_const::type Scalar; + typedef typename XprType::Index Index; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + + enum { + Layout = TensorEvaluator::Layout, + }; + + // Most of the code is assuming that both input tensors are ColMajor. If the + // inputs are RowMajor, we will "cheat" by swapping the LHS and RHS: + // If we want to compute A * B = C, where A is LHS and B is RHS, the code + // will pretend B is LHS and A is RHS. + typedef typename internal::conditional< + static_cast(Layout) == static_cast(ColMajor), LeftArgType, RightArgType>::type EvalLeftArgType; + typedef typename internal::conditional< + static_cast(Layout) == static_cast(ColMajor), RightArgType, LeftArgType>::type EvalRightArgType; + + static const int LDims = + internal::array_size::Dimensions>::value; + static const int RDims = + internal::array_size::Dimensions>::value; + static const int ContractDims = internal::array_size::value; + + typedef array left_dim_mapper_t; + typedef array right_dim_mapper_t; + + typedef array contract_t; + typedef array left_nocontract_t; + typedef array right_nocontract_t; + + static const int NumDims = LDims + RDims - 2 * ContractDims; + + typedef DSizes Dimensions; + + // typedefs needed in evalTo + typedef typename internal::remove_const::type LhsScalar; + typedef typename internal::remove_const::type RhsScalar; + + typedef TensorEvaluator LeftEvaluator; + typedef TensorEvaluator RightEvaluator; + + typedef typename LeftEvaluator::Dimensions LeftDimensions; + typedef typename RightEvaluator::Dimensions RightDimensions; + + EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device) : + Base(op, device) {} + + // We need to redefine this method to make nvcc happy + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* data) { + this->m_leftImpl.evalSubExprsIfNeeded(NULL); + this->m_rightImpl.evalSubExprsIfNeeded(NULL); + if (data) { + evalTo(data); + return false; + } else { + this->m_result = static_cast(this->m_device.allocate(this->dimensions().TotalSize() * sizeof(Scalar))); + evalTo(this->m_result); + return true; + } + } + + void evalTo(Scalar* buffer) const { + if (this->m_lhs_inner_dim_contiguous) { + if (this->m_rhs_inner_dim_contiguous) { + if (this->m_rhs_inner_dim_reordered) { + evalTyped(buffer); + } + else { + evalTyped(buffer); + } + } + else { + if (this->m_rhs_inner_dim_reordered) { + evalTyped(buffer); + } + else { + evalTyped(buffer); + } + } + } + else { + if (this->m_rhs_inner_dim_contiguous) { + if (this->m_rhs_inner_dim_reordered) { + evalTyped(buffer); + } + else { + evalTyped(buffer); + } + } + else { + if (this->m_rhs_inner_dim_reordered) { + evalTyped(buffer); + } + else { + evalTyped(buffer); + } + } + } + } + + template struct LaunchKernels { + static void Run(const LhsMapper& lhs, const RhsMapper& rhs, const OutputMapper& output, Index m, Index n, Index k, const GpuDevice& device) { + const Index m_blocks = (m + 63) / 64; + const Index n_blocks = (n + 63) / 64; + const dim3 num_blocks(m_blocks, n_blocks, 1); + const dim3 block_size(8, 8, 8); + LAUNCH_CUDA_KERNEL((EigenContractionKernel), num_blocks, block_size, 0, device, lhs, rhs, output, m, n, k); + } + }; + + template struct LaunchKernels { + static void Run(const LhsMapper& lhs, const RhsMapper& rhs, const OutputMapper& output, Index m, Index n, Index k, const GpuDevice& device) { + if (m < 768 || n < 768) { + const Index m_blocks = (m + 63) / 64; + const Index n_blocks = (n + 63) / 64; + const dim3 num_blocks(m_blocks, n_blocks, 1); + const dim3 block_size(16, 16, 1); + LAUNCH_CUDA_KERNEL((EigenFloatContractionKernel16x16), num_blocks, block_size, 0, device, lhs, rhs, output, m, n, k); + } else { + const Index m_blocks = (m + 127) / 128; + const Index n_blocks = (n + 63) / 64; + const dim3 num_blocks(m_blocks, n_blocks, 1); + const dim3 block_size(8, 32, 1); + LAUNCH_CUDA_KERNEL((EigenFloatContractionKernel), num_blocks, block_size, 0, device, lhs, rhs, output, m, n, k); + } + } + }; + + template + void evalTyped(Scalar* buffer) const { + // columns in left side, rows in right side + const Index k = this->m_k_size; + EIGEN_UNUSED_VARIABLE(k) + + // rows in left side + const Index m = this->m_i_size; + + // columns in right side + const Index n = this->m_j_size; + + // zero out the result buffer (which must be of size at least m * n * sizeof(Scalar) + this->m_device.memset(buffer, 0, m * n * sizeof(Scalar)); + + typedef internal::TensorContractionInputMapper LhsMapper; + + typedef internal::TensorContractionInputMapper RhsMapper; + + typedef internal::blas_data_mapper OutputMapper; + + + // initialize data mappers + LhsMapper lhs(this->m_leftImpl, this->m_left_nocontract_strides, this->m_i_strides, + this->m_left_contracting_strides, this->m_k_strides); + + RhsMapper rhs(this->m_rightImpl, this->m_right_nocontract_strides, this->m_j_strides, + this->m_right_contracting_strides, this->m_k_strides); + + OutputMapper output(buffer, m); + + setCudaSharedMemConfig(cudaSharedMemBankSizeEightByte); + LaunchKernels::Run(lhs, rhs, output, m, n, k, this->m_device); + } +}; + +} // end namespace Eigen + +#endif // EIGEN_USE_GPU and __CUDACC__ +#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_CUDA_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionMapper.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionMapper.h new file mode 100644 index 00000000..ab320a50 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionMapper.h @@ -0,0 +1,493 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_MAPPER_H +#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_MAPPER_H + +namespace Eigen { + +namespace internal { + +enum { + Rhs = 0, + Lhs = 1 +}; + +/* + * Implementation of the Eigen blas_data_mapper class for tensors. + */ +/// The make pointer class is used by sycl in order to build the mapper class on the device. For other platform the default make pointer is used which +/// is scalar * for CoeffLoader. +template class MakePointer_ = MakePointer> struct CoeffLoader; +template class MakePointer_ = MakePointer> class BaseTensorContractionMapper; + +template class MakePointer_> struct CoeffLoader { + enum { + DirectOffsets = false + }; + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE CoeffLoader(const Tensor& tensor) : m_tensor(tensor) { } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void offsetBuffer(typename Tensor::Index) { + eigen_assert(false && "unsupported"); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE typename Tensor::Scalar coeff(typename Tensor::Index index) const { return m_tensor.coeff(index); } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + typename Tensor::PacketReturnType packet(typename Tensor::Index index) const + { + return m_tensor.template packet(index); + } + + + private: + const Tensor m_tensor; +}; + +template class MakePointer_> struct CoeffLoader { + enum { + DirectOffsets = true + }; + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE CoeffLoader(const Tensor& tensor) : m_data(tensor.data()) {} + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void offsetBuffer(typename Tensor::Index offset) { + m_data += offset; + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE typename Tensor::Scalar coeff(typename Tensor::Index index) const { return loadConstant(m_data+index); } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + typename Tensor::PacketReturnType packet(typename Tensor::Index index) const + { + return internal::ploadt_ro(m_data + index); + } + private: + typedef typename Tensor::Scalar Scalar; + + typename MakePointer_::Type m_data; +}; + +template class MakePointer_ = MakePointer> +class SimpleTensorContractionMapper { + public: + EIGEN_DEVICE_FUNC + SimpleTensorContractionMapper(const Tensor& tensor, + const nocontract_t& nocontract_strides, + const nocontract_t& ij_strides, + const contract_t& contract_strides, + const contract_t& k_strides) : + m_tensor(tensor), + m_nocontract_strides(nocontract_strides), + m_ij_strides(ij_strides), + m_contract_strides(contract_strides), + m_k_strides(k_strides) { } + + enum { + DirectOffsets = CoeffLoader::DirectOffsets + }; + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void offsetBuffer(typename Tensor::Index offset) { + m_tensor.offsetBuffer(offset); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void prefetch(Index /*i*/) { } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar operator()(Index row) const { + // column major assumption + return operator()(row, 0); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar operator()(Index row, Index col) const { + return m_tensor.coeff(computeIndex(row, col)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Index computeIndex(Index row, Index col) const { + const bool left = (side == Lhs); + Index nocontract_val = left ? row : col; + Index linidx = 0; + for (int i = static_cast(array_size::value) - 1; i > 0; i--) { + const Index idx = nocontract_val / m_ij_strides[i]; + linidx += idx * m_nocontract_strides[i]; + nocontract_val -= idx * m_ij_strides[i]; + } + if (array_size::value > array_size::value) { + if (side == Lhs && inner_dim_contiguous) { + eigen_assert(m_nocontract_strides[0] == 1); + linidx += nocontract_val; + } else { + linidx += nocontract_val * m_nocontract_strides[0]; + } + } + + Index contract_val = left ? col : row; + if(array_size::value > 0) { + for (int i = static_cast(array_size::value) - 1; i > 0; i--) { + const Index idx = contract_val / m_k_strides[i]; + linidx += idx * m_contract_strides[i]; + contract_val -= idx * m_k_strides[i]; + } + + if (side == Rhs && inner_dim_contiguous) { + eigen_assert(m_contract_strides[0] == 1); + linidx += contract_val; + } else { + linidx += contract_val * m_contract_strides[0]; + } + } + + return linidx; + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE IndexPair computeIndexPair(Index row, Index col, const Index distance) const { + const bool left = (side == Lhs); + Index nocontract_val[2] = {left ? row : col, left ? row + distance : col}; + Index linidx[2] = {0, 0}; + if (array_size::value > array_size::value) { + for (int i = static_cast(array_size::value) - 1; i > 0; i--) { + const Index idx0 = nocontract_val[0] / m_ij_strides[i]; + const Index idx1 = nocontract_val[1] / m_ij_strides[i]; + linidx[0] += idx0 * m_nocontract_strides[i]; + linidx[1] += idx1 * m_nocontract_strides[i]; + nocontract_val[0] -= idx0 * m_ij_strides[i]; + nocontract_val[1] -= idx1 * m_ij_strides[i]; + } + if (side == Lhs && inner_dim_contiguous) { + eigen_assert(m_nocontract_strides[0] == 1); + linidx[0] += nocontract_val[0]; + linidx[1] += nocontract_val[1]; + } else { + linidx[0] += nocontract_val[0] * m_nocontract_strides[0]; + linidx[1] += nocontract_val[1] * m_nocontract_strides[0]; + } + } + + Index contract_val[2] = {left ? col : row, left ? col : row + distance}; + if (array_size::value> 0) { + for (int i = static_cast(array_size::value) - 1; i > 0; i--) { + const Index idx0 = contract_val[0] / m_k_strides[i]; + const Index idx1 = contract_val[1] / m_k_strides[i]; + linidx[0] += idx0 * m_contract_strides[i]; + linidx[1] += idx1 * m_contract_strides[i]; + contract_val[0] -= idx0 * m_k_strides[i]; + contract_val[1] -= idx1 * m_k_strides[i]; + } + + if (side == Rhs && inner_dim_contiguous) { + eigen_assert(m_contract_strides[0] == 1); + linidx[0] += contract_val[0]; + linidx[1] += contract_val[1]; + } else { + linidx[0] += contract_val[0] * m_contract_strides[0]; + linidx[1] += contract_val[1] * m_contract_strides[0]; + } + } + return IndexPair(linidx[0], linidx[1]); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Index firstAligned(Index size) const { + // Only claim alignment when we can compute the actual stride (ie when we're + // dealing with the lhs with inner_dim_contiguous. This is because the + // matrix-vector product relies on the stride when dealing with aligned inputs. + return (Alignment == Aligned) && (side == Lhs) && inner_dim_contiguous ? 0 : size; + } + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Index stride() const { + return ((side == Lhs) && inner_dim_contiguous && array_size::value > 0) ? m_contract_strides[0] : 1; + } + + protected: + CoeffLoader m_tensor; + const nocontract_t m_nocontract_strides; + const nocontract_t m_ij_strides; + const contract_t m_contract_strides; + const contract_t m_k_strides; +}; + +template class MakePointer_> +class BaseTensorContractionMapper : public SimpleTensorContractionMapper +{ + public: + typedef SimpleTensorContractionMapper ParentMapper; + + EIGEN_DEVICE_FUNC + BaseTensorContractionMapper(const Tensor& tensor, + const nocontract_t& nocontract_strides, + const nocontract_t& ij_strides, + const contract_t& contract_strides, + const contract_t& k_strides) : + ParentMapper(tensor, nocontract_strides, ij_strides, contract_strides, k_strides) { } + + typedef typename Tensor::PacketReturnType Packet; + typedef typename unpacket_traits::half HalfPacket; + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE PacketT load(Index i, Index j) const { + // whole method makes column major assumption + + // don't need to add offsets for now (because operator handles that) + // current code assumes packet size must be a multiple of 2 + EIGEN_STATIC_ASSERT(packet_size % 2 == 0, YOU_MADE_A_PROGRAMMING_MISTAKE); + + if (Tensor::PacketAccess && inner_dim_contiguous && !inner_dim_reordered) { + const Index index = this->computeIndex(i, j); + eigen_assert(this->computeIndex(i+packet_size-1, j) == index + packet_size-1); + return this->m_tensor.template packet(index); + } + + const IndexPair indexPair = this->computeIndexPair(i, j, packet_size - 1); + const Index first = indexPair.first; + const Index last = indexPair.second; + + // We can always do optimized packet reads from left hand side right now, because + // the vertical matrix dimension on the left hand side is never contracting. + // On the right hand side we need to check if the contracting dimensions may have + // been shuffled first. + if (Tensor::PacketAccess && + (side == Lhs || internal::array_size::value <= 1 || !inner_dim_reordered) && + (last - first) == (packet_size - 1)) { + + return this->m_tensor.template packet(first); + } + + EIGEN_ALIGN_MAX Scalar data[packet_size]; + + data[0] = this->m_tensor.coeff(first); + for (Index k = 1; k < packet_size - 1; k += 2) { + const IndexPair internal_pair = this->computeIndexPair(i + k, j, 1); + data[k] = this->m_tensor.coeff(internal_pair.first); + data[k + 1] = this->m_tensor.coeff(internal_pair.second); + } + data[packet_size - 1] = this->m_tensor.coeff(last); + + return pload(data); + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Packet loadPacket(Index i, Index j) const { + return this->load(i,j); + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE HalfPacket loadHalfPacket(Index i, Index j) const { + // whole method makes column major assumption + + // don't need to add offsets for now (because operator handles that) + const Index half_packet_size = unpacket_traits::size; + if (half_packet_size == packet_size) { + return loadPacket(i, j); + } + EIGEN_ALIGN_MAX Scalar data[half_packet_size]; + for (Index k = 0; k < half_packet_size; k++) { + data[k] = operator()(i + k, j); + } + return pload(data); + } +}; + + +template class MakePointer_> +class BaseTensorContractionMapper : public SimpleTensorContractionMapper +{ + public: + typedef SimpleTensorContractionMapper ParentMapper; + + EIGEN_DEVICE_FUNC + BaseTensorContractionMapper(const Tensor& tensor, + const nocontract_t& nocontract_strides, + const nocontract_t& ij_strides, + const contract_t& contract_strides, + const contract_t& k_strides) : + ParentMapper(tensor, nocontract_strides, ij_strides, contract_strides, k_strides) { } + + typedef typename Tensor::PacketReturnType Packet; + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Packet loadPacket(Index i, Index j) const { + EIGEN_ALIGN_MAX Scalar data[1]; + data[0] = this->m_tensor.coeff(this->computeIndex(i, j)); + return pload(data); + } + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE PacketT load(Index i, Index j) const { + EIGEN_ALIGN_MAX Scalar data[1]; + data[0] = this->m_tensor.coeff(this->computeIndex(i, j)); + return pload(data); + } + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Packet loadHalfPacket(Index i, Index j) const { + return loadPacket(i, j); + } +}; + + +template class MakePointer_=MakePointer> +class TensorContractionSubMapper { + public: + typedef typename Tensor::PacketReturnType Packet; + typedef typename unpacket_traits::half HalfPacket; + + typedef BaseTensorContractionMapper ParentMapper; + typedef TensorContractionSubMapper Self; + typedef Self LinearMapper; + + enum { + // We can use direct offsets iff the parent mapper supports then and we can compute the strides. + // TODO: we should also enable direct offsets for the Rhs case. + UseDirectOffsets = ParentMapper::DirectOffsets && (side == Lhs) && inner_dim_contiguous && (array_size::value > 0) + }; + + EIGEN_DEVICE_FUNC TensorContractionSubMapper(const ParentMapper& base_mapper, Index vert_offset, Index horiz_offset) + : m_base_mapper(base_mapper), m_vert_offset(vert_offset), m_horiz_offset(horiz_offset) { + // Bake the offsets into the buffer used by the base mapper whenever possible. This avoids the need to recompute + // this offset every time we attempt to access a coefficient. + if (UseDirectOffsets) { + Index stride = m_base_mapper.stride(); + m_base_mapper.offsetBuffer(vert_offset + horiz_offset * stride); + } + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Scalar operator()(Index i) const { + if (UseDirectOffsets) { + return m_base_mapper(i, 0); + } + return m_base_mapper(i + m_vert_offset, m_horiz_offset); + } + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Scalar operator()(Index i, Index j) const { + if (UseDirectOffsets) { + return m_base_mapper(i, j); + } + return m_base_mapper(i + m_vert_offset, j + m_horiz_offset); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Packet loadPacket(Index i) const { + if (UseDirectOffsets) { + return m_base_mapper.template loadPacket(i, 0); + } + return m_base_mapper.template loadPacket(i + m_vert_offset, m_horiz_offset); + } + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Packet loadPacket(Index i, Index j) const { + if (UseDirectOffsets) { + return m_base_mapper.template loadPacket(i, j); + } + return m_base_mapper.template loadPacket(i + m_vert_offset, j + m_horiz_offset); + } + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketT loadPacket(Index i, Index j) const { + if (UseDirectOffsets) { + return m_base_mapper.template load(i, j); + } + return m_base_mapper.template loadPacket(i + m_vert_offset, j + m_horiz_offset); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE HalfPacket loadHalfPacket(Index i) const { + if (UseDirectOffsets) { + return m_base_mapper.template loadHalfPacket(i, 0); + } + return m_base_mapper.template loadHalfPacket(i + m_vert_offset, m_horiz_offset); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void storePacket(Index i, const Packet& p) const { + if (UseDirectOffsets) { + m_base_mapper.storePacket(i, 0, p); + } + m_base_mapper.storePacket(i + m_vert_offset, m_horiz_offset, p); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE LinearMapper getLinearMapper(Index i, Index j) const { + if (UseDirectOffsets) { + return LinearMapper(m_base_mapper, i, j); + } + return LinearMapper(m_base_mapper, i + m_vert_offset, j + m_horiz_offset); + } + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketT load(Index i) const { + EIGEN_STATIC_ASSERT((internal::is_same::value), YOU_MADE_A_PROGRAMMING_MISTAKE); + const int ActualAlignment = (AlignmentType == Aligned) && (Alignment == Aligned) ? Aligned : Unaligned; + if (UseDirectOffsets) { + return m_base_mapper.template loadPacket(i, 0); + } + return m_base_mapper.template loadPacket(i + m_vert_offset, m_horiz_offset); + } + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool aligned(Index) const { + return false; + } + + private: + ParentMapper m_base_mapper; + const Index m_vert_offset; + const Index m_horiz_offset; +}; + + +template class MakePointer_=MakePointer> +class TensorContractionInputMapper + : public BaseTensorContractionMapper { + + public: + typedef Scalar_ Scalar; + typedef BaseTensorContractionMapper Base; + typedef TensorContractionSubMapper SubMapper; + typedef SubMapper VectorMapper; + + EIGEN_DEVICE_FUNC TensorContractionInputMapper(const Tensor& tensor, + const nocontract_t& nocontract_strides, + const nocontract_t& ij_strides, + const contract_t& contract_strides, + const contract_t& k_strides) + : Base(tensor, nocontract_strides, ij_strides, contract_strides, k_strides) { } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE SubMapper getSubMapper(Index i, Index j) const { + return SubMapper(*this, i, j); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE VectorMapper getVectorMapper(Index i, Index j) const { + return VectorMapper(*this, i, j); + } +}; + + + +} // end namespace internal +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_MAPPER_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionSycl.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionSycl.h new file mode 100644 index 00000000..e87de0c5 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionSycl.h @@ -0,0 +1,400 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Mehdi Goli Codeplay Software Ltd. +// Ralph Potter Codeplay Software Ltd. +// Luke Iwanski Codeplay Software Ltd. +// Contact: +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +/***************************************************************** + * TensorSyclConvertToDeviceExpression.h + * + * \brief: + * TensorContractionsycl + * +*****************************************************************/ + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_SYCL_H +#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_SYCL_H +namespace Eigen { + +template struct LaunchSyclKernels; +template +struct TensorEvaluator, const Eigen::SyclDevice> : + public TensorContractionEvaluatorBase, const Eigen::SyclDevice> > { + + typedef const Eigen::SyclDevice Device; + + typedef TensorEvaluator, Device> Self; + typedef TensorContractionEvaluatorBase Base; + typedef TensorContractionOp XprType; + typedef typename internal::remove_const::type Scalar; + typedef typename XprType::Index Index; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + + enum { + Layout = TensorEvaluator::Layout, + }; + + // Most of the code is assuming that both input tensors are ColMajor. If the + // inputs are RowMajor, we will "cheat" by swapping the LHS and RHS: + // If we want to compute A * B = C, where A is LHS and B is RHS, the code + // will pretend B is LHS and A is RHS. + typedef typename internal::conditional< + static_cast(Layout) == static_cast(ColMajor), LeftArgType, RightArgType>::type EvalLeftArgType; + typedef typename internal::conditional< + static_cast(Layout) == static_cast(ColMajor), RightArgType, LeftArgType>::type EvalRightArgType; + + static const int LDims = + internal::array_size::Dimensions>::value; + static const int RDims = + internal::array_size::Dimensions>::value; + static const int ContractDims = internal::array_size::value; + + typedef array left_dim_mapper_t; + typedef array right_dim_mapper_t; + + typedef array contract_t; + typedef array left_nocontract_t; + typedef array right_nocontract_t; + + static const int NumDims = LDims + RDims - 2 * ContractDims; + + typedef DSizes Dimensions; + + // typedefs needed in evalTo + typedef typename internal::remove_const::type LhsScalar; + typedef typename internal::remove_const::type RhsScalar; + + typedef TensorEvaluator LeftEvaluator; + typedef TensorEvaluator RightEvaluator; + + typedef typename LeftEvaluator::Dimensions LeftDimensions; + typedef typename RightEvaluator::Dimensions RightDimensions; + + EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device) : + Base(op, device) {} + + // We need to redefine this method to make nvcc happy + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* data) { + this->m_leftImpl.evalSubExprsIfNeeded(NULL); + this->m_rightImpl.evalSubExprsIfNeeded(NULL); + if (data) { + evalTo(data); + return false; + } else { + this->m_result = static_cast(this->m_device.allocate(this->dimensions().TotalSize() * sizeof(Scalar))); + evalTo(this->m_result); + return true; + } + } + const Eigen::SyclDevice& device() const {return this->m_device;} + void evalTo(Scalar* buffer) const { + // Here is the result + if (this->m_lhs_inner_dim_contiguous) { + if (this->m_rhs_inner_dim_contiguous) { + if (this->m_rhs_inner_dim_reordered) { + evalTyped(buffer); + } + else { + evalTyped(buffer); + } + } + else { + if (this->m_rhs_inner_dim_reordered) { + evalTyped(buffer); + } + else { + evalTyped(buffer); + } + } + } + else { + if (this->m_rhs_inner_dim_contiguous) { + if (this->m_rhs_inner_dim_reordered) { + evalTyped(buffer); + } + else { + evalTyped(buffer); + } + } + else { + if (this->m_rhs_inner_dim_reordered) { + evalTyped(buffer); + } + else { + evalTyped(buffer); + } + } + } + } + + template + void evalTyped(Scalar* buffer) const { + // columns in left side, rows in right side + const Index k = this->m_k_size; + EIGEN_UNUSED_VARIABLE(k) + // rows in left side + const Index m = this->m_i_size; + // columns in right side + const Index n = this->m_j_size; + + // zero out the result buffer (which must be of size at least m * n * sizeof(Scalar) + this->m_device.memset(buffer, 0, m * n * sizeof(Scalar)); + LaunchSyclKernels::Run(*this, buffer, m, n, k, + this->m_k_strides, this->m_left_contracting_strides, this->m_right_contracting_strides, + this->m_i_strides, this->m_j_strides, this->m_left_nocontract_strides, this->m_right_nocontract_strides); + } + // required by sycl to construct the expr on the device. Returns original left_impl + const TensorEvaluator& left_impl() const { + return choose(Cond(Layout) == static_cast(ColMajor)>(), this->m_leftImpl, this->m_rightImpl); + } + // required by sycl to construct the expr on the device. Returns original right_impl + const TensorEvaluator& right_impl() const { + return choose(Cond(Layout) == static_cast(ColMajor)>(), this->m_rightImpl, this->m_leftImpl); + } +}; + +template struct KernelConstructor{ + typedef typename Eigen::internal::traits::_LhsNested LHSHostExpr; + typedef typename Eigen::internal::traits::_RhsNested RHSHostExpr; + typedef typename Eigen::TensorSycl::internal::createPlaceHolderExpression::Type LHSPlaceHolderExpr; + typedef typename Eigen::TensorSycl::internal::createPlaceHolderExpression::Type RHSPlaceHolderExpr; + LHSFunctorExpr lhs_functors; + RHSFunctorExpr rhs_functors; + LhsLocalAcc localLhs; + RhsLocalAcc localRhs; + OutAccessor out_res; + Index roundUpK, M, N, K; + ContractT m_k_strides, m_left_contracting_strides, m_right_contracting_strides; + LeftNocontractT m_i_strides, m_left_nocontract_strides; + RightNocontractT m_j_strides, m_right_nocontract_strides; + LHSTupleType left_tuple_of_accessors; + RHSTupleType right_tuple_of_accessors; + Device dev; + + + KernelConstructor(LHSFunctorExpr lhs_functors_, RHSFunctorExpr rhs_functors_, LhsLocalAcc localLhs_, RhsLocalAcc localRhs_, OutAccessor out_res_, + Index roundUpK_, Index M_, Index N_, Index K_, ContractT m_k_strides_, ContractT m_left_contracting_strides_, + ContractT m_right_contracting_strides_, LeftNocontractT m_i_strides_, RightNocontractT m_j_strides_, + LeftNocontractT m_left_nocontract_strides_, RightNocontractT m_right_nocontract_strides_, LHSTupleType left_tuple_of_accessors_, RHSTupleType right_tuple_of_accessors_, Device dev_) + :lhs_functors(lhs_functors_), rhs_functors(rhs_functors_), localLhs(localLhs_), localRhs(localRhs_), out_res(out_res_), roundUpK(roundUpK_), M(M_), N(N_), K(K_), + m_k_strides(m_k_strides_), m_left_contracting_strides(m_left_contracting_strides_), + m_right_contracting_strides(m_right_contracting_strides_), + m_i_strides(m_i_strides_), m_left_nocontract_strides(m_left_nocontract_strides_), + m_j_strides(m_j_strides_), m_right_nocontract_strides(m_right_nocontract_strides_), + left_tuple_of_accessors(left_tuple_of_accessors_), right_tuple_of_accessors(right_tuple_of_accessors_), dev(dev_){} + + void operator()(cl::sycl::nd_item<1> itemID) { + typedef typename Eigen::TensorSycl::internal::ConvertToDeviceExpression::Type DevExpr; + typedef typename Eigen::TensorSycl::internal::ConvertToDeviceExpression::Type LHSDevExpr; + typedef typename Eigen::TensorSycl::internal::ConvertToDeviceExpression::Type RHSDevExpr; + auto lhs_dev_expr = Eigen::TensorSycl::internal::createDeviceExpression(lhs_functors, left_tuple_of_accessors); + auto rhs_dev_expr = Eigen::TensorSycl::internal::createDeviceExpression(rhs_functors, right_tuple_of_accessors); + typedef decltype(lhs_dev_expr.expr) LeftArgType; + typedef decltype(rhs_dev_expr.expr) RightArgType; + typedef typename internal::conditional(Eigen::internal::traits::Layout) == static_cast(ColMajor), LeftArgType, RightArgType>::type EvalLeftArgType; + typedef typename internal::conditional(Eigen::internal::traits::Layout) == static_cast(ColMajor), RightArgType, LeftArgType>::type EvalRightArgType; + typedef TensorEvaluator LeftEvaluator; + typedef TensorEvaluator RightEvaluator; + typedef internal::TensorContractionInputMapper LhsMapper; + + typedef internal::TensorContractionInputMapper RhsMapper; + // initialize data mappers must happen inside the kernel for device eval + LhsMapper lhs(LeftEvaluator(choose(Cond(Eigen::internal::traits::Layout) == static_cast(ColMajor)>(), + lhs_dev_expr.expr, rhs_dev_expr.expr), dev), m_left_nocontract_strides, m_i_strides, m_left_contracting_strides, m_k_strides); + RhsMapper rhs(RightEvaluator(choose(Cond(Eigen::internal::traits::Layout) == static_cast(ColMajor)>(), + rhs_dev_expr.expr, lhs_dev_expr.expr),dev), m_right_nocontract_strides, m_j_strides, m_right_contracting_strides, m_k_strides); + auto out_ptr = ConvertToActualTypeSycl(OutScalar, out_res); + // Matmul Kernel + // Thread identifiers + const Index mLocalThreadId = itemID.get_local(0); // Local ID row + const Index nLocalThreadId = itemID.get_local(1); // Local ID col + const Index mGroupId = itemID.get_group(0); // Work-group ID row + const Index nGroupId = itemID.get_group(1); // Work-group ID localCol + const Index linearLocalThreadId = nLocalThreadId*LocalThreadSizeM + mLocalThreadId; // linear local thread ID + // Allocate register space + float privateLhs; + float privateRhs[WorkLoadPerThreadN]; + float privateRes[WorkLoadPerThreadM][WorkLoadPerThreadN]; + // Initialise the privateResumulation registers + for (Index wLPTM=0; wLPTM(0); + } + // Tile Rhs + for (Index lPTR=0; lPTR(0); + + } + // Loop over all tiles + const Index numTiles = roundUpK/TileSizeDimK; + Index firstHalf=0; + do { + // Synchronise + itemID.barrier(cl::sycl::access::fence_space::local_space); + // Load the next tile of Lhs and Rhs into local memory + Index nextHalf = firstHalf + 1; + if (nextHalf < numTiles) { + // Tile A + for (Index lPTL=0; lPTL(0); + } + // Tile B + for (Index lPTR=0; lPTR(0); + } + } + // Loop over the values of a single tile + for (Index k=0; k struct LaunchSyclKernels { + +static const Index TileSizeDimM = 32ul; // Tile size for dimension M +static const Index TileSizeDimN = 32ul; // Tile size for dimension N +static const Index TileSizeDimK = 16ul; // Tile size for dimension K +static const Index WorkLoadPerThreadM = 4ul; // Work load per thread in dimension M +static const Index WorkLoadPerThreadN = 4ul; // work load per thread in dimension N +static const Index LocalThreadSizeM = (TileSizeDimM/WorkLoadPerThreadM); // Local thread size for the first dimension (M here) +static const Index LocalThreadSizeN = (TileSizeDimN/WorkLoadPerThreadN); // Local thread size for the second dimension (N here) +static const Index LoadPerThreadLhs = ((TileSizeDimK*WorkLoadPerThreadM*WorkLoadPerThreadN)/(TileSizeDimN)); // workload per thread for Lhs expression +static const Index LoadPerThreadRhs = ((TileSizeDimK*WorkLoadPerThreadM*WorkLoadPerThreadN)/(TileSizeDimM)); // workload per thread for Rhs expression + +// RoundUp function to make sure that the global threadId is divisable by local threadId +static Index RoundUp(Index x, Index y) { + return ((((x) + (y) - 1) / (y))*(y)); +} + +template< typename Self, typename OutScalar, typename ContractT, typename LeftNocontractT, typename RightNocontractT> + static void Run(const Self& self, OutScalar* buffer, Index M, Index N, Index K, + ContractT m_k_strides, ContractT m_left_contracting_strides, ContractT m_right_contracting_strides, + LeftNocontractT m_i_strides, RightNocontractT m_j_strides, LeftNocontractT m_left_nocontract_strides, RightNocontractT m_right_nocontract_strides){ + + typedef typename Self::XprType HostExpr; + typedef typename Eigen::internal::traits::_LhsNested LHSHostExpr; + typedef typename Eigen::internal::traits::_RhsNested RHSHostExpr; + typedef TensorEvaluator OrigLHSExpr; + typedef TensorEvaluator OrigRHSExpr; + typedef Eigen::TensorSycl::internal::FunctorExtractor LHSFunctorExpr; + typedef Eigen::TensorSycl::internal::FunctorExtractor RHSFunctorExpr; + // extract lhs functor list + LHSFunctorExpr lhs_functors = Eigen::TensorSycl::internal::extractFunctors(self.left_impl()); + // extract rhs functor list + RHSFunctorExpr rhs_functors = Eigen::TensorSycl::internal::extractFunctors(self.left_impl()); + + Index roundUpK = RoundUp(K, TileSizeDimK); + Index roundUpM = RoundUp(M, TileSizeDimM); + Index roundUpN = RoundUp(N, TileSizeDimN); + + self.device().sycl_queue().submit([&](cl::sycl::handler &cgh) { + /// work-around for gcc bug + typedef decltype(Eigen::TensorSycl::internal::createTupleOfAccessors(cgh, self.left_impl())) LHSTupleType; + /// work-around for gcc bug + typedef decltype(Eigen::TensorSycl::internal::createTupleOfAccessors(cgh, self.right_impl())) RHSTupleType; + // create lhs tuple of accessors + LHSTupleType left_tuple_of_accessors = Eigen::TensorSycl::internal::createTupleOfAccessors(cgh, self.left_impl()); + // create rhs tuple of accessors + RHSTupleType right_tuple_of_accessors = Eigen::TensorSycl::internal::createTupleOfAccessors(cgh, self.right_impl()); + + // Local memory for elements of Lhs + typedef cl::sycl::accessor LhsLocalAcc; + LhsLocalAcc localLhs(cl::sycl::range<1>(2* TileSizeDimM * TileSizeDimK), cgh); + // Local memory for elements of Rhs + typedef cl::sycl::accessor RhsLocalAcc; + RhsLocalAcc localRhs(cl::sycl::range<1>(2* TileSizeDimK * TileSizeDimN), cgh); + + typedef cl::sycl::accessor OutAccessor; + //OutScalar memory + OutAccessor out_res= self.device(). template get_sycl_accessor(cgh, buffer); + + // sycl parallel for + cgh.parallel_for(cl::sycl::nd_range<2>(cl::sycl::range<2>(roundUpM/WorkLoadPerThreadM, roundUpN/WorkLoadPerThreadN), + cl::sycl::range<2>(LocalThreadSizeM, LocalThreadSizeN)), + KernelConstructor(lhs_functors, rhs_functors, + localLhs, localRhs, out_res, roundUpK, M, N, K, m_k_strides, m_left_contracting_strides, m_right_contracting_strides,m_i_strides, m_j_strides, + m_left_nocontract_strides,m_right_nocontract_strides, left_tuple_of_accessors, right_tuple_of_accessors, Eigen::DefaultDevice())); + }); + self.device().asynchronousExec(); + } +}; + +} // end namespace Eigen +#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_SYCL_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionThreadPool.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionThreadPool.h new file mode 100644 index 00000000..d30cc96a --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionThreadPool.h @@ -0,0 +1,1252 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_THREAD_POOL_H +#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_THREAD_POOL_H + +// evaluator for thread pool device +#ifdef EIGEN_USE_THREADS + +namespace Eigen { + +#ifdef EIGEN_USE_SIMPLE_THREAD_POOL +namespace internal { + +template +struct packLhsArg { + LhsScalar* blockA; + const LhsMapper& lhs; + const Index m_start; + const Index k_start; + const Index mc; + const Index kc; +}; + +template +struct packRhsAndKernelArg { + const MaxSizeVector* blockAs; + RhsScalar* blockB; + const RhsMapper& rhs; + OutputMapper& output; + const Index m; + const Index k; + const Index n; + const Index mc; + const Index kc; + const Index nc; + const Index num_threads; + const Index num_blockAs; + const Index max_m; + const Index k_block_idx; + const Index m_block_idx; + const Index n_block_idx; + const Index m_blocks; + const Index n_blocks; + MaxSizeVector* kernel_notifications; + const MaxSizeVector* lhs_notifications; + const bool need_to_pack; +}; + +} // end namespace internal +#endif // EIGEN_USE_SIMPLE_THREAD_POOL + +template +struct TensorEvaluator, ThreadPoolDevice> : + public TensorContractionEvaluatorBase, ThreadPoolDevice> > { + + typedef ThreadPoolDevice Device; + + typedef TensorEvaluator, Device> Self; + typedef TensorContractionEvaluatorBase Base; + + typedef TensorContractionOp XprType; + typedef typename internal::remove_const::type Scalar; + typedef typename XprType::Index Index; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + + enum { + Layout = TensorEvaluator::Layout, + }; + + // Most of the code is assuming that both input tensors are ColMajor. If the + // inputs are RowMajor, we will "cheat" by swapping the LHS and RHS: + // If we want to compute A * B = C, where A is LHS and B is RHS, the code + // will pretend B is LHS and A is RHS. + typedef typename internal::conditional< + static_cast(Layout) == static_cast(ColMajor), LeftArgType, RightArgType>::type EvalLeftArgType; + typedef typename internal::conditional< + static_cast(Layout) == static_cast(ColMajor), RightArgType, LeftArgType>::type EvalRightArgType; + + static const int LDims = + internal::array_size::Dimensions>::value; + static const int RDims = + internal::array_size::Dimensions>::value; + static const int ContractDims = internal::array_size::value; + + typedef array left_dim_mapper_t; + typedef array right_dim_mapper_t; + + typedef array contract_t; + typedef array left_nocontract_t; + typedef array right_nocontract_t; + + static const int NumDims = LDims + RDims - 2 * ContractDims; + + typedef DSizes Dimensions; + + // typedefs needed in evalTo + typedef typename internal::remove_const::type LhsScalar; + typedef typename internal::remove_const::type RhsScalar; + typedef typename internal::gebp_traits Traits; + + typedef TensorEvaluator LeftEvaluator; + typedef TensorEvaluator RightEvaluator; + + TensorEvaluator(const XprType& op, const Device& device) : + Base(op, device) {} + +#ifndef EIGEN_USE_SIMPLE_THREAD_POOL + template + void evalProduct(Scalar* buffer) const { + const Index m = this->m_i_size; + const Index n = this->m_j_size; + const Index k = this->m_k_size; + if (m == 0 || n == 0 || k == 0) return; + +#if defined(EIGEN_VECTORIZE_AVX) && defined(EIGEN_USE_LIBXSMM) + if (this->m_can_use_xsmm) { + bool transposeA = !this->m_lhs_inner_dim_contiguous; + bool transposeB = !this->m_rhs_inner_dim_contiguous; + internal::TensorXsmmContractionBlocking + blocking(k, m, n, this->m_device.numThreads(), transposeA, + transposeB); + + if (blocking.num_threads() == 1) { + this->evalGemmXSMM(buffer); + } else { + ContextXsmm(this, buffer, m, n, k, blocking).run(); + } + return; + } +#endif + + typedef + typename internal::remove_const::type + LhsScalar; + typedef + typename internal::remove_const::type + RhsScalar; + typedef typename internal::gebp_traits Traits; + typedef TensorEvaluator LeftEvaluator; + typedef TensorEvaluator RightEvaluator; + typedef internal::TensorContractionInputMapper< + LhsScalar, Index, internal::Lhs, LeftEvaluator, left_nocontract_t, + contract_t, internal::packet_traits::size, + lhs_inner_dim_contiguous, false, Unaligned> + LhsMapper; + typedef internal::TensorContractionInputMapper< + RhsScalar, Index, internal::Rhs, RightEvaluator, right_nocontract_t, + contract_t, internal::packet_traits::size, + rhs_inner_dim_contiguous, rhs_inner_dim_reordered, Unaligned> + RhsMapper; + typedef internal::blas_data_mapper OutputMapper; + typedef internal::gemm_pack_lhs + LhsPacker; + typedef internal::gemm_pack_rhs< + RhsScalar, Index, typename RhsMapper::SubMapper, Traits::nr, ColMajor> + RhsPacker; + typedef internal::gebp_kernel + GebpKernel; + + + + // Compute a set of algorithm parameters: + // - kernel block sizes (bm, bn, bk) + // - task grain sizes (number of kernels executed per task: gm, gn) + // - number of threads + // - sharding by row/column + // - parallel packing or first lhs then rhs + // and some derived parameters: + // - number of tasks (nm, nn, nk) + // - number of kernels (nm0, nn0) + // Unfortunately, all these parameters are tightly interdependent. + // So in some cases we first compute approximate values, then compute other + // values based on these approximations and then refine the approximations. + + // There are lots of heuristics here. There is some reasoning behind them, + // but ultimately they are just tuned on contraction benchmarks for + // different input configurations, thread counts and instruction sets. + // So feel free to question any of them. + + // Compute whether we want to shard by row or by column. + // This is a first approximation, it will be refined later. Since we don't + // know number of threads yet we use 2, because what's we are most + // interested in at this point is whether it makes sense to use + // parallelization at all or not. + bool shard_by_col = shardByCol(m, n, 2); + + // First approximation of kernel blocking sizes. + // Again, we don't know number of threads yet, so we use 2. + Index bm, bn, bk; + if (shard_by_col) { + internal::TensorContractionBlocking + blocking(k, m, n, 2); + bm = blocking.mc(); + bn = blocking.nc(); + bk = blocking.kc(); + } else { + internal::TensorContractionBlocking + blocking(k, m, n, 2); + bm = blocking.mc(); + bn = blocking.nc(); + bk = blocking.kc(); + } + + // Compute optimal number of threads. + // Note: we use bk instead of k here because we are interested in amount of + // _parallelizable_ computations, and computations are not parallelizable + // across k dimension. + const TensorOpCost cost = + contractionCost(m, n, bm, bn, bk, shard_by_col, false); + int num_threads = TensorCostModel::numThreads( + static_cast(n) * m, cost, this->m_device.numThreads()); + + // TODO(dvyukov): this is a stop-gap to prevent regressions while the cost + // model is not tuned. Remove this when the cost model is tuned. + if (n == 1) num_threads = 1; + + if (num_threads == 1) { + // The single-threaded algorithm should be faster in this case. + if (n == 1) + this->template evalGemv(buffer); + else + this->template evalGemm(buffer); + return; + } + + // Now that we know number of threads, recalculate sharding and blocking. + shard_by_col = shardByCol(m, n, num_threads); + if (shard_by_col) { + internal::TensorContractionBlocking + blocking(k, m, n, num_threads); + bm = blocking.mc(); + bn = blocking.nc(); + bk = blocking.kc(); + } else { + internal::TensorContractionBlocking + blocking(k, m, n, num_threads); + bm = blocking.mc(); + bn = blocking.nc(); + bk = blocking.kc(); + } + + // Number of kernels for each dimension. + Index nm0 = divup(m, bm); + Index nn0 = divup(n, bn); + Index nk = divup(k, bk); + + // Calculate task grain size (number of kernels executed per task). + // This task size coarsening serves two purposes: + // 1. It reduces per-task overheads including synchronization overheads. + // 2. It allows to use caches better (reuse the same packed rhs in several + // consecutive kernels). + Index gm = 1; + Index gn = 1; + // If we are sharding by column, then we prefer to reduce rows first. + if (shard_by_col) { + gm = coarsenM(m, n, bm, bn, bk, gn, num_threads, shard_by_col); + gn = coarsenN(m, n, bm, bn, bk, gm, num_threads, shard_by_col); + } else { + gn = coarsenN(m, n, bm, bn, bk, gm, num_threads, shard_by_col); + gm = coarsenM(m, n, bm, bn, bk, gn, num_threads, shard_by_col); + } + // Number of tasks in each dimension. + Index nm = divup(nm0, gm); + Index nn = divup(nn0, gn); + + // Last by not least, decide whether we want to issue both lhs and rhs + // packing in parallel; or issue lhs packing first, and then issue rhs + // packing when lhs packing completes (for !shard_by_col lhs and rhs are + // swapped). Parallel packing allows more parallelism (for both packing and + // kernels), while sequential packing provides better locality (once + // a thread finishes rhs packing it proceed to kernels with that rhs). + // First, we are interested in parallel packing if there are few tasks. + bool parallel_pack = num_threads >= nm * nn; + // Also do parallel packing if all data fits into L2$. + if (m * bk * Index(sizeof(LhsScalar)) + n * bk * Index(sizeof(RhsScalar)) <= + l2CacheSize() * num_threads) + parallel_pack = true; + // But don't do it if we will use each rhs only once. Locality seems to be + // more important in this case. + if ((shard_by_col ? nm : nn) == 1) parallel_pack = false; + + LhsMapper lhs(this->m_leftImpl, this->m_left_nocontract_strides, + this->m_i_strides, this->m_left_contracting_strides, + this->m_k_strides); + + RhsMapper rhs(this->m_rightImpl, this->m_right_nocontract_strides, + this->m_j_strides, this->m_right_contracting_strides, + this->m_k_strides); + + Context(this->m_device, num_threads, lhs, rhs, buffer, m, n, + k, bm, bn, bk, nm, nn, nk, gm, gn, nm0, nn0, + shard_by_col, parallel_pack) + .run(); + } + + // Context coordinates a single parallel gemm operation. + template + class Context { + public: + Context(const Device& device, int num_threads, LhsMapper& lhs, + RhsMapper& rhs, Scalar* buffer, Index tm, Index tn, Index tk, Index bm, + Index bn, Index bk, Index nm, Index nn, Index nk, Index gm, + Index gn, Index nm0, Index nn0, bool shard_by_col, + bool parallel_pack) + : device_(device), + lhs_(lhs), + rhs_(rhs), + buffer_(buffer), + output_(buffer, tm), + num_threads_(num_threads), + shard_by_col_(shard_by_col), + parallel_pack_(parallel_pack), + m_(tm), + n_(tn), + k_(tk), + bm_(bm), + bn_(bn), + bk_(bk), + nm_(nm), + nn_(nn), + nk_(nk), + gm_(gm), + gn_(gn), + nm0_(nm0), + nn0_(nn0) + { + for (Index x = 0; x < P; x++) { + // Normal number of notifications for k slice switch is + // nm_ + nn_ + nm_ * nn_. However, first P - 1 slices will receive only + // nm_ + nn_ notifications, because they will not receive notifications + // from preceeding kernels. + state_switch_[x] = + x == 0 + ? 1 + : (parallel_pack_ ? nn_ + nm_ : (shard_by_col_ ? nn_ : nm_)) + + (x == P - 1 ? nm_ * nn_ : 0); + state_packing_ready_[x] = + parallel_pack_ ? 0 : (shard_by_col_ ? nm_ : nn_); + state_kernel_[x] = new std::atomic*[nm_]; + for (Index m = 0; m < nm_; m++) { + state_kernel_[x][m] = new std::atomic[nn_]; + // Kernels generally receive 3 notifications (previous kernel + 2 + // packing), but the first slice won't get notifications from previous + // kernels. + for (Index n = 0; n < nn_; n++) + state_kernel_[x][m][n].store( + (x == 0 ? 0 : 1) + (parallel_pack_ ? 2 : 1), + std::memory_order_relaxed); + } + } + + // Allocate memory for packed rhs/lhs matrices. + size_t align = numext::maxi(EIGEN_MAX_ALIGN_BYTES, 1); + size_t lhs_size = + divup(bm_ * bk_ * sizeof(LhsScalar), align) * align; + size_t rhs_size = + divup(bn_ * bk_ * sizeof(RhsScalar), align) * align; + packed_mem_ = static_cast(internal::aligned_malloc( + (nm0_ * lhs_size + nn0_ * rhs_size) * std::min(nk_, P - 1))); + char* mem = static_cast(packed_mem_); + for (Index x = 0; x < numext::mini(nk_, P - 1); x++) { + packed_lhs_[x].resize(nm0_); + for (Index m = 0; m < nm0_; m++) { + packed_lhs_[x][m] = reinterpret_cast(mem); + mem += lhs_size; + } + packed_rhs_[x].resize(nn0_); + for (Index n = 0; n < nn0_; n++) { + packed_rhs_[x][n] = reinterpret_cast(mem); + mem += rhs_size; + } + } + } + + ~Context() { + for (Index x = 0; x < P; x++) { + for (Index m = 0; m < nm_; m++) delete[] state_kernel_[x][m]; + delete[] state_kernel_[x]; + } + internal::aligned_free(packed_mem_); + } + + void run() { + // Kick off packing of the first slice. + signal_switch(0, 1); + // Wait for overall completion. + // TODO(dvyukov): this wait can lead to deadlock. + // If nthreads contractions are concurrently submitted from worker + // threads, this wait will block all worker threads and the system will + // deadlock. + done_.Wait(); + } + + private: + Notification done_; + const Device& device_; + LhsMapper& lhs_; + RhsMapper& rhs_; + Scalar* const buffer_; + OutputMapper output_; + const int num_threads_; + const bool shard_by_col_; + const bool parallel_pack_; + // Matrix sizes. + const Index m_; + const Index n_; + const Index k_; + // Block sizes. + const Index bm_; + const Index bn_; + const Index bk_; + // Number of tasks. + const Index nm_; + const Index nn_; + const Index nk_; + // Task grain sizes (number of kernels executed per task). + const Index gm_; + const Index gn_; + // Number of blocks (this is different from ni_/nn_ because of task size + // coarsening). + const Index nm0_; + const Index nn0_; + + // Parallelization strategy. + // + // Blocks related to the same k block can run in parallel because they write + // to different output blocks. So we parallelize within k slices, this + // gives us parallelism level of m x n. Before we can start any kernels + // related to k-th slice, we need to issue m lhs packing tasks and n rhs + // packing tasks. + // + // However, there is a bottleneck when we are finishing kernels for k-th + // slice (at the very end there is only 1 runnable kernel). To mitigate this + // bottleneck we allow kernels from k-th and k+1-th slices to run in + // parallel. Note that (m, n, k) and (m, n, k+1) kernels write to the same + // output block, so they must not run in parallel. + // + // This gives us the following dependency graph. + // On each k slice we have m x n kernel tasks, m lhs paking tasks and n rhs + // packing tasks. + // Kernel (m, n, k) can start when: + // - kernel (m, n, k-1) has finished + // - lhs packing (m, k) has finished + // - rhs packing (n, k) has finished + // Lhs/rhs packing can start when: + // - all k-1 packing has finished (artificially imposed to limit amount of + // parallel packing) + // + // On top of that we limit runnable tasks to two consecutive k slices. + // This is done to limit amount of memory we need for packed lhs/rhs + // (for each k slice we need m*bk + n*bk memory in packed_lhs_/packed_rhs_). + // + // state_switch_ tracks when we are ready to switch to the next k slice. + // state_kernel_[m][n] tracks when we are ready to kick off kernel (m, n). + // These variable are rolling over 3 consecutive k slices: first two we are + // actively executing + one to track completion of kernels in the second + // slice. + static const Index P = 3; + void* packed_mem_; + std::vector packed_lhs_[P - 1]; + std::vector packed_rhs_[P - 1]; + std::atomic** state_kernel_[P]; + // state_switch_ is frequently modified by worker threads, while other + // fields are read-only after constructor. Let's move it to a separate cache + // line to reduce cache-coherency traffic. + char pad_[128]; + std::atomic state_packing_ready_[P]; + std::atomic state_switch_[P]; + + void pack_lhs(Index m, Index k) { + const Index mend = m * gm_ + gm(m); + for (Index m1 = m * gm_; m1 < mend; m1++) + LhsPacker()(packed_lhs_[k % (P - 1)][m1], + lhs_.getSubMapper(m1 * bm_, k * bk_), bk(k), bm(m1)); + + if (!parallel_pack_ && shard_by_col_) { + signal_packing(k); + } else { + signal_switch(k + 1); + for (Index n = nn_ - 1; n >= 0; n--) signal_kernel(m, n, k, n == 0); + } + } + + void pack_rhs(Index n, Index k) { + const Index nend = n * gn_ + gn(n); + for (Index n1 = n * gn_; n1 < nend; n1++) { + if (k == 0) { + // Zero the output memory in parallel. + // On 10000x2x10000 mm zeroing can easily take half of time. + // Zero (bn x m) row. Safe to do here because all kernels that will + // write to this memory depend on completion of this task. + // Note: don't call device_.memset() here. device_.memset() blocks on + // thread pool worker thread, which can lead to underutilization and + // deadlocks. + memset(buffer_ + n1 * bn_ * m_, 0, bn(n1) * m_ * sizeof(Scalar)); + } + RhsPacker()(packed_rhs_[k % (P - 1)][n1], + rhs_.getSubMapper(k * bk_, n1 * bn_), bk(k), bn(n1)); + } + + if (parallel_pack_ || shard_by_col_) { + signal_switch(k + 1); + for (Index m = nm_ - 1; m >= 0; m--) signal_kernel(m, n, k, m == 0); + } else { + signal_packing(k); + } + } + + void kernel(Index m, Index n, Index k) { + // Note: order of iteration matters here. Iteration over m is innermost + // because we want to reuse the same packed rhs in consequetive tasks + // (rhs fits into L2$ while lhs only into L3$). + const Index nend = n * gn_ + gn(n); + const Index mend = m * gm_ + gm(m); + if (shard_by_col_) { + for (Index n1 = n * gn_; n1 < nend; n1++) { + for (Index m1 = m * gm_; m1 < mend; m1++) + GebpKernel()(output_.getSubMapper(m1 * bm_, n1 * bn_), + packed_lhs_[k % (P - 1)][m1], + packed_rhs_[k % (P - 1)][n1], bm(m1), bk(k), bn(n1), + Scalar(1), -1, -1, 0, 0); + } + } else { + for (Index m1 = m * gm_; m1 < mend; m1++) + for (Index n1 = n * gn_; n1 < nend; n1++) { + GebpKernel()(output_.getSubMapper(m1 * bm_, n1 * bn_), + packed_lhs_[k % (P - 1)][m1], + packed_rhs_[k % (P - 1)][n1], bm(m1), bk(k), bn(n1), + Scalar(1), -1, -1, 0, 0); + } + } + signal_kernel(m, n, k + 1, false); + signal_switch(k + 2); + } + + void signal_packing(Index k) { + eigen_assert(!parallel_pack_); + Index s = state_packing_ready_[k % P].fetch_sub(1); + eigen_assert(s > 0); + if (s != 1) return; + state_packing_ready_[k % P] = shard_by_col_ ? nm_ : nn_; + enqueue_packing(k, shard_by_col_); + } + + void signal_kernel(Index m, Index n, Index k, bool sync) { + std::atomic* state = &state_kernel_[k % P][m][n]; + Index s = state->load(); + eigen_assert(s > 0); + if (s != 1 && state->fetch_sub(1) != 1) return; + state->store(parallel_pack_ ? 3 : 2, std::memory_order_relaxed); + if (sync) + kernel(m, n, k); + else + device_.enqueueNoNotification([=]() { kernel(m, n, k); }); + } + + void signal_switch(Index k, Index v = 1) { + Index s = state_switch_[k % P].fetch_sub(v); + eigen_assert(s >= v); + if (s != v) return; + + // Ready to switch to the next k slice. + // Reset counter for the next iteration. + state_switch_[k % P] = + (parallel_pack_ ? nm_ + nn_ : (shard_by_col_ ? nn_ : nm_)) + + nm_ * nn_; + if (k < nk_) { + // Issue lhs/rhs packing. Their completion will in turn kick off + // kernels. + if (parallel_pack_) { + enqueue_packing(k, !shard_by_col_); + enqueue_packing(k, shard_by_col_); + } else if (shard_by_col_) { + enqueue_packing(k, false); + } else { + enqueue_packing(k, true); + } + + // Termination handling. + // Because kernel completion signals k + 2 switch, we need to finish nk + // + 2 slices without issuing any tasks on nk + 1 slice. So here we + // pretend that all nk + 1 packing tasks just finish instantly; so that + // nk + 2 switch only waits for completion of nk kernels. + } else if (k == nk_) { + signal_switch(k + 1, + parallel_pack_ ? nm_ + nn_ : (shard_by_col_ ? nn_ : nm_)); + } else { + done_.Notify(); + } + } + + // Enqueue all rhs/lhs packing for k-th slice. + void enqueue_packing(Index k, bool rhs) { + enqueue_packing_helper(0, rhs ? nn_ : nm_, k, rhs); + } + + void enqueue_packing_helper(Index start, Index end, Index k, bool rhs) { + if (end - start == 1) { + if (rhs) + pack_rhs(start, k); + else + pack_lhs(start, k); + } else { + Index mid = (start + end) / 2; + device_.enqueueNoNotification( + [=]() { enqueue_packing_helper(mid, end, k, rhs); }); + device_.enqueueNoNotification( + [=]() { enqueue_packing_helper(start, mid, k, rhs); }); + } + } + + // Block sizes with accounting for potentially incomplete last block. + Index bm(Index m) const { return m + 1 < nm0_ ? bm_ : m_ + bm_ - bm_ * nm0_; } + Index bn(Index n) const { return n + 1 < nn0_ ? bn_ : n_ + bn_ - bn_ * nn0_; } + Index bk(Index k) const { return k + 1 < nk_ ? bk_ : k_ + bk_ - bk_ * nk_; } + // Task grain sizes accounting for potentially incomplete last task. + Index gm(Index m) const { return m + 1 < nm_ ? gm_ : nm0_ + gm_ - gm_ * nm_; } + Index gn(Index n) const { return n + 1 < nn_ ? gn_ : nn0_ + gn_ - gn_ * nn_; } + + Context(const Context&) = delete; + void operator=(const Context&) = delete; + }; + + // Decide whether we want to shard m x n contraction by columns or by rows. + static bool shardByCol(Index m, Index n, Index num_threads) { + // Note: we are comparing both n and m against Traits::nr, it is not + // a mistake. We are trying to figure out how both n and m will fit into + // the main sharding dimension. + + // Sharding by column is the default + // ... unless there is enough data for vectorization over rows + if (m / num_threads >= Traits::nr && + // and not enough data for vectorization over columns + (n / num_threads < Traits::nr || + // ... or barely enough data for vectorization over columns, + // but it is not evenly dividable across threads + (n / num_threads < 4 * Traits::nr && + (n % (num_threads * Traits::nr)) != 0 && + // ... and it is evenly dividable across threads for rows + ((m % (num_threads * Traits::nr)) == 0 || + // .. or it is not evenly dividable for both dimensions but + // there is much more data over rows so that corner effects are + // mitigated. + (m / n >= 6))))) + return false; + // Wait, or if matrices are just substantially prolonged over the other + // dimension. + if (n / num_threads < 16 * Traits::nr && m > n * 32) return false; + return true; + } + + Index coarsenM(Index m, Index n, Index bm, Index bn, Index bk, Index gn, + int num_threads, bool shard_by_col) const { + Index gm = 1; + Index gm1 = 1; + Index nm0 = divup(m, bm); + Index nm1 = nm0; + for (;;) { + // Find the next candidate for m grain size. It needs to result in + // different number of blocks. E.g. if we have 10 kernels, we want to try + // 5 and 10, but not 6, 7, 8 and 9. + while (gm1 <= nm0 && nm1 == divup(nm0, gm1)) gm1++; + if (gm1 > nm0) break; + // Check the candidate. + int res = checkGrain(m, n, bm, bn, bk, gm1, gn, gm, gn, num_threads, + shard_by_col); + if (res < 0) break; + nm1 = divup(nm0, gm1); + if (res == 0) continue; + // Commit new grain size. + gm = gm1; + } + return gm; + } + + Index coarsenN(Index m, Index n, Index bm, Index bn, Index bk, Index gm, + int num_threads, bool shard_by_col) const { + Index gn = 1; + Index gn1 = 1; + Index nn0 = divup(n, bn); + Index nn1 = nn0; + for (;;) { + while (gn1 <= nn0 && nn1 == divup(nn0, gn1)) gn1++; + if (gn1 > nn0) break; + int res = checkGrain(m, n, bm, bn, bk, gm, gn1, gm, gn, num_threads, + shard_by_col); + if (res < 0) break; + nn1 = divup(nn0, gn1); + if (res == 0) continue; + gn = gn1; + } + return gn; + } + + // checkGrain checks whether grain (gm, gn) is suitable and is better than + // (oldgm, oldgn). + int checkGrain(Index m, Index n, Index bm, Index bn, Index bk, Index gm, + Index gn, Index oldgm, Index oldgn, int num_threads, + bool shard_by_col) const { + const TensorOpCost cost = + contractionCost(bm * gm, bn * gn, bm, bn, bk, shard_by_col, true); + double taskSize = TensorCostModel::taskSize( + static_cast(bm) * gm * bn * gn, cost); + // If the task is too small, then we agree on it regardless of anything + // else. Otherwise synchronization overheads will dominate. + if (taskSize < 1) return 1; + // If it is too large, then we reject it and all larger tasks. + if (taskSize > 2) return -1; + // Now we are in presumably good task size range. + // The main deciding factor here is parallelism. Consider that we have 12 + // kernels and 4 threads. Grains of 2, 3 and 4 all yield good task sizes. + // But 2/4 yield 6/3 tasks, which gives us parallelism of 0.75 (at most 3/4 + // of cores will be busy). While grain size 3 gives us 4 tasks, which gives + // us parallelism of 1 (we can load all cores). + Index nm0 = divup(m, bm); + Index nn0 = divup(n, bn); + Index new_tasks = divup(nm0, gm) * divup(nn0, gn); + double new_parallelism = static_cast(new_tasks) / + (divup(new_tasks, num_threads) * num_threads); + Index old_tasks = divup(nm0, oldgm) * divup(nn0, oldgn); + double old_parallelism = static_cast(old_tasks) / + (divup(old_tasks, num_threads) * num_threads); + if (new_parallelism > old_parallelism || new_parallelism == 1) return 1; + return 0; + } + +#else // EIGEN_USE_SIMPLE_THREAD_POOL + + template + void evalProduct(Scalar* buffer) const { + if (this->m_j_size == 1) { + this->template evalGemv(buffer); + return; + } + + evalGemm(buffer); + } + + template + void evalGemm(Scalar* buffer) const { + // columns in left side, rows in right side + const Index k = this->m_k_size; + + // rows in left side + const Index m = this->m_i_size; + + // columns in right side + const Index n = this->m_j_size; + + // zero out the result buffer (which must be of size at least m * n * sizeof(Scalar) + this->m_device.memset(buffer, 0, m * n * sizeof(Scalar)); + + + const int lhs_packet_size = internal::unpacket_traits::size; + const int rhs_packet_size = internal::unpacket_traits::size; + + typedef internal::TensorContractionInputMapper LhsMapper; + + typedef internal::TensorContractionInputMapper RhsMapper; + + typedef internal::blas_data_mapper OutputMapper; + + // TODO: packing could be faster sometimes if we supported row major tensor mappers + typedef internal::gemm_pack_lhs LhsPacker; + typedef internal::gemm_pack_rhs RhsPacker; + + // TODO: replace false, false with conjugate values? + typedef internal::gebp_kernel GebpKernel; + + typedef internal::packLhsArg packLArg; + typedef internal::packRhsAndKernelArg packRKArg; + + // initialize data mappers + LhsMapper lhs(this->m_leftImpl, this->m_left_nocontract_strides, this->m_i_strides, + this->m_left_contracting_strides, this->m_k_strides); + + RhsMapper rhs(this->m_rightImpl, this->m_right_nocontract_strides, this->m_j_strides, + this->m_right_contracting_strides, this->m_k_strides); + + OutputMapper output(buffer, m); + + // compute block sizes (which depend on number of threads) + const Index num_threads = this->m_device.numThreads(); + internal::TensorContractionBlocking blocking(k, m, n, num_threads); + Index mc = blocking.mc(); + Index nc = blocking.nc(); + Index kc = blocking.kc(); + eigen_assert(mc <= m); + eigen_assert(nc <= n); + eigen_assert(kc <= k); + +#define CEIL_DIV(a, b) (((a) + (b) - 1) / (b)) + const Index k_blocks = CEIL_DIV(k, kc); + const Index n_blocks = CEIL_DIV(n, nc); + const Index m_blocks = CEIL_DIV(m, mc); + const Index sizeA = mc * kc; + const Index sizeB = kc * nc; + + /* cout << "m: " << m << " n: " << n << " k: " << k << endl; + cout << "mc: " << mc << " nc: " << nc << " kc: " << kc << endl; + cout << "m_blocks: " << m_blocks << " n_blocks: " << n_blocks << " k_blocks: " << k_blocks << endl; + cout << "num threads: " << num_threads << endl; + */ + + // note: m_device.allocate should return 16 byte aligned pointers, but if blockA and blockB + // aren't 16 byte aligned segfaults will happen due to SIMD instructions + // note: You can get away with allocating just a single blockA and offsets and meet the + // the alignment requirements with the assumption that + // (Traits::mr * sizeof(ResScalar)) % 16 == 0 + const Index numBlockAs = numext::mini(num_threads, m_blocks); + MaxSizeVector blockAs(num_threads); + for (int i = 0; i < num_threads; i++) { + blockAs.push_back(static_cast(this->m_device.allocate(sizeA * sizeof(LhsScalar)))); + } + + // To circumvent alignment issues, I'm just going to separately allocate the memory for each thread + // TODO: is this too much memory to allocate? This simplifies coding a lot, but is wasteful. + // Other options: (1) reuse memory when a thread finishes. con: tricky + // (2) allocate block B memory in each thread. con: overhead + MaxSizeVector blockBs(n_blocks); + for (int i = 0; i < n_blocks; i++) { + blockBs.push_back(static_cast(this->m_device.allocate(sizeB * sizeof(RhsScalar)))); + } + + // lhs_notifications starts with all null Notifications + MaxSizeVector lhs_notifications(num_threads, nullptr); + + // this should really be numBlockAs * n_blocks; + const Index num_kernel_notifications = num_threads * n_blocks; + MaxSizeVector kernel_notifications(num_kernel_notifications, + nullptr); + + for (Index k_block_idx = 0; k_block_idx < k_blocks; k_block_idx++) { + const Index k_start = k_block_idx * kc; + // make sure we don't overshoot right edge of left matrix + const Index actual_kc = numext::mini(k_start + kc, k) - k_start; + + for (Index m_block_idx = 0; m_block_idx < m_blocks; m_block_idx += numBlockAs) { + const Index num_blocks = numext::mini(m_blocks-m_block_idx, numBlockAs); + + for (Index mt_block_idx = m_block_idx; mt_block_idx < m_block_idx+num_blocks; mt_block_idx++) { + const Index m_start = mt_block_idx * mc; + const Index actual_mc = numext::mini(m_start + mc, m) - m_start; + eigen_assert(actual_mc > 0); + + Index blockAId = (k_block_idx * m_blocks + mt_block_idx) % num_threads; + + for (int i = 0; i < n_blocks; ++i) { + Index notification_id = (blockAId * n_blocks + i); + // Wait for any current kernels using this slot to complete + // before using it. + if (kernel_notifications[notification_id]) { + wait_until_ready(kernel_notifications[notification_id]); + delete kernel_notifications[notification_id]; + } + kernel_notifications[notification_id] = new Notification(); + } + const packLArg arg = { + blockAs[blockAId], // blockA + lhs, // lhs + m_start, // m + k_start, // k + actual_mc, // mc + actual_kc, // kc + }; + + // Delete any existing notification since we may be + // replacing it. The algorithm should ensure that there are + // no existing waiters on this notification. + delete lhs_notifications[blockAId]; + lhs_notifications[blockAId] = + this->m_device.enqueue(&Self::packLhs, arg); + } + + // now start kernels. + const Index m_base_start = m_block_idx * mc; + const bool need_to_pack = m_block_idx == 0; + + for (Index n_block_idx = 0; n_block_idx < n_blocks; n_block_idx++) { + const Index n_start = n_block_idx * nc; + const Index actual_nc = numext::mini(n_start + nc, n) - n_start; + + // first make sure the previous kernels are all done before overwriting rhs. Also wait if + // we're going to start new k. In both cases need_to_pack is true. + if (need_to_pack) { + for (Index i = num_blocks; i < num_threads; ++i) { + Index blockAId = (k_block_idx * m_blocks + i + m_block_idx) % num_threads; + Index future_id = (blockAId * n_blocks + n_block_idx); + wait_until_ready(kernel_notifications[future_id]); + } + } + + packRKArg arg = { + &blockAs, // blockA + blockBs[n_block_idx], // blockB + rhs, // rhs + output, // output + m_base_start, // m + k_start, // k + n_start, // n + mc, // mc + actual_kc, // kc + actual_nc, // nc + num_threads, + numBlockAs, + m, + k_block_idx, + m_block_idx, + n_block_idx, // n_block_idx + m_blocks, // m_blocks + n_blocks, // n_blocks + &kernel_notifications, // kernel notifications + &lhs_notifications, // lhs notifications + need_to_pack, // need_to_pack + }; + + // We asynchronously kick off this function, which ends up + // notifying the appropriate kernel_notifications objects, + // which this thread waits on before exiting. + this->m_device.enqueueNoNotification(&Self::packRhsAndKernel, arg); + } + } + } + + // Make sure all the kernels are done. + for (size_t i = 0; i < kernel_notifications.size(); ++i) { + wait_until_ready(kernel_notifications[i]); + delete kernel_notifications[i]; + } + + // No need to wait for lhs notifications since they should have + // already been waited on. Just clean them up. + for (size_t i = 0; i < lhs_notifications.size(); ++i) { + delete lhs_notifications[i]; + } + + // deallocate all of the memory for both A and B's + for (size_t i = 0; i < blockAs.size(); i++) { + this->m_device.deallocate(blockAs[i]); + } + for (size_t i = 0; i < blockBs.size(); i++) { + this->m_device.deallocate(blockBs[i]); + } + +#undef CEIL_DIV + } + + /* + * Packs a LHS block of size (mt, kc) starting at lhs(m, k). Before packing + * the LHS block, check that all of the kernels that worked on the same + * mt_block_idx in the previous m_block are done. + */ + template + static void packLhs(const packLArg arg) { + // perform actual packing + LhsPacker pack_lhs; + pack_lhs(arg.blockA, arg.lhs.getSubMapper(arg.m_start, arg.k_start), arg.kc, arg.mc); + } + + /* + * Packs a RHS block of size (kc, nc) starting at (k, n) after checking that + * all kernels in the previous block are done. + * Then for each LHS future, we wait on the future and then call GEBP + * on the area packed by the future (which starts at + * blockA + future_idx * mt * kc) on the LHS and with the full packed + * RHS block. + * The output of this GEBP is written to output(m + i * mt, n). + */ + template + static void packRhsAndKernel(packRKArg arg) { + if (arg.need_to_pack) { + RhsPacker pack_rhs; + pack_rhs(arg.blockB, arg.rhs.getSubMapper(arg.k, arg.n), arg.kc, arg.nc); + } + + GebpKernel gebp; + for (Index mt_block_idx = 0; mt_block_idx < arg.num_blockAs; mt_block_idx++) { + const Index m_base_start = arg.m + arg.mc*mt_block_idx; + if (m_base_start < arg.max_m) { + Index blockAId = (arg.k_block_idx * arg.m_blocks + mt_block_idx + arg.m_block_idx) % arg.num_threads; + wait_until_ready((*arg.lhs_notifications)[blockAId]); + const Index actual_mc = numext::mini(m_base_start + arg.mc, arg.max_m) - m_base_start; + gebp(arg.output.getSubMapper(m_base_start, arg.n), + (*arg.blockAs)[blockAId], arg.blockB, + actual_mc, arg.kc, arg.nc, Scalar(1), -1, -1, 0, 0); + + // Notify that the kernel is done. + const Index set_idx = blockAId * arg.n_blocks + arg.n_block_idx; + (*arg.kernel_notifications)[set_idx]->Notify(); + } + } + } +#endif // EIGEN_USE_SIMPLE_THREAD_POOL + + TensorOpCost contractionCost(Index m, Index n, Index bm, Index bn, Index bk, + bool shard_by_col, bool prepacked) const { + const int packed_size = std::min(PacketType::size, + PacketType::size); + const int output_packet_size = internal::unpacket_traits::size; + const double kd = static_cast(bk); + // Peak VFMA bandwidth is 0.5. However if we have not enough data for + // vectorization bandwidth drops. The 4.0 and 2.0 bandwidth is determined + // experimentally. + double computeBandwidth = bk == 1 ? 4.0 : + (shard_by_col ? bn : bm) < Traits::nr || + (shard_by_col ? bm : bn) < Traits::mr ? 2.0 : 0.5; +#ifndef EIGEN_VECTORIZE_FMA + // Bandwidth of all of VFMA/MULPS/ADDPS is 0.5 on latest Intel processors. + // However for MULPS/ADDPS we have dependent sequence of 2 such instructions, + // so overall bandwidth is 1.0. + if (computeBandwidth == 0.5) computeBandwidth = 1.0; +#endif + // Computations. + TensorOpCost cost = TensorOpCost(0, 0, kd * computeBandwidth, true, packed_size); + // Output stores. + cost += TensorOpCost(0, sizeof(CoeffReturnType), 0, true, output_packet_size); + if (prepacked) { + // Packing and kernels are executed in different tasks. When we calculate + // task grain size we look only at kernel cost assuming that kernel + // is more expensive than packing. + return cost; + } + // Lhs/rhs loads + computations. + TensorOpCost lhsCost = this->m_leftImpl.costPerCoeff(true) * (kd / n); + TensorOpCost rhsCost = this->m_rightImpl.costPerCoeff(true) * (kd / m); + // Lhs packing memory cost does not contribute considerably to overall + // execution time because lhs is prefetched early and accessed sequentially. + if (shard_by_col) + lhsCost.dropMemoryCost(); + else + rhsCost.dropMemoryCost(); + return cost + lhsCost + rhsCost; + } + +#if defined(EIGEN_VECTORIZE_AVX) && defined(EIGEN_USE_LIBXSMM) + template + class ContextXsmm { + public: + ContextXsmm(const Self* self, Scalar* buffer, Index m, Index n, Index k, + const internal::TensorXsmmContractionBlocking& blocking): + device(self->m_device), + m(m), k(k), n(n), + stride_a(blocking.transposeA() ? k : m), + stride_b(blocking.transposeB() ? n : k), + stride_c(m), + bm(blocking.mc()), bk(blocking.kc()), bn(blocking.nc()), + blocks_m(blocking.blocks_m()), blocks_k(blocking.blocks_k()), + blocks_n(blocking.blocks_n()), + copyA(blocking.copyA()), copyB(blocking.copyB()), + transposeA(blocking.transposeA()), transposeB(blocking.transposeB()), + num_threads(blocking.num_threads()), + buffer(buffer), + leftData(self->m_leftImpl.data()), rightData(self->m_rightImpl.data()), + workers_done(blocking.num_threads()), + + packingA_jobs(0), packingB_jobs(0), compute_jobs(0), + packingA_done(blocking.blocks_m()), packingB_done(blocking.blocks_n()) {} + + void worker() { + // Pack + + if (copyA) { + while (true) { + uint32_t mk = packingA_jobs++; + Index mi = mk / blocks_k; + Index ki = mk % blocks_k; + if (mi >= blocks_m) break; + + LhsScalar * blockA = blocksA + (bk*bm) * (mi*blocks_k+ki); + if (transposeA) { + const LhsScalar * current_a = leftData + (bm*mi)*stride_a + (bk*ki); + libxsmm_otrans(blockA, current_a, sizeof(LhsScalar), actual_bk(ki), + actual_bm(mi), stride_a, bm); + } else { + const LhsScalar * current_a = leftData + (bk*ki)*stride_a + (bm*mi); + internal::pack_simple(blockA, current_a, + actual_bk(ki), actual_bm(mi), bm, stride_a); + } + packingA_done.at(mi)++; + } + } + + if (copyB) { + while (true) { + uint32_t nk = packingB_jobs++; + Index ni = nk / blocks_k; + Index ki = nk % blocks_k; + if (ni >= blocks_n) break; + + RhsScalar * blockB = blocksB + (bk*bn) * (ni*blocks_k+ki); + if (transposeB) { + const RhsScalar * current_b = rightData + (ki*bk)*stride_b + + (ni*bn); + libxsmm_otrans(blockB, current_b, sizeof(RhsScalar), actual_bn(ni), + actual_bk(ki), stride_b, bk); + } else { + const RhsScalar * current_b = rightData + (ni*bn)*stride_b + + (ki*bk); + internal::pack_simple(blockB, current_b, + actual_bn(ni), actual_bk(ki), bk, stride_b); + } + packingB_done.at(ni)++; + } + } + + // Compute + + while (true) { + uint32_t mn = compute_jobs++; + Index mi = mn / blocks_n; + Index ni = mn % blocks_n; + if (mi >= blocks_m) break; + + // Wait for mi, ni packings to be done. This is more fine-grained than + // waiting for all workers to finish packing. + while ((copyA && (packingA_done.at(mi) < blocks_k)) || + (copyB && (packingB_done.at(ni) < blocks_k))) + {} + + for (Index ki=0; ki < blocks_k; ++ki) { + const LhsScalar * current_a = copyA ? + blocksA + (bk*bm) * (mi*blocks_k+ki) : + leftData + (bk*ki)*stride_a + (bm*mi); + const RhsScalar * current_b = copyB ? + blocksB + (bk*bn) * (ni*blocks_k+ki) : + rightData + (ni*bn)*stride_b + (bk*ki); + + Index current_stride_a = copyA ? bm : stride_a; + Index current_stride_b = copyB ? bk : stride_b; + + // Memory may not be zeroed, overwrite instead of adding in first + // iteration. + float beta = ki == 0 ? 0 : 1; + + Scalar * current_c = buffer + (mi*bm) + (ni*bn)*stride_c; + internal::libxsmm_wrapper( + 0, actual_bm(mi), actual_bn(ni), actual_bk(ki), + current_stride_a, current_stride_b, stride_c, 1, beta, 0) + (current_a, current_b, current_c); + } + } + + workers_done.Notify(); + } + + void run() { + // Parallelization strategy. + // + // First pack A into blocks (sharding by m, k) and B (sharding by n,k), + // then shard by m, n. + // + // Do not use advanced ThreadPool queuing, just run a single long-standing + // function in each thread. + if (copyA) { + blocksA = static_cast(device.allocate( + (blocks_m*bm)*(blocks_k*bk)*sizeof(LhsScalar))); + } + if (copyB) { + blocksB = static_cast(device.allocate( + (blocks_n*bn)*(blocks_k*bk)*sizeof(RhsScalar))); + } + + for (Index i = 0; i < num_threads; ++i) { + device.enqueueNoNotification([=]() { worker(); }); + } + + workers_done.Wait(); + + if (copyA) { + device.deallocate(blocksA); + } + if (copyB) { + device.deallocate(blocksB); + } + } + + private: + // real block size for block index in [0, ..., blocks - 1]. + Index actual_bm(Index mi) const { + return mi != blocks_m - 1 ? bm : m + bm - bm * blocks_m; + } + Index actual_bk(Index ki) const { + return ki != blocks_k - 1 ? bk : k + bk - bk * blocks_k; + } + Index actual_bn(Index ni) const { + return ni != blocks_n - 1 ? bn : n + bn - bn * blocks_n; + } + + const Device& device; + Index m, k, n; + Index stride_a, stride_b, stride_c; + Index bm, bk, bn; // Block sizes. + Index blocks_m, blocks_k, blocks_n; // Number of blocks in each dimension. + bool copyA, copyB, transposeA, transposeB; + Index num_threads; + Scalar *buffer; + const LhsScalar *leftData; + const RhsScalar *rightData; + + LhsScalar *blocksA; + RhsScalar *blocksB; + // barrier for joining all threads after all done. + Barrier workers_done; + // "queues" of (mi,ki), (ki,ni), (mi,ni) jobs packed [0,p)x[0,q) -> [0, p*q) + std::atomic packingA_jobs; + std::atomic packingB_jobs; + std::atomic compute_jobs; + // already packed blocks for each mi-panel in A and ni-panel in B. + std::vector> packingA_done; + std::vector> packingB_done; + }; +#endif + +}; + +} // end namespace Eigen + +#endif // EIGEN_USE_THREADS +#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_THREAD_POOL_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConversion.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConversion.h new file mode 100644 index 00000000..b29968b6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConversion.h @@ -0,0 +1,282 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONVERSION_H +#define EIGEN_CXX11_TENSOR_TENSOR_CONVERSION_H + +namespace Eigen { + +/** \class TensorConversionOp + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor conversion class. This class makes it possible to vectorize + * type casting operations when the number of scalars per packet in the source + * and the destination type differ + */ +namespace internal { +template +struct traits > +{ + // Type promotion to handle the case where the types of the lhs and the rhs are different. + typedef TargetType Scalar; + typedef typename traits::StorageKind StorageKind; + typedef typename traits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = traits::NumDimensions; + static const int Layout = traits::Layout; + enum { Flags = 0 }; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorConversionOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorConversionOp type; +}; + +} // end namespace internal + + +template +struct PacketConverter { + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + PacketConverter(const TensorEvaluator& impl) + : m_impl(impl) {} + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TgtPacket packet(Index index) const { + return internal::pcast(m_impl.template packet(index)); + } + + private: + const TensorEvaluator& m_impl; +}; + + +template +struct PacketConverter { + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + PacketConverter(const TensorEvaluator& impl) + : m_impl(impl) {} + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TgtPacket packet(Index index) const { + const int SrcPacketSize = internal::unpacket_traits::size; + + SrcPacket src1 = m_impl.template packet(index); + SrcPacket src2 = m_impl.template packet(index + SrcPacketSize); + TgtPacket result = internal::pcast(src1, src2); + return result; + } + + private: + const TensorEvaluator& m_impl; +}; + +template +struct PacketConverter { + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + PacketConverter(const TensorEvaluator& impl) + : m_impl(impl) {} + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TgtPacket packet(Index index) const { + const int SrcPacketSize = internal::unpacket_traits::size; + + SrcPacket src1 = m_impl.template packet(index); + SrcPacket src2 = m_impl.template packet(index + SrcPacketSize); + SrcPacket src3 = m_impl.template packet(index + 2 * SrcPacketSize); + SrcPacket src4 = m_impl.template packet(index + 3 * SrcPacketSize); + TgtPacket result = internal::pcast(src1, src2, src3, src4); + return result; + } + + private: + const TensorEvaluator& m_impl; +}; + +template +struct PacketConverter { + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + PacketConverter(const TensorEvaluator& impl) + : m_impl(impl), m_maxIndex(impl.dimensions().TotalSize()) {} + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TgtPacket packet(Index index) const { + const int SrcPacketSize = internal::unpacket_traits::size; + // Only call m_impl.packet() when we have direct access to the underlying data. This + // ensures that we don't compute the subexpression twice. We may however load some + // coefficients twice, but in practice this doesn't negatively impact performance. + if (m_impl.data() && (index + SrcPacketSize < m_maxIndex)) { + // Force unaligned memory loads since we can't ensure alignment anymore + return internal::pcast(m_impl.template packet(index)); + } else { + const int TgtPacketSize = internal::unpacket_traits::size; + typedef typename internal::unpacket_traits::type SrcType; + typedef typename internal::unpacket_traits::type TgtType; + internal::scalar_cast_op converter; + EIGEN_ALIGN_MAX typename internal::unpacket_traits::type values[TgtPacketSize]; + for (int i = 0; i < TgtPacketSize; ++i) { + values[i] = converter(m_impl.coeff(index+i)); + } + TgtPacket rslt = internal::pload(values); + return rslt; + } + } + + private: + const TensorEvaluator& m_impl; + const typename TensorEvaluator::Index m_maxIndex; +}; + +template +class TensorConversionOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename internal::traits::Scalar Scalar; + typedef typename internal::traits::StorageKind StorageKind; + typedef typename internal::traits::Index Index; + typedef typename internal::nested::type Nested; + typedef Scalar CoeffReturnType; + typedef typename NumTraits::Real RealScalar; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorConversionOp(const XprType& xpr) + : m_xpr(xpr) {} + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + protected: + typename XprType::Nested m_xpr; +}; + +template struct ConversionSubExprEval { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool run(Eval& impl, Scalar*) { + impl.evalSubExprsIfNeeded(NULL); + return true; + } +}; + +template struct ConversionSubExprEval { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool run(Eval& impl, Scalar* data) { + return impl.evalSubExprsIfNeeded(data); + } +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorConversionOp XprType; + typedef typename XprType::Index Index; + typedef typename TensorEvaluator::Dimensions Dimensions; + typedef TargetType Scalar; + typedef TargetType CoeffReturnType; + typedef typename internal::remove_all::Scalar>::type SrcType; + typedef typename PacketType::type PacketReturnType; + typedef typename PacketType::type PacketSourceType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = false, + PacketAccess = true, + Layout = TensorEvaluator::Layout, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device) + { + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_impl.dimensions(); } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* data) + { + return ConversionSubExprEval::value, TensorEvaluator, Scalar>::run(m_impl, data); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() + { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + internal::scalar_cast_op converter; + return converter(m_impl.coeff(index)); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + const bool Vectorizable = TensorEvaluator::PacketAccess & + internal::type_casting_traits::VectorizedCast; + return PacketConv::run(m_impl, index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + const double cast_cost = TensorOpCost::CastCost(); + if (vectorized) { + const double SrcCoeffRatio = + internal::type_casting_traits::SrcCoeffRatio; + const double TgtCoeffRatio = + internal::type_casting_traits::TgtCoeffRatio; + return m_impl.costPerCoeff(vectorized) * (SrcCoeffRatio / PacketSize) + + TensorOpCost(0, 0, TgtCoeffRatio * (cast_cost / PacketSize)); + } else { + return m_impl.costPerCoeff(vectorized) + TensorOpCost(0, 0, cast_cost); + } + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + /// required by sycl in order to extract the sycl accessor + const TensorEvaluator& impl() const { return m_impl; } + + protected: + template + struct PacketConv { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType run(const TensorEvaluator& impl, Index index) { + internal::scalar_cast_op converter; + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + for (int i = 0; i < PacketSize; ++i) { + values[i] = converter(impl.coeff(index+i)); + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + }; + + template + struct PacketConv { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType run(const TensorEvaluator& impl, Index index) { + const int SrcCoeffRatio = internal::type_casting_traits::SrcCoeffRatio; + const int TgtCoeffRatio = internal::type_casting_traits::TgtCoeffRatio; + PacketConverter, PacketSourceType, PacketReturnType, + SrcCoeffRatio, TgtCoeffRatio> converter(impl); + return converter.template packet(index); + } + }; + + TensorEvaluator m_impl; +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_CONVERSION_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConvolution.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConvolution.h new file mode 100644 index 00000000..378f5ccc --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConvolution.h @@ -0,0 +1,1104 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_H +#define EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_H + +namespace Eigen { + +/** \class TensorConvolution + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor convolution class. + * + * + */ +namespace internal { + +template +class IndexMapper { + public: + IndexMapper(const InputDims& input_dims, const array& kernel_dims, + const array& indices) { + + array dimensions = input_dims; + for (int i = 0; i < NumKernelDims; ++i) { + const Index index = indices[i]; + const Index input_dim = input_dims[index]; + const Index kernel_dim = kernel_dims[i]; + const Index result_dim = input_dim - kernel_dim + 1; + dimensions[index] = result_dim; + } + + array inputStrides; + array outputStrides; + if (static_cast(Layout) == static_cast(ColMajor)) { + inputStrides[0] = 1; + outputStrides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + inputStrides[i] = inputStrides[i-1] * input_dims[i-1]; + outputStrides[i] = outputStrides[i-1] * dimensions[i-1]; + } + } else { + inputStrides[NumDims - 1] = 1; + outputStrides[NumDims - 1] = 1; + for (int i = static_cast(NumDims) - 2; i >= 0; --i) { + inputStrides[i] = inputStrides[i + 1] * input_dims[i + 1]; + outputStrides[i] = outputStrides[i + 1] * dimensions[i + 1]; + } + } + + array cudaInputDimensions; + array cudaOutputDimensions; + array tmp = dimensions; + array ordering; + const size_t offset = static_cast(Layout) == static_cast(ColMajor) + ? 0 + : NumDims - NumKernelDims; + for (int i = 0; i < NumKernelDims; ++i) { + const Index index = i + offset; + ordering[index] = indices[i]; + tmp[indices[i]] = -1; + cudaInputDimensions[index] = input_dims[indices[i]]; + cudaOutputDimensions[index] = dimensions[indices[i]]; + } + + int written = static_cast(Layout) == static_cast(ColMajor) + ? NumKernelDims + : 0; + for (int i = 0; i < NumDims; ++i) { + if (tmp[i] >= 0) { + ordering[written] = i; + cudaInputDimensions[written] = input_dims[i]; + cudaOutputDimensions[written] = dimensions[i]; + ++written; + } + } + + for (int i = 0; i < NumDims; ++i) { + m_inputStrides[i] = inputStrides[ordering[i]]; + m_outputStrides[i] = outputStrides[ordering[i]]; + } + + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = 0; i < NumDims; ++i) { + if (i > NumKernelDims) { + m_cudaInputStrides[i] = + m_cudaInputStrides[i - 1] * cudaInputDimensions[i - 1]; + m_cudaOutputStrides[i] = + m_cudaOutputStrides[i - 1] * cudaOutputDimensions[i - 1]; + } else { + m_cudaInputStrides[i] = 1; + m_cudaOutputStrides[i] = 1; + } + } + } else { + for (int i = NumDims - 1; i >= 0; --i) { + if (static_cast(i + 1) < offset) { + m_cudaInputStrides[i] = + m_cudaInputStrides[i + 1] * cudaInputDimensions[i + 1]; + m_cudaOutputStrides[i] = + m_cudaOutputStrides[i + 1] * cudaOutputDimensions[i + 1]; + } else { + m_cudaInputStrides[i] = 1; + m_cudaOutputStrides[i] = 1; + } + } + } + } + + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapCudaInputPlaneToTensorInputOffset(Index p) const { + Index inputIndex = 0; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int d = NumDims - 1; d > NumKernelDims; --d) { + const Index idx = p / m_cudaInputStrides[d]; + inputIndex += idx * m_inputStrides[d]; + p -= idx * m_cudaInputStrides[d]; + } + inputIndex += p * m_inputStrides[NumKernelDims]; + } else { + std::ptrdiff_t limit = 0; + if (NumKernelDims < NumDims) { + limit = NumDims - NumKernelDims - 1; + } + for (int d = 0; d < limit; ++d) { + const Index idx = p / m_cudaInputStrides[d]; + inputIndex += idx * m_inputStrides[d]; + p -= idx * m_cudaInputStrides[d]; + } + inputIndex += p * m_inputStrides[limit]; + } + return inputIndex; + } + + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapCudaOutputPlaneToTensorOutputOffset(Index p) const { + Index outputIndex = 0; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int d = NumDims - 1; d > NumKernelDims; --d) { + const Index idx = p / m_cudaOutputStrides[d]; + outputIndex += idx * m_outputStrides[d]; + p -= idx * m_cudaOutputStrides[d]; + } + outputIndex += p * m_outputStrides[NumKernelDims]; + } else { + std::ptrdiff_t limit = 0; + if (NumKernelDims < NumDims) { + limit = NumDims - NumKernelDims - 1; + } + for (int d = 0; d < limit; ++d) { + const Index idx = p / m_cudaOutputStrides[d]; + outputIndex += idx * m_outputStrides[d]; + p -= idx * m_cudaOutputStrides[d]; + } + outputIndex += p * m_outputStrides[limit]; + } + return outputIndex; + } + + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapCudaInputKernelToTensorInputOffset(Index i) const { + const size_t offset = static_cast(Layout) == static_cast(ColMajor) + ? 0 + : NumDims - NumKernelDims; + return i * m_inputStrides[offset]; + } + + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapCudaOutputKernelToTensorOutputOffset(Index i) const { + const size_t offset = static_cast(Layout) == static_cast(ColMajor) + ? 0 + : NumDims - NumKernelDims; + return i * m_outputStrides[offset]; + } + + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapCudaInputKernelToTensorInputOffset(Index i, Index j) const { + const size_t offset = static_cast(Layout) == static_cast(ColMajor) + ? 0 + : NumDims - NumKernelDims; + return i * m_inputStrides[offset] + j * m_inputStrides[offset + 1]; + } + + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapCudaOutputKernelToTensorOutputOffset(Index i, Index j) const { + const size_t offset = static_cast(Layout) == static_cast(ColMajor) + ? 0 + : NumDims - NumKernelDims; + return i * m_outputStrides[offset] + j * m_outputStrides[offset + 1]; + } + + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapCudaInputKernelToTensorInputOffset(Index i, Index j, Index k) const { + const size_t offset = static_cast(Layout) == static_cast(ColMajor) + ? 0 + : NumDims - NumKernelDims; + return i * m_inputStrides[offset] + j * m_inputStrides[offset + 1] + + k * m_inputStrides[offset + 2]; + } + + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapCudaOutputKernelToTensorOutputOffset(Index i, Index j, Index k) const { + const size_t offset = static_cast(Layout) == static_cast(ColMajor) + ? 0 + : NumDims - NumKernelDims; + return i * m_outputStrides[offset] + j * m_outputStrides[offset + 1] + + k * m_outputStrides[offset + 2]; + } + + private: + static const int NumDims = internal::array_size::value; + array m_inputStrides; + array m_outputStrides; + array m_cudaInputStrides; + array m_cudaOutputStrides; +}; + + + +template +struct traits > +{ + // Type promotion to handle the case where the types of the lhs and the rhs are different. + typedef typename promote_storage_type::ret Scalar; + typedef typename promote_storage_type::StorageKind, + typename traits::StorageKind>::ret StorageKind; + typedef typename promote_index_type::Index, + typename traits::Index>::type Index; + typedef typename InputXprType::Nested LhsNested; + typedef typename KernelXprType::Nested RhsNested; + typedef typename remove_reference::type _LhsNested; + typedef typename remove_reference::type _RhsNested; + static const int NumDimensions = traits::NumDimensions; + static const int Layout = traits::Layout; + + enum { + Flags = 0 + }; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorConvolutionOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorConvolutionOp type; +}; + +} // end namespace internal + + + +template +class TensorConvolutionOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename internal::promote_storage_type::ret CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorConvolutionOp(const InputXprType& input, const KernelXprType& kernel, const Indices& dims) + : m_input_xpr(input), m_kernel_xpr(kernel), m_indices(dims) {} + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const Indices& indices() const { return m_indices; } + + /** \returns the nested expressions */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const typename internal::remove_all::type& + inputExpression() const { return m_input_xpr; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const typename internal::remove_all::type& + kernelExpression() const { return m_kernel_xpr; } + + protected: + typename InputXprType::Nested m_input_xpr; + typename KernelXprType::Nested m_kernel_xpr; + const Indices m_indices; +}; + + +template +struct TensorEvaluator, Device> +{ + typedef TensorConvolutionOp XprType; + + static const int NumDims = internal::array_size::Dimensions>::value; + static const int NumKernelDims = internal::array_size::value; + typedef typename XprType::Index Index; + typedef DSizes Dimensions; + + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = TensorEvaluator::IsAligned & TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess & TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_inputImpl(op.inputExpression(), device), m_kernelImpl(op.kernelExpression(), device), m_kernelArg(op.kernelExpression()), m_kernel(NULL), m_local_kernel(false), m_device(device) + { + EIGEN_STATIC_ASSERT((static_cast(TensorEvaluator::Layout) == static_cast(TensorEvaluator::Layout)), YOU_MADE_A_PROGRAMMING_MISTAKE); + + const typename TensorEvaluator::Dimensions& input_dims = m_inputImpl.dimensions(); + const typename TensorEvaluator::Dimensions& kernel_dims = m_kernelImpl.dimensions(); + + if (static_cast(Layout) == static_cast(ColMajor)) { + m_inputStride[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_inputStride[i] = m_inputStride[i - 1] * input_dims[i - 1]; + } + } else { + m_inputStride[NumDims - 1] = 1; + for (int i = NumDims - 2; i >= 0; --i) { + m_inputStride[i] = m_inputStride[i + 1] * input_dims[i + 1]; + } + } + + m_dimensions = m_inputImpl.dimensions(); + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = 0; i < NumKernelDims; ++i) { + const Index index = op.indices()[i]; + const Index input_dim = input_dims[index]; + const Index kernel_dim = kernel_dims[i]; + const Index result_dim = input_dim - kernel_dim + 1; + m_dimensions[index] = result_dim; + if (i > 0) { + m_kernelStride[i] = m_kernelStride[i - 1] * kernel_dims[i - 1]; + } else { + m_kernelStride[0] = 1; + } + m_indexStride[i] = m_inputStride[index]; + } + + m_outputStride[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_outputStride[i] = m_outputStride[i - 1] * m_dimensions[i - 1]; + } + } else { + for (int i = NumKernelDims - 1; i >= 0; --i) { + const Index index = op.indices()[i]; + const Index input_dim = input_dims[index]; + const Index kernel_dim = kernel_dims[i]; + const Index result_dim = input_dim - kernel_dim + 1; + m_dimensions[index] = result_dim; + if (i < NumKernelDims - 1) { + m_kernelStride[i] = m_kernelStride[i + 1] * kernel_dims[i + 1]; + } else { + m_kernelStride[NumKernelDims - 1] = 1; + } + m_indexStride[i] = m_inputStride[index]; + } + + m_outputStride[NumDims - 1] = 1; + for (int i = NumDims - 2; i >= 0; --i) { + m_outputStride[i] = m_outputStride[i + 1] * m_dimensions[i + 1]; + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar*) { + m_inputImpl.evalSubExprsIfNeeded(NULL); + preloadKernel(); + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_inputImpl.cleanup(); + if (m_local_kernel) { + m_device.deallocate((void*)m_kernel); + m_local_kernel = false; + } + m_kernel = NULL; + } + + void evalTo(typename XprType::Scalar* buffer) { + evalSubExprsIfNeeded(NULL); + for (int i = 0; i < dimensions().TotalSize(); ++i) { + buffer[i] += coeff(i); + } + cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + CoeffReturnType result = CoeffReturnType(0); + convolve(firstInput(index), 0, NumKernelDims-1, result); + return result; + } + + template + EIGEN_DEVICE_FUNC PacketReturnType packet(const Index index) const + { + Index indices[2] = {index, index+PacketSize-1}; + Index startInputs[2] = {0, 0}; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i > 0; --i) { + const Index idx0 = indices[0] / m_outputStride[i]; + const Index idx1 = indices[1] / m_outputStride[i]; + startInputs[0] += idx0 * m_inputStride[i]; + startInputs[1] += idx1 * m_inputStride[i]; + indices[0] -= idx0 * m_outputStride[i]; + indices[1] -= idx1 * m_outputStride[i]; + } + } else { + for (int i = 0; i < NumDims - 1; ++i) { + const Index idx0 = indices[0] / m_outputStride[i]; + const Index idx1 = indices[1] / m_outputStride[i]; + startInputs[0] += idx0 * m_inputStride[i]; + startInputs[1] += idx1 * m_inputStride[i]; + indices[0] -= idx0 * m_outputStride[i]; + indices[1] -= idx1 * m_outputStride[i]; + } + } + startInputs[0] += indices[0]; + startInputs[1] += indices[1]; + + if (startInputs[1]-startInputs[0] == PacketSize-1) { + PacketReturnType result = internal::pset1(0); + convolvePacket(startInputs[0], 0, NumKernelDims-1, result); + return result; + } else { + EIGEN_ALIGN_MAX Scalar data[PacketSize]; + data[0] = Scalar(0); + convolve(startInputs[0], 0, NumKernelDims-1, data[0]); + for (int i = 1; i < PacketSize-1; ++i) { + data[i] = Scalar(0); + convolve(firstInput(index+i), 0, NumKernelDims-1, data[i]); + } + data[PacketSize-1] = Scalar(0); + convolve(startInputs[1], 0, NumKernelDims-1, data[PacketSize-1]); + return internal::pload(data); + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + const double kernel_size = m_kernelImpl.dimensions().TotalSize(); + // We ignore the use of fused multiply-add. + const double convolve_compute_cost = + TensorOpCost::AddCost() + TensorOpCost::MulCost(); + const double firstIndex_compute_cost = + NumDims * + (2 * TensorOpCost::AddCost() + 2 * TensorOpCost::MulCost() + + TensorOpCost::DivCost()); + return TensorOpCost(0, 0, firstIndex_compute_cost, vectorized, PacketSize) + + kernel_size * (m_inputImpl.costPerCoeff(vectorized) + + m_kernelImpl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, convolve_compute_cost, vectorized, + PacketSize)); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + private: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index firstInput(Index index) const { + Index startInput = 0; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i > 0; --i) { + const Index idx = index / m_outputStride[i]; + startInput += idx * m_inputStride[i]; + index -= idx * m_outputStride[i]; + } + } else { + for (int i = 0; i < NumDims - 1; ++i) { + const Index idx = index / m_outputStride[i]; + startInput += idx * m_inputStride[i]; + index -= idx * m_outputStride[i]; + } + } + startInput += index; + return startInput; + } + + EIGEN_DEVICE_FUNC void convolve(Index firstIndex, Index firstKernel, int DimIndex, CoeffReturnType& accum) const { + for (int j = 0; j < m_kernelImpl.dimensions()[DimIndex]; ++j) { + const Index input = firstIndex + j * m_indexStride[DimIndex]; + const Index kernel = firstKernel + j * m_kernelStride[DimIndex]; + if (DimIndex > 0) { + convolve(input, kernel, DimIndex-1, accum); + } else { + accum += m_inputImpl.coeff(input) * m_kernel[kernel]; + } + } + } + + template + EIGEN_DEVICE_FUNC void convolvePacket(Index firstIndex, Index firstKernel, int DimIndex, Packet& accum) const { + for (int j = 0; j < m_kernelImpl.dimensions()[DimIndex]; ++j) { + const Index input = firstIndex + j * m_indexStride[DimIndex]; + const Index kernel = firstKernel + j * m_kernelStride[DimIndex]; + if (DimIndex > 0) { + convolvePacket(input, kernel, DimIndex-1, accum); + } else { + accum = internal::pmadd(m_inputImpl.template packet(input), internal::pset1(m_kernel[kernel]), accum); + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void preloadKernel() { + // Don't make a local copy of the kernel unless we have to (i.e. it's an + // expression that needs to be evaluated) + const Scalar* in_place = m_kernelImpl.data(); + if (in_place) { + m_kernel = in_place; + m_local_kernel = false; + } else { + size_t kernel_sz = m_kernelImpl.dimensions().TotalSize() * sizeof(Scalar); + Scalar* local = (Scalar*)m_device.allocate(kernel_sz); + typedef TensorEvalToOp EvalTo; + EvalTo evalToTmp(local, m_kernelArg); + const bool PacketAccess = internal::IsVectorizable::value; + internal::TensorExecutor::run(evalToTmp, m_device); + + m_kernel = local; + m_local_kernel = true; + } + } + + array m_inputStride; + array m_outputStride; + + array m_indexStride; + array m_kernelStride; + TensorEvaluator m_inputImpl; + TensorEvaluator m_kernelImpl; + Dimensions m_dimensions; + + KernelArgType m_kernelArg; + const Scalar* m_kernel; + bool m_local_kernel; + const Device& m_device; +}; + + + + +// Use an optimized implementation of the evaluation code for GPUs whenever possible. +#if defined(EIGEN_USE_GPU) && defined(__CUDACC__) + +template +struct GetKernelSize { + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int operator() (const int /*kernelSize*/) const { + return StaticKernelSize; + } +}; +template <> +struct GetKernelSize { + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int operator() (const int kernelSize) const { + return kernelSize; + } +}; + +template +__global__ void EigenConvolutionKernel1D( + InputEvaluator eval, + const internal::IndexMapper + indexMapper, + const float* __restrict kernel, const int numPlanes, const int numX, + const int maxX, const int kernelSize, float* buffer) { + extern __shared__ float s[]; + + const int first_x = blockIdx.x * maxX; + const int last_x = (first_x + maxX < numX ? first_x + maxX : numX) - 1; + const int num_x_input = last_x - first_x + GetKernelSize()(kernelSize); + const int num_x_output = last_x - first_x + 1; + + const int first_plane = blockIdx.y * blockDim.y; + const int plane_stride = blockDim.y * gridDim.y; + + for (int p = first_plane + threadIdx.y; p < numPlanes; p += plane_stride) { + // Load inputs to shared memory + const int plane_input_offset = indexMapper.mapCudaInputPlaneToTensorInputOffset(p); + const int plane_kernel_offset = threadIdx.y * num_x_input; + #pragma unroll + for (int i = threadIdx.x; i < num_x_input; i += blockDim.x) { + const int tensor_index = plane_input_offset + indexMapper.mapCudaInputKernelToTensorInputOffset(i+first_x); + s[i + plane_kernel_offset] = eval.coeff(tensor_index); + } + + __syncthreads(); + + // Compute the convolution + const int plane_output_offset = indexMapper.mapCudaOutputPlaneToTensorOutputOffset(p); + + #pragma unroll + for (int i = threadIdx.x; i < num_x_output; i += blockDim.x) { + const int kernel_offset = plane_kernel_offset + i; + float result = 0.0f; + #pragma unroll + for (int k = 0; k < GetKernelSize()(kernelSize); ++k) { + result += s[k + kernel_offset] * kernel[k]; + } + const int tensor_index = plane_output_offset + indexMapper.mapCudaOutputKernelToTensorOutputOffset(i+first_x); + buffer[tensor_index] = result; + } + __syncthreads(); + } +}; + +template +__global__ void EigenConvolutionKernel2D( + InputEvaluator eval, + const internal::IndexMapper + indexMapper, + const float* __restrict kernel, const int numPlanes, const int numX, + const int maxX, const int numY, const int maxY, const int kernelSizeX, + const int kernelSizeY, float* buffer) { + extern __shared__ float s[]; + + const int first_x = blockIdx.x * maxX; + const int last_x = (first_x + maxX < numX ? first_x + maxX : numX) - 1; + const int num_x_input = last_x - first_x + GetKernelSize()(kernelSizeX); + const int num_x_output = last_x - first_x + 1; + + const int first_y = blockIdx.y * maxY; + const int last_y = (first_y + maxY < numY ? first_y + maxY : numY) - 1; + const int num_y_input = last_y - first_y + GetKernelSize()(kernelSizeY); + const int num_y_output = last_y - first_y + 1; + + const int first_plane = blockIdx.z * blockDim.z; + const int plane_stride = blockDim.z * gridDim.z; + + for (int p = first_plane + threadIdx.z; p < numPlanes; p += plane_stride) { + + const int plane_input_offset = indexMapper.mapCudaInputPlaneToTensorInputOffset(p); + const int plane_kernel_offset = threadIdx.z * num_y_input; + + // Load inputs to shared memory + #pragma unroll + for (int j = threadIdx.y; j < num_y_input; j += blockDim.y) { + const int input_offset = num_x_input * (j + plane_kernel_offset); + #pragma unroll + for (int i = threadIdx.x; i < num_x_input; i += blockDim.x) { + const int tensor_index = plane_input_offset + indexMapper.mapCudaInputKernelToTensorInputOffset(i+first_x, j+first_y); + s[i + input_offset] = eval.coeff(tensor_index); + } + } + + __syncthreads(); + + // Convolution + const int plane_output_offset = indexMapper.mapCudaOutputPlaneToTensorOutputOffset(p); + + #pragma unroll + for (int j = threadIdx.y; j < num_y_output; j += blockDim.y) { + #pragma unroll + for (int i = threadIdx.x; i < num_x_output; i += blockDim.x) { + float result = 0.0f; + #pragma unroll + for (int l = 0; l < GetKernelSize()(kernelSizeY); ++l) { + const int kernel_offset = kernelSizeX * l; + const int input_offset = i + num_x_input * (j + l + plane_kernel_offset); + #pragma unroll + for (int k = 0; k < GetKernelSize()(kernelSizeX); ++k) { + result += s[k + input_offset] * kernel[k + kernel_offset]; + } + } + const int tensor_index = plane_output_offset + indexMapper.mapCudaOutputKernelToTensorOutputOffset(i+first_x, j+first_y); + buffer[tensor_index] = result; + } + } + + __syncthreads(); + } +}; + +template +__global__ void EigenConvolutionKernel3D( + InputEvaluator eval, + const internal::IndexMapper + indexMapper, + const float* __restrict kernel, const size_t numPlanes, const size_t numX, + const size_t maxX, const size_t numY, const size_t maxY, const size_t numZ, + const size_t maxZ, const size_t kernelSizeX, const size_t kernelSizeY, + const size_t kernelSizeZ, float* buffer) { + extern __shared__ float s[]; + + // Load inputs to shared memory + const int first_x = blockIdx.x * maxX; + const int last_x = (first_x + maxX < numX ? first_x + maxX : numX) - 1; + const int num_x_input = last_x - first_x + kernelSizeX; + + const int first_y = blockIdx.y * maxY; + const int last_y = (first_y + maxY < numY ? first_y + maxY : numY) - 1; + const int num_y_input = last_y - first_y + kernelSizeY; + + const int first_z = blockIdx.z * maxZ; + const int last_z = (first_z + maxZ < numZ ? first_z + maxZ : numZ) - 1; + const int num_z_input = last_z - first_z + kernelSizeZ; + + for (int p = 0; p < numPlanes; ++p) { + + const int plane_input_offset = indexMapper.mapCudaInputPlaneToTensorInputOffset(p); + const int plane_kernel_offset = 0; + + for (int k = threadIdx.z; k < num_z_input; k += blockDim.z) { + for (int j = threadIdx.y; j < num_y_input; j += blockDim.y) { + for (int i = threadIdx.x; i < num_x_input; i += blockDim.x) { + const int tensor_index = plane_input_offset + indexMapper.mapCudaInputKernelToTensorInputOffset(i+first_x, j+first_y, k+first_z); + s[i + num_x_input * (j + num_y_input * (k + plane_kernel_offset))] = eval.coeff(tensor_index); + } + } + } + + __syncthreads(); + + // Convolution + const int num_z_output = last_z - first_z + 1; + const int num_y_output = last_y - first_y + 1; + const int num_x_output = last_x - first_x + 1; + const int plane_output_offset = indexMapper.mapCudaOutputPlaneToTensorOutputOffset(p); + + for (int k = threadIdx.z; k < num_z_output; k += blockDim.z) { + for (int j = threadIdx.y; j < num_y_output; j += blockDim.y) { + for (int i = threadIdx.x; i < num_x_output; i += blockDim.x) { + float result = 0.0f; + for (int n = 0; n < kernelSizeZ; ++n) { + for (int m = 0; m < kernelSizeY; ++m) { + for (int l = 0; l < kernelSizeX; ++l) { + result += s[i + l + num_x_input * (j + m + num_y_input * (k + n + plane_kernel_offset))] * kernel[l + kernelSizeX * (m + kernelSizeY * n)]; + } + } + } + const int tensor_index = plane_output_offset + indexMapper.mapCudaOutputKernelToTensorOutputOffset(i+first_x, j+first_y, k+first_z); + buffer[tensor_index] = result; + } + } + } + __syncthreads(); + } +}; + + + +template +struct TensorEvaluator, GpuDevice> +{ + typedef TensorConvolutionOp XprType; + + static const int NumDims = internal::array_size::Dimensions>::value; + static const int NumKernelDims = internal::array_size::value; + typedef typename XprType::Index Index; + typedef DSizes Dimensions; + typedef typename TensorEvaluator::Dimensions KernelDimensions; + + enum { + IsAligned = TensorEvaluator::IsAligned & TensorEvaluator::IsAligned, + PacketAccess = false, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const GpuDevice& device) + : m_inputImpl(op.inputExpression(), device), m_kernelArg(op.kernelExpression()), m_kernelImpl(op.kernelExpression(), device), m_indices(op.indices()), m_buf(NULL), m_kernel(NULL), m_local_kernel(false), m_device(device) + { + EIGEN_STATIC_ASSERT((static_cast(TensorEvaluator::Layout) == static_cast(TensorEvaluator::Layout)), YOU_MADE_A_PROGRAMMING_MISTAKE); + + const typename TensorEvaluator::Dimensions& input_dims = m_inputImpl.dimensions(); + const typename TensorEvaluator::Dimensions& kernel_dims = m_kernelImpl.dimensions(); + + m_dimensions = m_inputImpl.dimensions(); + for (int i = 0; i < NumKernelDims; ++i) { + const Index index = op.indices()[i]; + const Index input_dim = input_dims[index]; + const Index kernel_dim = kernel_dims[i]; + const Index result_dim = input_dim - kernel_dim + 1; + m_dimensions[index] = result_dim; + } + } + + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + typedef typename InputArgType::Scalar Scalar; + static const int PacketSize = internal::unpacket_traits::size; + + EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* data) { + preloadKernel(); + m_inputImpl.evalSubExprsIfNeeded(NULL); + if (data) { + executeEval(data); + return false; + } else { + m_buf = (Scalar*)m_device.allocate(dimensions().TotalSize() * sizeof(Scalar)); + executeEval(m_buf); + return true; + } + } + + EIGEN_STRONG_INLINE void cleanup() { + m_inputImpl.cleanup(); + if (m_buf) { + m_device.deallocate(m_buf); + m_buf = NULL; + } + if (m_local_kernel) { + m_device.deallocate((void*)m_kernel); + m_local_kernel = false; + } + m_kernel = NULL; + } + + EIGEN_STRONG_INLINE void preloadKernel() { + // Don't make a local copy of the kernel unless we have to (i.e. it's an + // expression that needs to be evaluated) + const Scalar* in_place = m_kernelImpl.data(); + if (in_place) { + m_kernel = in_place; + m_local_kernel = false; + } else { + size_t kernel_sz = m_kernelImpl.dimensions().TotalSize() * sizeof(Scalar); + Scalar* local = (Scalar*)m_device.allocate(kernel_sz); + typedef TensorEvalToOp EvalTo; + EvalTo evalToTmp(local, m_kernelArg); + const bool PacketAccess = internal::IsVectorizable::value; + internal::TensorExecutor::run(evalToTmp, m_device); + + m_kernel = local; + m_local_kernel = true; + } + } + + static unsigned int ceil(unsigned int num, unsigned int denom) { + const unsigned int rounded_toward_zero = num / denom; + if (num > rounded_toward_zero * denom) { + return rounded_toward_zero + 1; + } + return rounded_toward_zero; + } + + void executeEval(Scalar* data) const { + typedef typename TensorEvaluator::Dimensions InputDims; + + const int maxSharedMem = m_device.sharedMemPerBlock(); + const int maxThreadsPerBlock = m_device.maxCudaThreadsPerBlock(); + const int maxBlocksPerProcessor = m_device.maxCudaThreadsPerMultiProcessor() / maxThreadsPerBlock; + const int numMultiProcessors = m_device.getNumCudaMultiProcessors(); + const int warpSize = 32; + + switch (NumKernelDims) { + case 1: { + const int kernel_size = m_kernelImpl.dimensions().TotalSize(); + + const int numX = dimensions()[m_indices[0]]; + const int numP = dimensions().TotalSize() / numX; + int maxX; + dim3 block_size; + + const int single_stride_dim = + static_cast(Layout) == static_cast(ColMajor) + ? 0 + : m_inputImpl.dimensions().rank() - 1; + if (m_indices[0] == single_stride_dim) { + // Maximum the reuse + const int inner_dim = ((maxSharedMem / (sizeof(Scalar)) - kernel_size + 1 + 31) / 32) * 32; + maxX = numext::mini(inner_dim, numX); + const int maxP = numext::mini(maxSharedMem / ((kernel_size - 1 + maxX) * sizeof(Scalar)), numP); + block_size.x = numext::mini(maxThreadsPerBlock, maxX); + block_size.y = numext::mini(maxThreadsPerBlock / block_size.x, maxP); + } + else { + // Read as much as possible alongside the inner most dimension, that is the plane + const int inner_dim = maxSharedMem / ((warpSize + kernel_size) * sizeof(Scalar)); + const int maxP = numext::mini(inner_dim, numP); + maxX = numext::mini(maxSharedMem / (inner_dim * sizeof(Scalar)) - kernel_size + 1, numX); + + block_size.x = numext::mini(warpSize, maxX); + block_size.y = numext::mini(maxThreadsPerBlock/block_size.x, maxP); + } + + const int shared_mem = block_size.y * (maxX + kernel_size - 1) * sizeof(Scalar); + assert(shared_mem <= maxSharedMem); + + const int num_x_blocks = ceil(numX, maxX); + const int blocksPerProcessor = numext::mini(maxBlocksPerProcessor, maxSharedMem / shared_mem); + const int num_y_blocks = ceil(numMultiProcessors * blocksPerProcessor, num_x_blocks); + + dim3 num_blocks(num_x_blocks, numext::mini(num_y_blocks, ceil(numP, block_size.y))); + + + //cout << "launching 1D kernel with block_size.x: " << block_size.x << " block_size.y: " << block_size.y << " num_blocks.x: " << num_blocks.x << " num_blocks.y: " << num_blocks.y << " maxX: " << maxX << " shared_mem: " << shared_mem << " in stream " << m_device.stream() << endl; + + const array indices(m_indices[0]); + const array kernel_dims(m_kernelImpl.dimensions()[0]); + internal::IndexMapper indexMapper( + m_inputImpl.dimensions(), kernel_dims, indices); + switch(kernel_size) { + case 4: { + LAUNCH_CUDA_KERNEL((EigenConvolutionKernel1D, Index, InputDims, 4>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, 4, data); + break; + } + case 7: { + LAUNCH_CUDA_KERNEL((EigenConvolutionKernel1D, Index, InputDims, 7>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, 7, data); + break; + } + default: { + LAUNCH_CUDA_KERNEL((EigenConvolutionKernel1D, Index, InputDims, Dynamic>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, kernel_size, data); + } + } + break; + } + + case 2: { + const int idxX = + static_cast(Layout) == static_cast(ColMajor) ? 0 : 1; + const int idxY = + static_cast(Layout) == static_cast(ColMajor) ? 1 : 0; + const int kernel_size_x = m_kernelImpl.dimensions()[idxX]; + const int kernel_size_y = m_kernelImpl.dimensions()[idxY]; + + const int numX = dimensions()[m_indices[idxX]]; + const int numY = dimensions()[m_indices[idxY]]; + const int numP = dimensions().TotalSize() / (numX*numY); + + const float scaling_factor = sqrtf(static_cast(maxSharedMem) / (sizeof(Scalar) * kernel_size_y * kernel_size_x)); + + // Snap maxX to warp size + int inner_dim = ((static_cast(scaling_factor * kernel_size_x) - kernel_size_x + 1 + 32) / 32) * 32; + const int maxX = numext::mini(inner_dim, numX); + const int maxY = numext::mini(maxSharedMem / (sizeof(Scalar) * (maxX + kernel_size_x - 1)) - kernel_size_y + 1, numY); + const int maxP = numext::mini(maxSharedMem / ((kernel_size_x - 1 + maxX) * (kernel_size_y - 1 + maxY) * sizeof(Scalar)), numP); + + dim3 block_size; + block_size.x = numext::mini(1024, maxX); + block_size.y = numext::mini(1024/block_size.x, maxY); + block_size.z = numext::mini(1024/(block_size.x*block_size.y), maxP); + + const int shared_mem = block_size.z * (maxX + kernel_size_x - 1) * (maxY + kernel_size_y - 1) * sizeof(Scalar); + assert(shared_mem <= maxSharedMem); + + const int num_x_blocks = ceil(numX, maxX); + const int num_y_blocks = ceil(numY, maxY); + const int blocksPerProcessor = numext::mini(maxBlocksPerProcessor, maxSharedMem / shared_mem); + const int num_z_blocks = ceil(numMultiProcessors * blocksPerProcessor, num_x_blocks * num_y_blocks); + + dim3 num_blocks(num_x_blocks, num_y_blocks, numext::mini(num_z_blocks, ceil(numP, block_size.z))); + + + //cout << "launching 2D kernel with block_size.x: " << block_size.x << " block_size.y: " << block_size.y << " block_size.z: " << block_size.z << " num_blocks.x: " << num_blocks.x << " num_blocks.y: " << num_blocks.y << " num_blocks.z: " << num_blocks.z << " maxX: " << maxX << " maxY: " << maxY << " maxP: " << maxP << " shared_mem: " << shared_mem << " in stream " << m_device.stream() << endl; + + const array indices(m_indices[idxX], m_indices[idxY]); + const array kernel_dims(m_kernelImpl.dimensions()[idxX], + m_kernelImpl.dimensions()[idxY]); + internal::IndexMapper indexMapper( + m_inputImpl.dimensions(), kernel_dims, indices); + switch (kernel_size_x) { + case 4: { + switch (kernel_size_y) { + case 7: { + LAUNCH_CUDA_KERNEL((EigenConvolutionKernel2D, Index, InputDims, 4, 7>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, 4, 7, data); + break; + } + default: { + LAUNCH_CUDA_KERNEL((EigenConvolutionKernel2D, Index, InputDims, 4, Dynamic>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, 4, kernel_size_y, data); + break; + } + } + break; + } + case 7: { + switch (kernel_size_y) { + case 4: { + LAUNCH_CUDA_KERNEL((EigenConvolutionKernel2D, Index, InputDims, 7, 4>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, 7, 4, data); + break; + } + default: { + LAUNCH_CUDA_KERNEL((EigenConvolutionKernel2D, Index, InputDims, 7, Dynamic>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, 7, kernel_size_y, data); + break; + } + } + break; + } + default: { + LAUNCH_CUDA_KERNEL((EigenConvolutionKernel2D, Index, InputDims, Dynamic, Dynamic>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, kernel_size_x, kernel_size_y, data); + break; + } + } + break; + } + + case 3: { + const int idxX = + static_cast(Layout) == static_cast(ColMajor) ? 0 : 2; + const int idxY = + static_cast(Layout) == static_cast(ColMajor) ? 1 : 1; + const int idxZ = + static_cast(Layout) == static_cast(ColMajor) ? 2 : 0; + + const int kernel_size_x = m_kernelImpl.dimensions()[idxX]; + const int kernel_size_y = m_kernelImpl.dimensions()[idxY]; + const int kernel_size_z = m_kernelImpl.dimensions()[idxZ]; + + const int numX = dimensions()[m_indices[idxX]]; + const int numY = dimensions()[m_indices[idxY]]; + const int numZ = dimensions()[m_indices[idxZ]]; + const int numP = dimensions().TotalSize() / (numX*numY*numZ); + + const int maxX = numext::mini(128, numext::mini(maxSharedMem / (sizeof(Scalar) * kernel_size_y * kernel_size_z) - kernel_size_x + 1, numX)); + const int maxY = numext::mini(128, numext::mini(maxSharedMem / (sizeof(Scalar) * (maxX + kernel_size_x - 1) * kernel_size_z) - kernel_size_y + 1, numY)); + const int maxZ = numext::mini(128, numext::mini(maxSharedMem / (sizeof(Scalar) * (maxX + kernel_size_x - 1) * (maxY + kernel_size_y - 1)) - kernel_size_z + 1, numZ)); + + dim3 block_size; + block_size.x = numext::mini(32, maxX); + block_size.y = numext::mini(32, maxY); + block_size.z = numext::mini(1024/(block_size.x*block_size.y), maxZ); + dim3 num_blocks(ceil(numX, maxX), ceil(numY, maxY), ceil(numZ, maxZ)); + + const int shared_mem = (maxX + kernel_size_x - 1) * (maxY + kernel_size_y - 1) * (maxZ + kernel_size_z - 1) * sizeof(Scalar); + assert(shared_mem <= maxSharedMem); + + //cout << "launching 3D kernel with block_size.x: " << block_size.x << " block_size.y: " << block_size.y << " block_size.z: " << block_size.z << " num_blocks.x: " << num_blocks.x << " num_blocks.y: " << num_blocks.y << " num_blocks.z: " << num_blocks.z << " shared_mem: " << shared_mem << " in stream " << m_device.stream() << endl; + const array indices(m_indices[idxX], m_indices[idxY], + m_indices[idxZ]); + const array kernel_dims(m_kernelImpl.dimensions()[idxX], + m_kernelImpl.dimensions()[idxY], + m_kernelImpl.dimensions()[idxZ]); + internal::IndexMapper indexMapper( + m_inputImpl.dimensions(), kernel_dims, indices); + + LAUNCH_CUDA_KERNEL((EigenConvolutionKernel3D, Index, InputDims>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, numZ, maxZ, kernel_size_x, kernel_size_y, kernel_size_z, data); + break; + } + + default: { + EIGEN_STATIC_ASSERT((NumKernelDims >= 1 && NumKernelDims <= 3), THIS_METHOD_IS_ONLY_FOR_OBJECTS_OF_A_SPECIFIC_SIZE); + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + eigen_assert(m_buf); + eigen_assert(index < m_dimensions.TotalSize()); + return m_buf[index]; + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(const Index index) const + { + eigen_assert(m_buf); + eigen_assert(index < m_dimensions.TotalSize()); + return internal::ploadt(m_buf+index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + // TODO(rmlarsen): FIXME: For now, this is just a copy of the CPU cost + // model. + const double kernel_size = m_kernelImpl.dimensions().TotalSize(); + // We ignore the use of fused multiply-add. + const double convolve_compute_cost = + TensorOpCost::AddCost() + TensorOpCost::MulCost(); + const double firstIndex_compute_cost = + NumDims * + (2 * TensorOpCost::AddCost() + 2 * TensorOpCost::MulCost() + + TensorOpCost::DivCost()); + return TensorOpCost(0, 0, firstIndex_compute_cost, vectorized, PacketSize) + + kernel_size * (m_inputImpl.costPerCoeff(vectorized) + + m_kernelImpl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, convolve_compute_cost, vectorized, + PacketSize)); + } + + private: + // No assignment (copies are needed by the kernels) + TensorEvaluator& operator = (const TensorEvaluator&); + + TensorEvaluator m_inputImpl; + TensorEvaluator m_kernelImpl; + KernelArgType m_kernelArg; + Indices m_indices; + Dimensions m_dimensions; + Scalar* m_buf; + const Scalar* m_kernel; + bool m_local_kernel; + + const GpuDevice& m_device; +}; +#endif + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConvolutionSycl.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConvolutionSycl.h new file mode 100644 index 00000000..4247c1c4 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConvolutionSycl.h @@ -0,0 +1,476 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Mehdi Goli Codeplay Software Ltd. +// Ralph Potter Codeplay Software Ltd. +// Luke Iwanski Codeplay Software Ltd. +// Contact: +// Copyright (C) 2016 Benoit Steiner + +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_SYCL_H +#define EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_SYCL_H + +namespace Eigen { + +/** \class TensorConvolution + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor convolution class. + * + * + */ +template +struct EigenConvolutionKernel1D{ +typedef typename TensorSycl::internal::createPlaceHolderExpression::Type PlaceHolderExpr; +internal::IndexMapper::Layout> indexMapper; +Kernel_accessor kernel_filter; +const size_t kernelSize, range_x, range_y; +Buffer_accessor buffer_acc; +Local_accessor local_acc; +FunctorExpr functors; +TupleType tuple_of_accessors; +EigenConvolutionKernel1D(internal::IndexMapper::Layout> indexMapper_, + Kernel_accessor kernel_filter_, const size_t kernelSize_, const size_t range_x_, const size_t range_y_, + Buffer_accessor buffer_acc_, Local_accessor local_acc_, FunctorExpr functors_, TupleType tuple_of_accessors_) + :indexMapper(indexMapper_), kernel_filter(kernel_filter_), kernelSize(kernelSize_), range_x(range_x_), range_y(range_y_), + buffer_acc(buffer_acc_), local_acc(local_acc_), functors(functors_), tuple_of_accessors(tuple_of_accessors_) {} + + void operator()(cl::sycl::nd_item<2> itemID) { + typedef typename TensorSycl::internal::ConvertToDeviceExpression::Type DevExpr; + auto device_expr =TensorSycl::internal::createDeviceExpression(functors, tuple_of_accessors); + auto device_evaluator = Eigen::TensorEvaluator(device_expr.expr, Eigen::DefaultDevice()); + + auto buffer_ptr = ConvertToActualTypeSycl(CoeffReturnType, buffer_acc); + auto kernel_ptr = ConvertToActualTypeSycl(KernelType, kernel_filter); + + const size_t num_x_input = (itemID.get_local_range()[0] +kernelSize -1); //the required row to be calculated for the for each plane in shered memory + const size_t plane_kernel_offset = itemID.get_local(1) * num_x_input; + const size_t first_input_start = itemID.get_group(0)*itemID.get_local_range()[0]; + const size_t plane_tensor_offset =indexMapper.mapCudaInputPlaneToTensorInputOffset(itemID.get_global(1)); + /// fill the shared memory + for (size_t i = itemID.get_local(0); i < num_x_input ; i += itemID.get_local_range()[0]) { + const size_t local_index = i + plane_kernel_offset ; + const size_t tensor_index = plane_tensor_offset + indexMapper.mapCudaInputKernelToTensorInputOffset(i + first_input_start); + if(((i + first_input_start) < (range_x +kernelSize-1)) && itemID.get_global(1)< range_y){ + local_acc[local_index] = device_evaluator.coeff(tensor_index); + } + else local_acc[local_index]=0.0f; + } + + itemID.barrier(cl::sycl::access::fence_space::local_space); + + // calculate the convolution + const size_t first_output_start =itemID.get_group(0)*(itemID.get_local_range()[0]); // output start x + if(itemID.get_global(0)< range_x && itemID.get_global(1)< range_y){ + CoeffReturnType result = static_cast(0); + const size_t index = plane_kernel_offset+ itemID.get_local(0); + for (size_t k = 0; k < kernelSize; ++k) { + result += (local_acc[k + index] * kernel_ptr[k]); + } + const size_t tensor_index = indexMapper.mapCudaOutputPlaneToTensorOutputOffset(itemID.get_global(1)) + +indexMapper.mapCudaOutputKernelToTensorOutputOffset(itemID.get_local(0) + first_output_start); + buffer_ptr[tensor_index] = result; + } + } +}; + + +template +struct EigenConvolutionKernel2D{ +typedef typename TensorSycl::internal::createPlaceHolderExpression::Type PlaceHolderExpr; +internal::IndexMapper::Layout> indexMapper; +Kernel_accessor kernel_filter; +const size_t kernelSize_x, kernelSize_y, range_x, range_y , range_z; +Buffer_accessor buffer_acc; +Local_accessor local_acc; +FunctorExpr functors; +TupleType tuple_of_accessors; +EigenConvolutionKernel2D(internal::IndexMapper::Layout> indexMapper_, + Kernel_accessor kernel_filter_, const size_t kernelSize_x_, const size_t kernelSize_y_ ,const size_t range_x_, const size_t range_y_, const size_t range_z_, + Buffer_accessor buffer_acc_, Local_accessor local_acc_, FunctorExpr functors_, TupleType tuple_of_accessors_) + :indexMapper(indexMapper_), kernel_filter(kernel_filter_), kernelSize_x(kernelSize_x_), kernelSize_y(kernelSize_y_), range_x(range_x_), range_y(range_y_), range_z(range_z_), + buffer_acc(buffer_acc_), local_acc(local_acc_), functors(functors_), tuple_of_accessors(tuple_of_accessors_) {} + + void operator()(cl::sycl::nd_item<3> itemID) { + typedef typename TensorSycl::internal::ConvertToDeviceExpression::Type DevExpr; + auto device_expr =TensorSycl::internal::createDeviceExpression(functors, tuple_of_accessors); + auto device_evaluator = Eigen::TensorEvaluator(device_expr.expr, Eigen::DefaultDevice()); + + auto buffer_ptr = ConvertToActualTypeSycl(CoeffReturnType, buffer_acc); + auto kernel_ptr = ConvertToActualTypeSycl(KernelType, kernel_filter); + const size_t num_x_input = (itemID.get_local_range()[0] +kernelSize_x -1); //the required row to be calculated for the for each plane in shered memory + const size_t num_y_input = (itemID.get_local_range()[1] +kernelSize_y -1); //the required row to be calculated for the for each plane in shered memory + const size_t plane_input_offset = indexMapper.mapCudaInputPlaneToTensorInputOffset(itemID.get_global(2)); + const size_t plane_kernel_offset = itemID.get_local(2) * num_y_input; + + /// fill the shared memory + const size_t first_x_input_start = itemID.get_group(0)*itemID.get_local_range()[0]; + const size_t first_y_input_start = itemID.get_group(1)*itemID.get_local_range()[1]; + for (size_t j = itemID.get_local(1); j < num_y_input; j += itemID.get_local_range()[1]) { + const size_t local_input_offset = num_x_input * (j + plane_kernel_offset); + for (size_t i = itemID.get_local(0); i < num_x_input ; i += itemID.get_local_range()[0]) { + const size_t local_index = i + local_input_offset; + const size_t tensor_index = plane_input_offset + indexMapper.mapCudaInputKernelToTensorInputOffset(i + first_x_input_start, j+ first_y_input_start ); + if(((i + first_x_input_start) < (range_x +kernelSize_x-1)) &&((j + first_y_input_start) < (range_y +kernelSize_y-1)) && itemID.get_global(2)< range_z){ + local_acc[local_index] = device_evaluator.coeff(tensor_index); + } + else local_acc[local_index]=0.0f; + } + } + + itemID.barrier(cl::sycl::access::fence_space::local_space); + + // calculate the convolution + const size_t fitst_x_output_start =itemID.get_group(0)*(itemID.get_local_range()[0]); // output start x + const size_t fitst_y_output_start =itemID.get_group(1)*(itemID.get_local_range()[1]); // output start y + if(itemID.get_global(0)< range_x && itemID.get_global(1)< range_y && itemID.get_global(2)< range_z){ + CoeffReturnType result = static_cast(0); + for (size_t j = 0; j < kernelSize_y; j++) { + size_t kernel_offset =kernelSize_x * j; + const size_t index = (num_x_input*(plane_kernel_offset + j+ itemID.get_local(1))) + itemID.get_local(0); + for (size_t i = 0; i < kernelSize_x; i++) { + result += (local_acc[i + index] * kernel_ptr[i+kernel_offset]); + } + } + const size_t tensor_index = indexMapper.mapCudaOutputPlaneToTensorOutputOffset(itemID.get_global(2)) + +indexMapper.mapCudaOutputKernelToTensorOutputOffset(itemID.get_local(0) + fitst_x_output_start, itemID.get_local(1) + fitst_y_output_start); + buffer_ptr[tensor_index] = result; + } + } +}; + + + +template +struct EigenConvolutionKernel3D{ +typedef typename TensorSycl::internal::createPlaceHolderExpression::Type PlaceHolderExpr; +internal::IndexMapper::Layout> indexMapper; +Kernel_accessor kernel_filter; +const size_t kernelSize_x, kernelSize_y, kernelSize_z, range_x, range_y , range_z, numP; +Buffer_accessor buffer_acc; +Local_accessor local_acc; +FunctorExpr functors; +TupleType tuple_of_accessors; +EigenConvolutionKernel3D(internal::IndexMapper::Layout> indexMapper_, + Kernel_accessor kernel_filter_, const size_t kernelSize_x_, const size_t kernelSize_y_ , const size_t kernelSize_z_ , + const size_t range_x_, const size_t range_y_, const size_t range_z_, const size_t numP_, + Buffer_accessor buffer_acc_, Local_accessor local_acc_, FunctorExpr functors_, TupleType tuple_of_accessors_) + :indexMapper(indexMapper_), kernel_filter(kernel_filter_), kernelSize_x(kernelSize_x_), kernelSize_y(kernelSize_y_), + kernelSize_z(kernelSize_z_), range_x(range_x_), range_y(range_y_), range_z(range_z_), numP(numP_), + buffer_acc(buffer_acc_), local_acc(local_acc_), functors(functors_), tuple_of_accessors(tuple_of_accessors_) {} + + void operator()(cl::sycl::nd_item<3> itemID) { + typedef typename TensorSycl::internal::ConvertToDeviceExpression::Type DevExpr; + auto device_expr =TensorSycl::internal::createDeviceExpression(functors, tuple_of_accessors); + auto device_evaluator = Eigen::TensorEvaluator(device_expr.expr, Eigen::DefaultDevice()); + + auto buffer_ptr = ConvertToActualTypeSycl(CoeffReturnType, buffer_acc); + auto kernel_ptr = ConvertToActualTypeSycl(KernelType, kernel_filter); + const size_t num_x_input = (itemID.get_local_range()[0] +kernelSize_x -1); //the required row to be calculated for the for each plane in shered memory + const size_t num_y_input = (itemID.get_local_range()[1] +kernelSize_y -1); //the required row to be calculated for the for each plane in shered memory + const size_t num_z_input = (itemID.get_local_range()[2] +kernelSize_z -1); //the required row to be calculated for the for each plane in shered memory + const size_t first_x_input_start = itemID.get_group(0)*itemID.get_local_range()[0]; + const size_t first_y_input_start = itemID.get_group(1)*itemID.get_local_range()[1]; + const size_t first_z_input_start = itemID.get_group(2)*itemID.get_local_range()[2]; + for(size_t p=0; p(0); + for (size_t k = 0; k < kernelSize_z; k++) { + for (size_t j = 0; j < kernelSize_y; j++) { + for (size_t i = 0; i < kernelSize_x; i++) { + const size_t kernel_index =i + kernelSize_x * (j + kernelSize_y * k); + const size_t local_index = ((i+ itemID.get_local(0))+ num_x_input*((j+ itemID.get_local(1)) + num_y_input * (k+ itemID.get_local(2)))); + result += (local_acc[local_index] * kernel_ptr[kernel_index]); + } + } + } + const size_t tensor_index = indexMapper.mapCudaOutputPlaneToTensorOutputOffset(p) + +indexMapper.mapCudaOutputKernelToTensorOutputOffset(itemID.get_local(0) + fitst_x_output_start, itemID.get_local(1) + fitst_y_output_start, itemID.get_local(2) + fitst_z_output_start ); + buffer_ptr[tensor_index] = result; + } + + itemID.barrier(cl::sycl::access::fence_space::local_space); + } + } +}; + + +template +struct TensorEvaluator, const Eigen::SyclDevice> +{ + typedef TensorConvolutionOp XprType; + + static const int NumDims = internal::array_size::Dimensions>::value; + static const int NumKernelDims = internal::array_size::value; + typedef typename XprType::Index Index; + typedef DSizes Dimensions; + typedef typename TensorEvaluator::Dimensions KernelDimensions; + typedef const Eigen::SyclDevice Device; + + enum { + IsAligned = TensorEvaluator::IsAligned & TensorEvaluator::IsAligned, + PacketAccess = false, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Eigen::SyclDevice& device) + : m_inputImpl(op.inputExpression(), device), m_kernelArg(op.kernelExpression()), m_kernelImpl(op.kernelExpression(), device), m_indices(op.indices()), m_buf(NULL), m_kernel(NULL), m_local_kernel(false), m_device(device) + { + EIGEN_STATIC_ASSERT((static_cast(TensorEvaluator::Layout) == static_cast(TensorEvaluator::Layout)), YOU_MADE_A_PROGRAMMING_MISTAKE); + + const typename TensorEvaluator::Dimensions& input_dims = m_inputImpl.dimensions(); + const typename TensorEvaluator::Dimensions& kernel_dims = m_kernelImpl.dimensions(); + + m_dimensions = m_inputImpl.dimensions(); + for (int i = 0; i < NumKernelDims; ++i) { + const Index index = op.indices()[i]; + const Index input_dim = input_dims[index]; + const Index kernel_dim = kernel_dims[i]; + const Index result_dim = input_dim - kernel_dim + 1; + m_dimensions[index] = result_dim; + } + } + + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + typedef typename InputArgType::Scalar Scalar; + static const int PacketSize = internal::unpacket_traits::size; + + EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* data) { + preloadKernel(); + m_inputImpl.evalSubExprsIfNeeded(NULL); + if (data) { + executeEval(data); + return false; + } else { + m_buf = (Scalar*)m_device.allocate(dimensions().TotalSize() * sizeof(Scalar)); + executeEval(m_buf); + return true; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_inputImpl.cleanup(); + if (m_buf) { + m_device.deallocate(m_buf); + m_buf = NULL; + } + if (m_local_kernel) { + m_device.deallocate((void*)m_kernel); + m_local_kernel = false; + } + m_kernel = NULL; + } + /// used by sycl in order to build the sycl buffer + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Device& device() const{return m_device;} + /// used by sycl in order to build the sycl buffer + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType* data() const { return m_buf; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void preloadKernel() { + // Don't make a local copy of the kernel unless we have to (i.e. it's an + // expression that needs to be evaluated) + const Scalar* in_place = m_kernelImpl.data(); + if (in_place) { + m_kernel = in_place; + m_local_kernel = false; + } else { + size_t kernel_sz = m_kernelImpl.dimensions().TotalSize() * sizeof(Scalar); + Scalar* local = (Scalar*)m_device.allocate(kernel_sz); + typedef TensorEvalToOp EvalTo; + EvalTo evalToTmp(local, m_kernelArg); + const bool PacketAccess = internal::IsVectorizable::value; + internal::TensorExecutor::run(evalToTmp, m_device); + m_kernel = local; + m_local_kernel = true; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void executeEval(Scalar* data) const { + typedef TensorEvaluator InputEvaluator; + typedef typename InputEvaluator::Dimensions InputDims; + + typedef Eigen::TensorSycl::internal::FunctorExtractor InputFunctorExpr; + // extract input functor list + InputFunctorExpr input_functors = Eigen::TensorSycl::internal::extractFunctors(m_inputImpl); + + + m_device.sycl_queue().submit([&](cl::sycl::handler &cgh) { + + typedef cl::sycl::accessor InputLocalAcc; + /// work-around for gcc 4.8 auto bug + typedef decltype(Eigen::TensorSycl::internal::createTupleOfAccessors(cgh, m_inputImpl)) InputTupleType; + // create input tuple of accessors + InputTupleType tuple_of_accessors = Eigen::TensorSycl::internal::createTupleOfAccessors(cgh, m_inputImpl); + + typedef cl::sycl::accessor OutputAccessorType; + OutputAccessorType out_res= m_device. template get_sycl_accessor(cgh, data); + typedef cl::sycl::accessor KernelAccessorType; + KernelAccessorType kernel_acc= m_device. template get_sycl_accessor(cgh, m_kernel); + + switch (NumKernelDims) { + case 1: { + const size_t numX = dimensions()[m_indices[0]]; + const size_t numP = dimensions().TotalSize() / numX; + const size_t kernel_size = m_kernelImpl.dimensions().TotalSize(); + size_t range_x, GRange_x, tileSize_x, range_y, GRange_y, tileSize_y; + m_device.parallel_for_setup(numX, numP, tileSize_x,tileSize_y,range_x,range_y, GRange_x, GRange_y ); + const size_t shared_mem =(tileSize_x +kernel_size -1)*(tileSize_y); + assert(static_cast(shared_mem) <= m_device.sharedMemPerBlock()); + auto global_range=cl::sycl::range<2>(GRange_x, GRange_y); // global range + auto local_range=cl::sycl::range<2>(tileSize_x, tileSize_y); // local range + InputLocalAcc local_acc(cl::sycl::range<1>(shared_mem), cgh); + const array indices{{m_indices[0]}}; + const array kernel_dims{{m_kernelImpl.dimensions()[0]}}; + internal::IndexMapper indexMapper(m_inputImpl.dimensions(), kernel_dims, indices); + cgh.parallel_for(cl::sycl::nd_range<2>(global_range, local_range), + EigenConvolutionKernel1D( + indexMapper,kernel_acc, kernel_size, numX, numP, out_res, local_acc, input_functors, tuple_of_accessors)); + break; + } + + case 2: { + const size_t idxX =static_cast(Layout) == static_cast(ColMajor) ? 0 : 1; + const size_t idxY =static_cast(Layout) == static_cast(ColMajor) ? 1 : 0; + const size_t kernel_size_x = m_kernelImpl.dimensions()[idxX]; + const size_t kernel_size_y = m_kernelImpl.dimensions()[idxY]; + const size_t numX = dimensions()[m_indices[idxX]]; + const size_t numY = dimensions()[m_indices[idxY]]; + const size_t numP = dimensions().TotalSize() / (numX*numY); + size_t range_x, GRange_x, tileSize_x, range_y, GRange_y, tileSize_y, range_z, GRange_z, tileSize_z; + m_device.parallel_for_setup(numX, numY, numP, tileSize_x, tileSize_y, tileSize_z, range_x, range_y, range_z, GRange_x, GRange_y, GRange_z ); + const size_t shared_mem =(tileSize_x +kernel_size_x -1)*(tileSize_y +kernel_size_y -1) * tileSize_z; + assert(static_cast(shared_mem) <= m_device.sharedMemPerBlock()); + auto global_range=cl::sycl::range<3>(GRange_x, GRange_y, GRange_z); // global range + auto local_range=cl::sycl::range<3>(tileSize_x, tileSize_y, tileSize_z); // local range + InputLocalAcc local_acc(cl::sycl::range<1>(shared_mem), cgh); + const array indices {{m_indices[idxX], m_indices[idxY]}}; + const array kernel_dims{{m_kernelImpl.dimensions()[idxX], m_kernelImpl.dimensions()[idxY]}}; + internal::IndexMapper indexMapper(m_inputImpl.dimensions(), kernel_dims, indices); + cgh.parallel_for(cl::sycl::nd_range<3>(global_range, local_range), + EigenConvolutionKernel2D( + indexMapper,kernel_acc, kernel_size_x, kernel_size_y, numX, numY, numP, out_res, local_acc, input_functors, tuple_of_accessors)); + break; + } + + case 3: { + const size_t idxX =static_cast(Layout) == static_cast(ColMajor) ? 0 : 2; + const size_t idxY =static_cast(Layout) == static_cast(ColMajor) ? 1 : 1; + const size_t idxZ =static_cast(Layout) == static_cast(ColMajor) ? 2 : 0; + const size_t kernel_size_x = m_kernelImpl.dimensions()[idxX]; + const size_t kernel_size_y = m_kernelImpl.dimensions()[idxY]; + const size_t kernel_size_z = m_kernelImpl.dimensions()[idxZ]; + const size_t numX = dimensions()[m_indices[idxX]]; + const size_t numY = dimensions()[m_indices[idxY]]; + const size_t numZ = dimensions()[m_indices[idxZ]]; + const size_t numP = dimensions().TotalSize() / (numX*numY*numZ); + const array indices{{m_indices[idxX], m_indices[idxY], m_indices[idxZ]}}; + const array kernel_dims{{m_kernelImpl.dimensions()[idxX],m_kernelImpl.dimensions()[idxY], m_kernelImpl.dimensions()[idxZ]}}; + internal::IndexMapper indexMapper(m_inputImpl.dimensions(), kernel_dims, indices); + size_t range_x, GRange_x, tileSize_x, range_y, GRange_y, tileSize_y, range_z, GRange_z, tileSize_z; + m_device.parallel_for_setup(numX, numY, numZ, tileSize_x, tileSize_y, tileSize_z, range_x, range_y, range_z, GRange_x, GRange_y, GRange_z ); + const size_t shared_mem =(tileSize_x +kernel_size_x -1)*(tileSize_y +kernel_size_y -1) * (tileSize_z +kernel_size_y -1); + assert(static_cast(shared_mem) <= m_device.sharedMemPerBlock()); + auto global_range=cl::sycl::range<3>(GRange_x, GRange_y, GRange_z); // global range + auto local_range=cl::sycl::range<3>(tileSize_x, tileSize_y, tileSize_z); // local range + InputLocalAcc local_acc(cl::sycl::range<1>(shared_mem), cgh); + cgh.parallel_for(cl::sycl::nd_range<3>(global_range, local_range), + EigenConvolutionKernel3D( + indexMapper,kernel_acc, kernel_size_x, kernel_size_y, kernel_size_z, numX, numY, + numZ, numP, out_res, local_acc, input_functors, tuple_of_accessors)); + break; + } + + default: { + EIGEN_STATIC_ASSERT((NumKernelDims >= 1 && NumKernelDims <= 3), THIS_METHOD_IS_ONLY_FOR_OBJECTS_OF_A_SPECIFIC_SIZE); + } + } + }); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + eigen_assert(m_buf); + eigen_assert(index < m_dimensions.TotalSize()); + return m_buf[index]; + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(const Index index) const + { + eigen_assert(m_buf); + eigen_assert(index < m_dimensions.TotalSize()); + return internal::ploadt(m_buf+index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + // TODO(rmlarsen): FIXME: For now, this is just a copy of the CPU cost + // model. + const double kernel_size = m_kernelImpl.dimensions().TotalSize(); + // We ignore the use of fused multiply-add. + const double convolve_compute_cost = + TensorOpCost::AddCost() + TensorOpCost::MulCost(); + const double firstIndex_compute_cost = + NumDims * + (2 * TensorOpCost::AddCost() + 2 * TensorOpCost::MulCost() + + TensorOpCost::DivCost()); + return TensorOpCost(0, 0, firstIndex_compute_cost, vectorized, PacketSize) + + kernel_size * (m_inputImpl.costPerCoeff(vectorized) + + m_kernelImpl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, convolve_compute_cost, vectorized, + PacketSize)); + } + + private: + // No assignment (copies are needed by the kernels) + TensorEvaluator& operator = (const TensorEvaluator&); + TensorEvaluator m_inputImpl; + KernelArgType m_kernelArg; + TensorEvaluator m_kernelImpl; + Indices m_indices; + Dimensions m_dimensions; + Scalar* m_buf; + const Scalar* m_kernel; + bool m_local_kernel; + const Eigen::SyclDevice& m_device; +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorCostModel.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorCostModel.h new file mode 100644 index 00000000..83c449cf --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorCostModel.h @@ -0,0 +1,212 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2016 Rasmus Munk Larsen +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_COST_MODEL_H +#define EIGEN_CXX11_TENSOR_TENSOR_COST_MODEL_H + +namespace Eigen { + +/** \class TensorEvaluator + * \ingroup CXX11_Tensor_Module + * + * \brief A cost model used to limit the number of threads used for evaluating + * tensor expression. + * + */ + +// Class storing the cost of evaluating a tensor expression in terms of the +// estimated number of operand bytes loads, bytes stored, and compute cycles. +class TensorOpCost { + public: + // TODO(rmlarsen): Fix the scalar op costs in Eigen proper. Even a simple + // model based on minimal reciprocal throughput numbers from Intel or + // Agner Fog's tables would be better than what is there now. + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int MulCost() { + return internal::functor_traits< + internal::scalar_product_op >::Cost; + } + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int AddCost() { + return internal::functor_traits >::Cost; + } + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int DivCost() { + return internal::functor_traits< + internal::scalar_quotient_op >::Cost; + } + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int ModCost() { + return internal::functor_traits >::Cost; + } + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int CastCost() { + return internal::functor_traits< + internal::scalar_cast_op >::Cost; + } + + EIGEN_DEVICE_FUNC + TensorOpCost() : bytes_loaded_(0), bytes_stored_(0), compute_cycles_(0) {} + EIGEN_DEVICE_FUNC + TensorOpCost(double bytes_loaded, double bytes_stored, double compute_cycles) + : bytes_loaded_(bytes_loaded), + bytes_stored_(bytes_stored), + compute_cycles_(compute_cycles) {} + + EIGEN_DEVICE_FUNC + TensorOpCost(double bytes_loaded, double bytes_stored, double compute_cycles, + bool vectorized, double packet_size) + : bytes_loaded_(bytes_loaded), + bytes_stored_(bytes_stored), + compute_cycles_(vectorized ? compute_cycles / packet_size + : compute_cycles) { + eigen_assert(bytes_loaded >= 0 && (numext::isfinite)(bytes_loaded)); + eigen_assert(bytes_stored >= 0 && (numext::isfinite)(bytes_stored)); + eigen_assert(compute_cycles >= 0 && (numext::isfinite)(compute_cycles)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double bytes_loaded() const { + return bytes_loaded_; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double bytes_stored() const { + return bytes_stored_; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double compute_cycles() const { + return compute_cycles_; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double total_cost( + double load_cost, double store_cost, double compute_cost) const { + return load_cost * bytes_loaded_ + store_cost * bytes_stored_ + + compute_cost * compute_cycles_; + } + + // Drop memory access component. Intended for cases when memory accesses are + // sequential or are completely masked by computations. + EIGEN_DEVICE_FUNC void dropMemoryCost() { + bytes_loaded_ = 0; + bytes_stored_ = 0; + } + + // TODO(rmlarsen): Define min in terms of total cost, not elementwise. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost cwiseMin( + const TensorOpCost& rhs) const { + double bytes_loaded = numext::mini(bytes_loaded_, rhs.bytes_loaded()); + double bytes_stored = numext::mini(bytes_stored_, rhs.bytes_stored()); + double compute_cycles = numext::mini(compute_cycles_, rhs.compute_cycles()); + return TensorOpCost(bytes_loaded, bytes_stored, compute_cycles); + } + + // TODO(rmlarsen): Define max in terms of total cost, not elementwise. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost cwiseMax( + const TensorOpCost& rhs) const { + double bytes_loaded = numext::maxi(bytes_loaded_, rhs.bytes_loaded()); + double bytes_stored = numext::maxi(bytes_stored_, rhs.bytes_stored()); + double compute_cycles = numext::maxi(compute_cycles_, rhs.compute_cycles()); + return TensorOpCost(bytes_loaded, bytes_stored, compute_cycles); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost& operator+=( + const TensorOpCost& rhs) { + bytes_loaded_ += rhs.bytes_loaded(); + bytes_stored_ += rhs.bytes_stored(); + compute_cycles_ += rhs.compute_cycles(); + return *this; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost& operator*=(double rhs) { + bytes_loaded_ *= rhs; + bytes_stored_ *= rhs; + compute_cycles_ *= rhs; + return *this; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE friend TensorOpCost operator+( + TensorOpCost lhs, const TensorOpCost& rhs) { + lhs += rhs; + return lhs; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE friend TensorOpCost operator*( + TensorOpCost lhs, double rhs) { + lhs *= rhs; + return lhs; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE friend TensorOpCost operator*( + double lhs, TensorOpCost rhs) { + rhs *= lhs; + return rhs; + } + + friend std::ostream& operator<<(std::ostream& os, const TensorOpCost& tc) { + return os << "[bytes_loaded = " << tc.bytes_loaded() + << ", bytes_stored = " << tc.bytes_stored() + << ", compute_cycles = " << tc.compute_cycles() << "]"; + } + + private: + double bytes_loaded_; + double bytes_stored_; + double compute_cycles_; +}; + +// TODO(rmlarsen): Implement a policy that chooses an "optimal" number of theads +// in [1:max_threads] instead of just switching multi-threading off for small +// work units. +template +class TensorCostModel { + public: + // Scaling from Eigen compute cost to device cycles. + static const int kDeviceCyclesPerComputeCycle = 1; + + // Costs in device cycles. + static const int kStartupCycles = 100000; + static const int kPerThreadCycles = 100000; + static const int kTaskSize = 40000; + + // Returns the number of threads in [1:max_threads] to use for + // evaluating an expression with the given output size and cost per + // coefficient. + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int numThreads( + double output_size, const TensorOpCost& cost_per_coeff, int max_threads) { + double cost = totalCost(output_size, cost_per_coeff); + int threads = (cost - kStartupCycles) / kPerThreadCycles + 0.9; + return numext::mini(max_threads, numext::maxi(1, threads)); + } + + // taskSize assesses parallel task size. + // Value of 1.0 means ideal parallel task size. Values < 1.0 mean that task + // granularity needs to be increased to mitigate parallelization overheads. + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double taskSize( + double output_size, const TensorOpCost& cost_per_coeff) { + return totalCost(output_size, cost_per_coeff) / kTaskSize; + } + + private: + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double totalCost( + double output_size, const TensorOpCost& cost_per_coeff) { + // Cost of memory fetches from L2 cache. 64 is typical cache line size. + // 11 is L2 cache latency on Haswell. + // We don't know whether data is in L1, L2 or L3. But we are most interested + // in single-threaded computational time around 100us-10ms (smaller time + // is too small for parallelization, larger time is not intersting + // either because we are probably using all available threads already). + // And for the target time range, L2 seems to be what matters. Data set + // fitting into L1 is too small to take noticeable time. Data set fitting + // only into L3 presumably will take more than 10ms to load and process. + const double kLoadCycles = 1.0 / 64 * 11; + const double kStoreCycles = 1.0 / 64 * 11; + // Scaling from Eigen compute cost to device cycles. + return output_size * + cost_per_coeff.total_cost(kLoadCycles, kStoreCycles, + kDeviceCyclesPerComputeCycle); + } +}; + +} // namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_COST_MODEL_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorCustomOp.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorCustomOp.h new file mode 100644 index 00000000..e020d076 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorCustomOp.h @@ -0,0 +1,313 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CUSTOM_OP_H +#define EIGEN_CXX11_TENSOR_TENSOR_CUSTOM_OP_H + +namespace Eigen { + +/** \class TensorCustomUnaryOp + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor custom class. + * + * + */ +namespace internal { +template +struct traits > +{ + typedef typename XprType::Scalar Scalar; + typedef typename XprType::StorageKind StorageKind; + typedef typename XprType::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = traits::NumDimensions; + static const int Layout = traits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorCustomUnaryOp& type; +}; + +template +struct nested > +{ + typedef TensorCustomUnaryOp type; +}; + +} // end namespace internal + + + +template +class TensorCustomUnaryOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename internal::nested::type Nested; + typedef typename internal::traits::StorageKind StorageKind; + typedef typename internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCustomUnaryOp(const XprType& expr, const CustomUnaryFunc& func) + : m_expr(expr), m_func(func) {} + + EIGEN_DEVICE_FUNC + const CustomUnaryFunc& func() const { return m_func; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_expr; } + + protected: + typename XprType::Nested m_expr; + const CustomUnaryFunc m_func; +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorCustomUnaryOp ArgType; + typedef typename internal::traits::Index Index; + static const int NumDims = internal::traits::NumDimensions; + typedef DSizes Dimensions; + typedef typename internal::remove_const::type Scalar; + typedef typename internal::remove_const::type CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = false, + PacketAccess = (internal::packet_traits::size > 1), + BlockAccess = false, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const ArgType& op, const Device& device) + : m_op(op), m_device(device), m_result(NULL) + { + m_dimensions = op.func().dimensions(op.expression()); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType* data) { + if (data) { + evalTo(data); + return false; + } else { + m_result = static_cast( + m_device.allocate(dimensions().TotalSize() * sizeof(Scalar))); + evalTo(m_result); + return true; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + if (m_result != NULL) { + m_device.deallocate(m_result); + m_result = NULL; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const { + return m_result[index]; + } + + template + EIGEN_DEVICE_FUNC PacketReturnType packet(Index index) const { + return internal::ploadt(m_result + index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + // TODO(rmlarsen): Extend CustomOp API to return its cost estimate. + return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC CoeffReturnType* data() const { return m_result; } + + protected: + EIGEN_DEVICE_FUNC void evalTo(Scalar* data) { + TensorMap > result( + data, m_dimensions); + m_op.func().eval(m_op.expression(), result, m_device); + } + + Dimensions m_dimensions; + const ArgType m_op; + const Device& m_device; + CoeffReturnType* m_result; +}; + + + +/** \class TensorCustomBinaryOp + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor custom class. + * + * + */ +namespace internal { +template +struct traits > +{ + typedef typename internal::promote_storage_type::ret Scalar; + typedef typename internal::promote_storage_type::ret CoeffReturnType; + typedef typename promote_storage_type::StorageKind, + typename traits::StorageKind>::ret StorageKind; + typedef typename promote_index_type::Index, + typename traits::Index>::type Index; + typedef typename LhsXprType::Nested LhsNested; + typedef typename RhsXprType::Nested RhsNested; + typedef typename remove_reference::type _LhsNested; + typedef typename remove_reference::type _RhsNested; + static const int NumDimensions = traits::NumDimensions; + static const int Layout = traits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorCustomBinaryOp& type; +}; + +template +struct nested > +{ + typedef TensorCustomBinaryOp type; +}; + +} // end namespace internal + + + +template +class TensorCustomBinaryOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename internal::traits::CoeffReturnType CoeffReturnType; + typedef typename internal::nested::type Nested; + typedef typename internal::traits::StorageKind StorageKind; + typedef typename internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCustomBinaryOp(const LhsXprType& lhs, const RhsXprType& rhs, const CustomBinaryFunc& func) + + : m_lhs_xpr(lhs), m_rhs_xpr(rhs), m_func(func) {} + + EIGEN_DEVICE_FUNC + const CustomBinaryFunc& func() const { return m_func; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + lhsExpression() const { return m_lhs_xpr; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + rhsExpression() const { return m_rhs_xpr; } + + protected: + typename LhsXprType::Nested m_lhs_xpr; + typename RhsXprType::Nested m_rhs_xpr; + const CustomBinaryFunc m_func; +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorCustomBinaryOp XprType; + typedef typename internal::traits::Index Index; + static const int NumDims = internal::traits::NumDimensions; + typedef DSizes Dimensions; + typedef typename XprType::Scalar Scalar; + typedef typename internal::remove_const::type CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = false, + PacketAccess = (internal::packet_traits::size > 1), + BlockAccess = false, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_op(op), m_device(device), m_result(NULL) + { + m_dimensions = op.func().dimensions(op.lhsExpression(), op.rhsExpression()); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType* data) { + if (data) { + evalTo(data); + return false; + } else { + m_result = static_cast(m_device.allocate(dimensions().TotalSize() * sizeof(Scalar))); + evalTo(m_result); + return true; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + if (m_result != NULL) { + m_device.deallocate(m_result); + m_result = NULL; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const { + return m_result[index]; + } + + template + EIGEN_DEVICE_FUNC PacketReturnType packet(Index index) const { + return internal::ploadt(m_result + index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + // TODO(rmlarsen): Extend CustomOp API to return its cost estimate. + return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC CoeffReturnType* data() const { return m_result; } + + protected: + EIGEN_DEVICE_FUNC void evalTo(Scalar* data) { + TensorMap > result(data, m_dimensions); + m_op.func().eval(m_op.lhsExpression(), m_op.rhsExpression(), result, m_device); + } + + Dimensions m_dimensions; + const XprType m_op; + const Device& m_device; + CoeffReturnType* m_result; +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_CUSTOM_OP_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDevice.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDevice.h new file mode 100644 index 00000000..29e50a3b --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDevice.h @@ -0,0 +1,68 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_DEVICE_H +#define EIGEN_CXX11_TENSOR_TENSOR_DEVICE_H + +namespace Eigen { + +/** \class TensorDevice + * \ingroup CXX11_Tensor_Module + * + * \brief Pseudo expression providing an operator = that will evaluate its argument + * on the specified computing 'device' (GPU, thread pool, ...) + * + * Example: + * C.device(EIGEN_GPU) = A + B; + * + * Todo: operator *= and /=. + */ + +template class TensorDevice { + public: + TensorDevice(const DeviceType& device, ExpressionType& expression) : m_device(device), m_expression(expression) {} + + template + EIGEN_STRONG_INLINE TensorDevice& operator=(const OtherDerived& other) { + typedef TensorAssignOp Assign; + Assign assign(m_expression, other); + internal::TensorExecutor::run(assign, m_device); + return *this; + } + + template + EIGEN_STRONG_INLINE TensorDevice& operator+=(const OtherDerived& other) { + typedef typename OtherDerived::Scalar Scalar; + typedef TensorCwiseBinaryOp, const ExpressionType, const OtherDerived> Sum; + Sum sum(m_expression, other); + typedef TensorAssignOp Assign; + Assign assign(m_expression, sum); + internal::TensorExecutor::run(assign, m_device); + return *this; + } + + template + EIGEN_STRONG_INLINE TensorDevice& operator-=(const OtherDerived& other) { + typedef typename OtherDerived::Scalar Scalar; + typedef TensorCwiseBinaryOp, const ExpressionType, const OtherDerived> Difference; + Difference difference(m_expression, other); + typedef TensorAssignOp Assign; + Assign assign(m_expression, difference); + internal::TensorExecutor::run(assign, m_device); + return *this; + } + + protected: + const DeviceType& m_device; + ExpressionType& m_expression; +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_DEVICE_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceCuda.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceCuda.h new file mode 100644 index 00000000..be8d6938 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceCuda.h @@ -0,0 +1,340 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#if defined(EIGEN_USE_GPU) && !defined(EIGEN_CXX11_TENSOR_TENSOR_DEVICE_CUDA_H) +#define EIGEN_CXX11_TENSOR_TENSOR_DEVICE_CUDA_H + +namespace Eigen { + +static const int kCudaScratchSize = 1024; + +// This defines an interface that GPUDevice can take to use +// CUDA streams underneath. +class StreamInterface { + public: + virtual ~StreamInterface() {} + + virtual const cudaStream_t& stream() const = 0; + virtual const cudaDeviceProp& deviceProperties() const = 0; + + // Allocate memory on the actual device where the computation will run + virtual void* allocate(size_t num_bytes) const = 0; + virtual void deallocate(void* buffer) const = 0; + + // Return a scratchpad buffer of size 1k + virtual void* scratchpad() const = 0; + + // Return a semaphore. The semaphore is initially initialized to 0, and + // each kernel using it is responsible for resetting to 0 upon completion + // to maintain the invariant that the semaphore is always equal to 0 upon + // each kernel start. + virtual unsigned int* semaphore() const = 0; +}; + +static cudaDeviceProp* m_deviceProperties; +static bool m_devicePropInitialized = false; + +static void initializeDeviceProp() { + if (!m_devicePropInitialized) { + // Attempts to ensure proper behavior in the case of multiple threads + // calling this function simultaneously. This would be trivial to + // implement if we could use std::mutex, but unfortunately mutex don't + // compile with nvcc, so we resort to atomics and thread fences instead. + // Note that if the caller uses a compiler that doesn't support c++11 we + // can't ensure that the initialization is thread safe. +#if __cplusplus >= 201103L + static std::atomic first(true); + if (first.exchange(false)) { +#else + static bool first = true; + if (first) { + first = false; +#endif + // We're the first thread to reach this point. + int num_devices; + cudaError_t status = cudaGetDeviceCount(&num_devices); + if (status != cudaSuccess) { + std::cerr << "Failed to get the number of CUDA devices: " + << cudaGetErrorString(status) + << std::endl; + assert(status == cudaSuccess); + } + m_deviceProperties = new cudaDeviceProp[num_devices]; + for (int i = 0; i < num_devices; ++i) { + status = cudaGetDeviceProperties(&m_deviceProperties[i], i); + if (status != cudaSuccess) { + std::cerr << "Failed to initialize CUDA device #" + << i + << ": " + << cudaGetErrorString(status) + << std::endl; + assert(status == cudaSuccess); + } + } + +#if __cplusplus >= 201103L + std::atomic_thread_fence(std::memory_order_release); +#endif + m_devicePropInitialized = true; + } else { + // Wait for the other thread to inititialize the properties. + while (!m_devicePropInitialized) { +#if __cplusplus >= 201103L + std::atomic_thread_fence(std::memory_order_acquire); +#endif + EIGEN_SLEEP(1000); + } + } + } +} + +static const cudaStream_t default_stream = cudaStreamDefault; + +class CudaStreamDevice : public StreamInterface { + public: + // Use the default stream on the current device + CudaStreamDevice() : stream_(&default_stream), scratch_(NULL), semaphore_(NULL) { + cudaGetDevice(&device_); + initializeDeviceProp(); + } + // Use the default stream on the specified device + CudaStreamDevice(int device) : stream_(&default_stream), device_(device), scratch_(NULL), semaphore_(NULL) { + initializeDeviceProp(); + } + // Use the specified stream. Note that it's the + // caller responsibility to ensure that the stream can run on + // the specified device. If no device is specified the code + // assumes that the stream is associated to the current gpu device. + CudaStreamDevice(const cudaStream_t* stream, int device = -1) + : stream_(stream), device_(device), scratch_(NULL), semaphore_(NULL) { + if (device < 0) { + cudaGetDevice(&device_); + } else { + int num_devices; + cudaError_t err = cudaGetDeviceCount(&num_devices); + EIGEN_UNUSED_VARIABLE(err) + assert(err == cudaSuccess); + assert(device < num_devices); + device_ = device; + } + initializeDeviceProp(); + } + + virtual ~CudaStreamDevice() { + if (scratch_) { + deallocate(scratch_); + } + } + + const cudaStream_t& stream() const { return *stream_; } + const cudaDeviceProp& deviceProperties() const { + return m_deviceProperties[device_]; + } + virtual void* allocate(size_t num_bytes) const { + cudaError_t err = cudaSetDevice(device_); + EIGEN_UNUSED_VARIABLE(err) + assert(err == cudaSuccess); + void* result; + err = cudaMalloc(&result, num_bytes); + assert(err == cudaSuccess); + assert(result != NULL); + return result; + } + virtual void deallocate(void* buffer) const { + cudaError_t err = cudaSetDevice(device_); + EIGEN_UNUSED_VARIABLE(err) + assert(err == cudaSuccess); + assert(buffer != NULL); + err = cudaFree(buffer); + assert(err == cudaSuccess); + } + + virtual void* scratchpad() const { + if (scratch_ == NULL) { + scratch_ = allocate(kCudaScratchSize + sizeof(unsigned int)); + } + return scratch_; + } + + virtual unsigned int* semaphore() const { + if (semaphore_ == NULL) { + char* scratch = static_cast(scratchpad()) + kCudaScratchSize; + semaphore_ = reinterpret_cast(scratch); + cudaError_t err = cudaMemsetAsync(semaphore_, 0, sizeof(unsigned int), *stream_); + EIGEN_UNUSED_VARIABLE(err) + assert(err == cudaSuccess); + } + return semaphore_; + } + + private: + const cudaStream_t* stream_; + int device_; + mutable void* scratch_; + mutable unsigned int* semaphore_; +}; + +struct GpuDevice { + // The StreamInterface is not owned: the caller is + // responsible for its initialization and eventual destruction. + explicit GpuDevice(const StreamInterface* stream) : stream_(stream), max_blocks_(INT_MAX) { + eigen_assert(stream); + } + explicit GpuDevice(const StreamInterface* stream, int num_blocks) : stream_(stream), max_blocks_(num_blocks) { + eigen_assert(stream); + } + // TODO(bsteiner): This is an internal API, we should not expose it. + EIGEN_STRONG_INLINE const cudaStream_t& stream() const { + return stream_->stream(); + } + + EIGEN_STRONG_INLINE void* allocate(size_t num_bytes) const { + return stream_->allocate(num_bytes); + } + + EIGEN_STRONG_INLINE void deallocate(void* buffer) const { + stream_->deallocate(buffer); + } + + EIGEN_STRONG_INLINE void* scratchpad() const { + return stream_->scratchpad(); + } + + EIGEN_STRONG_INLINE unsigned int* semaphore() const { + return stream_->semaphore(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memcpy(void* dst, const void* src, size_t n) const { +#ifndef __CUDA_ARCH__ + cudaError_t err = cudaMemcpyAsync(dst, src, n, cudaMemcpyDeviceToDevice, + stream_->stream()); + EIGEN_UNUSED_VARIABLE(err) + assert(err == cudaSuccess); +#else + EIGEN_UNUSED_VARIABLE(dst); + EIGEN_UNUSED_VARIABLE(src); + EIGEN_UNUSED_VARIABLE(n); + eigen_assert(false && "The default device should be used instead to generate kernel code"); +#endif + } + + EIGEN_STRONG_INLINE void memcpyHostToDevice(void* dst, const void* src, size_t n) const { + cudaError_t err = + cudaMemcpyAsync(dst, src, n, cudaMemcpyHostToDevice, stream_->stream()); + EIGEN_UNUSED_VARIABLE(err) + assert(err == cudaSuccess); + } + + EIGEN_STRONG_INLINE void memcpyDeviceToHost(void* dst, const void* src, size_t n) const { + cudaError_t err = + cudaMemcpyAsync(dst, src, n, cudaMemcpyDeviceToHost, stream_->stream()); + EIGEN_UNUSED_VARIABLE(err) + assert(err == cudaSuccess); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memset(void* buffer, int c, size_t n) const { +#ifndef __CUDA_ARCH__ + cudaError_t err = cudaMemsetAsync(buffer, c, n, stream_->stream()); + EIGEN_UNUSED_VARIABLE(err) + assert(err == cudaSuccess); +#else + eigen_assert(false && "The default device should be used instead to generate kernel code"); +#endif + } + + EIGEN_STRONG_INLINE size_t numThreads() const { + // FIXME + return 32; + } + + EIGEN_STRONG_INLINE size_t firstLevelCacheSize() const { + // FIXME + return 48*1024; + } + + EIGEN_STRONG_INLINE size_t lastLevelCacheSize() const { + // We won't try to take advantage of the l2 cache for the time being, and + // there is no l3 cache on cuda devices. + return firstLevelCacheSize(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void synchronize() const { +#if defined(__CUDACC__) && !defined(__CUDA_ARCH__) + cudaError_t err = cudaStreamSynchronize(stream_->stream()); + if (err != cudaSuccess) { + std::cerr << "Error detected in CUDA stream: " + << cudaGetErrorString(err) + << std::endl; + assert(err == cudaSuccess); + } +#else + assert(false && "The default device should be used instead to generate kernel code"); +#endif + } + + EIGEN_STRONG_INLINE int getNumCudaMultiProcessors() const { + return stream_->deviceProperties().multiProcessorCount; + } + EIGEN_STRONG_INLINE int maxCudaThreadsPerBlock() const { + return stream_->deviceProperties().maxThreadsPerBlock; + } + EIGEN_STRONG_INLINE int maxCudaThreadsPerMultiProcessor() const { + return stream_->deviceProperties().maxThreadsPerMultiProcessor; + } + EIGEN_STRONG_INLINE int sharedMemPerBlock() const { + return stream_->deviceProperties().sharedMemPerBlock; + } + EIGEN_STRONG_INLINE int majorDeviceVersion() const { + return stream_->deviceProperties().major; + } + EIGEN_STRONG_INLINE int minorDeviceVersion() const { + return stream_->deviceProperties().minor; + } + + EIGEN_STRONG_INLINE int maxBlocks() const { + return max_blocks_; + } + + // This function checks if the CUDA runtime recorded an error for the + // underlying stream device. + inline bool ok() const { +#ifdef __CUDACC__ + cudaError_t error = cudaStreamQuery(stream_->stream()); + return (error == cudaSuccess) || (error == cudaErrorNotReady); +#else + return false; +#endif + } + + private: + const StreamInterface* stream_; + int max_blocks_; +}; + +#define LAUNCH_CUDA_KERNEL(kernel, gridsize, blocksize, sharedmem, device, ...) \ + (kernel) <<< (gridsize), (blocksize), (sharedmem), (device).stream() >>> (__VA_ARGS__); \ + assert(cudaGetLastError() == cudaSuccess); + + +// FIXME: Should be device and kernel specific. +#ifdef __CUDACC__ +static EIGEN_DEVICE_FUNC inline void setCudaSharedMemConfig(cudaSharedMemConfig config) { +#ifndef __CUDA_ARCH__ + cudaError_t status = cudaDeviceSetSharedMemConfig(config); + EIGEN_UNUSED_VARIABLE(status) + assert(status == cudaSuccess); +#else + EIGEN_UNUSED_VARIABLE(config) +#endif +} +#endif + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_DEVICE_CUDA_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceDefault.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceDefault.h new file mode 100644 index 00000000..ccaaa6cb --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceDefault.h @@ -0,0 +1,81 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_DEVICE_DEFAULT_H +#define EIGEN_CXX11_TENSOR_TENSOR_DEVICE_DEFAULT_H + + +namespace Eigen { + +// Default device for the machine (typically a single cpu core) +struct DefaultDevice { + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void* allocate(size_t num_bytes) const { + return internal::aligned_malloc(num_bytes); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void deallocate(void* buffer) const { + internal::aligned_free(buffer); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memcpy(void* dst, const void* src, size_t n) const { + ::memcpy(dst, src, n); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memcpyHostToDevice(void* dst, const void* src, size_t n) const { + memcpy(dst, src, n); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memcpyDeviceToHost(void* dst, const void* src, size_t n) const { + memcpy(dst, src, n); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memset(void* buffer, int c, size_t n) const { + ::memset(buffer, c, n); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE size_t numThreads() const { +#ifndef __CUDA_ARCH__ + // Running on the host CPU + return 1; +#else + // Running on a CUDA device + return 32; +#endif + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE size_t firstLevelCacheSize() const { +#if !defined(__CUDA_ARCH__) && !defined(__SYCL_DEVICE_ONLY__) + // Running on the host CPU + return l1CacheSize(); +#else + // Running on a CUDA device, return the amount of shared memory available. + return 48*1024; +#endif + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE size_t lastLevelCacheSize() const { +#if !defined(__CUDA_ARCH__) && !defined(__SYCL_DEVICE_ONLY__) + // Running single threaded on the host CPU + return l3CacheSize(); +#else + // Running on a CUDA device + return firstLevelCacheSize(); +#endif + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int majorDeviceVersion() const { +#ifndef __CUDA_ARCH__ + // Running single threaded on the host CPU + // Should return an enum that encodes the ISA supported by the CPU + return 1; +#else + // Running on a CUDA device + return __CUDA_ARCH__ / 100; +#endif + } +}; + +} // namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_DEVICE_DEFAULT_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceSycl.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceSycl.h new file mode 100644 index 00000000..e209799b --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceSycl.h @@ -0,0 +1,415 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Mehdi Goli Codeplay Software Ltd. +// Ralph Potter Codeplay Software Ltd. +// Luke Iwanski Codeplay Software Ltd. +// Contact: +// Copyright (C) 2016 Benoit Steiner + +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#if defined(EIGEN_USE_SYCL) && !defined(EIGEN_CXX11_TENSOR_TENSOR_DEVICE_SYCL_H) +#define EIGEN_CXX11_TENSOR_TENSOR_DEVICE_SYCL_H + +namespace Eigen { + + #define ConvertToActualTypeSycl(Scalar, buf_acc) reinterpret_cast::pointer_t>((&(*buf_acc.get_pointer()))) + + template class MemCopyFunctor { + public: + MemCopyFunctor(read_accessor src_acc, write_accessor dst_acc, size_t rng, size_t i, size_t offset) : m_src_acc(src_acc), m_dst_acc(dst_acc), m_rng(rng), m_i(i), m_offset(offset) {} + + void operator()(cl::sycl::nd_item<1> itemID) { + auto src_ptr = ConvertToActualTypeSycl(Scalar, m_src_acc); + auto dst_ptr = ConvertToActualTypeSycl(Scalar, m_dst_acc); + auto globalid = itemID.get_global_linear_id(); + if (globalid < m_rng) { + dst_ptr[globalid + m_i] = src_ptr[globalid + m_offset]; + } + } + + private: + read_accessor m_src_acc; + write_accessor m_dst_acc; + size_t m_rng; + size_t m_i; + size_t m_offset; + }; + + struct memsetkernelFunctor{ + typedef cl::sycl::accessor AccType; + AccType m_acc; + const size_t m_rng, m_c; + memsetkernelFunctor(AccType acc, const size_t rng, const size_t c):m_acc(acc), m_rng(rng), m_c(c){} + void operator()(cl::sycl::nd_item<1> itemID) { + auto globalid=itemID.get_global_linear_id(); + if (globalid< m_rng) m_acc[globalid] = m_c; + } + + }; + +EIGEN_STRONG_INLINE auto get_sycl_supported_devices()->decltype(cl::sycl::device::get_devices()){ + auto devices = cl::sycl::device::get_devices(); + std::vector::iterator it =devices.begin(); + while(it!=devices.end()) { + /// get_devices returns all the available opencl devices. Either use device_selector or exclude devices that computecpp does not support (AMD OpenCL for CPU ) + auto s= (*it).template get_info(); + std::transform(s.begin(), s.end(), s.begin(), ::tolower); + if((*it).is_cpu() && s.find("amd")!=std::string::npos && s.find("apu") == std::string::npos){ // remove amd cpu as it is not supported by computecpp allow APUs + it=devices.erase(it); + } + else{ + ++it; + } + } + return devices; +} + +struct QueueInterface { + /// class members: + bool exception_caught_ = false; + + mutable std::mutex mutex_; + + /// std::map is the container used to make sure that we create only one buffer + /// per pointer. The lifespan of the buffer now depends on the lifespan of SyclDevice. + /// If a non-read-only pointer is needed to be accessed on the host we should manually deallocate it. + mutable std::map> buffer_map; + /// sycl queue + mutable cl::sycl::queue m_queue; + /// creating device by using cl::sycl::selector or cl::sycl::device both are the same and can be captured through dev_Selector typename + /// SyclStreamDevice is not owned. it is the caller's responsibility to destroy it. + template explicit QueueInterface(const dev_Selector& s): +#ifdef EIGEN_EXCEPTIONS + m_queue(cl::sycl::queue(s, [&](cl::sycl::exception_list l) { + for (const auto& e : l) { + try { + if (e) { + exception_caught_ = true; + std::rethrow_exception(e); + } + } catch (cl::sycl::exception e) { + std::cerr << e.what() << std::endl; + } + } + })) +#else +m_queue(cl::sycl::queue(s, [&](cl::sycl::exception_list l) { + for (const auto& e : l) { + if (e) { + exception_caught_ = true; + std::cerr << "Error detected Inside Sycl Device."<< std::endl; + + } + } +})) +#endif + {} + + /// Allocating device pointer. This pointer is actually an 8 bytes host pointer used as key to access the sycl device buffer. + /// The reason is that we cannot use device buffer as a pointer as a m_data in Eigen leafNode expressions. So we create a key + /// pointer to be used in Eigen expression construction. When we convert the Eigen construction into the sycl construction we + /// use this pointer as a key in our buffer_map and we make sure that we dedicate only one buffer only for this pointer. + /// The device pointer would be deleted by calling deallocate function. + EIGEN_STRONG_INLINE void* allocate(size_t num_bytes) const { + auto buf = cl::sycl::buffer(cl::sycl::range<1>(num_bytes)); + auto ptr =buf.get_access().get_pointer(); + buf.set_final_data(nullptr); + std::lock_guard lock(mutex_); + buffer_map.insert(std::pair>(static_cast(ptr),buf)); + return static_cast(ptr); + } + + /// This is used to deallocate the device pointer. p is used as a key inside + /// the map to find the device buffer and delete it. + EIGEN_STRONG_INLINE void deallocate(void *p) const { + std::lock_guard lock(mutex_); + auto it = buffer_map.find(static_cast(p)); + if (it != buffer_map.end()) { + buffer_map.erase(it); + } + } + + EIGEN_STRONG_INLINE void deallocate_all() const { + std::lock_guard lock(mutex_); + buffer_map.clear(); + } + + EIGEN_STRONG_INLINE std::map>::iterator find_buffer(const void* ptr) const { + std::lock_guard lock(mutex_); + auto it1 = buffer_map.find(static_cast(ptr)); + if (it1 != buffer_map.end()){ + return it1; + } + else{ + for(std::map>::iterator it=buffer_map.begin(); it!=buffer_map.end(); ++it){ + auto size = it->second.get_size(); + if((it->first < (static_cast(ptr))) && ((static_cast(ptr)) < (it->first + size)) ) return it; + } + } + std::cerr << "No sycl buffer found. Make sure that you have allocated memory for your buffer by calling malloc-ed function."<< std::endl; + abort(); + } + + // This function checks if the runtime recorded an error for the + // underlying stream device. + EIGEN_STRONG_INLINE bool ok() const { + if (!exception_caught_) { + m_queue.wait_and_throw(); + } + return !exception_caught_; + } + + // destructor + ~QueueInterface() { buffer_map.clear(); } +}; + +struct SyclDevice { + // class member. + QueueInterface* m_queue_stream; + /// QueueInterface is not owned. it is the caller's responsibility to destroy it. + explicit SyclDevice(QueueInterface* queue_stream) : m_queue_stream(queue_stream){} + + /// Creation of sycl accessor for a buffer. This function first tries to find + /// the buffer in the buffer_map. If found it gets the accessor from it, if not, + /// the function then adds an entry by creating a sycl buffer for that particular pointer. + template EIGEN_STRONG_INLINE cl::sycl::accessor + get_sycl_accessor(cl::sycl::handler &cgh, const void* ptr) const { + return (get_sycl_buffer(ptr).template get_access(cgh)); + } + + /// Accessing the created sycl device buffer for the device pointer + EIGEN_STRONG_INLINE cl::sycl::buffer& get_sycl_buffer(const void * ptr) const { + return m_queue_stream->find_buffer(ptr)->second; + } + + /// This is used to prepare the number of threads and also the number of threads per block for sycl kernels + template + EIGEN_STRONG_INLINE void parallel_for_setup(Index n, Index &tileSize, Index &rng, Index &GRange) const { + tileSize =static_cast(sycl_queue().get_device(). template get_info()); + auto s= sycl_queue().get_device().template get_info(); + std::transform(s.begin(), s.end(), s.begin(), ::tolower); + if(sycl_queue().get_device().is_cpu()){ // intel doesnot allow to use max workgroup size + tileSize=std::min(static_cast(256), static_cast(tileSize)); + } + rng = n; + if (rng==0) rng=static_cast(1); + GRange=rng; + if (tileSize>GRange) tileSize=GRange; + else if(GRange>tileSize){ + Index xMode = static_cast(GRange % tileSize); + if (xMode != 0) GRange += static_cast(tileSize - xMode); + } + } + + /// This is used to prepare the number of threads and also the number of threads per block for sycl kernels + template + EIGEN_STRONG_INLINE void parallel_for_setup(Index dim0, Index dim1, Index &tileSize0, Index &tileSize1, Index &rng0, Index &rng1, Index &GRange0, Index &GRange1) const { + Index max_workgroup_Size = static_cast(maxSyclThreadsPerBlock()); + if(sycl_queue().get_device().is_cpu()){ // intel doesnot allow to use max workgroup size + max_workgroup_Size=std::min(static_cast(256), static_cast(max_workgroup_Size)); + } + Index pow_of_2 = static_cast(std::log2(max_workgroup_Size)); + tileSize1 =static_cast(std::pow(2, static_cast(pow_of_2/2))); + rng1=dim1; + if (rng1==0 ) rng1=static_cast(1); + GRange1=rng1; + if (tileSize1>GRange1) tileSize1=GRange1; + else if(GRange1>tileSize1){ + Index xMode = static_cast(GRange1 % tileSize1); + if (xMode != 0) GRange1 += static_cast(tileSize1 - xMode); + } + tileSize0 = static_cast(max_workgroup_Size/tileSize1); + rng0 = dim0; + if (rng0==0 ) rng0=static_cast(1); + GRange0=rng0; + if (tileSize0>GRange0) tileSize0=GRange0; + else if(GRange0>tileSize0){ + Index xMode = static_cast(GRange0 % tileSize0); + if (xMode != 0) GRange0 += static_cast(tileSize0 - xMode); + } + } + + + + /// This is used to prepare the number of threads and also the number of threads per block for sycl kernels + template + EIGEN_STRONG_INLINE void parallel_for_setup(Index dim0, Index dim1,Index dim2, Index &tileSize0, Index &tileSize1, Index &tileSize2, Index &rng0, Index &rng1, Index &rng2, Index &GRange0, Index &GRange1, Index &GRange2) const { + Index max_workgroup_Size = static_cast(maxSyclThreadsPerBlock()); + if(sycl_queue().get_device().is_cpu()){ // intel doesnot allow to use max workgroup size + max_workgroup_Size=std::min(static_cast(256), static_cast(max_workgroup_Size)); + } + Index pow_of_2 = static_cast(std::log2(max_workgroup_Size)); + tileSize2 =static_cast(std::pow(2, static_cast(pow_of_2/3))); + rng2=dim2; + if (rng2==0 ) rng1=static_cast(1); + GRange2=rng2; + if (tileSize2>GRange2) tileSize2=GRange2; + else if(GRange2>tileSize2){ + Index xMode = static_cast(GRange2 % tileSize2); + if (xMode != 0) GRange2 += static_cast(tileSize2 - xMode); + } + pow_of_2 = static_cast(std::log2(static_cast(max_workgroup_Size/tileSize2))); + tileSize1 =static_cast(std::pow(2, static_cast(pow_of_2/2))); + rng1=dim1; + if (rng1==0 ) rng1=static_cast(1); + GRange1=rng1; + if (tileSize1>GRange1) tileSize1=GRange1; + else if(GRange1>tileSize1){ + Index xMode = static_cast(GRange1 % tileSize1); + if (xMode != 0) GRange1 += static_cast(tileSize1 - xMode); + } + tileSize0 = static_cast(max_workgroup_Size/(tileSize1*tileSize2)); + rng0 = dim0; + if (rng0==0 ) rng0=static_cast(1); + GRange0=rng0; + if (tileSize0>GRange0) tileSize0=GRange0; + else if(GRange0>tileSize0){ + Index xMode = static_cast(GRange0 % tileSize0); + if (xMode != 0) GRange0 += static_cast(tileSize0 - xMode); + } + } + /// allocate device memory + EIGEN_STRONG_INLINE void *allocate(size_t num_bytes) const { + return m_queue_stream->allocate(num_bytes); + } + /// deallocate device memory + EIGEN_STRONG_INLINE void deallocate(void *p) const { + m_queue_stream->deallocate(p); + } + + // some runtime conditions that can be applied here + EIGEN_STRONG_INLINE bool isDeviceSuitable() const { return true; } + + /// the memcpy function + template EIGEN_STRONG_INLINE void memcpy(void *dst, const Index *src, size_t n) const { + auto it1 = m_queue_stream->find_buffer(static_cast(src)); + auto it2 = m_queue_stream->find_buffer(dst); + auto offset= (static_cast(static_cast(src))) - it1->first; + auto i= (static_cast(dst)) - it2->first; + offset/=sizeof(Index); + i/=sizeof(Index); + size_t rng, GRange, tileSize; + parallel_for_setup(n/sizeof(Index), tileSize, rng, GRange); + sycl_queue().submit([&](cl::sycl::handler &cgh) { + auto src_acc =it1->second.template get_access(cgh); + auto dst_acc =it2->second.template get_access(cgh); + typedef decltype(src_acc) read_accessor; + typedef decltype(dst_acc) write_accessor; + cgh.parallel_for(cl::sycl::nd_range<1>(cl::sycl::range<1>(GRange), cl::sycl::range<1>(tileSize)), MemCopyFunctor(src_acc, dst_acc, rng, i, offset)); + }); + synchronize(); + } + + /// The memcpyHostToDevice is used to copy the device only pointer to a host pointer. Using the device + /// pointer created as a key we find the sycl buffer and get the host accessor with discard_write mode + /// on it. Using a discard_write accessor guarantees that we do not bring back the current value of the + /// buffer to host. Then we use the memcpy to copy the data to the host accessor. The first time that + /// this buffer is accessed, the data will be copied to the device. + template EIGEN_STRONG_INLINE void memcpyHostToDevice(Index *dst, const Index *src, size_t n) const { + auto host_acc= get_sycl_buffer(dst). template get_access(); + ::memcpy(host_acc.get_pointer(), src, n); + } + /// The memcpyDeviceToHost is used to copy the data from host to device. Here, in order to avoid double copying the data. We create a sycl + /// buffer with map_allocator for the destination pointer with a discard_write accessor on it. The lifespan of the buffer is bound to the + /// lifespan of the memcpyDeviceToHost function. We create a kernel to copy the data, from the device- only source buffer to the destination + /// buffer with map_allocator on the gpu in parallel. At the end of the function call the destination buffer would be destroyed and the data + /// would be available on the dst pointer using fast copy technique (map_allocator). In this case we can make sure that we copy the data back + /// to the cpu only once per function call. + template EIGEN_STRONG_INLINE void memcpyDeviceToHost(void *dst, const Index *src, size_t n) const { + auto it = m_queue_stream->find_buffer(src); + auto offset =static_cast(static_cast(src))- it->first; + offset/=sizeof(Index); + size_t rng, GRange, tileSize; + parallel_for_setup(n/sizeof(Index), tileSize, rng, GRange); + // Assuming that the dst is the start of the destination pointer + auto dest_buf = cl::sycl::buffer >(static_cast(dst), cl::sycl::range<1>(n)); + sycl_queue().submit([&](cl::sycl::handler &cgh) { + auto src_acc= it->second.template get_access(cgh); + auto dst_acc =dest_buf.template get_access(cgh); + typedef decltype(src_acc) read_accessor; + typedef decltype(dst_acc) write_accessor; + cgh.parallel_for( cl::sycl::nd_range<1>(cl::sycl::range<1>(GRange), cl::sycl::range<1>(tileSize)), MemCopyFunctor(src_acc, dst_acc, rng, 0, offset)); + }); + synchronize(); + } + /// returning the sycl queue + EIGEN_STRONG_INLINE cl::sycl::queue& sycl_queue() const { return m_queue_stream->m_queue;} + /// Here is the implementation of memset function on sycl. + EIGEN_STRONG_INLINE void memset(void *data, int c, size_t n) const { + size_t rng, GRange, tileSize; + parallel_for_setup(n, tileSize, rng, GRange); + sycl_queue().submit(memsetCghFunctor(get_sycl_buffer(static_cast(static_cast(data))),rng, GRange, tileSize, c )); + synchronize(); + } + + struct memsetCghFunctor{ + cl::sycl::buffer& m_buf; + const size_t& rng , GRange, tileSize; + const int &c; + memsetCghFunctor(cl::sycl::buffer& buff, const size_t& rng_, const size_t& GRange_, const size_t& tileSize_, const int& c_) + :m_buf(buff), rng(rng_), GRange(GRange_), tileSize(tileSize_), c(c_){} + + void operator()(cl::sycl::handler &cgh) const { + auto buf_acc = m_buf.template get_access(cgh); + cgh.parallel_for(cl::sycl::nd_range<1>(cl::sycl::range<1>(GRange), cl::sycl::range<1>(tileSize)), memsetkernelFunctor(buf_acc, rng, c)); + } + }; + + EIGEN_STRONG_INLINE size_t firstLevelCacheSize() const { + // FIXME + return 48*1024; + } + + EIGEN_STRONG_INLINE size_t lastLevelCacheSize() const { + // We won't try to take advantage of the l2 cache for the time being, and + // there is no l3 cache on cuda devices. + return firstLevelCacheSize(); + } + EIGEN_STRONG_INLINE unsigned long getNumSyclMultiProcessors() const { + return sycl_queue().get_device(). template get_info(); + // return stream_->deviceProperties().multiProcessorCount; + } + EIGEN_STRONG_INLINE unsigned long maxSyclThreadsPerBlock() const { + return sycl_queue().get_device(). template get_info(); + + // return stream_->deviceProperties().maxThreadsPerBlock; + } + EIGEN_STRONG_INLINE unsigned long maxSyclThreadsPerMultiProcessor() const { + // OpenCL doesnot have such concept + return 2;//sycl_queue().get_device(). template get_info(); + // return stream_->deviceProperties().maxThreadsPerMultiProcessor; + } + EIGEN_STRONG_INLINE size_t sharedMemPerBlock() const { + return sycl_queue().get_device(). template get_info(); + // return stream_->deviceProperties().sharedMemPerBlock; + } + /// No need for sycl it should act the same as CPU version + EIGEN_STRONG_INLINE int majorDeviceVersion() const { return 1; } + + EIGEN_STRONG_INLINE void synchronize() const { + sycl_queue().wait_and_throw(); //pass + } + + EIGEN_STRONG_INLINE void asynchronousExec() const { + ///FIXEDME:: currently there is a race condition regarding the asynch scheduler. + //sycl_queue().throw_asynchronous();// does not pass. Temporarily disabled + sycl_queue().wait_and_throw(); //pass + + } + // This function checks if the runtime recorded an error for the + // underlying stream device. + EIGEN_STRONG_INLINE bool ok() const { + return m_queue_stream->ok(); + } +}; + + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_DEVICE_SYCL_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceThreadPool.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceThreadPool.h new file mode 100644 index 00000000..16180ca6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceThreadPool.h @@ -0,0 +1,268 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#if defined(EIGEN_USE_THREADS) && !defined(EIGEN_CXX11_TENSOR_TENSOR_DEVICE_THREAD_POOL_H) +#define EIGEN_CXX11_TENSOR_TENSOR_DEVICE_THREAD_POOL_H + +namespace Eigen { + +// Barrier is an object that allows one or more threads to wait until +// Notify has been called a specified number of times. +class Barrier { + public: + Barrier(unsigned int count) : state_(count << 1), notified_(false) { + eigen_assert(((count << 1) >> 1) == count); + } + ~Barrier() { + eigen_assert((state_>>1) == 0); + } + + void Notify() { + unsigned int v = state_.fetch_sub(2, std::memory_order_acq_rel) - 2; + if (v != 1) { + eigen_assert(((v + 2) & ~1) != 0); + return; // either count has not dropped to 0, or waiter is not waiting + } + std::unique_lock l(mu_); + eigen_assert(!notified_); + notified_ = true; + cv_.notify_all(); + } + + void Wait() { + unsigned int v = state_.fetch_or(1, std::memory_order_acq_rel); + if ((v >> 1) == 0) return; + std::unique_lock l(mu_); + while (!notified_) { + cv_.wait(l); + } + } + + private: + std::mutex mu_; + std::condition_variable cv_; + std::atomic state_; // low bit is waiter flag + bool notified_; +}; + + +// Notification is an object that allows a user to to wait for another +// thread to signal a notification that an event has occurred. +// +// Multiple threads can wait on the same Notification object, +// but only one caller must call Notify() on the object. +struct Notification : Barrier { + Notification() : Barrier(1) {}; +}; + + +// Runs an arbitrary function and then calls Notify() on the passed in +// Notification. +template struct FunctionWrapperWithNotification +{ + static void run(Notification* n, Function f, Args... args) { + f(args...); + if (n) { + n->Notify(); + } + } +}; + +template struct FunctionWrapperWithBarrier +{ + static void run(Barrier* b, Function f, Args... args) { + f(args...); + if (b) { + b->Notify(); + } + } +}; + +template +static EIGEN_STRONG_INLINE void wait_until_ready(SyncType* n) { + if (n) { + n->Wait(); + } +} + + +// Build a thread pool device on top the an existing pool of threads. +struct ThreadPoolDevice { + // The ownership of the thread pool remains with the caller. + ThreadPoolDevice(ThreadPoolInterface* pool, int num_cores) : pool_(pool), num_threads_(num_cores) { } + + EIGEN_STRONG_INLINE void* allocate(size_t num_bytes) const { + return internal::aligned_malloc(num_bytes); + } + + EIGEN_STRONG_INLINE void deallocate(void* buffer) const { + internal::aligned_free(buffer); + } + + EIGEN_STRONG_INLINE void memcpy(void* dst, const void* src, size_t n) const { + ::memcpy(dst, src, n); + } + EIGEN_STRONG_INLINE void memcpyHostToDevice(void* dst, const void* src, size_t n) const { + memcpy(dst, src, n); + } + EIGEN_STRONG_INLINE void memcpyDeviceToHost(void* dst, const void* src, size_t n) const { + memcpy(dst, src, n); + } + + EIGEN_STRONG_INLINE void memset(void* buffer, int c, size_t n) const { + ::memset(buffer, c, n); + } + + EIGEN_STRONG_INLINE int numThreads() const { + return num_threads_; + } + + EIGEN_STRONG_INLINE size_t firstLevelCacheSize() const { + return l1CacheSize(); + } + + EIGEN_STRONG_INLINE size_t lastLevelCacheSize() const { + // The l3 cache size is shared between all the cores. + return l3CacheSize() / num_threads_; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int majorDeviceVersion() const { + // Should return an enum that encodes the ISA supported by the CPU + return 1; + } + + template + EIGEN_STRONG_INLINE Notification* enqueue(Function&& f, Args&&... args) const { + Notification* n = new Notification(); + pool_->Schedule(std::bind(&FunctionWrapperWithNotification::run, n, f, args...)); + return n; + } + + template + EIGEN_STRONG_INLINE void enqueue_with_barrier(Barrier* b, + Function&& f, + Args&&... args) const { + pool_->Schedule(std::bind( + &FunctionWrapperWithBarrier::run, b, f, args...)); + } + + template + EIGEN_STRONG_INLINE void enqueueNoNotification(Function&& f, Args&&... args) const { + pool_->Schedule(std::bind(f, args...)); + } + + // Returns a logical thread index between 0 and pool_->NumThreads() - 1 if + // called from one of the threads in pool_. Returns -1 otherwise. + EIGEN_STRONG_INLINE int currentThreadId() const { + return pool_->CurrentThreadId(); + } + + // parallelFor executes f with [0, n) arguments in parallel and waits for + // completion. F accepts a half-open interval [first, last). + // Block size is choosen based on the iteration cost and resulting parallel + // efficiency. If block_align is not nullptr, it is called to round up the + // block size. + void parallelFor(Index n, const TensorOpCost& cost, + std::function block_align, + std::function f) const { + typedef TensorCostModel CostModel; + if (n <= 1 || numThreads() == 1 || + CostModel::numThreads(n, cost, static_cast(numThreads())) == 1) { + f(0, n); + return; + } + + // Calculate block size based on (1) the iteration cost and (2) parallel + // efficiency. We want blocks to be not too small to mitigate + // parallelization overheads; not too large to mitigate tail + // effect and potential load imbalance and we also want number + // of blocks to be evenly dividable across threads. + + double block_size_f = 1.0 / CostModel::taskSize(1, cost); + Index block_size = numext::mini(n, numext::maxi(1, block_size_f)); + const Index max_block_size = + numext::mini(n, numext::maxi(1, 2 * block_size_f)); + if (block_align) { + Index new_block_size = block_align(block_size); + eigen_assert(new_block_size >= block_size); + block_size = numext::mini(n, new_block_size); + } + Index block_count = divup(n, block_size); + // Calculate parallel efficiency as fraction of total CPU time used for + // computations: + double max_efficiency = + static_cast(block_count) / + (divup(block_count, numThreads()) * numThreads()); + // Now try to increase block size up to max_block_size as long as it + // doesn't decrease parallel efficiency. + for (Index prev_block_count = block_count; prev_block_count > 1;) { + // This is the next block size that divides size into a smaller number + // of blocks than the current block_size. + Index coarser_block_size = divup(n, prev_block_count - 1); + if (block_align) { + Index new_block_size = block_align(coarser_block_size); + eigen_assert(new_block_size >= coarser_block_size); + coarser_block_size = numext::mini(n, new_block_size); + } + if (coarser_block_size > max_block_size) { + break; // Reached max block size. Stop. + } + // Recalculate parallel efficiency. + const Index coarser_block_count = divup(n, coarser_block_size); + eigen_assert(coarser_block_count < prev_block_count); + prev_block_count = coarser_block_count; + const double coarser_efficiency = + static_cast(coarser_block_count) / + (divup(coarser_block_count, numThreads()) * numThreads()); + if (coarser_efficiency + 0.01 >= max_efficiency) { + // Taking it. + block_size = coarser_block_size; + block_count = coarser_block_count; + if (max_efficiency < coarser_efficiency) { + max_efficiency = coarser_efficiency; + } + } + } + + // Recursively divide size into halves until we reach block_size. + // Division code rounds mid to block_size, so we are guaranteed to get + // block_count leaves that do actual computations. + Barrier barrier(static_cast(block_count)); + std::function handleRange; + handleRange = [=, &handleRange, &barrier, &f](Index first, Index last) { + if (last - first <= block_size) { + // Single block or less, execute directly. + f(first, last); + barrier.Notify(); + return; + } + // Split into halves and submit to the pool. + Index mid = first + divup((last - first) / 2, block_size) * block_size; + pool_->Schedule([=, &handleRange]() { handleRange(mid, last); }); + handleRange(first, mid); + }; + handleRange(0, n); + barrier.Wait(); + } + + // Convenience wrapper for parallelFor that does not align blocks. + void parallelFor(Index n, const TensorOpCost& cost, + std::function f) const { + parallelFor(n, cost, nullptr, std::move(f)); + } + + private: + ThreadPoolInterface* pool_; + int num_threads_; +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_DEVICE_THREAD_POOL_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDimensionList.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDimensionList.h new file mode 100644 index 00000000..1a30e45f --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDimensionList.h @@ -0,0 +1,236 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_DIMENSION_LIST_H +#define EIGEN_CXX11_TENSOR_TENSOR_DIMENSION_LIST_H + +namespace Eigen { + +/** \internal + * + * \class TensorDimensionList + * \ingroup CXX11_Tensor_Module + * + * \brief Special case of tensor index list used to list all the dimensions of a tensor of rank n. + * + * \sa Tensor + */ + +template struct DimensionList { + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE + const Index operator[] (const Index i) const { return i; } +}; + +namespace internal { + +template struct array_size > { + static const size_t value = Rank; +}; +template struct array_size > { + static const size_t value = Rank; +}; + +template const Index array_get(DimensionList&) { + return n; +} +template const Index array_get(const DimensionList&) { + return n; +} + + +#if EIGEN_HAS_CONSTEXPR +template +struct index_known_statically_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex) { + return true; + } +}; +template +struct index_known_statically_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex) { + return true; + } +}; + +template +struct all_indices_known_statically_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run() { + return true; + } +}; +template +struct all_indices_known_statically_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run() { + return true; + } +}; + +template +struct indices_statically_known_to_increase_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run() { + return true; + } +}; +template +struct indices_statically_known_to_increase_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run() { + return true; + } +}; + +template +struct index_statically_eq_impl > { + static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return i == value; + } +}; +template +struct index_statically_eq_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return i == value; + } +}; + +template +struct index_statically_ne_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return i != value; + } +}; +template +struct index_statically_ne_impl > { + static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return i != value; + } +}; + +template +struct index_statically_gt_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return i > value; + } +}; +template +struct index_statically_gt_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return i > value; + } +}; + +template +struct index_statically_lt_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return i < value; + } +}; +template +struct index_statically_lt_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return i < value; + } +}; + +#else +template +struct index_known_statically_impl > { + EIGEN_DEVICE_FUNC static EIGEN_ALWAYS_INLINE bool run(const DenseIndex) { + return true; + } +}; +template +struct index_known_statically_impl > { + EIGEN_DEVICE_FUNC static EIGEN_ALWAYS_INLINE bool run(const DenseIndex) { + return true; + } +}; + +template +struct all_indices_known_statically_impl > { + EIGEN_DEVICE_FUNC static EIGEN_ALWAYS_INLINE bool run() { + return true; + } +}; +template +struct all_indices_known_statically_impl > { + EIGEN_DEVICE_FUNC static EIGEN_ALWAYS_INLINE bool run() { + return true; + } +}; + +template +struct indices_statically_known_to_increase_impl > { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run() { + return true; + } +}; +template +struct indices_statically_known_to_increase_impl > { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run() { + return true; + } +}; + +template +struct index_statically_eq_impl > { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) { + return false; + } +}; +template +struct index_statically_eq_impl > { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) { + return false; + } +}; + +template +struct index_statically_ne_impl > { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex){ + return false; + } +}; +template +struct index_statically_ne_impl > { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) { + return false; + } +}; + +template +struct index_statically_gt_impl > { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) { + return false; + } +}; +template +struct index_statically_gt_impl > { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) { + return false; + } +}; + +template +struct index_statically_lt_impl > { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) { + return false; + } +}; +template +struct index_statically_lt_impl > { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) { + return false; + } +}; +#endif + +} // end namespace internal +} // end namespace Eigen + + +#endif // EIGEN_CXX11_TENSOR_TENSOR_DIMENSION_LIST_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDimensions.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDimensions.h new file mode 100644 index 00000000..86405e69 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDimensions.h @@ -0,0 +1,430 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_DIMENSIONS_H +#define EIGEN_CXX11_TENSOR_TENSOR_DIMENSIONS_H + + +namespace Eigen { + +/** \internal + * + * \class TensorDimensions + * \ingroup CXX11_Tensor_Module + * + * \brief Set of classes used to encode and store the dimensions of a Tensor. + * + * The Sizes class encodes as part of the type the number of dimensions and the + * sizes corresponding to each dimension. It uses no storage space since it is + * entirely known at compile time. + * The DSizes class is its dynamic sibling: the number of dimensions is known + * at compile time but the sizes are set during execution. + * + * \sa Tensor + */ + +// Boilerplate code +namespace internal { + +template struct dget { + static const std::ptrdiff_t value = get::value; +}; + + +template +struct fixed_size_tensor_index_linearization_helper +{ + template EIGEN_DEVICE_FUNC + static inline Index run(array const& indices, + const Dimensions& dimensions) + { + return array_get(indices) + + dget::value * + fixed_size_tensor_index_linearization_helper::run(indices, dimensions); + } +}; + +template +struct fixed_size_tensor_index_linearization_helper +{ + template EIGEN_DEVICE_FUNC + static inline Index run(array const&, const Dimensions&) + { + return 0; + } +}; + +template +struct fixed_size_tensor_index_extraction_helper +{ + template EIGEN_DEVICE_FUNC + static inline Index run(const Index index, + const Dimensions& dimensions) + { + const Index mult = (index == n-1) ? 1 : 0; + return array_get(dimensions) * mult + + fixed_size_tensor_index_extraction_helper::run(index, dimensions); + } +}; + +template +struct fixed_size_tensor_index_extraction_helper +{ + template EIGEN_DEVICE_FUNC + static inline Index run(const Index, + const Dimensions&) + { + return 0; + } + }; + +} // end namespace internal + + +// Fixed size +#ifndef EIGEN_EMULATE_CXX11_META_H +template +struct Sizes { + typedef internal::numeric_list Base; + const Base t = Base(); + static const std::ptrdiff_t total_size = internal::arg_prod(Indices...); + static const size_t count = Base::count; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t rank() const { + return Base::count; + } + + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t TotalSize() { + return internal::arg_prod(Indices...); + } + + EIGEN_DEVICE_FUNC Sizes() { } + template + explicit EIGEN_DEVICE_FUNC Sizes(const array& /*indices*/) { + // todo: add assertion + } +#if EIGEN_HAS_VARIADIC_TEMPLATES + template EIGEN_DEVICE_FUNC Sizes(DenseIndex...) { } + explicit EIGEN_DEVICE_FUNC Sizes(std::initializer_list /*l*/) { + // todo: add assertion + } +#endif + + template Sizes& operator = (const T& /*other*/) { + // add assertion failure if the size of other is different + return *this; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t operator[] (const std::size_t index) const { + return internal::fixed_size_tensor_index_extraction_helper::run(index, t); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + size_t IndexOfColMajor(const array& indices) const { + return internal::fixed_size_tensor_index_linearization_helper::run(indices, t); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + size_t IndexOfRowMajor(const array& indices) const { + return internal::fixed_size_tensor_index_linearization_helper::run(indices, t); + } +}; + +namespace internal { +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t array_prod(const Sizes&) { + return Sizes::total_size; +} +} + +#else + +template +struct non_zero_size { + typedef internal::type2val type; +}; +template <> +struct non_zero_size<0> { + typedef internal::null_type type; +}; + +template struct Sizes { + typedef typename internal::make_type_list::type, typename non_zero_size::type, typename non_zero_size::type, typename non_zero_size::type, typename non_zero_size::type >::type Base; + static const size_t count = Base::count; + static const std::size_t total_size = internal::arg_prod::value; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE size_t rank() const { + return count; + } + + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE size_t TotalSize() { + return internal::arg_prod::value; + } + + Sizes() { } + template + explicit Sizes(const array& /*indices*/) { + // todo: add assertion + } + template Sizes& operator = (const T& /*other*/) { + // add assertion failure if the size of other is different + return *this; + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template Sizes(DenseIndex... /*indices*/) { } + explicit Sizes(std::initializer_list) { + // todo: add assertion + } +#else + EIGEN_DEVICE_FUNC explicit Sizes(const DenseIndex) { + } + EIGEN_DEVICE_FUNC Sizes(const DenseIndex, const DenseIndex) { + } + EIGEN_DEVICE_FUNC Sizes(const DenseIndex, const DenseIndex, const DenseIndex) { + } + EIGEN_DEVICE_FUNC Sizes(const DenseIndex, const DenseIndex, const DenseIndex, const DenseIndex) { + } + EIGEN_DEVICE_FUNC Sizes(const DenseIndex, const DenseIndex, const DenseIndex, const DenseIndex, const DenseIndex) { + } +#endif + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex operator[] (const int index) const { + switch (index) { + case 0: + return internal::get<0, Base>::value; + case 1: + return internal::get<1, Base>::value; + case 2: + return internal::get<2, Base>::value; + case 3: + return internal::get<3, Base>::value; + case 4: + return internal::get<4, Base>::value; + default: + eigen_assert(false && "index overflow"); + return static_cast(-1); + } + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + size_t IndexOfColMajor(const array& indices) const { + return internal::fixed_size_tensor_index_linearization_helper::run(indices, *reinterpret_cast(this)); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + size_t IndexOfRowMajor(const array& indices) const { + return internal::fixed_size_tensor_index_linearization_helper::run(indices, *reinterpret_cast(this)); + } +}; + +namespace internal { +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::size_t array_prod(const Sizes&) { + return Sizes::total_size; +} +} + +#endif + +// Boilerplate +namespace internal { +template +struct tensor_index_linearization_helper +{ + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Index run(array const& indices, array const& dimensions) + { + return array_get(indices) + + array_get(dimensions) * + tensor_index_linearization_helper::run(indices, dimensions); + } +}; + +template +struct tensor_index_linearization_helper +{ + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Index run(array const& indices, array const&) + { + return array_get(indices); + } +}; +} // end namespace internal + + + +// Dynamic size +template +struct DSizes : array { + typedef array Base; + static const int count = NumDims; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE size_t rank() const { + return NumDims; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex TotalSize() const { + return (NumDims == 0) ? 1 : internal::array_prod(*static_cast(this)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DSizes() { + for (int i = 0 ; i < NumDims; ++i) { + (*this)[i] = 0; + } + } + EIGEN_DEVICE_FUNC explicit DSizes(const array& a) : Base(a) { } + + EIGEN_DEVICE_FUNC explicit DSizes(const DenseIndex i0) { + eigen_assert(NumDims == 1); + (*this)[0] = i0; + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE explicit DSizes(DenseIndex firstDimension, DenseIndex secondDimension, IndexTypes... otherDimensions) : Base({{firstDimension, secondDimension, otherDimensions...}}) { + EIGEN_STATIC_ASSERT(sizeof...(otherDimensions) + 2 == NumDims, YOU_MADE_A_PROGRAMMING_MISTAKE) + } +#else + EIGEN_DEVICE_FUNC DSizes(const DenseIndex i0, const DenseIndex i1) { + eigen_assert(NumDims == 2); + (*this)[0] = i0; + (*this)[1] = i1; + } + EIGEN_DEVICE_FUNC DSizes(const DenseIndex i0, const DenseIndex i1, const DenseIndex i2) { + eigen_assert(NumDims == 3); + (*this)[0] = i0; + (*this)[1] = i1; + (*this)[2] = i2; + } + EIGEN_DEVICE_FUNC DSizes(const DenseIndex i0, const DenseIndex i1, const DenseIndex i2, const DenseIndex i3) { + eigen_assert(NumDims == 4); + (*this)[0] = i0; + (*this)[1] = i1; + (*this)[2] = i2; + (*this)[3] = i3; + } + EIGEN_DEVICE_FUNC DSizes(const DenseIndex i0, const DenseIndex i1, const DenseIndex i2, const DenseIndex i3, const DenseIndex i4) { + eigen_assert(NumDims == 5); + (*this)[0] = i0; + (*this)[1] = i1; + (*this)[2] = i2; + (*this)[3] = i3; + (*this)[4] = i4; + } +#endif + + EIGEN_DEVICE_FUNC DSizes& operator = (const array& other) { + *static_cast(this) = other; + return *this; + } + + // A constexpr would be so much better here + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex IndexOfColMajor(const array& indices) const { + return internal::tensor_index_linearization_helper::run(indices, *static_cast(this)); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex IndexOfRowMajor(const array& indices) const { + return internal::tensor_index_linearization_helper::run(indices, *static_cast(this)); + } +}; + + + + +// Boilerplate +namespace internal { +template +struct tensor_vsize_index_linearization_helper +{ + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Index run(array const& indices, std::vector const& dimensions) + { + return array_get(indices) + + array_get(dimensions) * + tensor_vsize_index_linearization_helper::run(indices, dimensions); + } +}; + +template +struct tensor_vsize_index_linearization_helper +{ + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Index run(array const& indices, std::vector const&) + { + return array_get(indices); + } +}; +} // end namespace internal + + +namespace internal { + +template struct array_size > { + static const size_t value = NumDims; +}; +template struct array_size > { + static const size_t value = NumDims; +}; +#ifndef EIGEN_EMULATE_CXX11_META_H +template struct array_size > { +static const std::ptrdiff_t value = Sizes::count; +}; +template struct array_size > { +static const std::ptrdiff_t value = Sizes::count; +}; +template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t array_get(const Sizes&) { + return get >::value; +} +template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t array_get(const Sizes<>&) { + eigen_assert(false && "should never be called"); + return -1; +} +#else +template struct array_size > { + static const size_t value = Sizes::count; +}; +template struct array_size > { + static const size_t value = Sizes::count; +}; +template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::size_t array_get(const Sizes&) { + return get::Base>::value; +} + +#endif + + +template +struct sizes_match_below_dim { + static EIGEN_DEVICE_FUNC inline bool run(Dims1&, Dims2&) { + return false; + } +}; +template +struct sizes_match_below_dim { + static EIGEN_DEVICE_FUNC inline bool run(Dims1& dims1, Dims2& dims2) { + return (array_get(dims1) == array_get(dims2)) & + sizes_match_below_dim::run(dims1, dims2); + } +}; +template +struct sizes_match_below_dim { + static EIGEN_DEVICE_FUNC inline bool run(Dims1&, Dims2&) { + return true; + } +}; + +} // end namespace internal + + +template +EIGEN_DEVICE_FUNC bool dimensions_match(Dims1& dims1, Dims2& dims2) { + return internal::sizes_match_below_dim::value, internal::array_size::value>::run(dims1, dims2); +} + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_DIMENSIONS_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorEvalTo.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorEvalTo.h new file mode 100644 index 00000000..82dd1e64 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorEvalTo.h @@ -0,0 +1,184 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_EVAL_TO_H +#define EIGEN_CXX11_TENSOR_TENSOR_EVAL_TO_H + +namespace Eigen { + +/** \class TensorForcedEval + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor reshaping class. + * + * + */ +namespace internal { +template class MakePointer_> +struct traits > +{ + // Type promotion to handle the case where the types of the lhs and the rhs are different. + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; + + enum { + Flags = 0 + }; + template + struct MakePointer { + // Intermediate typedef to workaround MSVC issue. + typedef MakePointer_ MakePointerT; + typedef typename MakePointerT::Type Type; + typedef typename MakePointerT::RefType RefType; + + + }; +}; + +template class MakePointer_> +struct eval, Eigen::Dense> +{ + typedef const TensorEvalToOp& type; +}; + +template class MakePointer_> +struct nested, 1, typename eval >::type> +{ + typedef TensorEvalToOp type; +}; + +} // end namespace internal + + + + +template class MakePointer_> +class TensorEvalToOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename internal::remove_const::type CoeffReturnType; + typedef typename MakePointer_::Type PointerType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvalToOp(PointerType buffer, const XprType& expr) + : m_xpr(expr), m_buffer(buffer) {} + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + EIGEN_DEVICE_FUNC PointerType buffer() const { return m_buffer; } + + protected: + typename XprType::Nested m_xpr; + PointerType m_buffer; +}; + + + +template class MakePointer_> +struct TensorEvaluator, Device> +{ + typedef TensorEvalToOp XprType; + typedef typename ArgType::Scalar Scalar; + typedef typename TensorEvaluator::Dimensions Dimensions; + typedef typename XprType::Index Index; + typedef typename internal::remove_const::type CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = true + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device), m_device(device), + m_buffer(op.buffer()), m_op(op), m_expression(op.expression()) + { } + + // Used for accessor extraction in SYCL Managed TensorMap: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const XprType& op() const { + return m_op; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ~TensorEvaluator() { + } + + typedef typename internal::traits >::template MakePointer::Type DevicePointer; + EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_impl.dimensions(); } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(DevicePointer scalar) { + EIGEN_UNUSED_VARIABLE(scalar); + eigen_assert(scalar == NULL); + return m_impl.evalSubExprsIfNeeded(m_buffer); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalScalar(Index i) { + m_buffer[i] = m_impl.coeff(i); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalPacket(Index i) { + internal::pstoret(m_buffer + i, m_impl.template packet::IsAligned ? Aligned : Unaligned>(i)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + return m_buffer[index]; + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + return internal::ploadt(m_buffer + index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + // We assume that evalPacket or evalScalar is called to perform the + // assignment and account for the cost of the write here. + return m_impl.costPerCoeff(vectorized) + + TensorOpCost(0, sizeof(CoeffReturnType), 0, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC DevicePointer data() const { return m_buffer; } + ArgType expression() const { return m_expression; } + + /// required by sycl in order to extract the accessor + const TensorEvaluator& impl() const { return m_impl; } + /// added for sycl in order to construct the buffer from the sycl device + const Device& device() const{return m_device;} + + private: + TensorEvaluator m_impl; + const Device& m_device; + DevicePointer m_buffer; + const XprType& m_op; + const ArgType m_expression; +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_EVAL_TO_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorEvaluator.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorEvaluator.h new file mode 100644 index 00000000..d6415817 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorEvaluator.h @@ -0,0 +1,640 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_EVALUATOR_H +#define EIGEN_CXX11_TENSOR_TENSOR_EVALUATOR_H + +namespace Eigen { + +/** \class TensorEvaluator + * \ingroup CXX11_Tensor_Module + * + * \brief The tensor evaluator classes. + * + * These classes are responsible for the evaluation of the tensor expression. + * + * TODO: add support for more types of expressions, in particular expressions + * leading to lvalues (slicing, reshaping, etc...) + */ + +// Generic evaluator +template +struct TensorEvaluator +{ + typedef typename Derived::Index Index; + typedef typename Derived::Scalar Scalar; + typedef typename Derived::Scalar CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + typedef typename Derived::Dimensions Dimensions; + typedef Derived XprType; + + // NumDimensions is -1 for variable dim tensors + static const int NumCoords = internal::traits::NumDimensions > 0 ? + internal::traits::NumDimensions : 0; + + enum { + IsAligned = Derived::IsAligned, + PacketAccess = (internal::unpacket_traits::size > 1), + Layout = Derived::Layout, + CoordAccess = NumCoords > 0, + RawAccess = true + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const Derived& m, const Device& device) + : m_data(const_cast::template MakePointer::Type>(m.data())), m_dims(m.dimensions()), m_device(device), m_impl(m) + { } + + // Used for accessor extraction in SYCL Managed TensorMap: + const Derived& derived() const { return m_impl; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dims; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType* dest) { + if (dest) { + m_device.memcpy((void*)dest, m_data, sizeof(Scalar) * m_dims.TotalSize()); + return false; + } + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const { + eigen_assert(m_data); + return m_data[index]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + typename internal::traits::template MakePointer::RefType + coeffRef(Index index) { + eigen_assert(m_data); + return m_data[index]; + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + PacketReturnType packet(Index index) const + { + return internal::ploadt(m_data + index); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketReturnType& x) + { + return internal::pstoret(m_data + index, x); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(const array& coords) const { + eigen_assert(m_data); + if (static_cast(Layout) == static_cast(ColMajor)) { + return m_data[m_dims.IndexOfColMajor(coords)]; + } else { + return m_data[m_dims.IndexOfRowMajor(coords)]; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + typename internal::traits::template MakePointer::RefType + coeffRef(const array& coords) { + eigen_assert(m_data); + if (static_cast(Layout) == static_cast(ColMajor)) { + return m_data[m_dims.IndexOfColMajor(coords)]; + } else { + return m_data[m_dims.IndexOfRowMajor(coords)]; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, + internal::unpacket_traits::size); + } + + EIGEN_DEVICE_FUNC typename internal::traits::template MakePointer::Type data() const { return m_data; } + + /// required by sycl in order to construct sycl buffer from raw pointer + const Device& device() const{return m_device;} + + protected: + typename internal::traits::template MakePointer::Type m_data; + Dimensions m_dims; + const Device& m_device; + const Derived& m_impl; +}; + +namespace { +template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T loadConstant(const T* address) { + return *address; +} +// Use the texture cache on CUDA devices whenever possible +#if defined(__CUDA_ARCH__) && __CUDA_ARCH__ >= 350 +template <> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float loadConstant(const float* address) { + return __ldg(address); +} +template <> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double loadConstant(const double* address) { + return __ldg(address); +} +template <> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +Eigen::half loadConstant(const Eigen::half* address) { + return Eigen::half(half_impl::raw_uint16_to_half(__ldg(&address->x))); +} +#endif +} + + +// Default evaluator for rvalues +template +struct TensorEvaluator +{ + typedef typename Derived::Index Index; + typedef typename Derived::Scalar Scalar; + typedef typename Derived::Scalar CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + typedef typename Derived::Dimensions Dimensions; + typedef const Derived XprType; + + + // NumDimensions is -1 for variable dim tensors + static const int NumCoords = internal::traits::NumDimensions > 0 ? + internal::traits::NumDimensions : 0; + + enum { + IsAligned = Derived::IsAligned, + PacketAccess = (internal::unpacket_traits::size > 1), + Layout = Derived::Layout, + CoordAccess = NumCoords > 0, + RawAccess = true + }; + + // Used for accessor extraction in SYCL Managed TensorMap: + const Derived& derived() const { return m_impl; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const Derived& m, const Device& device) + : m_data(m.data()), m_dims(m.dimensions()), m_device(device), m_impl(m) + { } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dims; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType* data) { + if (!NumTraits::type>::RequireInitialization && data) { + m_device.memcpy((void*)data, m_data, m_dims.TotalSize() * sizeof(Scalar)); + return false; + } + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const { + eigen_assert(m_data); + return loadConstant(m_data+index); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + PacketReturnType packet(Index index) const + { + return internal::ploadt_ro(m_data + index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(const array& coords) const { + eigen_assert(m_data); + const Index index = (static_cast(Layout) == static_cast(ColMajor)) ? m_dims.IndexOfColMajor(coords) + : m_dims.IndexOfRowMajor(coords); + return loadConstant(m_data+index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, + internal::unpacket_traits::size); + } + + EIGEN_DEVICE_FUNC typename internal::traits::template MakePointer::Type data() const { return m_data; } + + /// added for sycl in order to construct the buffer from the sycl device + const Device& device() const{return m_device;} + + protected: + typename internal::traits::template MakePointer::Type m_data; + Dimensions m_dims; + const Device& m_device; + const Derived& m_impl; +}; + + + + +// -------------------- CwiseNullaryOp -------------------- + +template +struct TensorEvaluator, Device> +{ + typedef TensorCwiseNullaryOp XprType; + + enum { + IsAligned = true, + PacketAccess = internal::functor_traits::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC + TensorEvaluator(const XprType& op, const Device& device) + : m_functor(op.functor()), m_argImpl(op.nestedExpression(), device), m_wrapper() + { } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename internal::traits::Scalar CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + typedef typename TensorEvaluator::Dimensions Dimensions; + + EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_argImpl.dimensions(); } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType*) { return true; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { } + + EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const + { + return m_wrapper(m_functor, index); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + return m_wrapper.template packetOp(m_functor, index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, + internal::unpacket_traits::size); + } + + EIGEN_DEVICE_FUNC CoeffReturnType* data() const { return NULL; } + + /// required by sycl in order to extract the accessor + const TensorEvaluator& impl() const { return m_argImpl; } + /// required by sycl in order to extract the accessor + NullaryOp functor() const { return m_functor; } + + + private: + const NullaryOp m_functor; + TensorEvaluator m_argImpl; + const internal::nullary_wrapper m_wrapper; +}; + + + +// -------------------- CwiseUnaryOp -------------------- + +template +struct TensorEvaluator, Device> +{ + typedef TensorCwiseUnaryOp XprType; + + enum { + IsAligned = TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess & internal::functor_traits::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device) + : m_functor(op.functor()), + m_argImpl(op.nestedExpression(), device) + { } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename internal::traits::Scalar CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + typedef typename TensorEvaluator::Dimensions Dimensions; + + EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_argImpl.dimensions(); } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar*) { + m_argImpl.evalSubExprsIfNeeded(NULL); + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_argImpl.cleanup(); + } + + EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const + { + return m_functor(m_argImpl.coeff(index)); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + return m_functor.packetOp(m_argImpl.template packet(index)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + const double functor_cost = internal::functor_traits::Cost; + return m_argImpl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, functor_cost, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC CoeffReturnType* data() const { return NULL; } + + /// required by sycl in order to extract the accessor + const TensorEvaluator & impl() const { return m_argImpl; } + /// added for sycl in order to construct the buffer from sycl device + UnaryOp functor() const { return m_functor; } + + + private: + const UnaryOp m_functor; + TensorEvaluator m_argImpl; +}; + + +// -------------------- CwiseBinaryOp -------------------- + +template +struct TensorEvaluator, Device> +{ + typedef TensorCwiseBinaryOp XprType; + + enum { + IsAligned = TensorEvaluator::IsAligned & TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess & TensorEvaluator::PacketAccess & + internal::functor_traits::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device) + : m_functor(op.functor()), + m_leftImpl(op.lhsExpression(), device), + m_rightImpl(op.rhsExpression(), device) + { + EIGEN_STATIC_ASSERT((static_cast(TensorEvaluator::Layout) == static_cast(TensorEvaluator::Layout) || internal::traits::NumDimensions <= 1), YOU_MADE_A_PROGRAMMING_MISTAKE); + eigen_assert(dimensions_match(m_leftImpl.dimensions(), m_rightImpl.dimensions())); + } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename internal::traits::Scalar CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + typedef typename TensorEvaluator::Dimensions Dimensions; + + EIGEN_DEVICE_FUNC const Dimensions& dimensions() const + { + // TODO: use right impl instead if right impl dimensions are known at compile time. + return m_leftImpl.dimensions(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType*) { + m_leftImpl.evalSubExprsIfNeeded(NULL); + m_rightImpl.evalSubExprsIfNeeded(NULL); + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_leftImpl.cleanup(); + m_rightImpl.cleanup(); + } + + EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const + { + return m_functor(m_leftImpl.coeff(index), m_rightImpl.coeff(index)); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + return m_functor.packetOp(m_leftImpl.template packet(index), m_rightImpl.template packet(index)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + const double functor_cost = internal::functor_traits::Cost; + return m_leftImpl.costPerCoeff(vectorized) + + m_rightImpl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, functor_cost, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC CoeffReturnType* data() const { return NULL; } + /// required by sycl in order to extract the accessor + const TensorEvaluator& left_impl() const { return m_leftImpl; } + /// required by sycl in order to extract the accessor + const TensorEvaluator& right_impl() const { return m_rightImpl; } + /// required by sycl in order to extract the accessor + BinaryOp functor() const { return m_functor; } + + private: + const BinaryOp m_functor; + TensorEvaluator m_leftImpl; + TensorEvaluator m_rightImpl; +}; + +// -------------------- CwiseTernaryOp -------------------- + +template +struct TensorEvaluator, Device> +{ + typedef TensorCwiseTernaryOp XprType; + + enum { + IsAligned = TensorEvaluator::IsAligned & TensorEvaluator::IsAligned & TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess & TensorEvaluator::PacketAccess & TensorEvaluator::PacketAccess & + internal::functor_traits::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device) + : m_functor(op.functor()), + m_arg1Impl(op.arg1Expression(), device), + m_arg2Impl(op.arg2Expression(), device), + m_arg3Impl(op.arg3Expression(), device) + { + EIGEN_STATIC_ASSERT((static_cast(TensorEvaluator::Layout) == static_cast(TensorEvaluator::Layout) || internal::traits::NumDimensions <= 1), YOU_MADE_A_PROGRAMMING_MISTAKE); + + EIGEN_STATIC_ASSERT((internal::is_same::StorageKind, + typename internal::traits::StorageKind>::value), + STORAGE_KIND_MUST_MATCH) + EIGEN_STATIC_ASSERT((internal::is_same::StorageKind, + typename internal::traits::StorageKind>::value), + STORAGE_KIND_MUST_MATCH) + EIGEN_STATIC_ASSERT((internal::is_same::Index, + typename internal::traits::Index>::value), + STORAGE_INDEX_MUST_MATCH) + EIGEN_STATIC_ASSERT((internal::is_same::Index, + typename internal::traits::Index>::value), + STORAGE_INDEX_MUST_MATCH) + + eigen_assert(dimensions_match(m_arg1Impl.dimensions(), m_arg2Impl.dimensions()) && dimensions_match(m_arg1Impl.dimensions(), m_arg3Impl.dimensions())); + } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename internal::traits::Scalar CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + typedef typename TensorEvaluator::Dimensions Dimensions; + + EIGEN_DEVICE_FUNC const Dimensions& dimensions() const + { + // TODO: use arg2 or arg3 dimensions if they are known at compile time. + return m_arg1Impl.dimensions(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType*) { + m_arg1Impl.evalSubExprsIfNeeded(NULL); + m_arg2Impl.evalSubExprsIfNeeded(NULL); + m_arg3Impl.evalSubExprsIfNeeded(NULL); + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_arg1Impl.cleanup(); + m_arg2Impl.cleanup(); + m_arg3Impl.cleanup(); + } + + EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const + { + return m_functor(m_arg1Impl.coeff(index), m_arg2Impl.coeff(index), m_arg3Impl.coeff(index)); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + return m_functor.packetOp(m_arg1Impl.template packet(index), + m_arg2Impl.template packet(index), + m_arg3Impl.template packet(index)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + const double functor_cost = internal::functor_traits::Cost; + return m_arg1Impl.costPerCoeff(vectorized) + + m_arg2Impl.costPerCoeff(vectorized) + + m_arg3Impl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, functor_cost, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC CoeffReturnType* data() const { return NULL; } + + /// required by sycl in order to extract the accessor + const TensorEvaluator & arg1Impl() const { return m_arg1Impl; } + /// required by sycl in order to extract the accessor + const TensorEvaluator& arg2Impl() const { return m_arg2Impl; } + /// required by sycl in order to extract the accessor + const TensorEvaluator& arg3Impl() const { return m_arg3Impl; } + + private: + const TernaryOp m_functor; + TensorEvaluator m_arg1Impl; + TensorEvaluator m_arg2Impl; + TensorEvaluator m_arg3Impl; +}; + + +// -------------------- SelectOp -------------------- + +template +struct TensorEvaluator, Device> +{ + typedef TensorSelectOp XprType; + typedef typename XprType::Scalar Scalar; + + enum { + IsAligned = TensorEvaluator::IsAligned & TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess & TensorEvaluator::PacketAccess & + internal::packet_traits::HasBlend, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device) + : m_condImpl(op.ifExpression(), device), + m_thenImpl(op.thenExpression(), device), + m_elseImpl(op.elseExpression(), device) + { + EIGEN_STATIC_ASSERT((static_cast(TensorEvaluator::Layout) == static_cast(TensorEvaluator::Layout)), YOU_MADE_A_PROGRAMMING_MISTAKE); + EIGEN_STATIC_ASSERT((static_cast(TensorEvaluator::Layout) == static_cast(TensorEvaluator::Layout)), YOU_MADE_A_PROGRAMMING_MISTAKE); + eigen_assert(dimensions_match(m_condImpl.dimensions(), m_thenImpl.dimensions())); + eigen_assert(dimensions_match(m_thenImpl.dimensions(), m_elseImpl.dimensions())); + } + + typedef typename XprType::Index Index; + typedef typename internal::traits::Scalar CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + typedef typename TensorEvaluator::Dimensions Dimensions; + + EIGEN_DEVICE_FUNC const Dimensions& dimensions() const + { + // TODO: use then or else impl instead if they happen to be known at compile time. + return m_condImpl.dimensions(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType*) { + m_condImpl.evalSubExprsIfNeeded(NULL); + m_thenImpl.evalSubExprsIfNeeded(NULL); + m_elseImpl.evalSubExprsIfNeeded(NULL); + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_condImpl.cleanup(); + m_thenImpl.cleanup(); + m_elseImpl.cleanup(); + } + + EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const + { + return m_condImpl.coeff(index) ? m_thenImpl.coeff(index) : m_elseImpl.coeff(index); + } + template + EIGEN_DEVICE_FUNC PacketReturnType packet(Index index) const + { + internal::Selector select; + for (Index i = 0; i < PacketSize; ++i) { + select.select[i] = m_condImpl.coeff(index+i); + } + return internal::pblend(select, + m_thenImpl.template packet(index), + m_elseImpl.template packet(index)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + return m_condImpl.costPerCoeff(vectorized) + + m_thenImpl.costPerCoeff(vectorized) + .cwiseMax(m_elseImpl.costPerCoeff(vectorized)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType* data() const { return NULL; } + /// required by sycl in order to extract the accessor + const TensorEvaluator & cond_impl() const { return m_condImpl; } + /// required by sycl in order to extract the accessor + const TensorEvaluator& then_impl() const { return m_thenImpl; } + /// required by sycl in order to extract the accessor + const TensorEvaluator& else_impl() const { return m_elseImpl; } + + private: + TensorEvaluator m_condImpl; + TensorEvaluator m_thenImpl; + TensorEvaluator m_elseImpl; +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_EVALUATOR_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorExecutor.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorExecutor.h new file mode 100644 index 00000000..f01d77c0 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorExecutor.h @@ -0,0 +1,288 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_EXECUTOR_H +#define EIGEN_CXX11_TENSOR_TENSOR_EXECUTOR_H + +namespace Eigen { + +/** \class TensorExecutor + * \ingroup CXX11_Tensor_Module + * + * \brief The tensor executor class. + * + * This class is responsible for launch the evaluation of the expression on + * the specified computing device. + */ +namespace internal { + +// Default strategy: the expression is evaluated with a single cpu thread. +template +class TensorExecutor +{ + public: + typedef typename Expression::Index Index; + EIGEN_DEVICE_FUNC + static inline void run(const Expression& expr, const Device& device = Device()) + { + TensorEvaluator evaluator(expr, device); + const bool needs_assign = evaluator.evalSubExprsIfNeeded(NULL); + if (needs_assign) + { + const Index size = array_prod(evaluator.dimensions()); + for (Index i = 0; i < size; ++i) { + evaluator.evalScalar(i); + } + } + evaluator.cleanup(); + } +}; + + +template +class TensorExecutor +{ + public: + typedef typename Expression::Index Index; + EIGEN_DEVICE_FUNC + static inline void run(const Expression& expr, const DefaultDevice& device = DefaultDevice()) + { + TensorEvaluator evaluator(expr, device); + const bool needs_assign = evaluator.evalSubExprsIfNeeded(NULL); + if (needs_assign) + { + const Index size = array_prod(evaluator.dimensions()); + const int PacketSize = unpacket_traits::PacketReturnType>::size; + // Give the compiler a strong hint to unroll the loop. But don't insist + // on unrolling, because if the function is expensive the compiler should not + // unroll the loop at the expense of inlining. + const Index UnrolledSize = (size / (4 * PacketSize)) * 4 * PacketSize; + for (Index i = 0; i < UnrolledSize; i += 4*PacketSize) { + for (Index j = 0; j < 4; j++) { + evaluator.evalPacket(i + j * PacketSize); + } + } + const Index VectorizedSize = (size / PacketSize) * PacketSize; + for (Index i = UnrolledSize; i < VectorizedSize; i += PacketSize) { + evaluator.evalPacket(i); + } + for (Index i = VectorizedSize; i < size; ++i) { + evaluator.evalScalar(i); + } + } + evaluator.cleanup(); + } +}; + + + +// Multicore strategy: the index space is partitioned and each partition is executed on a single core +#ifdef EIGEN_USE_THREADS +template +struct EvalRange { + static void run(Evaluator* evaluator_in, const Index first, const Index last) { + Evaluator evaluator = *evaluator_in; + eigen_assert(last >= first); + for (Index i = first; i < last; ++i) { + evaluator.evalScalar(i); + } + } + + static Index alignBlockSize(Index size) { + return size; + } +}; + +template +struct EvalRange { + static const int PacketSize = unpacket_traits::size; + + static void run(Evaluator* evaluator_in, const Index first, const Index last) { + Evaluator evaluator = *evaluator_in; + eigen_assert(last >= first); + Index i = first; + if (last - first >= PacketSize) { + eigen_assert(first % PacketSize == 0); + Index last_chunk_offset = last - 4 * PacketSize; + // Give the compiler a strong hint to unroll the loop. But don't insist + // on unrolling, because if the function is expensive the compiler should not + // unroll the loop at the expense of inlining. + for (; i <= last_chunk_offset; i += 4*PacketSize) { + for (Index j = 0; j < 4; j++) { + evaluator.evalPacket(i + j * PacketSize); + } + } + last_chunk_offset = last - PacketSize; + for (; i <= last_chunk_offset; i += PacketSize) { + evaluator.evalPacket(i); + } + } + for (; i < last; ++i) { + evaluator.evalScalar(i); + } + } + + static Index alignBlockSize(Index size) { + // Align block size to packet size and account for unrolling in run above. + if (size >= 16 * PacketSize) { + return (size + 4 * PacketSize - 1) & ~(4 * PacketSize - 1); + } + // Aligning to 4 * PacketSize would increase block size by more than 25%. + return (size + PacketSize - 1) & ~(PacketSize - 1); + } +}; + +template +class TensorExecutor { + public: + typedef typename Expression::Index Index; + static inline void run(const Expression& expr, const ThreadPoolDevice& device) + { + typedef TensorEvaluator Evaluator; + Evaluator evaluator(expr, device); + const bool needs_assign = evaluator.evalSubExprsIfNeeded(NULL); + if (needs_assign) + { + const Index size = array_prod(evaluator.dimensions()); +#if !defined(EIGEN_USE_SIMPLE_THREAD_POOL) + device.parallelFor(size, evaluator.costPerCoeff(Vectorizable), + EvalRange::alignBlockSize, + [&evaluator](Index first, Index last) { + EvalRange::run(&evaluator, first, last); + }); +#else + size_t num_threads = device.numThreads(); + if (num_threads > 1) { + num_threads = TensorCostModel::numThreads( + size, evaluator.costPerCoeff(Vectorizable), num_threads); + } + if (num_threads == 1) { + EvalRange::run(&evaluator, 0, size); + } else { + const Index PacketSize = Vectorizable ? unpacket_traits::size : 1; + Index blocksz = std::ceil(static_cast(size)/num_threads) + PacketSize - 1; + const Index blocksize = numext::maxi(PacketSize, (blocksz - (blocksz % PacketSize))); + const Index numblocks = size / blocksize; + + Barrier barrier(numblocks); + for (int i = 0; i < numblocks; ++i) { + device.enqueue_with_barrier( + &barrier, &EvalRange::run, + &evaluator, i * blocksize, (i + 1) * blocksize); + } + if (numblocks * blocksize < size) { + EvalRange::run( + &evaluator, numblocks * blocksize, size); + } + barrier.Wait(); + } +#endif // defined(!EIGEN_USE_SIMPLE_THREAD_POOL) + } + evaluator.cleanup(); + } +}; +#endif // EIGEN_USE_THREADS + + +// GPU: the evaluation of the expression is offloaded to a GPU. +#if defined(EIGEN_USE_GPU) + +template +class TensorExecutor { + public: + typedef typename Expression::Index Index; + static void run(const Expression& expr, const GpuDevice& device); +}; + + +#if defined(__CUDACC__) +template +struct EigenMetaKernelEval { + static __device__ EIGEN_ALWAYS_INLINE + void run(Evaluator& eval, Index first, Index last, Index step_size) { + for (Index i = first; i < last; i += step_size) { + eval.evalScalar(i); + } + } +}; + +template +struct EigenMetaKernelEval { + static __device__ EIGEN_ALWAYS_INLINE + void run(Evaluator& eval, Index first, Index last, Index step_size) { + const Index PacketSize = unpacket_traits::size; + const Index vectorized_size = (last / PacketSize) * PacketSize; + const Index vectorized_step_size = step_size * PacketSize; + + // Use the vector path + for (Index i = first * PacketSize; i < vectorized_size; + i += vectorized_step_size) { + eval.evalPacket(i); + } + for (Index i = vectorized_size + first; i < last; i += step_size) { + eval.evalScalar(i); + } + } +}; + +template +__global__ void +__launch_bounds__(1024) +EigenMetaKernel(Evaluator eval, Index size) { + + const Index first_index = blockIdx.x * blockDim.x + threadIdx.x; + const Index step_size = blockDim.x * gridDim.x; + + const bool vectorizable = Evaluator::PacketAccess & Evaluator::IsAligned; + EigenMetaKernelEval::run(eval, first_index, size, step_size); +} + +/*static*/ +template +inline void TensorExecutor::run( + const Expression& expr, const GpuDevice& device) { + TensorEvaluator evaluator(expr, device); + const bool needs_assign = evaluator.evalSubExprsIfNeeded(NULL); + if (needs_assign) { + const int block_size = device.maxCudaThreadsPerBlock(); + const int max_blocks = device.getNumCudaMultiProcessors() * + device.maxCudaThreadsPerMultiProcessor() / block_size; + const Index size = array_prod(evaluator.dimensions()); + // Create a least one block to ensure we won't crash when tensorflow calls with tensors of size 0. + const int num_blocks = numext::maxi(numext::mini(max_blocks, divup(size, block_size)), 1); + + LAUNCH_CUDA_KERNEL( + (EigenMetaKernel, Index>), + num_blocks, block_size, 0, device, evaluator, size); + } + evaluator.cleanup(); +} + +#endif // __CUDACC__ +#endif // EIGEN_USE_GPU + +// SYCL Executor policy +#ifdef EIGEN_USE_SYCL + +template +class TensorExecutor { +public: + static inline void run(const Expression &expr, const SyclDevice &device) { + // call TensorSYCL module + TensorSycl::run(expr, device); + } +}; + +#endif + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_EXECUTOR_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorExpr.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorExpr.h new file mode 100644 index 00000000..85dfc7a6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorExpr.h @@ -0,0 +1,371 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_EXPR_H +#define EIGEN_CXX11_TENSOR_TENSOR_EXPR_H + +namespace Eigen { + +/** \class TensorExpr + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor expression classes. + * + * The TensorCwiseNullaryOp class applies a nullary operators to an expression. + * This is typically used to generate constants. + * + * The TensorCwiseUnaryOp class represents an expression where a unary operator + * (e.g. cwiseSqrt) is applied to an expression. + * + * The TensorCwiseBinaryOp class represents an expression where a binary + * operator (e.g. addition) is applied to a lhs and a rhs expression. + * + */ +namespace internal { +template +struct traits > + : traits +{ + typedef traits XprTraits; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::Nested XprTypeNested; + typedef typename remove_reference::type _XprTypeNested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; + + enum { + Flags = 0 + }; +}; + +} // end namespace internal + + + +template +class TensorCwiseNullaryOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef TensorCwiseNullaryOp Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCwiseNullaryOp(const XprType& xpr, const NullaryOp& func = NullaryOp()) + : m_xpr(xpr), m_functor(func) {} + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + nestedExpression() const { return m_xpr; } + + EIGEN_DEVICE_FUNC + const NullaryOp& functor() const { return m_functor; } + + protected: + typename XprType::Nested m_xpr; + const NullaryOp m_functor; +}; + + + +namespace internal { +template +struct traits > + : traits +{ + // TODO(phli): Add InputScalar, InputPacket. Check references to + // current Scalar/Packet to see if the intent is Input or Output. + typedef typename result_of::type Scalar; + typedef traits XprTraits; + typedef typename XprType::Nested XprTypeNested; + typedef typename remove_reference::type _XprTypeNested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorCwiseUnaryOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorCwiseUnaryOp type; +}; + +} // end namespace internal + + + +template +class TensorCwiseUnaryOp : public TensorBase, ReadOnlyAccessors> +{ + public: + // TODO(phli): Add InputScalar, InputPacket. Check references to + // current Scalar/Packet to see if the intent is Input or Output. + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef Scalar CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCwiseUnaryOp(const XprType& xpr, const UnaryOp& func = UnaryOp()) + : m_xpr(xpr), m_functor(func) {} + + EIGEN_DEVICE_FUNC + const UnaryOp& functor() const { return m_functor; } + + /** \returns the nested expression */ + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + nestedExpression() const { return m_xpr; } + + protected: + typename XprType::Nested m_xpr; + const UnaryOp m_functor; +}; + + +namespace internal { +template +struct traits > +{ + // Type promotion to handle the case where the types of the lhs and the rhs + // are different. + // TODO(phli): Add Lhs/RhsScalar, Lhs/RhsPacket. Check references to + // current Scalar/Packet to see if the intent is Inputs or Output. + typedef typename result_of< + BinaryOp(typename LhsXprType::Scalar, + typename RhsXprType::Scalar)>::type Scalar; + typedef traits XprTraits; + typedef typename promote_storage_type< + typename traits::StorageKind, + typename traits::StorageKind>::ret StorageKind; + typedef typename promote_index_type< + typename traits::Index, + typename traits::Index>::type Index; + typedef typename LhsXprType::Nested LhsNested; + typedef typename RhsXprType::Nested RhsNested; + typedef typename remove_reference::type _LhsNested; + typedef typename remove_reference::type _RhsNested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; + + enum { + Flags = 0 + }; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorCwiseBinaryOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorCwiseBinaryOp type; +}; + +} // end namespace internal + + + +template +class TensorCwiseBinaryOp : public TensorBase, ReadOnlyAccessors> +{ + public: + // TODO(phli): Add Lhs/RhsScalar, Lhs/RhsPacket. Check references to + // current Scalar/Packet to see if the intent is Inputs or Output. + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef Scalar CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCwiseBinaryOp(const LhsXprType& lhs, const RhsXprType& rhs, const BinaryOp& func = BinaryOp()) + : m_lhs_xpr(lhs), m_rhs_xpr(rhs), m_functor(func) {} + + EIGEN_DEVICE_FUNC + const BinaryOp& functor() const { return m_functor; } + + /** \returns the nested expressions */ + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + lhsExpression() const { return m_lhs_xpr; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + rhsExpression() const { return m_rhs_xpr; } + + protected: + typename LhsXprType::Nested m_lhs_xpr; + typename RhsXprType::Nested m_rhs_xpr; + const BinaryOp m_functor; +}; + + +namespace internal { +template +struct traits > +{ + // Type promotion to handle the case where the types of the args are different. + typedef typename result_of< + TernaryOp(typename Arg1XprType::Scalar, + typename Arg2XprType::Scalar, + typename Arg3XprType::Scalar)>::type Scalar; + typedef traits XprTraits; + typedef typename traits::StorageKind StorageKind; + typedef typename traits::Index Index; + typedef typename Arg1XprType::Nested Arg1Nested; + typedef typename Arg2XprType::Nested Arg2Nested; + typedef typename Arg3XprType::Nested Arg3Nested; + typedef typename remove_reference::type _Arg1Nested; + typedef typename remove_reference::type _Arg2Nested; + typedef typename remove_reference::type _Arg3Nested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; + + enum { + Flags = 0 + }; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorCwiseTernaryOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorCwiseTernaryOp type; +}; + +} // end namespace internal + + + +template +class TensorCwiseTernaryOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef Scalar CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCwiseTernaryOp(const Arg1XprType& arg1, const Arg2XprType& arg2, const Arg3XprType& arg3, const TernaryOp& func = TernaryOp()) + : m_arg1_xpr(arg1), m_arg2_xpr(arg2), m_arg3_xpr(arg3), m_functor(func) {} + + EIGEN_DEVICE_FUNC + const TernaryOp& functor() const { return m_functor; } + + /** \returns the nested expressions */ + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + arg1Expression() const { return m_arg1_xpr; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + arg2Expression() const { return m_arg2_xpr; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + arg3Expression() const { return m_arg3_xpr; } + + protected: + typename Arg1XprType::Nested m_arg1_xpr; + typename Arg2XprType::Nested m_arg2_xpr; + typename Arg3XprType::Nested m_arg3_xpr; + const TernaryOp m_functor; +}; + + +namespace internal { +template +struct traits > + : traits +{ + typedef typename traits::Scalar Scalar; + typedef traits XprTraits; + typedef typename promote_storage_type::StorageKind, + typename traits::StorageKind>::ret StorageKind; + typedef typename promote_index_type::Index, + typename traits::Index>::type Index; + typedef typename IfXprType::Nested IfNested; + typedef typename ThenXprType::Nested ThenNested; + typedef typename ElseXprType::Nested ElseNested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorSelectOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorSelectOp type; +}; + +} // end namespace internal + + +template +class TensorSelectOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename internal::promote_storage_type::ret CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC + TensorSelectOp(const IfXprType& a_condition, + const ThenXprType& a_then, + const ElseXprType& a_else) + : m_condition(a_condition), m_then(a_then), m_else(a_else) + { } + + EIGEN_DEVICE_FUNC + const IfXprType& ifExpression() const { return m_condition; } + + EIGEN_DEVICE_FUNC + const ThenXprType& thenExpression() const { return m_then; } + + EIGEN_DEVICE_FUNC + const ElseXprType& elseExpression() const { return m_else; } + + protected: + typename IfXprType::Nested m_condition; + typename ThenXprType::Nested m_then; + typename ElseXprType::Nested m_else; +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_EXPR_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFFT.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFFT.h new file mode 100644 index 00000000..f060191a --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFFT.h @@ -0,0 +1,651 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Jianwei Cui +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_FFT_H +#define EIGEN_CXX11_TENSOR_TENSOR_FFT_H + +// This code requires the ability to initialize arrays of constant +// values directly inside a class. +#if __cplusplus >= 201103L || EIGEN_COMP_MSVC >= 1900 + +namespace Eigen { + +/** \class TensorFFT + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor FFT class. + * + * TODO: + * Vectorize the Cooley Tukey and the Bluestein algorithm + * Add support for multithreaded evaluation + * Improve the performance on GPU + */ + +template struct MakeComplex { + template + EIGEN_DEVICE_FUNC + T operator() (const T& val) const { return val; } +}; + +template <> struct MakeComplex { + template + EIGEN_DEVICE_FUNC + std::complex operator() (const T& val) const { return std::complex(val, 0); } +}; + +template <> struct MakeComplex { + template + EIGEN_DEVICE_FUNC + std::complex operator() (const std::complex& val) const { return val; } +}; + +template struct PartOf { + template T operator() (const T& val) const { return val; } +}; + +template <> struct PartOf { + template T operator() (const std::complex& val) const { return val.real(); } +}; + +template <> struct PartOf { + template T operator() (const std::complex& val) const { return val.imag(); } +}; + +namespace internal { +template +struct traits > : public traits { + typedef traits XprTraits; + typedef typename NumTraits::Real RealScalar; + typedef typename std::complex ComplexScalar; + typedef typename XprTraits::Scalar InputScalar; + typedef typename conditional::type OutputScalar; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> { + typedef const TensorFFTOp& type; +}; + +template +struct nested, 1, typename eval >::type> { + typedef TensorFFTOp type; +}; + +} // end namespace internal + +template +class TensorFFTOp : public TensorBase, ReadOnlyAccessors> { + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename std::complex ComplexScalar; + typedef typename internal::conditional::type OutputScalar; + typedef OutputScalar CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorFFTOp(const XprType& expr, const FFT& fft) + : m_xpr(expr), m_fft(fft) {} + + EIGEN_DEVICE_FUNC + const FFT& fft() const { return m_fft; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& expression() const { + return m_xpr; + } + + protected: + typename XprType::Nested m_xpr; + const FFT m_fft; +}; + +// Eval as rvalue +template +struct TensorEvaluator, Device> { + typedef TensorFFTOp XprType; + typedef typename XprType::Index Index; + static const int NumDims = internal::array_size::Dimensions>::value; + typedef DSizes Dimensions; + typedef typename XprType::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename std::complex ComplexScalar; + typedef typename TensorEvaluator::Dimensions InputDimensions; + typedef internal::traits XprTraits; + typedef typename XprTraits::Scalar InputScalar; + typedef typename internal::conditional::type OutputScalar; + typedef OutputScalar CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = false, + PacketAccess = true, + BlockAccess = false, + Layout = TensorEvaluator::Layout, + CoordAccess = false, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) : m_fft(op.fft()), m_impl(op.expression(), device), m_data(NULL), m_device(device) { + const typename TensorEvaluator::Dimensions& input_dims = m_impl.dimensions(); + for (int i = 0; i < NumDims; ++i) { + eigen_assert(input_dims[i] > 0); + m_dimensions[i] = input_dims[i]; + } + + if (static_cast(Layout) == static_cast(ColMajor)) { + m_strides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_strides[i] = m_strides[i - 1] * m_dimensions[i - 1]; + } + } else { + m_strides[NumDims - 1] = 1; + for (int i = NumDims - 2; i >= 0; --i) { + m_strides[i] = m_strides[i + 1] * m_dimensions[i + 1]; + } + } + m_size = m_dimensions.TotalSize(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { + return m_dimensions; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(OutputScalar* data) { + m_impl.evalSubExprsIfNeeded(NULL); + if (data) { + evalToBuf(data); + return false; + } else { + m_data = (CoeffReturnType*)m_device.allocate(sizeof(CoeffReturnType) * m_size); + evalToBuf(m_data); + return true; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + if (m_data) { + m_device.deallocate(m_data); + m_data = NULL; + } + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE CoeffReturnType coeff(Index index) const { + return m_data[index]; + } + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketReturnType + packet(Index index) const { + return internal::ploadt(m_data + index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return m_data; } + + + private: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalToBuf(OutputScalar* data) { + const bool write_to_out = internal::is_same::value; + ComplexScalar* buf = write_to_out ? (ComplexScalar*)data : (ComplexScalar*)m_device.allocate(sizeof(ComplexScalar) * m_size); + + for (Index i = 0; i < m_size; ++i) { + buf[i] = MakeComplex::value>()(m_impl.coeff(i)); + } + + for (size_t i = 0; i < m_fft.size(); ++i) { + Index dim = m_fft[i]; + eigen_assert(dim >= 0 && dim < NumDims); + Index line_len = m_dimensions[dim]; + eigen_assert(line_len >= 1); + ComplexScalar* line_buf = (ComplexScalar*)m_device.allocate(sizeof(ComplexScalar) * line_len); + const bool is_power_of_two = isPowerOfTwo(line_len); + const Index good_composite = is_power_of_two ? 0 : findGoodComposite(line_len); + const Index log_len = is_power_of_two ? getLog2(line_len) : getLog2(good_composite); + + ComplexScalar* a = is_power_of_two ? NULL : (ComplexScalar*)m_device.allocate(sizeof(ComplexScalar) * good_composite); + ComplexScalar* b = is_power_of_two ? NULL : (ComplexScalar*)m_device.allocate(sizeof(ComplexScalar) * good_composite); + ComplexScalar* pos_j_base_powered = is_power_of_two ? NULL : (ComplexScalar*)m_device.allocate(sizeof(ComplexScalar) * (line_len + 1)); + if (!is_power_of_two) { + // Compute twiddle factors + // t_n = exp(sqrt(-1) * pi * n^2 / line_len) + // for n = 0, 1,..., line_len-1. + // For n > 2 we use the recurrence t_n = t_{n-1}^2 / t_{n-2} * t_1^2 + pos_j_base_powered[0] = ComplexScalar(1, 0); + if (line_len > 1) { + const RealScalar pi_over_len(EIGEN_PI / line_len); + const ComplexScalar pos_j_base = ComplexScalar( + std::cos(pi_over_len), std::sin(pi_over_len)); + pos_j_base_powered[1] = pos_j_base; + if (line_len > 2) { + const ComplexScalar pos_j_base_sq = pos_j_base * pos_j_base; + for (int j = 2; j < line_len + 1; ++j) { + pos_j_base_powered[j] = pos_j_base_powered[j - 1] * + pos_j_base_powered[j - 1] / + pos_j_base_powered[j - 2] * pos_j_base_sq; + } + } + } + } + + for (Index partial_index = 0; partial_index < m_size / line_len; ++partial_index) { + const Index base_offset = getBaseOffsetFromIndex(partial_index, dim); + + // get data into line_buf + const Index stride = m_strides[dim]; + if (stride == 1) { + m_device.memcpy(line_buf, &buf[base_offset], line_len*sizeof(ComplexScalar)); + } else { + Index offset = base_offset; + for (int j = 0; j < line_len; ++j, offset += stride) { + line_buf[j] = buf[offset]; + } + } + + // processs the line + if (is_power_of_two) { + processDataLineCooleyTukey(line_buf, line_len, log_len); + } + else { + processDataLineBluestein(line_buf, line_len, good_composite, log_len, a, b, pos_j_base_powered); + } + + // write back + if (FFTDir == FFT_FORWARD && stride == 1) { + m_device.memcpy(&buf[base_offset], line_buf, line_len*sizeof(ComplexScalar)); + } else { + Index offset = base_offset; + const ComplexScalar div_factor = ComplexScalar(1.0 / line_len, 0); + for (int j = 0; j < line_len; ++j, offset += stride) { + buf[offset] = (FFTDir == FFT_FORWARD) ? line_buf[j] : line_buf[j] * div_factor; + } + } + } + m_device.deallocate(line_buf); + if (!is_power_of_two) { + m_device.deallocate(a); + m_device.deallocate(b); + m_device.deallocate(pos_j_base_powered); + } + } + + if(!write_to_out) { + for (Index i = 0; i < m_size; ++i) { + data[i] = PartOf()(buf[i]); + } + m_device.deallocate(buf); + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static bool isPowerOfTwo(Index x) { + eigen_assert(x > 0); + return !(x & (x - 1)); + } + + // The composite number for padding, used in Bluestein's FFT algorithm + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static Index findGoodComposite(Index n) { + Index i = 2; + while (i < 2 * n - 1) i *= 2; + return i; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static Index getLog2(Index m) { + Index log2m = 0; + while (m >>= 1) log2m++; + return log2m; + } + + // Call Cooley Tukey algorithm directly, data length must be power of 2 + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void processDataLineCooleyTukey(ComplexScalar* line_buf, Index line_len, Index log_len) { + eigen_assert(isPowerOfTwo(line_len)); + scramble_FFT(line_buf, line_len); + compute_1D_Butterfly(line_buf, line_len, log_len); + } + + // Call Bluestein's FFT algorithm, m is a good composite number greater than (2 * n - 1), used as the padding length + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void processDataLineBluestein(ComplexScalar* line_buf, Index line_len, Index good_composite, Index log_len, ComplexScalar* a, ComplexScalar* b, const ComplexScalar* pos_j_base_powered) { + Index n = line_len; + Index m = good_composite; + ComplexScalar* data = line_buf; + + for (Index i = 0; i < n; ++i) { + if(FFTDir == FFT_FORWARD) { + a[i] = data[i] * numext::conj(pos_j_base_powered[i]); + } + else { + a[i] = data[i] * pos_j_base_powered[i]; + } + } + for (Index i = n; i < m; ++i) { + a[i] = ComplexScalar(0, 0); + } + + for (Index i = 0; i < n; ++i) { + if(FFTDir == FFT_FORWARD) { + b[i] = pos_j_base_powered[i]; + } + else { + b[i] = numext::conj(pos_j_base_powered[i]); + } + } + for (Index i = n; i < m - n; ++i) { + b[i] = ComplexScalar(0, 0); + } + for (Index i = m - n; i < m; ++i) { + if(FFTDir == FFT_FORWARD) { + b[i] = pos_j_base_powered[m-i]; + } + else { + b[i] = numext::conj(pos_j_base_powered[m-i]); + } + } + + scramble_FFT(a, m); + compute_1D_Butterfly(a, m, log_len); + + scramble_FFT(b, m); + compute_1D_Butterfly(b, m, log_len); + + for (Index i = 0; i < m; ++i) { + a[i] *= b[i]; + } + + scramble_FFT(a, m); + compute_1D_Butterfly(a, m, log_len); + + //Do the scaling after ifft + for (Index i = 0; i < m; ++i) { + a[i] /= m; + } + + for (Index i = 0; i < n; ++i) { + if(FFTDir == FFT_FORWARD) { + data[i] = a[i] * numext::conj(pos_j_base_powered[i]); + } + else { + data[i] = a[i] * pos_j_base_powered[i]; + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static void scramble_FFT(ComplexScalar* data, Index n) { + eigen_assert(isPowerOfTwo(n)); + Index j = 1; + for (Index i = 1; i < n; ++i){ + if (j > i) { + std::swap(data[j-1], data[i-1]); + } + Index m = n >> 1; + while (m >= 2 && j > m) { + j -= m; + m >>= 1; + } + j += m; + } + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void butterfly_2(ComplexScalar* data) { + ComplexScalar tmp = data[1]; + data[1] = data[0] - data[1]; + data[0] += tmp; + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void butterfly_4(ComplexScalar* data) { + ComplexScalar tmp[4]; + tmp[0] = data[0] + data[1]; + tmp[1] = data[0] - data[1]; + tmp[2] = data[2] + data[3]; + if (Dir == FFT_FORWARD) { + tmp[3] = ComplexScalar(0.0, -1.0) * (data[2] - data[3]); + } else { + tmp[3] = ComplexScalar(0.0, 1.0) * (data[2] - data[3]); + } + data[0] = tmp[0] + tmp[2]; + data[1] = tmp[1] + tmp[3]; + data[2] = tmp[0] - tmp[2]; + data[3] = tmp[1] - tmp[3]; + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void butterfly_8(ComplexScalar* data) { + ComplexScalar tmp_1[8]; + ComplexScalar tmp_2[8]; + + tmp_1[0] = data[0] + data[1]; + tmp_1[1] = data[0] - data[1]; + tmp_1[2] = data[2] + data[3]; + if (Dir == FFT_FORWARD) { + tmp_1[3] = (data[2] - data[3]) * ComplexScalar(0, -1); + } else { + tmp_1[3] = (data[2] - data[3]) * ComplexScalar(0, 1); + } + tmp_1[4] = data[4] + data[5]; + tmp_1[5] = data[4] - data[5]; + tmp_1[6] = data[6] + data[7]; + if (Dir == FFT_FORWARD) { + tmp_1[7] = (data[6] - data[7]) * ComplexScalar(0, -1); + } else { + tmp_1[7] = (data[6] - data[7]) * ComplexScalar(0, 1); + } + tmp_2[0] = tmp_1[0] + tmp_1[2]; + tmp_2[1] = tmp_1[1] + tmp_1[3]; + tmp_2[2] = tmp_1[0] - tmp_1[2]; + tmp_2[3] = tmp_1[1] - tmp_1[3]; + tmp_2[4] = tmp_1[4] + tmp_1[6]; +// SQRT2DIV2 = sqrt(2)/2 +#define SQRT2DIV2 0.7071067811865476 + if (Dir == FFT_FORWARD) { + tmp_2[5] = (tmp_1[5] + tmp_1[7]) * ComplexScalar(SQRT2DIV2, -SQRT2DIV2); + tmp_2[6] = (tmp_1[4] - tmp_1[6]) * ComplexScalar(0, -1); + tmp_2[7] = (tmp_1[5] - tmp_1[7]) * ComplexScalar(-SQRT2DIV2, -SQRT2DIV2); + } else { + tmp_2[5] = (tmp_1[5] + tmp_1[7]) * ComplexScalar(SQRT2DIV2, SQRT2DIV2); + tmp_2[6] = (tmp_1[4] - tmp_1[6]) * ComplexScalar(0, 1); + tmp_2[7] = (tmp_1[5] - tmp_1[7]) * ComplexScalar(-SQRT2DIV2, SQRT2DIV2); + } + data[0] = tmp_2[0] + tmp_2[4]; + data[1] = tmp_2[1] + tmp_2[5]; + data[2] = tmp_2[2] + tmp_2[6]; + data[3] = tmp_2[3] + tmp_2[7]; + data[4] = tmp_2[0] - tmp_2[4]; + data[5] = tmp_2[1] - tmp_2[5]; + data[6] = tmp_2[2] - tmp_2[6]; + data[7] = tmp_2[3] - tmp_2[7]; + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void butterfly_1D_merge( + ComplexScalar* data, Index n, Index n_power_of_2) { + // Original code: + // RealScalar wtemp = std::sin(M_PI/n); + // RealScalar wpi = -std::sin(2 * M_PI/n); + const RealScalar wtemp = m_sin_PI_div_n_LUT[n_power_of_2]; + const RealScalar wpi = (Dir == FFT_FORWARD) + ? m_minus_sin_2_PI_div_n_LUT[n_power_of_2] + : -m_minus_sin_2_PI_div_n_LUT[n_power_of_2]; + + const ComplexScalar wp(wtemp, wpi); + const ComplexScalar wp_one = wp + ComplexScalar(1, 0); + const ComplexScalar wp_one_2 = wp_one * wp_one; + const ComplexScalar wp_one_3 = wp_one_2 * wp_one; + const ComplexScalar wp_one_4 = wp_one_3 * wp_one; + const Index n2 = n / 2; + ComplexScalar w(1.0, 0.0); + for (Index i = 0; i < n2; i += 4) { + ComplexScalar temp0(data[i + n2] * w); + ComplexScalar temp1(data[i + 1 + n2] * w * wp_one); + ComplexScalar temp2(data[i + 2 + n2] * w * wp_one_2); + ComplexScalar temp3(data[i + 3 + n2] * w * wp_one_3); + w = w * wp_one_4; + + data[i + n2] = data[i] - temp0; + data[i] += temp0; + + data[i + 1 + n2] = data[i + 1] - temp1; + data[i + 1] += temp1; + + data[i + 2 + n2] = data[i + 2] - temp2; + data[i + 2] += temp2; + + data[i + 3 + n2] = data[i + 3] - temp3; + data[i + 3] += temp3; + } + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void compute_1D_Butterfly( + ComplexScalar* data, Index n, Index n_power_of_2) { + eigen_assert(isPowerOfTwo(n)); + if (n > 8) { + compute_1D_Butterfly(data, n / 2, n_power_of_2 - 1); + compute_1D_Butterfly(data + n / 2, n / 2, n_power_of_2 - 1); + butterfly_1D_merge(data, n, n_power_of_2); + } else if (n == 8) { + butterfly_8(data); + } else if (n == 4) { + butterfly_4(data); + } else if (n == 2) { + butterfly_2(data); + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index getBaseOffsetFromIndex(Index index, Index omitted_dim) const { + Index result = 0; + + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i > omitted_dim; --i) { + const Index partial_m_stride = m_strides[i] / m_dimensions[omitted_dim]; + const Index idx = index / partial_m_stride; + index -= idx * partial_m_stride; + result += idx * m_strides[i]; + } + result += index; + } + else { + for (Index i = 0; i < omitted_dim; ++i) { + const Index partial_m_stride = m_strides[i] / m_dimensions[omitted_dim]; + const Index idx = index / partial_m_stride; + index -= idx * partial_m_stride; + result += idx * m_strides[i]; + } + result += index; + } + // Value of index_coords[omitted_dim] is not determined to this step + return result; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index getIndexFromOffset(Index base, Index omitted_dim, Index offset) const { + Index result = base + offset * m_strides[omitted_dim] ; + return result; + } + + protected: + Index m_size; + const FFT& m_fft; + Dimensions m_dimensions; + array m_strides; + TensorEvaluator m_impl; + CoeffReturnType* m_data; + const Device& m_device; + + // This will support a maximum FFT size of 2^32 for each dimension + // m_sin_PI_div_n_LUT[i] = (-2) * std::sin(M_PI / std::pow(2,i)) ^ 2; + const RealScalar m_sin_PI_div_n_LUT[32] = { + RealScalar(0.0), + RealScalar(-2), + RealScalar(-0.999999999999999), + RealScalar(-0.292893218813453), + RealScalar(-0.0761204674887130), + RealScalar(-0.0192147195967696), + RealScalar(-0.00481527332780311), + RealScalar(-0.00120454379482761), + RealScalar(-3.01181303795779e-04), + RealScalar(-7.52981608554592e-05), + RealScalar(-1.88247173988574e-05), + RealScalar(-4.70619042382852e-06), + RealScalar(-1.17654829809007e-06), + RealScalar(-2.94137117780840e-07), + RealScalar(-7.35342821488550e-08), + RealScalar(-1.83835707061916e-08), + RealScalar(-4.59589268710903e-09), + RealScalar(-1.14897317243732e-09), + RealScalar(-2.87243293150586e-10), + RealScalar( -7.18108232902250e-11), + RealScalar(-1.79527058227174e-11), + RealScalar(-4.48817645568941e-12), + RealScalar(-1.12204411392298e-12), + RealScalar(-2.80511028480785e-13), + RealScalar(-7.01277571201985e-14), + RealScalar(-1.75319392800498e-14), + RealScalar(-4.38298482001247e-15), + RealScalar(-1.09574620500312e-15), + RealScalar(-2.73936551250781e-16), + RealScalar(-6.84841378126949e-17), + RealScalar(-1.71210344531737e-17), + RealScalar(-4.28025861329343e-18) + }; + + // m_minus_sin_2_PI_div_n_LUT[i] = -std::sin(2 * M_PI / std::pow(2,i)); + const RealScalar m_minus_sin_2_PI_div_n_LUT[32] = { + RealScalar(0.0), + RealScalar(0.0), + RealScalar(-1.00000000000000e+00), + RealScalar(-7.07106781186547e-01), + RealScalar(-3.82683432365090e-01), + RealScalar(-1.95090322016128e-01), + RealScalar(-9.80171403295606e-02), + RealScalar(-4.90676743274180e-02), + RealScalar(-2.45412285229123e-02), + RealScalar(-1.22715382857199e-02), + RealScalar(-6.13588464915448e-03), + RealScalar(-3.06795676296598e-03), + RealScalar(-1.53398018628477e-03), + RealScalar(-7.66990318742704e-04), + RealScalar(-3.83495187571396e-04), + RealScalar(-1.91747597310703e-04), + RealScalar(-9.58737990959773e-05), + RealScalar(-4.79368996030669e-05), + RealScalar(-2.39684498084182e-05), + RealScalar(-1.19842249050697e-05), + RealScalar(-5.99211245264243e-06), + RealScalar(-2.99605622633466e-06), + RealScalar(-1.49802811316901e-06), + RealScalar(-7.49014056584716e-07), + RealScalar(-3.74507028292384e-07), + RealScalar(-1.87253514146195e-07), + RealScalar(-9.36267570730981e-08), + RealScalar(-4.68133785365491e-08), + RealScalar(-2.34066892682746e-08), + RealScalar(-1.17033446341373e-08), + RealScalar(-5.85167231706864e-09), + RealScalar(-2.92583615853432e-09) + }; +}; + +} // end namespace Eigen + +#endif // EIGEN_HAS_CONSTEXPR + + +#endif // EIGEN_CXX11_TENSOR_TENSOR_FFT_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFixedSize.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFixedSize.h new file mode 100644 index 00000000..fcee5f60 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFixedSize.h @@ -0,0 +1,389 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_FIXED_SIZE_H +#define EIGEN_CXX11_TENSOR_TENSOR_FIXED_SIZE_H + +namespace Eigen { + +/** \class TensorFixedSize + * \ingroup CXX11_Tensor_Module + * + * \brief The fixed sized version of the tensor class. + * + * The fixed sized equivalent of + * Eigen::Tensor t(3, 5, 7); + * is + * Eigen::TensorFixedSize> t; + */ + +template +class TensorFixedSize : public TensorBase > +{ + public: + typedef TensorFixedSize Self; + typedef TensorBase > Base; + typedef typename Eigen::internal::nested::type Nested; + typedef typename internal::traits::StorageKind StorageKind; + typedef typename internal::traits::Index Index; + typedef Scalar_ Scalar; + typedef typename NumTraits::Real RealScalar; + typedef typename Base::CoeffReturnType CoeffReturnType; + + static const int Options = Options_; + + enum { + IsAligned = bool(EIGEN_MAX_ALIGN_BYTES>0), + Layout = Options_ & RowMajor ? RowMajor : ColMajor, + CoordAccess = true, + RawAccess = true + }; + + typedef Dimensions_ Dimensions; + static const std::size_t NumIndices = Dimensions::count; + + protected: + TensorStorage m_storage; + + public: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rank() const { return NumIndices; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index dimension(std::size_t n) const { return m_storage.dimensions()[n]; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_storage.dimensions(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index size() const { return m_storage.size(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar *data() { return m_storage.data(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar *data() const { return m_storage.data(); } + + // This makes EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED + // work, because that uses base().coeffRef() - and we don't yet + // implement a similar class hierarchy + inline Self& base() { return *this; } + inline const Self& base() const { return *this; } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(Index firstIndex, IndexTypes... otherIndices) const + { + // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + return coeff(array{{firstIndex, otherIndices...}}); + } +#endif + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& coeff(const array& indices) const + { + eigen_internal_assert(checkIndexRange(indices)); + return m_storage.data()[linearizedIndex(indices)]; + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& coeff(Index index) const + { + eigen_internal_assert(index >= 0 && index < size()); + return m_storage.data()[index]; + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& coeff() const + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE); + return m_storage.data()[0]; + } + + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index firstIndex, IndexTypes... otherIndices) + { + // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + return coeffRef(array{{firstIndex, otherIndices...}}); + } +#endif + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& coeffRef(const array& indices) + { + eigen_internal_assert(checkIndexRange(indices)); + return m_storage.data()[linearizedIndex(indices)]; + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& coeffRef(Index index) + { + eigen_internal_assert(index >= 0 && index < size()); + return m_storage.data()[index]; + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& coeffRef() + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE); + return m_storage.data()[0]; + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator()(Index firstIndex, IndexTypes... otherIndices) const + { + // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + return this->operator()(array{{firstIndex, otherIndices...}}); + } +#else + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1) const + { + if (Options&RowMajor) { + const Index index = i1 + i0 * m_storage.dimensions()[1]; + return m_storage.data()[index]; + } else { + const Index index = i0 + i1 * m_storage.dimensions()[0]; + return m_storage.data()[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2) const + { + if (Options&RowMajor) { + const Index index = i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0); + return m_storage.data()[index]; + } else { + const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * i2); + return m_storage.data()[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2, Index i3) const + { + if (Options&RowMajor) { + const Index index = i3 + m_storage.dimensions()[3] * (i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0)); + return m_storage.data()[index]; + } else { + const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * (i2 + m_storage.dimensions()[2] * i3)); + return m_storage.data()[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2, Index i3, Index i4) const + { + if (Options&RowMajor) { + const Index index = i4 + m_storage.dimensions()[4] * (i3 + m_storage.dimensions()[3] * (i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0))); + return m_storage.data()[index]; + } else { + const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * (i2 + m_storage.dimensions()[2] * (i3 + m_storage.dimensions()[3] * i4))); + return m_storage.data()[index]; + } + } +#endif + + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(const array& indices) const + { + eigen_assert(checkIndexRange(indices)); + return coeff(indices); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index index) const + { + eigen_internal_assert(index >= 0 && index < size()); + return coeff(index); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()() const + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE); + return coeff(); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator[](Index index) const + { + // The bracket operator is only for vectors, use the parenthesis operator instead. + EIGEN_STATIC_ASSERT(NumIndices == 1, YOU_MADE_A_PROGRAMMING_MISTAKE); + return coeff(index); + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator()(Index firstIndex, IndexTypes... otherIndices) + { + // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + return operator()(array{{firstIndex, otherIndices...}}); + } +#else + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1) + { + if (Options&RowMajor) { + const Index index = i1 + i0 * m_storage.dimensions()[1]; + return m_storage.data()[index]; + } else { + const Index index = i0 + i1 * m_storage.dimensions()[0]; + return m_storage.data()[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2) + { + if (Options&RowMajor) { + const Index index = i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0); + return m_storage.data()[index]; + } else { + const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * i2); + return m_storage.data()[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3) + { + if (Options&RowMajor) { + const Index index = i3 + m_storage.dimensions()[3] * (i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0)); + return m_storage.data()[index]; + } else { + const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * (i2 + m_storage.dimensions()[2] * i3)); + return m_storage.data()[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3, Index i4) + { + if (Options&RowMajor) { + const Index index = i4 + m_storage.dimensions()[4] * (i3 + m_storage.dimensions()[3] * (i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0))); + return m_storage.data()[index]; + } else { + const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * (i2 + m_storage.dimensions()[2] * (i3 + m_storage.dimensions()[3] * i4))); + return m_storage.data()[index]; + } + } +#endif + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(const array& indices) + { + eigen_assert(checkIndexRange(indices)); + return coeffRef(indices); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index index) + { + eigen_assert(index >= 0 && index < size()); + return coeffRef(index); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()() + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE); + return coeffRef(); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator[](Index index) + { + // The bracket operator is only for vectors, use the parenthesis operator instead + EIGEN_STATIC_ASSERT(NumIndices == 1, YOU_MADE_A_PROGRAMMING_MISTAKE) + return coeffRef(index); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorFixedSize() + : m_storage() + { + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorFixedSize(const Self& other) + : m_storage(other.m_storage) + { + } + +#if EIGEN_HAS_RVALUE_REFERENCES + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorFixedSize(Self&& other) + : m_storage(other.m_storage) + { + } +#endif + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorFixedSize(const TensorBase& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other.derived()); + internal::TensorExecutor::run(assign, DefaultDevice()); + } + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorFixedSize(const TensorBase& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other.derived()); + internal::TensorExecutor::run(assign, DefaultDevice()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorFixedSize& operator=(const TensorFixedSize& other) + { + // FIXME: check that the dimensions of other match the dimensions of *this. + // Unfortunately this isn't possible yet when the rhs is an expression. + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorFixedSize& operator=(const OtherDerived& other) + { + // FIXME: check that the dimensions of other match the dimensions of *this. + // Unfortunately this isn't possible yet when the rhs is an expression. + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + protected: + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE bool checkIndexRange(const array& /*indices*/) const + { + using internal::array_apply_and_reduce; + using internal::array_zip_and_reduce; + using internal::greater_equal_zero_op; + using internal::logical_and_op; + using internal::lesser_op; + + return true; + // check whether the indices are all >= 0 + /* array_apply_and_reduce(indices) && + // check whether the indices fit in the dimensions + array_zip_and_reduce(indices, m_storage.dimensions());*/ + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Index linearizedIndex(const array& indices) const + { + if (Options&RowMajor) { + return m_storage.dimensions().IndexOfRowMajor(indices); + } else { + return m_storage.dimensions().IndexOfColMajor(indices); + } + } +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_FIXED_SIZE_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorForcedEval.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorForcedEval.h new file mode 100644 index 00000000..abe85c86 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorForcedEval.h @@ -0,0 +1,162 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_FORCED_EVAL_H +#define EIGEN_CXX11_TENSOR_TENSOR_FORCED_EVAL_H + +namespace Eigen { + +/** \class TensorForcedEval + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor reshaping class. + * + * + */ +/// template class MakePointer_ is added to convert the host pointer to the device pointer. +/// It is added due to the fact that for our device compiler T* is not allowed. +/// If we wanted to use the same Evaluator functions we have to convert that type to our pointer T. +/// This is done through our MakePointer_ class. By default the Type in the MakePointer_ is T* . +/// Therefore, by adding the default value, we managed to convert the type and it does not break any +/// existing code as its default value is T*. +namespace internal { +template +struct traits > +{ + // Type promotion to handle the case where the types of the lhs and the rhs are different. + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename traits::StorageKind StorageKind; + typedef typename traits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; + + enum { + Flags = 0 + }; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorForcedEvalOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorForcedEvalOp type; +}; + +} // end namespace internal + + + +template +class TensorForcedEvalOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename internal::remove_const::type CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorForcedEvalOp(const XprType& expr) + : m_xpr(expr) {} + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + protected: + typename XprType::Nested m_xpr; +}; + + +template +struct TensorEvaluator, Device> +{ + typedef TensorForcedEvalOp XprType; + typedef typename ArgType::Scalar Scalar; + typedef typename TensorEvaluator::Dimensions Dimensions; + typedef typename XprType::Index Index; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = true, + PacketAccess = (PacketSize > 1), + Layout = TensorEvaluator::Layout, + RawAccess = true + }; + + EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device) + /// op_ is used for sycl + : m_impl(op.expression(), device), m_op(op.expression()), m_device(device), m_buffer(NULL) + { } + + EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_impl.dimensions(); } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType*) { + const Index numValues = internal::array_prod(m_impl.dimensions()); + m_buffer = (CoeffReturnType*)m_device.allocate(numValues * sizeof(CoeffReturnType)); + // Should initialize the memory in case we're dealing with non POD types. + if (NumTraits::RequireInitialization) { + for (Index i = 0; i < numValues; ++i) { + new(m_buffer+i) CoeffReturnType(); + } + } + typedef TensorEvalToOp< const typename internal::remove_const::type > EvalTo; + EvalTo evalToTmp(m_buffer, m_op); + const bool PacketAccess = internal::IsVectorizable::value; + internal::TensorExecutor::type, PacketAccess>::run(evalToTmp, m_device); + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_device.deallocate(m_buffer); + m_buffer = NULL; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + return m_buffer[index]; + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + return internal::ploadt(m_buffer + index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType* data() const { return m_buffer; } + + /// required by sycl in order to extract the sycl accessor + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const TensorEvaluator& impl() { return m_impl; } + /// used by sycl in order to build the sycl buffer + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Device& device() const{return m_device;} + private: + TensorEvaluator m_impl; + const ArgType m_op; + const Device& m_device; + CoeffReturnType* m_buffer; +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_FORCED_EVAL_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorForwardDeclarations.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorForwardDeclarations.h new file mode 100644 index 00000000..2e638992 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorForwardDeclarations.h @@ -0,0 +1,121 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_FORWARD_DECLARATIONS_H +#define EIGEN_CXX11_TENSOR_TENSOR_FORWARD_DECLARATIONS_H + +namespace Eigen { + +// MakePointer class is used as a container of the adress space of the pointer +// on the host and on the device. From the host side it generates the T* pointer +// and when EIGEN_USE_SYCL is used it construct a buffer with a map_allocator to +// T* m_data on the host. It is always called on the device. +// Specialisation of MakePointer class for creating the sycl buffer with +// map_allocator. +template struct MakePointer { + typedef T* Type; + typedef T& RefType; +}; +#if defined(EIGEN_USE_SYCL) +namespace TensorSycl { +namespace internal{ +template class ReductionFunctor; +template +class FullReductionKernelFunctor; +} +} +#endif + + + +template class MakePointer_ = MakePointer> class TensorMap; +template class Tensor; +template class TensorFixedSize; +template class TensorRef; +template class TensorBase; + +template class TensorCwiseNullaryOp; +template class TensorCwiseUnaryOp; +template class TensorCwiseBinaryOp; +template class TensorCwiseTernaryOp; +template class TensorSelectOp; +template class MakePointer_ = MakePointer > class TensorReductionOp; +template class TensorIndexTupleOp; +template class TensorTupleReducerOp; +template class TensorConcatenationOp; +template class TensorContractionOp; +template class TensorConversionOp; +template class TensorConvolutionOp; +template class TensorFFTOp; +template class TensorPatchOp; +template class TensorImagePatchOp; +template class TensorVolumePatchOp; +template class TensorBroadcastingOp; +template class TensorChippingOp; +template class TensorReshapingOp; +template class TensorLayoutSwapOp; +template class TensorSlicingOp; +template class TensorReverseOp; +template class TensorPaddingOp; +template class TensorShufflingOp; +template class TensorStridingOp; +template class TensorStridingSlicingOp; +template class TensorInflationOp; +template class TensorGeneratorOp; +template class TensorAssignOp; +template class TensorScanOp; + +template class TensorCustomUnaryOp; +template class TensorCustomBinaryOp; + +template class MakePointer_ = MakePointer> class TensorEvalToOp; +template class TensorForcedEvalOp; + +template class TensorDevice; +template struct TensorEvaluator; + +struct DefaultDevice; +struct ThreadPoolDevice; +struct GpuDevice; +struct SyclDevice; + +enum FFTResultType { + RealPart = 0, + ImagPart = 1, + BothParts = 2 +}; + +enum FFTDirection { + FFT_FORWARD = 0, + FFT_REVERSE = 1 +}; + + +namespace internal { + +template +struct IsVectorizable { + static const bool value = TensorEvaluator::PacketAccess; +}; + +template +struct IsVectorizable { + static const bool value = TensorEvaluator::PacketAccess && + TensorEvaluator::IsAligned; +}; + +template ::value> +class TensorExecutor; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_FORWARD_DECLARATIONS_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFunctors.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFunctors.h new file mode 100644 index 00000000..3b4f8eda --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFunctors.h @@ -0,0 +1,489 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_FUNCTORS_H +#define EIGEN_CXX11_TENSOR_TENSOR_FUNCTORS_H + +namespace Eigen { +namespace internal { + + +/** \internal + * \brief Template functor to compute the modulo between an array and a scalar. + */ +template +struct scalar_mod_op { + EIGEN_DEVICE_FUNC scalar_mod_op(const Scalar& divisor) : m_divisor(divisor) {} + EIGEN_DEVICE_FUNC inline Scalar operator() (const Scalar& a) const { return a % m_divisor; } + const Scalar m_divisor; +}; +template +struct functor_traits > +{ enum { Cost = scalar_div_cost::value, PacketAccess = false }; }; + + +/** \internal + * \brief Template functor to compute the modulo between 2 arrays. + */ +template +struct scalar_mod2_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_mod2_op) + EIGEN_DEVICE_FUNC inline Scalar operator() (const Scalar& a, const Scalar& b) const { return a % b; } +}; +template +struct functor_traits > +{ enum { Cost = scalar_div_cost::value, PacketAccess = false }; }; + +template +struct scalar_fmod_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_fmod_op) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar + operator()(const Scalar& a, const Scalar& b) const { + return numext::fmod(a, b); + } +}; +template +struct functor_traits > { + enum { Cost = 13, // Reciprocal throughput of FPREM on Haswell. + PacketAccess = false }; +}; + + +/** \internal + * \brief Template functor to compute the sigmoid of a scalar + * \sa class CwiseUnaryOp, ArrayBase::sigmoid() + */ +template +struct scalar_sigmoid_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_sigmoid_op) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T operator()(const T& x) const { + const T one = T(1); + return one / (one + numext::exp(-x)); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Packet packetOp(const Packet& x) const { + const Packet one = pset1(T(1)); + return pdiv(one, padd(one, pexp(pnegate(x)))); + } +}; + +template +struct functor_traits > { + enum { + Cost = NumTraits::AddCost * 2 + NumTraits::MulCost * 6, + PacketAccess = packet_traits::HasAdd && packet_traits::HasDiv && + packet_traits::HasNegate && packet_traits::HasExp + }; +}; + + +template +struct reducer_traits { + enum { + Cost = 1, + PacketAccess = false + }; +}; + +// Standard reduction functors +template struct SumReducer +{ + static const bool PacketAccess = packet_traits::HasAdd; + static const bool IsStateful = false; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) const { + internal::scalar_sum_op sum_op; + *accum = sum_op(*accum, t); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reducePacket(const Packet& p, Packet* accum) const { + (*accum) = padd(*accum, p); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const { + internal::scalar_cast_op conv; + return conv(0); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet initializePacket() const { + return pset1(initialize()); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T accum) const { + return accum; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet finalizePacket(const Packet& vaccum) const { + return vaccum; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalizeBoth(const T saccum, const Packet& vaccum) const { + internal::scalar_sum_op sum_op; + return sum_op(saccum, predux(vaccum)); + } +}; + +template +struct reducer_traits, Device> { + enum { + Cost = NumTraits::AddCost, + PacketAccess = PacketType::HasAdd + }; +}; + + +template struct MeanReducer +{ + static const bool PacketAccess = packet_traits::HasAdd && !NumTraits::IsInteger; + static const bool IsStateful = true; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + MeanReducer() : scalarCount_(0), packetCount_(0) { } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) { + internal::scalar_sum_op sum_op; + *accum = sum_op(*accum, t); + scalarCount_++; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reducePacket(const Packet& p, Packet* accum) { + (*accum) = padd(*accum, p); + packetCount_++; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const { + internal::scalar_cast_op conv; + return conv(0); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet initializePacket() const { + return pset1(initialize()); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T accum) const { + return accum / scalarCount_; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet finalizePacket(const Packet& vaccum) const { + return pdiv(vaccum, pset1(packetCount_)); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalizeBoth(const T saccum, const Packet& vaccum) const { + internal::scalar_sum_op sum_op; + return sum_op(saccum, predux(vaccum)) / (scalarCount_ + packetCount_ * unpacket_traits::size); + } + + protected: + DenseIndex scalarCount_; + DenseIndex packetCount_; +}; + +template +struct reducer_traits, Device> { + enum { + Cost = NumTraits::AddCost, + PacketAccess = PacketType::HasAdd + }; +}; + + +template +struct MinMaxBottomValue { + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE T bottom_value() { + return Eigen::NumTraits::lowest(); + } +}; +template +struct MinMaxBottomValue { + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE T bottom_value() { + return -Eigen::NumTraits::infinity(); + } +}; +template +struct MinMaxBottomValue { + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE T bottom_value() { + return Eigen::NumTraits::highest(); + } +}; +template +struct MinMaxBottomValue { + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE T bottom_value() { + return Eigen::NumTraits::infinity(); + } +}; + + +template struct MaxReducer +{ + static const bool PacketAccess = packet_traits::HasMax; + static const bool IsStateful = false; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) const { + if (t > *accum) { *accum = t; } + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reducePacket(const Packet& p, Packet* accum) const { + (*accum) = pmax(*accum, p); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const { + return MinMaxBottomValue::IsInteger>::bottom_value(); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet initializePacket() const { + return pset1(initialize()); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T accum) const { + return accum; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet finalizePacket(const Packet& vaccum) const { + return vaccum; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalizeBoth(const T saccum, const Packet& vaccum) const { + return numext::maxi(saccum, predux_max(vaccum)); + } +}; + +template +struct reducer_traits, Device> { + enum { + Cost = NumTraits::AddCost, + PacketAccess = PacketType::HasMax + }; +}; + + +template struct MinReducer +{ + static const bool PacketAccess = packet_traits::HasMin; + static const bool IsStateful = false; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) const { + if (t < *accum) { *accum = t; } + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reducePacket(const Packet& p, Packet* accum) const { + (*accum) = pmin(*accum, p); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const { + return MinMaxBottomValue::IsInteger>::bottom_value(); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet initializePacket() const { + return pset1(initialize()); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T accum) const { + return accum; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet finalizePacket(const Packet& vaccum) const { + return vaccum; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalizeBoth(const T saccum, const Packet& vaccum) const { + return numext::mini(saccum, predux_min(vaccum)); + } +}; + +template +struct reducer_traits, Device> { + enum { + Cost = NumTraits::AddCost, + PacketAccess = PacketType::HasMin + }; +}; + + +template struct ProdReducer +{ + static const bool PacketAccess = packet_traits::HasMul; + static const bool IsStateful = false; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) const { + internal::scalar_product_op prod_op; + (*accum) = prod_op(*accum, t); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reducePacket(const Packet& p, Packet* accum) const { + (*accum) = pmul(*accum, p); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const { + internal::scalar_cast_op conv; + return conv(1); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet initializePacket() const { + return pset1(initialize()); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T accum) const { + return accum; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet finalizePacket(const Packet& vaccum) const { + return vaccum; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalizeBoth(const T saccum, const Packet& vaccum) const { + internal::scalar_product_op prod_op; + return prod_op(saccum, predux_mul(vaccum)); + } +}; + +template +struct reducer_traits, Device> { + enum { + Cost = NumTraits::MulCost, + PacketAccess = PacketType::HasMul + }; +}; + + +struct AndReducer +{ + static const bool PacketAccess = false; + static const bool IsStateful = false; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(bool t, bool* accum) const { + *accum = *accum && t; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool initialize() const { + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool finalize(bool accum) const { + return accum; + } +}; + +template +struct reducer_traits { + enum { + Cost = 1, + PacketAccess = false + }; +}; + + +struct OrReducer { + static const bool PacketAccess = false; + static const bool IsStateful = false; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(bool t, bool* accum) const { + *accum = *accum || t; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool initialize() const { + return false; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool finalize(bool accum) const { + return accum; + } +}; + +template +struct reducer_traits { + enum { + Cost = 1, + PacketAccess = false + }; +}; + + +// Argmin/Argmax reducers +template struct ArgMaxTupleReducer +{ + static const bool PacketAccess = false; + static const bool IsStateful = false; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) const { + if (t.second > accum->second) { *accum = t; } + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const { + return T(0, NumTraits::lowest()); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T& accum) const { + return accum; + } +}; + +template +struct reducer_traits, Device> { + enum { + Cost = NumTraits::AddCost, + PacketAccess = false + }; +}; + + +template struct ArgMinTupleReducer +{ + static const bool PacketAccess = false; + static const bool IsStateful = false; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T& t, T* accum) const { + if (t.second < accum->second) { *accum = t; } + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const { + return T(0, NumTraits::highest()); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T& accum) const { + return accum; + } +}; + +template +struct reducer_traits, Device> { + enum { + Cost = NumTraits::AddCost, + PacketAccess = false + }; +}; + + +template +class GaussianGenerator { + public: + static const bool PacketAccess = false; + + EIGEN_DEVICE_FUNC GaussianGenerator(const array& means, + const array& std_devs) + : m_means(means) + { + for (size_t i = 0; i < NumDims; ++i) { + m_two_sigmas[i] = std_devs[i] * std_devs[i] * 2; + } + } + + EIGEN_DEVICE_FUNC T operator()(const array& coordinates) const { + T tmp = T(0); + for (size_t i = 0; i < NumDims; ++i) { + T offset = coordinates[i] - m_means[i]; + tmp += offset * offset / m_two_sigmas[i]; + } + return numext::exp(-tmp); + } + + private: + array m_means; + array m_two_sigmas; +}; + +template +struct functor_traits > { + enum { + Cost = NumDims * (2 * NumTraits::AddCost + NumTraits::MulCost + + functor_traits >::Cost) + + functor_traits >::Cost, + PacketAccess = GaussianGenerator::PacketAccess + }; +}; + +} // end namespace internal +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_FUNCTORS_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGenerator.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGenerator.h new file mode 100644 index 00000000..eb1d4934 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGenerator.h @@ -0,0 +1,185 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_GENERATOR_H +#define EIGEN_CXX11_TENSOR_TENSOR_GENERATOR_H + +namespace Eigen { + +/** \class TensorGenerator + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor generator class. + * + * + */ +namespace internal { +template +struct traits > : public traits +{ + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorGeneratorOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorGeneratorOp type; +}; + +} // end namespace internal + + + +template +class TensorGeneratorOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorGeneratorOp(const XprType& expr, const Generator& generator) + : m_xpr(expr), m_generator(generator) {} + + EIGEN_DEVICE_FUNC + const Generator& generator() const { return m_generator; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + protected: + typename XprType::Nested m_xpr; + const Generator m_generator; +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorGeneratorOp XprType; + typedef typename XprType::Index Index; + typedef typename TensorEvaluator::Dimensions Dimensions; + static const int NumDims = internal::array_size::value; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + enum { + IsAligned = false, + PacketAccess = (internal::unpacket_traits::size > 1), + BlockAccess = false, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_generator(op.generator()) + { + TensorEvaluator impl(op.expression(), device); + m_dimensions = impl.dimensions(); + + if (static_cast(Layout) == static_cast(ColMajor)) { + m_strides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_strides[i] = m_strides[i - 1] * m_dimensions[i - 1]; + } + } else { + m_strides[NumDims - 1] = 1; + for (int i = NumDims - 2; i >= 0; --i) { + m_strides[i] = m_strides[i + 1] * m_dimensions[i + 1]; + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* /*data*/) { + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + array coords; + extract_coordinates(index, coords); + return m_generator(coords); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + const int packetSize = internal::unpacket_traits::size; + EIGEN_STATIC_ASSERT((packetSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index+packetSize-1 < dimensions().TotalSize()); + + EIGEN_ALIGN_MAX typename internal::remove_const::type values[packetSize]; + for (int i = 0; i < packetSize; ++i) { + values[i] = coeff(index+i); + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool) const { + // TODO(rmlarsen): This is just a placeholder. Define interface to make + // generators return their cost. + return TensorOpCost(0, 0, TensorOpCost::AddCost() + + TensorOpCost::MulCost()); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + protected: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void extract_coordinates(Index index, array& coords) const { + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i > 0; --i) { + const Index idx = index / m_strides[i]; + index -= idx * m_strides[i]; + coords[i] = idx; + } + coords[0] = index; + } else { + for (int i = 0; i < NumDims - 1; ++i) { + const Index idx = index / m_strides[i]; + index -= idx * m_strides[i]; + coords[i] = idx; + } + coords[NumDims-1] = index; + } + } + + Dimensions m_dimensions; + array m_strides; + Generator m_generator; +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_GENERATOR_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGlobalFunctions.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGlobalFunctions.h new file mode 100644 index 00000000..665b861c --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGlobalFunctions.h @@ -0,0 +1,33 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2016 Eugene Brevdo +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_GLOBAL_FUNCTIONS_H +#define EIGEN_CXX11_TENSOR_TENSOR_GLOBAL_FUNCTIONS_H + +namespace Eigen { + +/** \cpp11 \returns an expression of the coefficient-wise betainc(\a x, \a a, \a b) to the given tensors. + * + * This function computes the regularized incomplete beta function (integral). + * + */ +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const + TensorCwiseTernaryOp, + const ADerived, const BDerived, const XDerived> + betainc(const ADerived& a, const BDerived& b, const XDerived& x) { + return TensorCwiseTernaryOp< + internal::scalar_betainc_op, const ADerived, + const BDerived, const XDerived>( + a, b, x, internal::scalar_betainc_op()); +} + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_GLOBAL_FUNCTIONS_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIO.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIO.h new file mode 100644 index 00000000..a901c5dd --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIO.h @@ -0,0 +1,79 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_IO_H +#define EIGEN_CXX11_TENSOR_TENSOR_IO_H + +namespace Eigen { + +namespace internal { + +// Print the tensor as a 2d matrix +template +struct TensorPrinter { + static void run (std::ostream& os, const Tensor& tensor) { + typedef typename internal::remove_const::type Scalar; + typedef typename Tensor::Index Index; + const Index total_size = internal::array_prod(tensor.dimensions()); + if (total_size > 0) { + const Index first_dim = Eigen::internal::array_get<0>(tensor.dimensions()); + static const int layout = Tensor::Layout; + Map > matrix(const_cast(tensor.data()), first_dim, total_size/first_dim); + os << matrix; + } + } +}; + + +// Print the tensor as a vector +template +struct TensorPrinter { + static void run (std::ostream& os, const Tensor& tensor) { + typedef typename internal::remove_const::type Scalar; + typedef typename Tensor::Index Index; + const Index total_size = internal::array_prod(tensor.dimensions()); + if (total_size > 0) { + Map > array(const_cast(tensor.data()), total_size); + os << array; + } + } +}; + + +// Print the tensor as a scalar +template +struct TensorPrinter { + static void run (std::ostream& os, const Tensor& tensor) { + os << tensor.coeff(0); + } +}; +} + +template +std::ostream& operator << (std::ostream& os, const TensorBase& expr) { + typedef TensorEvaluator, DefaultDevice> Evaluator; + typedef typename Evaluator::Dimensions Dimensions; + + // Evaluate the expression if needed + TensorForcedEvalOp eval = expr.eval(); + Evaluator tensor(eval, DefaultDevice()); + tensor.evalSubExprsIfNeeded(NULL); + + // Print the result + static const int rank = internal::array_size::value; + internal::TensorPrinter::run(os, tensor); + + // Cleanup. + tensor.cleanup(); + return os; +} + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_IO_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorImagePatch.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorImagePatch.h new file mode 100644 index 00000000..566856ed --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorImagePatch.h @@ -0,0 +1,509 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_IMAGE_PATCH_H +#define EIGEN_CXX11_TENSOR_TENSOR_IMAGE_PATCH_H + +namespace Eigen { + +/** \class TensorImagePatch + * \ingroup CXX11_Tensor_Module + * + * \brief Patch extraction specialized for image processing. + * This assumes that the input has a least 3 dimensions ordered as follow: + * 1st dimension: channels (of size d) + * 2nd dimension: rows (of size r) + * 3rd dimension: columns (of size c) + * There can be additional dimensions such as time (for video) or batch (for + * bulk processing after the first 3. + * Calling the image patch code with patch_rows and patch_cols is equivalent + * to calling the regular patch extraction code with parameters d, patch_rows, + * patch_cols, and 1 for all the additional dimensions. + */ +namespace internal { +template +struct traits > : public traits +{ + typedef typename internal::remove_const::type Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions + 1; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorImagePatchOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorImagePatchOp type; +}; + +} // end namespace internal + +template +class TensorImagePatchOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorImagePatchOp(const XprType& expr, DenseIndex patch_rows, DenseIndex patch_cols, + DenseIndex row_strides, DenseIndex col_strides, + DenseIndex in_row_strides, DenseIndex in_col_strides, + DenseIndex row_inflate_strides, DenseIndex col_inflate_strides, + PaddingType padding_type, Scalar padding_value) + : m_xpr(expr), m_patch_rows(patch_rows), m_patch_cols(patch_cols), + m_row_strides(row_strides), m_col_strides(col_strides), + m_in_row_strides(in_row_strides), m_in_col_strides(in_col_strides), + m_row_inflate_strides(row_inflate_strides), m_col_inflate_strides(col_inflate_strides), + m_padding_explicit(false), m_padding_top(0), m_padding_bottom(0), m_padding_left(0), m_padding_right(0), + m_padding_type(padding_type), m_padding_value(padding_value) {} + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorImagePatchOp(const XprType& expr, DenseIndex patch_rows, DenseIndex patch_cols, + DenseIndex row_strides, DenseIndex col_strides, + DenseIndex in_row_strides, DenseIndex in_col_strides, + DenseIndex row_inflate_strides, DenseIndex col_inflate_strides, + DenseIndex padding_top, DenseIndex padding_bottom, + DenseIndex padding_left, DenseIndex padding_right, + Scalar padding_value) + : m_xpr(expr), m_patch_rows(patch_rows), m_patch_cols(patch_cols), + m_row_strides(row_strides), m_col_strides(col_strides), + m_in_row_strides(in_row_strides), m_in_col_strides(in_col_strides), + m_row_inflate_strides(row_inflate_strides), m_col_inflate_strides(col_inflate_strides), + m_padding_explicit(true), m_padding_top(padding_top), m_padding_bottom(padding_bottom), + m_padding_left(padding_left), m_padding_right(padding_right), + m_padding_type(PADDING_VALID), m_padding_value(padding_value) {} + + EIGEN_DEVICE_FUNC + DenseIndex patch_rows() const { return m_patch_rows; } + EIGEN_DEVICE_FUNC + DenseIndex patch_cols() const { return m_patch_cols; } + EIGEN_DEVICE_FUNC + DenseIndex row_strides() const { return m_row_strides; } + EIGEN_DEVICE_FUNC + DenseIndex col_strides() const { return m_col_strides; } + EIGEN_DEVICE_FUNC + DenseIndex in_row_strides() const { return m_in_row_strides; } + EIGEN_DEVICE_FUNC + DenseIndex in_col_strides() const { return m_in_col_strides; } + EIGEN_DEVICE_FUNC + DenseIndex row_inflate_strides() const { return m_row_inflate_strides; } + EIGEN_DEVICE_FUNC + DenseIndex col_inflate_strides() const { return m_col_inflate_strides; } + EIGEN_DEVICE_FUNC + bool padding_explicit() const { return m_padding_explicit; } + EIGEN_DEVICE_FUNC + DenseIndex padding_top() const { return m_padding_top; } + EIGEN_DEVICE_FUNC + DenseIndex padding_bottom() const { return m_padding_bottom; } + EIGEN_DEVICE_FUNC + DenseIndex padding_left() const { return m_padding_left; } + EIGEN_DEVICE_FUNC + DenseIndex padding_right() const { return m_padding_right; } + EIGEN_DEVICE_FUNC + PaddingType padding_type() const { return m_padding_type; } + EIGEN_DEVICE_FUNC + Scalar padding_value() const { return m_padding_value; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + protected: + typename XprType::Nested m_xpr; + const DenseIndex m_patch_rows; + const DenseIndex m_patch_cols; + const DenseIndex m_row_strides; + const DenseIndex m_col_strides; + const DenseIndex m_in_row_strides; + const DenseIndex m_in_col_strides; + const DenseIndex m_row_inflate_strides; + const DenseIndex m_col_inflate_strides; + const bool m_padding_explicit; + const DenseIndex m_padding_top; + const DenseIndex m_padding_bottom; + const DenseIndex m_padding_left; + const DenseIndex m_padding_right; + const PaddingType m_padding_type; + const Scalar m_padding_value; +}; + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorImagePatchOp XprType; + typedef typename XprType::Index Index; + static const int NumInputDims = internal::array_size::Dimensions>::value; + static const int NumDims = NumInputDims + 1; + typedef DSizes Dimensions; + typedef typename internal::remove_const::type Scalar; + typedef TensorEvaluator, + Device> Self; + typedef TensorEvaluator Impl; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = false, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device) + { + EIGEN_STATIC_ASSERT((NumDims >= 4), YOU_MADE_A_PROGRAMMING_MISTAKE); + + m_paddingValue = op.padding_value(); + + const typename TensorEvaluator::Dimensions& input_dims = m_impl.dimensions(); + + // Caches a few variables. + if (static_cast(Layout) == static_cast(ColMajor)) { + m_inputDepth = input_dims[0]; + m_inputRows = input_dims[1]; + m_inputCols = input_dims[2]; + } else { + m_inputDepth = input_dims[NumInputDims-1]; + m_inputRows = input_dims[NumInputDims-2]; + m_inputCols = input_dims[NumInputDims-3]; + } + + m_row_strides = op.row_strides(); + m_col_strides = op.col_strides(); + + // Input strides and effective input/patch size + m_in_row_strides = op.in_row_strides(); + m_in_col_strides = op.in_col_strides(); + m_row_inflate_strides = op.row_inflate_strides(); + m_col_inflate_strides = op.col_inflate_strides(); + // The "effective" input rows and input cols are the input rows and cols + // after inflating them with zeros. + // For examples, a 2x3 matrix with row_inflate_strides and + // col_inflate_strides of 2 comes from: + // A B C + // D E F + // + // to a matrix is 3 x 5: + // + // A . B . C + // . . . . . + // D . E . F + + m_input_rows_eff = (m_inputRows - 1) * m_row_inflate_strides + 1; + m_input_cols_eff = (m_inputCols - 1) * m_col_inflate_strides + 1; + m_patch_rows_eff = op.patch_rows() + (op.patch_rows() - 1) * (m_in_row_strides - 1); + m_patch_cols_eff = op.patch_cols() + (op.patch_cols() - 1) * (m_in_col_strides - 1); + + if (op.padding_explicit()) { + m_outputRows = numext::ceil((m_input_rows_eff + op.padding_top() + op.padding_bottom() - m_patch_rows_eff + 1.f) / static_cast(m_row_strides)); + m_outputCols = numext::ceil((m_input_cols_eff + op.padding_left() + op.padding_right() - m_patch_cols_eff + 1.f) / static_cast(m_col_strides)); + m_rowPaddingTop = op.padding_top(); + m_colPaddingLeft = op.padding_left(); + } else { + // Computing padding from the type + switch (op.padding_type()) { + case PADDING_VALID: + m_outputRows = numext::ceil((m_input_rows_eff - m_patch_rows_eff + 1.f) / static_cast(m_row_strides)); + m_outputCols = numext::ceil((m_input_cols_eff - m_patch_cols_eff + 1.f) / static_cast(m_col_strides)); + // Calculate the padding + m_rowPaddingTop = numext::maxi(0, ((m_outputRows - 1) * m_row_strides + m_patch_rows_eff - m_input_rows_eff) / 2); + m_colPaddingLeft = numext::maxi(0, ((m_outputCols - 1) * m_col_strides + m_patch_cols_eff - m_input_cols_eff) / 2); + break; + case PADDING_SAME: + m_outputRows = numext::ceil(m_input_rows_eff / static_cast(m_row_strides)); + m_outputCols = numext::ceil(m_input_cols_eff / static_cast(m_col_strides)); + // Calculate the padding + m_rowPaddingTop = ((m_outputRows - 1) * m_row_strides + m_patch_rows_eff - m_input_rows_eff) / 2; + m_colPaddingLeft = ((m_outputCols - 1) * m_col_strides + m_patch_cols_eff - m_input_cols_eff) / 2; + break; + default: + eigen_assert(false && "unexpected padding"); + } + } + eigen_assert(m_outputRows > 0); + eigen_assert(m_outputCols > 0); + + // Dimensions for result of extraction. + if (static_cast(Layout) == static_cast(ColMajor)) { + // ColMajor + // 0: depth + // 1: patch_rows + // 2: patch_cols + // 3: number of patches + // 4 and beyond: anything else (such as batch). + m_dimensions[0] = input_dims[0]; + m_dimensions[1] = op.patch_rows(); + m_dimensions[2] = op.patch_cols(); + m_dimensions[3] = m_outputRows * m_outputCols; + for (int i = 4; i < NumDims; ++i) { + m_dimensions[i] = input_dims[i-1]; + } + } else { + // RowMajor + // NumDims-1: depth + // NumDims-2: patch_rows + // NumDims-3: patch_cols + // NumDims-4: number of patches + // NumDims-5 and beyond: anything else (such as batch). + m_dimensions[NumDims-1] = input_dims[NumInputDims-1]; + m_dimensions[NumDims-2] = op.patch_rows(); + m_dimensions[NumDims-3] = op.patch_cols(); + m_dimensions[NumDims-4] = m_outputRows * m_outputCols; + for (int i = NumDims-5; i >= 0; --i) { + m_dimensions[i] = input_dims[i]; + } + } + + // Strides for moving the patch in various dimensions. + if (static_cast(Layout) == static_cast(ColMajor)) { + m_colStride = m_dimensions[1]; + m_patchStride = m_colStride * m_dimensions[2] * m_dimensions[0]; + m_otherStride = m_patchStride * m_dimensions[3]; + } else { + m_colStride = m_dimensions[NumDims-2]; + m_patchStride = m_colStride * m_dimensions[NumDims-3] * m_dimensions[NumDims-1]; + m_otherStride = m_patchStride * m_dimensions[NumDims-4]; + } + + // Strides for navigating through the input tensor. + m_rowInputStride = m_inputDepth; + m_colInputStride = m_inputDepth * m_inputRows; + m_patchInputStride = m_inputDepth * m_inputRows * m_inputCols; + + // Fast representations of different variables. + m_fastOtherStride = internal::TensorIntDivisor(m_otherStride); + m_fastPatchStride = internal::TensorIntDivisor(m_patchStride); + m_fastColStride = internal::TensorIntDivisor(m_colStride); + m_fastInflateRowStride = internal::TensorIntDivisor(m_row_inflate_strides); + m_fastInflateColStride = internal::TensorIntDivisor(m_col_inflate_strides); + m_fastInputColsEff = internal::TensorIntDivisor(m_input_cols_eff); + + // Number of patches in the width dimension. + m_fastOutputRows = internal::TensorIntDivisor(m_outputRows); + if (static_cast(Layout) == static_cast(ColMajor)) { + m_fastOutputDepth = internal::TensorIntDivisor(m_dimensions[0]); + } else { + m_fastOutputDepth = internal::TensorIntDivisor(m_dimensions[NumDims-1]); + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* /*data*/) { + m_impl.evalSubExprsIfNeeded(NULL); + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + // Patch index corresponding to the passed in index. + const Index patchIndex = index / m_fastPatchStride; + // Find the offset of the element wrt the location of the first element. + const Index patchOffset = (index - patchIndex * m_patchStride) / m_fastOutputDepth; + + // Other ways to index this element. + const Index otherIndex = (NumDims == 4) ? 0 : index / m_fastOtherStride; + const Index patch2DIndex = (NumDims == 4) ? patchIndex : (index - otherIndex * m_otherStride) / m_fastPatchStride; + + // Calculate col index in the input original tensor. + const Index colIndex = patch2DIndex / m_fastOutputRows; + const Index colOffset = patchOffset / m_fastColStride; + const Index inputCol = colIndex * m_col_strides + colOffset * m_in_col_strides - m_colPaddingLeft; + const Index origInputCol = (m_col_inflate_strides == 1) ? inputCol : ((inputCol >= 0) ? (inputCol / m_fastInflateColStride) : 0); + if (inputCol < 0 || inputCol >= m_input_cols_eff || + ((m_col_inflate_strides != 1) && (inputCol != origInputCol * m_col_inflate_strides))) { + return Scalar(m_paddingValue); + } + + // Calculate row index in the original input tensor. + const Index rowIndex = patch2DIndex - colIndex * m_outputRows; + const Index rowOffset = patchOffset - colOffset * m_colStride; + const Index inputRow = rowIndex * m_row_strides + rowOffset * m_in_row_strides - m_rowPaddingTop; + const Index origInputRow = (m_row_inflate_strides == 1) ? inputRow : ((inputRow >= 0) ? (inputRow / m_fastInflateRowStride) : 0); + if (inputRow < 0 || inputRow >= m_input_rows_eff || + ((m_row_inflate_strides != 1) && (inputRow != origInputRow * m_row_inflate_strides))) { + return Scalar(m_paddingValue); + } + + const int depth_index = static_cast(Layout) == static_cast(ColMajor) ? 0 : NumDims - 1; + const Index depth = index - (index / m_fastOutputDepth) * m_dimensions[depth_index]; + + const Index inputIndex = depth + origInputRow * m_rowInputStride + origInputCol * m_colInputStride + otherIndex * m_patchInputStride; + return m_impl.coeff(inputIndex); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index+PacketSize-1 < dimensions().TotalSize()); + + if (m_in_row_strides != 1 || m_in_col_strides != 1 || m_row_inflate_strides != 1 || m_col_inflate_strides != 1) { + return packetWithPossibleZero(index); + } + + const Index indices[2] = {index, index + PacketSize - 1}; + const Index patchIndex = indices[0] / m_fastPatchStride; + if (patchIndex != indices[1] / m_fastPatchStride) { + return packetWithPossibleZero(index); + } + const Index otherIndex = (NumDims == 4) ? 0 : indices[0] / m_fastOtherStride; + eigen_assert(otherIndex == indices[1] / m_fastOtherStride); + + // Find the offset of the element wrt the location of the first element. + const Index patchOffsets[2] = {(indices[0] - patchIndex * m_patchStride) / m_fastOutputDepth, + (indices[1] - patchIndex * m_patchStride) / m_fastOutputDepth}; + + const Index patch2DIndex = (NumDims == 4) ? patchIndex : (indices[0] - otherIndex * m_otherStride) / m_fastPatchStride; + eigen_assert(patch2DIndex == (indices[1] - otherIndex * m_otherStride) / m_fastPatchStride); + + const Index colIndex = patch2DIndex / m_fastOutputRows; + const Index colOffsets[2] = {patchOffsets[0] / m_fastColStride, patchOffsets[1] / m_fastColStride}; + + // Calculate col indices in the original input tensor. + const Index inputCols[2] = {colIndex * m_col_strides + colOffsets[0] - + m_colPaddingLeft, colIndex * m_col_strides + colOffsets[1] - m_colPaddingLeft}; + if (inputCols[1] < 0 || inputCols[0] >= m_inputCols) { + return internal::pset1(Scalar(m_paddingValue)); + } + + if (inputCols[0] == inputCols[1]) { + const Index rowIndex = patch2DIndex - colIndex * m_outputRows; + const Index rowOffsets[2] = {patchOffsets[0] - colOffsets[0]*m_colStride, patchOffsets[1] - colOffsets[1]*m_colStride}; + eigen_assert(rowOffsets[0] <= rowOffsets[1]); + // Calculate col indices in the original input tensor. + const Index inputRows[2] = {rowIndex * m_row_strides + rowOffsets[0] - + m_rowPaddingTop, rowIndex * m_row_strides + rowOffsets[1] - m_rowPaddingTop}; + + if (inputRows[1] < 0 || inputRows[0] >= m_inputRows) { + return internal::pset1(Scalar(m_paddingValue)); + } + + if (inputRows[0] >= 0 && inputRows[1] < m_inputRows) { + // no padding + const int depth_index = static_cast(Layout) == static_cast(ColMajor) ? 0 : NumDims - 1; + const Index depth = index - (index / m_fastOutputDepth) * m_dimensions[depth_index]; + const Index inputIndex = depth + inputRows[0] * m_rowInputStride + inputCols[0] * m_colInputStride + otherIndex * m_patchInputStride; + return m_impl.template packet(inputIndex); + } + } + + return packetWithPossibleZero(index); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + const TensorEvaluator& impl() const { return m_impl; } + + Index rowPaddingTop() const { return m_rowPaddingTop; } + Index colPaddingLeft() const { return m_colPaddingLeft; } + Index outputRows() const { return m_outputRows; } + Index outputCols() const { return m_outputCols; } + Index userRowStride() const { return m_row_strides; } + Index userColStride() const { return m_col_strides; } + Index userInRowStride() const { return m_in_row_strides; } + Index userInColStride() const { return m_in_col_strides; } + Index rowInflateStride() const { return m_row_inflate_strides; } + Index colInflateStride() const { return m_col_inflate_strides; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + // We conservatively estimate the cost for the code path where the computed + // index is inside the original image and + // TensorEvaluator::CoordAccess is false. + const double compute_cost = 3 * TensorOpCost::DivCost() + + 6 * TensorOpCost::MulCost() + + 8 * TensorOpCost::MulCost(); + return m_impl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, compute_cost, vectorized, PacketSize); + } + + protected: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetWithPossibleZero(Index index) const + { + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + for (int i = 0; i < PacketSize; ++i) { + values[i] = coeff(index+i); + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + + Dimensions m_dimensions; + + Index m_otherStride; + Index m_patchStride; + Index m_colStride; + Index m_row_strides; + Index m_col_strides; + + Index m_in_row_strides; + Index m_in_col_strides; + Index m_row_inflate_strides; + Index m_col_inflate_strides; + + Index m_input_rows_eff; + Index m_input_cols_eff; + Index m_patch_rows_eff; + Index m_patch_cols_eff; + + internal::TensorIntDivisor m_fastOtherStride; + internal::TensorIntDivisor m_fastPatchStride; + internal::TensorIntDivisor m_fastColStride; + internal::TensorIntDivisor m_fastInflateRowStride; + internal::TensorIntDivisor m_fastInflateColStride; + internal::TensorIntDivisor m_fastInputColsEff; + + Index m_rowInputStride; + Index m_colInputStride; + Index m_patchInputStride; + + Index m_inputDepth; + Index m_inputRows; + Index m_inputCols; + + Index m_outputRows; + Index m_outputCols; + + Index m_rowPaddingTop; + Index m_colPaddingLeft; + + internal::TensorIntDivisor m_fastOutputRows; + internal::TensorIntDivisor m_fastOutputDepth; + + Scalar m_paddingValue; + + TensorEvaluator m_impl; +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_IMAGE_PATCH_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIndexList.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIndexList.h new file mode 100644 index 00000000..3209fecd --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIndexList.h @@ -0,0 +1,725 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_INDEX_LIST_H +#define EIGEN_CXX11_TENSOR_TENSOR_INDEX_LIST_H + + +#if EIGEN_HAS_CONSTEXPR && EIGEN_HAS_VARIADIC_TEMPLATES + +#define EIGEN_HAS_INDEX_LIST + +namespace Eigen { + +/** \internal + * + * \class TensorIndexList + * \ingroup CXX11_Tensor_Module + * + * \brief Set of classes used to encode a set of Tensor dimensions/indices. + * + * The indices in the list can be known at compile time or at runtime. A mix + * of static and dynamic indices can also be provided if needed. The tensor + * code will attempt to take advantage of the indices that are known at + * compile time to optimize the code it generates. + * + * This functionality requires a c++11 compliant compiler. If your compiler + * is older you need to use arrays of indices instead. + * + * Several examples are provided in the cxx11_tensor_index_list.cpp file. + * + * \sa Tensor + */ + +template +struct type2index { + static const DenseIndex value = n; + EIGEN_DEVICE_FUNC constexpr operator DenseIndex() const { return n; } + EIGEN_DEVICE_FUNC void set(DenseIndex val) { + eigen_assert(val == n); + } +}; + +// This can be used with IndexPairList to get compile-time constant pairs, +// such as IndexPairList, type2indexpair<3,4>>(). +template +struct type2indexpair { + static const DenseIndex first = f; + static const DenseIndex second = s; + + constexpr EIGEN_DEVICE_FUNC operator IndexPair() const { + return IndexPair(f, s); + } + + EIGEN_DEVICE_FUNC void set(const IndexPair& val) { + eigen_assert(val.first == f); + eigen_assert(val.second == s); + } +}; + + +template struct NumTraits > +{ + typedef DenseIndex Real; + enum { + IsComplex = 0, + RequireInitialization = false, + ReadCost = 1, + AddCost = 1, + MulCost = 1 + }; + + EIGEN_DEVICE_FUNC static inline Real epsilon() { return 0; } + EIGEN_DEVICE_FUNC static inline Real dummy_precision() { return 0; } + EIGEN_DEVICE_FUNC static inline Real highest() { return n; } + EIGEN_DEVICE_FUNC static inline Real lowest() { return n; } +}; + +namespace internal { +template +EIGEN_DEVICE_FUNC void update_value(T& val, DenseIndex new_val) { + val = new_val; +} +template +EIGEN_DEVICE_FUNC void update_value(type2index& val, DenseIndex new_val) { + val.set(new_val); +} + +template +EIGEN_DEVICE_FUNC void update_value(T& val, IndexPair new_val) { + val = new_val; +} +template +EIGEN_DEVICE_FUNC void update_value(type2indexpair& val, IndexPair new_val) { + val.set(new_val); +} + + +template +struct is_compile_time_constant { + static constexpr bool value = false; +}; + +template +struct is_compile_time_constant > { + static constexpr bool value = true; +}; +template +struct is_compile_time_constant > { + static constexpr bool value = true; +}; +template +struct is_compile_time_constant& > { + static constexpr bool value = true; +}; +template +struct is_compile_time_constant& > { + static constexpr bool value = true; +}; + +template +struct is_compile_time_constant > { + static constexpr bool value = true; +}; +template +struct is_compile_time_constant > { + static constexpr bool value = true; +}; +template +struct is_compile_time_constant& > { + static constexpr bool value = true; +}; +template +struct is_compile_time_constant& > { + static constexpr bool value = true; +}; + + +template +struct IndexTuple; + +template +struct IndexTuple { + EIGEN_DEVICE_FUNC constexpr IndexTuple() : head(), others() { } + EIGEN_DEVICE_FUNC constexpr IndexTuple(const T& v, const O... o) : head(v), others(o...) { } + + constexpr static int count = 1 + sizeof...(O); + T head; + IndexTuple others; + typedef T Head; + typedef IndexTuple Other; +}; + +template + struct IndexTuple { + EIGEN_DEVICE_FUNC constexpr IndexTuple() : head() { } + EIGEN_DEVICE_FUNC constexpr IndexTuple(const T& v) : head(v) { } + + constexpr static int count = 1; + T head; + typedef T Head; +}; + + +template +struct IndexTupleExtractor; + +template +struct IndexTupleExtractor { + + typedef typename IndexTupleExtractor::ValType ValType; + + EIGEN_DEVICE_FUNC static constexpr ValType& get_val(IndexTuple& val) { + return IndexTupleExtractor::get_val(val.others); + } + + EIGEN_DEVICE_FUNC static constexpr const ValType& get_val(const IndexTuple& val) { + return IndexTupleExtractor::get_val(val.others); + } + template + EIGEN_DEVICE_FUNC static void set_val(IndexTuple& val, V& new_val) { + IndexTupleExtractor::set_val(val.others, new_val); + } + +}; + +template + struct IndexTupleExtractor<0, T, O...> { + + typedef T ValType; + + EIGEN_DEVICE_FUNC static constexpr ValType& get_val(IndexTuple& val) { + return val.head; + } + EIGEN_DEVICE_FUNC static constexpr const ValType& get_val(const IndexTuple& val) { + return val.head; + } + template + EIGEN_DEVICE_FUNC static void set_val(IndexTuple& val, V& new_val) { + val.head = new_val; + } +}; + + + +template +EIGEN_DEVICE_FUNC constexpr typename IndexTupleExtractor::ValType& array_get(IndexTuple& tuple) { + return IndexTupleExtractor::get_val(tuple); +} +template +EIGEN_DEVICE_FUNC constexpr const typename IndexTupleExtractor::ValType& array_get(const IndexTuple& tuple) { + return IndexTupleExtractor::get_val(tuple); +} +template + struct array_size > { + static const size_t value = IndexTuple::count; +}; +template + struct array_size > { + static const size_t value = IndexTuple::count; +}; + + + + +template +struct tuple_coeff { + template + EIGEN_DEVICE_FUNC static constexpr ValueT get(const DenseIndex i, const IndexTuple& t) { + // return array_get(t) * (i == Idx) + tuple_coeff::get(i, t) * (i != Idx); + return (i == Idx ? array_get(t) : tuple_coeff::get(i, t)); + } + template + EIGEN_DEVICE_FUNC static void set(const DenseIndex i, IndexTuple& t, const ValueT& value) { + if (i == Idx) { + update_value(array_get(t), value); + } else { + tuple_coeff::set(i, t, value); + } + } + + template + EIGEN_DEVICE_FUNC static constexpr bool value_known_statically(const DenseIndex i, const IndexTuple& t) { + return ((i == Idx) & is_compile_time_constant::ValType>::value) || + tuple_coeff::value_known_statically(i, t); + } + + template + EIGEN_DEVICE_FUNC static constexpr bool values_up_to_known_statically(const IndexTuple& t) { + return is_compile_time_constant::ValType>::value && + tuple_coeff::values_up_to_known_statically(t); + } + + template + EIGEN_DEVICE_FUNC static constexpr bool values_up_to_statically_known_to_increase(const IndexTuple& t) { + return is_compile_time_constant::ValType>::value && + is_compile_time_constant::ValType>::value && + array_get(t) > array_get(t) && + tuple_coeff::values_up_to_statically_known_to_increase(t); + } +}; + +template +struct tuple_coeff<0, ValueT> { + template + EIGEN_DEVICE_FUNC static constexpr ValueT get(const DenseIndex /*i*/, const IndexTuple& t) { + // eigen_assert (i == 0); // gcc fails to compile assertions in constexpr + return array_get<0>(t)/* * (i == 0)*/; + } + template + EIGEN_DEVICE_FUNC static void set(const DenseIndex i, IndexTuple& t, const ValueT value) { + eigen_assert (i == 0); + update_value(array_get<0>(t), value); + } + template + EIGEN_DEVICE_FUNC static constexpr bool value_known_statically(const DenseIndex i, const IndexTuple&) { + return is_compile_time_constant::ValType>::value & (i == 0); + } + + template + EIGEN_DEVICE_FUNC static constexpr bool values_up_to_known_statically(const IndexTuple&) { + return is_compile_time_constant::ValType>::value; + } + + template + EIGEN_DEVICE_FUNC static constexpr bool values_up_to_statically_known_to_increase(const IndexTuple&) { + return true; + } +}; +} // namespace internal + + + +template +struct IndexList : internal::IndexTuple { + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC constexpr DenseIndex operator[] (const DenseIndex i) const { + return internal::tuple_coeff >::value-1, DenseIndex>::get(i, *this); + } + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC constexpr DenseIndex get(const DenseIndex i) const { + return internal::tuple_coeff >::value-1, DenseIndex>::get(i, *this); + } + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC void set(const DenseIndex i, const DenseIndex value) { + return internal::tuple_coeff >::value-1, DenseIndex>::set(i, *this, value); + } + + EIGEN_DEVICE_FUNC constexpr IndexList(const internal::IndexTuple& other) : internal::IndexTuple(other) { } + EIGEN_DEVICE_FUNC constexpr IndexList(FirstType& first, OtherTypes... other) : internal::IndexTuple(first, other...) { } + EIGEN_DEVICE_FUNC constexpr IndexList() : internal::IndexTuple() { } + + EIGEN_DEVICE_FUNC constexpr bool value_known_statically(const DenseIndex i) const { + return internal::tuple_coeff >::value-1, DenseIndex>::value_known_statically(i, *this); + } + EIGEN_DEVICE_FUNC constexpr bool all_values_known_statically() const { + return internal::tuple_coeff >::value-1, DenseIndex>::values_up_to_known_statically(*this); + } + + EIGEN_DEVICE_FUNC constexpr bool values_statically_known_to_increase() const { + return internal::tuple_coeff >::value-1, DenseIndex>::values_up_to_statically_known_to_increase(*this); + } +}; + + +template +constexpr IndexList make_index_list(FirstType val1, OtherTypes... other_vals) { + return IndexList(val1, other_vals...); +} + + +template +struct IndexPairList : internal::IndexTuple { + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC constexpr IndexPair operator[] (const DenseIndex i) const { + return internal::tuple_coeff >::value-1, IndexPair>::get(i, *this); + } + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC void set(const DenseIndex i, const IndexPair value) { + return internal::tuple_coeff>::value-1, IndexPair >::set(i, *this, value); + } + + EIGEN_DEVICE_FUNC constexpr IndexPairList(const internal::IndexTuple& other) : internal::IndexTuple(other) { } + EIGEN_DEVICE_FUNC constexpr IndexPairList() : internal::IndexTuple() { } + + EIGEN_DEVICE_FUNC constexpr bool value_known_statically(const DenseIndex i) const { + return internal::tuple_coeff >::value-1, DenseIndex>::value_known_statically(i, *this); + } +}; + +namespace internal { + +template size_t array_prod(const IndexList& sizes) { + size_t result = 1; + for (int i = 0; i < array_size >::value; ++i) { + result *= sizes[i]; + } + return result; +} + +template struct array_size > { + static const size_t value = array_size >::value; +}; +template struct array_size > { + static const size_t value = array_size >::value; +}; + +template struct array_size > { + static const size_t value = std::tuple_size >::value; +}; +template struct array_size > { + static const size_t value = std::tuple_size >::value; +}; + +template EIGEN_DEVICE_FUNC constexpr DenseIndex array_get(IndexList& a) { + return IndexTupleExtractor::get_val(a); +} +template EIGEN_DEVICE_FUNC constexpr DenseIndex array_get(const IndexList& a) { + return IndexTupleExtractor::get_val(a); +} + +template +struct index_known_statically_impl { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex) { + return false; + } +}; + +template +struct index_known_statically_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i) { + return IndexList().value_known_statically(i); + } +}; + +template +struct index_known_statically_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i) { + return IndexList().value_known_statically(i); + } +}; + + +template +struct all_indices_known_statically_impl { + static constexpr bool run() { + return false; + } +}; + +template +struct all_indices_known_statically_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run() { + return IndexList().all_values_known_statically(); + } +}; + +template +struct all_indices_known_statically_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run() { + return IndexList().all_values_known_statically(); + } +}; + + +template +struct indices_statically_known_to_increase_impl { + EIGEN_DEVICE_FUNC static constexpr bool run() { + return false; + } +}; + +template + struct indices_statically_known_to_increase_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run() { + return Eigen::IndexList().values_statically_known_to_increase(); + } +}; + +template + struct indices_statically_known_to_increase_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run() { + return Eigen::IndexList().values_statically_known_to_increase(); + } +}; + + +template +struct index_statically_eq_impl { + EIGEN_DEVICE_FUNC static constexpr bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_statically_eq_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexList().value_known_statically(i) & + (IndexList().get(i) == value); + } +}; + +template +struct index_statically_eq_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexList().value_known_statically(i) & + (IndexList().get(i) == value); + } +}; + + +template +struct index_statically_ne_impl { + EIGEN_DEVICE_FUNC static constexpr bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_statically_ne_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexList().value_known_statically(i) & + (IndexList().get(i) != value); + } +}; + +template +struct index_statically_ne_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexList().value_known_statically(i) & + (IndexList().get(i) != value); + } +}; + + +template +struct index_statically_gt_impl { + EIGEN_DEVICE_FUNC static constexpr bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_statically_gt_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexList().value_known_statically(i) & + (IndexList().get(i) > value); + } +}; + +template +struct index_statically_gt_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexList().value_known_statically(i) & + (IndexList().get(i) > value); + } +}; + + + +template +struct index_statically_lt_impl { + EIGEN_DEVICE_FUNC static constexpr bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_statically_lt_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexList().value_known_statically(i) & + (IndexList().get(i) < value); + } +}; + +template +struct index_statically_lt_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexList().value_known_statically(i) & + (IndexList().get(i) < value); + } +}; + + + +template +struct index_pair_first_statically_eq_impl { + EIGEN_DEVICE_FUNC static constexpr bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_pair_first_statically_eq_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexPairList().value_known_statically(i) & + (IndexPairList().operator[](i).first == value); + } +}; + +template +struct index_pair_first_statically_eq_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexPairList().value_known_statically(i) & + (IndexPairList().operator[](i).first == value); + } +}; + + + +template +struct index_pair_second_statically_eq_impl { + EIGEN_DEVICE_FUNC static constexpr bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_pair_second_statically_eq_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexPairList().value_known_statically(i) & + (IndexPairList().operator[](i).second == value); + } +}; + +template +struct index_pair_second_statically_eq_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexPairList().value_known_statically(i) & + (IndexPairList().operator[](i).second == value); + } +}; + + +} // end namespace internal +} // end namespace Eigen + +#else + +namespace Eigen { +namespace internal { + +template +struct index_known_statically_impl { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex) { + return false; + } +}; + +template +struct all_indices_known_statically_impl { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run() { + return false; + } +}; + +template +struct indices_statically_known_to_increase_impl { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run() { + return false; + } +}; + +template +struct index_statically_eq_impl { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_statically_ne_impl { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_statically_gt_impl { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_statically_lt_impl { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_pair_first_statically_eq_impl { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_pair_second_statically_eq_impl { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(DenseIndex, DenseIndex) { + return false; + } +}; + + + +} // end namespace internal +} // end namespace Eigen + +#endif + + +namespace Eigen { +namespace internal { +template +static EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_known_statically(DenseIndex i) { + return index_known_statically_impl::run(i); +} + +template +static EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool all_indices_known_statically() { + return all_indices_known_statically_impl::run(); +} + +template +static EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool indices_statically_known_to_increase() { + return indices_statically_known_to_increase_impl::run(); +} + +template +static EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_statically_eq(DenseIndex i, DenseIndex value) { + return index_statically_eq_impl::run(i, value); +} + +template +static EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_statically_ne(DenseIndex i, DenseIndex value) { + return index_statically_ne_impl::run(i, value); +} + +template +static EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_statically_gt(DenseIndex i, DenseIndex value) { + return index_statically_gt_impl::run(i, value); +} + +template +static EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_statically_lt(DenseIndex i, DenseIndex value) { + return index_statically_lt_impl::run(i, value); +} + +template +static EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_pair_first_statically_eq(DenseIndex i, DenseIndex value) { + return index_pair_first_statically_eq_impl::run(i, value); +} + +template +static EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_pair_second_statically_eq(DenseIndex i, DenseIndex value) { + return index_pair_second_statically_eq_impl::run(i, value); +} + +} // end namespace internal +} // end namespace Eigen + + +#endif // EIGEN_CXX11_TENSOR_TENSOR_INDEX_LIST_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorInflation.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorInflation.h new file mode 100644 index 00000000..f391fb9e --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorInflation.h @@ -0,0 +1,229 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Ke Yang +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_INFLATION_H +#define EIGEN_CXX11_TENSOR_TENSOR_INFLATION_H + +namespace Eigen { + +/** \class TensorInflation + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor inflation class. + * + * + */ +namespace internal { +template +struct traits > : public traits +{ + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorInflationOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorInflationOp type; +}; + +} // end namespace internal + +template +class TensorInflationOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorInflationOp(const XprType& expr, const Strides& strides) + : m_xpr(expr), m_strides(strides) {} + + EIGEN_DEVICE_FUNC + const Strides& strides() const { return m_strides; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + protected: + typename XprType::Nested m_xpr; + const Strides m_strides; +}; + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorInflationOp XprType; + typedef typename XprType::Index Index; + static const int NumDims = internal::array_size::Dimensions>::value; + typedef DSizes Dimensions; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = /*TensorEvaluator::IsAligned*/ false, + PacketAccess = TensorEvaluator::PacketAccess, + BlockAccess = false, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device), m_strides(op.strides()) + { + m_dimensions = m_impl.dimensions(); + // Expand each dimension to the inflated dimension. + for (int i = 0; i < NumDims; ++i) { + m_dimensions[i] = (m_dimensions[i] - 1) * op.strides()[i] + 1; + } + + // Remember the strides for fast division. + for (int i = 0; i < NumDims; ++i) { + m_fastStrides[i] = internal::TensorIntDivisor(m_strides[i]); + } + + const typename TensorEvaluator::Dimensions& input_dims = m_impl.dimensions(); + if (static_cast(Layout) == static_cast(ColMajor)) { + m_outputStrides[0] = 1; + m_inputStrides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_outputStrides[i] = m_outputStrides[i-1] * m_dimensions[i-1]; + m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1]; + } + } else { // RowMajor + m_outputStrides[NumDims-1] = 1; + m_inputStrides[NumDims-1] = 1; + for (int i = NumDims - 2; i >= 0; --i) { + m_outputStrides[i] = m_outputStrides[i+1] * m_dimensions[i+1]; + m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1]; + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* /*data*/) { + m_impl.evalSubExprsIfNeeded(NULL); + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + // Computes the input index given the output index. Returns true if the output + // index doesn't fall into a hole. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool getInputIndex(Index index, Index* inputIndex) const + { + eigen_assert(index < dimensions().TotalSize()); + *inputIndex = 0; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i > 0; --i) { + const Index idx = index / m_outputStrides[i]; + if (idx != idx / m_fastStrides[i] * m_strides[i]) { + return false; + } + *inputIndex += idx / m_strides[i] * m_inputStrides[i]; + index -= idx * m_outputStrides[i]; + } + if (index != index / m_fastStrides[0] * m_strides[0]) { + return false; + } + *inputIndex += index / m_strides[0]; + return true; + } else { + for (int i = 0; i < NumDims - 1; ++i) { + const Index idx = index / m_outputStrides[i]; + if (idx != idx / m_fastStrides[i] * m_strides[i]) { + return false; + } + *inputIndex += idx / m_strides[i] * m_inputStrides[i]; + index -= idx * m_outputStrides[i]; + } + if (index != index / m_fastStrides[NumDims-1] * m_strides[NumDims-1]) { + return false; + } + *inputIndex += index / m_strides[NumDims - 1]; + } + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + Index inputIndex = 0; + if (getInputIndex(index, &inputIndex)) { + return m_impl.coeff(inputIndex); + } else { + return Scalar(0); + } + } + + // TODO(yangke): optimize this function so that we can detect and produce + // all-zero packets + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index+PacketSize-1 < dimensions().TotalSize()); + + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + for (int i = 0; i < PacketSize; ++i) { + values[i] = coeff(index+i); + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + const double compute_cost = NumDims * (3 * TensorOpCost::DivCost() + + 3 * TensorOpCost::MulCost() + + 2 * TensorOpCost::AddCost()); + const double input_size = m_impl.dimensions().TotalSize(); + const double output_size = m_dimensions.TotalSize(); + if (output_size == 0) + return TensorOpCost(); + return m_impl.costPerCoeff(vectorized) + + TensorOpCost(sizeof(CoeffReturnType) * input_size / output_size, 0, + compute_cost, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + protected: + Dimensions m_dimensions; + array m_outputStrides; + array m_inputStrides; + TensorEvaluator m_impl; + const Strides m_strides; + array, NumDims> m_fastStrides; +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_INFLATION_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorInitializer.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorInitializer.h new file mode 100644 index 00000000..33edc49e --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorInitializer.h @@ -0,0 +1,82 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_INITIALIZER_H +#define EIGEN_CXX11_TENSOR_TENSOR_INITIALIZER_H + +#if EIGEN_HAS_VARIADIC_TEMPLATES + +#include + +namespace Eigen { + +/** \class TensorInitializer + * \ingroup CXX11_Tensor_Module + * + * \brief Helper template to initialize Tensors from std::initializer_lists. + */ +namespace internal { + +template +struct Initializer { + typedef std::initializer_list< + typename Initializer::InitList> InitList; + + static void run(TensorEvaluator& tensor, + Eigen::array::Index, traits::NumDimensions>* indices, + const InitList& vals) { + int i = 0; + for (auto v : vals) { + (*indices)[traits::NumDimensions - N] = i++; + Initializer::run(tensor, indices, v); + } + } +}; + +template +struct Initializer { + typedef std::initializer_list::Scalar> InitList; + + static void run(TensorEvaluator& tensor, + Eigen::array::Index, traits::NumDimensions>* indices, + const InitList& vals) { + int i = 0; + // There is likely a faster way to do that than iterating. + for (auto v : vals) { + (*indices)[traits::NumDimensions - 1] = i++; + tensor.coeffRef(*indices) = v; + } + } +}; + +template +struct Initializer { + typedef typename traits::Scalar InitList; + + static void run(TensorEvaluator& tensor, + Eigen::array::Index, traits::NumDimensions>*, + const InitList& v) { + tensor.coeffRef(0) = v; + } +}; + + +template +void initialize_tensor(TensorEvaluator& tensor, + const typename Initializer::NumDimensions>::InitList& vals) { + Eigen::array::Index, traits::NumDimensions> indices; + Initializer::NumDimensions>::run(tensor, &indices, vals); +} + +} // namespace internal +} // namespace Eigen + +#endif // EIGEN_HAS_VARIADIC_TEMPLATES + +#endif // EIGEN_CXX11_TENSOR_TENSOR_INITIALIZER_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIntDiv.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIntDiv.h new file mode 100644 index 00000000..ef1c9c42 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIntDiv.h @@ -0,0 +1,263 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_INTDIV_H +#define EIGEN_CXX11_TENSOR_TENSOR_INTDIV_H + + +namespace Eigen { + +/** \internal + * + * \class TensorIntDiv + * \ingroup CXX11_Tensor_Module + * + * \brief Fast integer division by a constant. + * + * See the paper from Granlund and Montgomery for explanation. + * (at http://dx.doi.org/10.1145/773473.178249) + * + * \sa Tensor + */ + +namespace internal { + +namespace { + + // Note: result is undefined if val == 0 + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE + typename internal::enable_if::type count_leading_zeros(const T val) + { +#ifdef __CUDA_ARCH__ + return __clz(val); +#elif defined(__SYCL_DEVICE_ONLY__) + return cl::sycl::clz(val); +#elif EIGEN_COMP_MSVC + unsigned long index; + _BitScanReverse(&index, val); + return 31 - index; +#else + EIGEN_STATIC_ASSERT(sizeof(unsigned long long) == 8, YOU_MADE_A_PROGRAMMING_MISTAKE); + return __builtin_clz(static_cast(val)); +#endif + } + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE + typename internal::enable_if::type count_leading_zeros(const T val) + { +#ifdef __CUDA_ARCH__ + return __clzll(val); +#elif defined(__SYCL_DEVICE_ONLY__) + return cl::sycl::clz(val); +#elif EIGEN_COMP_MSVC && EIGEN_ARCH_x86_64 + unsigned long index; + _BitScanReverse64(&index, val); + return 63 - index; +#elif EIGEN_COMP_MSVC + // MSVC's _BitScanReverse64 is not available for 32bits builds. + unsigned int lo = (unsigned int)(val&0xffffffff); + unsigned int hi = (unsigned int)((val>>32)&0xffffffff); + int n; + if(hi==0) + n = 32 + count_leading_zeros(lo); + else + n = count_leading_zeros(hi); + return n; +#else + EIGEN_STATIC_ASSERT(sizeof(unsigned long long) == 8, YOU_MADE_A_PROGRAMMING_MISTAKE); + return __builtin_clzll(static_cast(val)); +#endif + } + + template + struct UnsignedTraits { + typedef typename conditional::type type; + }; + + template + struct DividerTraits { + typedef typename UnsignedTraits::type type; + static const int N = sizeof(T) * 8; + }; + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE uint32_t muluh(const uint32_t a, const T b) { +#if defined(__CUDA_ARCH__) + return __umulhi(a, b); +#elif defined(__SYCL_DEVICE_ONLY__) + return cl::sycl::mul_hi(a, static_cast(b)); +#else + return (static_cast(a) * b) >> 32; +#endif + } + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE uint64_t muluh(const uint64_t a, const T b) { +#if defined(__CUDA_ARCH__) + return __umul64hi(a, b); +#elif defined(__SYCL_DEVICE_ONLY__) + return cl::sycl::mul_hi(a, static_cast(b)); +#elif defined(__SIZEOF_INT128__) + __uint128_t v = static_cast<__uint128_t>(a) * static_cast<__uint128_t>(b); + return static_cast(v >> 64); +#else + return (TensorUInt128, uint64_t>(a) * TensorUInt128, uint64_t>(b)).upper(); +#endif + } + + template + struct DividerHelper { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE uint32_t computeMultiplier(const int log_div, const T divider) { + EIGEN_STATIC_ASSERT(N == 32, YOU_MADE_A_PROGRAMMING_MISTAKE); + return static_cast((static_cast(1) << (N+log_div)) / divider - (static_cast(1) << N) + 1); + } + }; + + template + struct DividerHelper<64, T> { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE uint64_t computeMultiplier(const int log_div, const T divider) { +#if defined(__SIZEOF_INT128__) && !defined(__CUDA_ARCH__) && !defined(__SYCL_DEVICE_ONLY__) + return static_cast((static_cast<__uint128_t>(1) << (64+log_div)) / static_cast<__uint128_t>(divider) - (static_cast<__uint128_t>(1) << 64) + 1); +#else + const uint64_t shift = 1ULL << log_div; + TensorUInt128 result = TensorUInt128 >(shift, 0) / TensorUInt128, uint64_t>(divider) + - TensorUInt128, static_val<0> >(1, 0) + + TensorUInt128, static_val<1> >(1); + return static_cast(result); +#endif + } + }; +} + + +template +struct TensorIntDivisor { + public: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorIntDivisor() { + multiplier = 0; + shift1 = 0; + shift2 = 0; + } + + // Must have 0 < divider < 2^31. This is relaxed to + // 0 < divider < 2^63 when using 64-bit indices on platforms that support + // the __uint128_t type. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorIntDivisor(const T divider) { + const int N = DividerTraits::N; + eigen_assert(static_cast::type>(divider) < NumTraits::highest()/2); + eigen_assert(divider > 0); + + // fast ln2 + const int leading_zeros = count_leading_zeros(static_cast(divider)); + int log_div = N - leading_zeros; + // if divider is a power of two then log_div is 1 more than it should be. + if ((static_cast::type>(1) << (log_div-1)) == static_cast::type>(divider)) + log_div--; + + multiplier = DividerHelper::computeMultiplier(log_div, divider); + shift1 = log_div > 1 ? 1 : log_div; + shift2 = log_div > 1 ? log_div-1 : 0; + } + + // Must have 0 <= numerator. On platforms that dont support the __uint128_t + // type numerator should also be less than 2^32-1. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T divide(const T numerator) const { + eigen_assert(static_cast::type>(numerator) < NumTraits::highest()/2); + //eigen_assert(numerator >= 0); // this is implicitly asserted by the line above + + UnsignedType t1 = muluh(multiplier, numerator); + UnsignedType t = (static_cast(numerator) - t1) >> shift1; + return (t1 + t) >> shift2; + } + + private: + typedef typename DividerTraits::type UnsignedType; + UnsignedType multiplier; + int32_t shift1; + int32_t shift2; +}; + + +// Optimized version for signed 32 bit integers. +// Derived from Hacker's Delight. +// Only works for divisors strictly greater than one +template <> +class TensorIntDivisor { + public: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorIntDivisor() { + magic = 0; + shift = 0; + } + // Must have 2 <= divider + EIGEN_DEVICE_FUNC TensorIntDivisor(int32_t divider) { + eigen_assert(divider >= 2); + calcMagic(divider); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE int divide(const int32_t n) const { +#ifdef __CUDA_ARCH__ + return (__umulhi(magic, n) >> shift); +#elif defined(__SYCL_DEVICE_ONLY__) + return (cl::sycl::mul_hi(static_cast(magic), static_cast(n)) >> shift); +#else + uint64_t v = static_cast(magic) * static_cast(n); + return (static_cast(v >> 32) >> shift); +#endif + } + +private: + // Compute the magic numbers. See Hacker's Delight section 10 for an in + // depth explanation. + EIGEN_DEVICE_FUNC void calcMagic(int32_t d) { + const unsigned two31 = 0x80000000; // 2**31. + unsigned ad = d; + unsigned t = two31 + (ad >> 31); + unsigned anc = t - 1 - t%ad; // Absolute value of nc. + int p = 31; // Init. p. + unsigned q1 = two31/anc; // Init. q1 = 2**p/|nc|. + unsigned r1 = two31 - q1*anc; // Init. r1 = rem(2**p, |nc|). + unsigned q2 = two31/ad; // Init. q2 = 2**p/|d|. + unsigned r2 = two31 - q2*ad; // Init. r2 = rem(2**p, |d|). + unsigned delta = 0; + do { + p = p + 1; + q1 = 2*q1; // Update q1 = 2**p/|nc|. + r1 = 2*r1; // Update r1 = rem(2**p, |nc|). + if (r1 >= anc) { // (Must be an unsigned + q1 = q1 + 1; // comparison here). + r1 = r1 - anc;} + q2 = 2*q2; // Update q2 = 2**p/|d|. + r2 = 2*r2; // Update r2 = rem(2**p, |d|). + if (r2 >= ad) { // (Must be an unsigned + q2 = q2 + 1; // comparison here). + r2 = r2 - ad;} + delta = ad - r2; + } while (q1 < delta || (q1 == delta && r1 == 0)); + + magic = (unsigned)(q2 + 1); + shift = p - 32; + } + + uint32_t magic; + int32_t shift; +}; + + +template +static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T operator / (const T& numerator, const TensorIntDivisor& divisor) { + return divisor.divide(numerator); +} + + +} // end namespace internal +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_INTDIV_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorLayoutSwap.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorLayoutSwap.h new file mode 100644 index 00000000..cd0109ef --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorLayoutSwap.h @@ -0,0 +1,209 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_LAYOUT_SWAP_H +#define EIGEN_CXX11_TENSOR_TENSOR_LAYOUT_SWAP_H + +namespace Eigen { + +/** \class TensorLayoutSwap + * \ingroup CXX11_Tensor_Module + * + * \brief Swap the layout from col-major to row-major, or row-major + * to col-major, and invert the order of the dimensions. + * + * Beware: the dimensions are reversed by this operation. If you want to + * preserve the ordering of the dimensions, you need to combine this + * operation with a shuffle. + * + * \example: + * Tensor input(2, 4); + * Tensor output = input.swap_layout(); + * eigen_assert(output.dimension(0) == 4); + * eigen_assert(output.dimension(1) == 2); + * + * array shuffle(1, 0); + * output = input.swap_layout().shuffle(shuffle); + * eigen_assert(output.dimension(0) == 2); + * eigen_assert(output.dimension(1) == 4); + * + */ +namespace internal { +template +struct traits > : public traits +{ + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = traits::NumDimensions; + static const int Layout = (traits::Layout == ColMajor) ? RowMajor : ColMajor; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorLayoutSwapOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorLayoutSwapOp type; +}; + +} // end namespace internal + + + +template +class TensorLayoutSwapOp : public TensorBase, WriteAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename internal::remove_const::type CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorLayoutSwapOp(const XprType& expr) + : m_xpr(expr) {} + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorLayoutSwapOp& operator = (const TensorLayoutSwapOp& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorLayoutSwapOp& operator = (const OtherDerived& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + protected: + typename XprType::Nested m_xpr; +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorLayoutSwapOp XprType; + typedef typename XprType::Index Index; + static const int NumDims = internal::array_size::Dimensions>::value; + typedef DSizes Dimensions; + + enum { + IsAligned = TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = (static_cast(TensorEvaluator::Layout) == static_cast(ColMajor)) ? RowMajor : ColMajor, + CoordAccess = false, // to be implemented + RawAccess = TensorEvaluator::RawAccess + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device) + { + for(int i = 0; i < NumDims; ++i) { + m_dimensions[i] = m_impl.dimensions()[NumDims-1-i]; + } + } + + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType* data) { + return m_impl.evalSubExprsIfNeeded(data); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + return m_impl.coeff(index); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + return m_impl.template packet(index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + return m_impl.costPerCoeff(vectorized); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return m_impl.data(); } + + const TensorEvaluator& impl() const { return m_impl; } + + protected: + TensorEvaluator m_impl; + Dimensions m_dimensions; +}; + + +// Eval as lvalue +template + struct TensorEvaluator, Device> + : public TensorEvaluator, Device> +{ + typedef TensorEvaluator, Device> Base; + typedef TensorLayoutSwapOp XprType; + + enum { + IsAligned = TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = (static_cast(TensorEvaluator::Layout) == static_cast(ColMajor)) ? RowMajor : ColMajor, + CoordAccess = false // to be implemented + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : Base(op, device) + { } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index) + { + return this->m_impl.coeffRef(index); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketReturnType& x) + { + this->m_impl.template writePacket(index, x); + } +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_LAYOUT_SWAP_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMacros.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMacros.h new file mode 100644 index 00000000..f92e39d6 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMacros.h @@ -0,0 +1,62 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_META_MACROS_H +#define EIGEN_CXX11_TENSOR_TENSOR_META_MACROS_H + + +/** use this macro in sfinae selection in templated functions + * + * template::value , int >::type = 0 + * > + * void foo(){} + * + * becomes => + * + * template::value ) + * > + * void foo(){} + */ + +// SFINAE requires variadic templates +#ifndef __CUDACC__ +#if EIGEN_HAS_VARIADIC_TEMPLATES + // SFINAE doesn't work for gcc <= 4.7 + #ifdef EIGEN_COMP_GNUC + #if EIGEN_GNUC_AT_LEAST(4,8) + #define EIGEN_HAS_SFINAE + #endif + #else + #define EIGEN_HAS_SFINAE + #endif +#endif +#endif + +#define EIGEN_SFINAE_ENABLE_IF( __condition__ ) \ + typename internal::enable_if< ( __condition__ ) , int >::type = 0 + + +#if EIGEN_HAS_CONSTEXPR +#define EIGEN_CONSTEXPR constexpr +#else +#define EIGEN_CONSTEXPR +#endif + + +#if EIGEN_OS_WIN || EIGEN_OS_WIN64 +#define EIGEN_SLEEP(n) Sleep(n) +#elif EIGEN_OS_GNULINUX +#define EIGEN_SLEEP(n) usleep(n * 1000); +#else +#define EIGEN_SLEEP(n) sleep(std::max(1, n/1000)) +#endif + +#endif diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMap.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMap.h new file mode 100644 index 00000000..a8e55757 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMap.h @@ -0,0 +1,321 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_MAP_H +#define EIGEN_CXX11_TENSOR_TENSOR_MAP_H + +namespace Eigen { + +/** \class TensorMap + * \ingroup CXX11_Tensor_Module + * + * \brief A tensor expression mapping an existing array of data. + * + */ +/// template class MakePointer_ is added to convert the host pointer to the device pointer. +/// It is added due to the fact that for our device compiler T* is not allowed. +/// If we wanted to use the same Evaluator functions we have to convert that type to our pointer T. +/// This is done through our MakePointer_ class. By default the Type in the MakePointer_ is T* . +/// Therefore, by adding the default value, we managed to convert the type and it does not break any +/// existing code as its default value is T*. +template class MakePointer_> class TensorMap : public TensorBase > +{ + public: + typedef TensorMap Self; + typedef typename PlainObjectType::Base Base; + typedef typename Eigen::internal::nested::type Nested; + typedef typename internal::traits::StorageKind StorageKind; + typedef typename internal::traits::Index Index; + typedef typename internal::traits::Scalar Scalar; + typedef typename NumTraits::Real RealScalar; + typedef typename Base::CoeffReturnType CoeffReturnType; + + /* typedef typename internal::conditional< + bool(internal::is_lvalue::value), + Scalar *, + const Scalar *>::type + PointerType;*/ + typedef typename MakePointer_::Type PointerType; + typedef PointerType PointerArgType; + + static const int Options = Options_; + + static const Index NumIndices = PlainObjectType::NumIndices; + typedef typename PlainObjectType::Dimensions Dimensions; + + enum { + IsAligned = ((int(Options_)&Aligned)==Aligned), + Layout = PlainObjectType::Layout, + CoordAccess = true, + RawAccess = true + }; + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorMap(PointerArgType dataPtr) : m_data(dataPtr), m_dimensions() { + // The number of dimensions used to construct a tensor must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT((0 == NumIndices || NumIndices == Dynamic), YOU_MADE_A_PROGRAMMING_MISTAKE) + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorMap(PointerArgType dataPtr, Index firstDimension, IndexTypes... otherDimensions) : m_data(dataPtr), m_dimensions(firstDimension, otherDimensions...) { + // The number of dimensions used to construct a tensor must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT((sizeof...(otherDimensions) + 1 == NumIndices || NumIndices == Dynamic), YOU_MADE_A_PROGRAMMING_MISTAKE) + } +#else + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorMap(PointerArgType dataPtr, Index firstDimension) : m_data(dataPtr), m_dimensions(firstDimension) { + // The number of dimensions used to construct a tensor must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT((1 == NumIndices || NumIndices == Dynamic), YOU_MADE_A_PROGRAMMING_MISTAKE) + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorMap(PointerArgType dataPtr, Index dim1, Index dim2) : m_data(dataPtr), m_dimensions(dim1, dim2) { + EIGEN_STATIC_ASSERT(2 == NumIndices || NumIndices == Dynamic, YOU_MADE_A_PROGRAMMING_MISTAKE) + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorMap(PointerArgType dataPtr, Index dim1, Index dim2, Index dim3) : m_data(dataPtr), m_dimensions(dim1, dim2, dim3) { + EIGEN_STATIC_ASSERT(3 == NumIndices || NumIndices == Dynamic, YOU_MADE_A_PROGRAMMING_MISTAKE) + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorMap(PointerArgType dataPtr, Index dim1, Index dim2, Index dim3, Index dim4) : m_data(dataPtr), m_dimensions(dim1, dim2, dim3, dim4) { + EIGEN_STATIC_ASSERT(4 == NumIndices || NumIndices == Dynamic, YOU_MADE_A_PROGRAMMING_MISTAKE) + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorMap(PointerArgType dataPtr, Index dim1, Index dim2, Index dim3, Index dim4, Index dim5) : m_data(dataPtr), m_dimensions(dim1, dim2, dim3, dim4, dim5) { + EIGEN_STATIC_ASSERT(5 == NumIndices || NumIndices == Dynamic, YOU_MADE_A_PROGRAMMING_MISTAKE) + } +#endif + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorMap(PointerArgType dataPtr, const array& dimensions) + : m_data(dataPtr), m_dimensions(dimensions) + { } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorMap(PointerArgType dataPtr, const Dimensions& dimensions) + : m_data(dataPtr), m_dimensions(dimensions) + { } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorMap(PlainObjectType& tensor) + : m_data(tensor.data()), m_dimensions(tensor.dimensions()) + { } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Index rank() const { return m_dimensions.rank(); } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Index dimension(Index n) const { return m_dimensions[n]; } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Index size() const { return m_dimensions.TotalSize(); } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE PointerType data() { return m_data; } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const PointerType data() const { return m_data; } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(const array& indices) const + { + // eigen_assert(checkIndexRange(indices)); + if (PlainObjectType::Options&RowMajor) { + const Index index = m_dimensions.IndexOfRowMajor(indices); + return m_data[index]; + } else { + const Index index = m_dimensions.IndexOfColMajor(indices); + return m_data[index]; + } + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()() const + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE) + return m_data[0]; + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index index) const + { + eigen_internal_assert(index >= 0 && index < size()); + return m_data[index]; + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index firstIndex, Index secondIndex, IndexTypes... otherIndices) const + { + EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + if (PlainObjectType::Options&RowMajor) { + const Index index = m_dimensions.IndexOfRowMajor(array{{firstIndex, secondIndex, otherIndices...}}); + return m_data[index]; + } else { + const Index index = m_dimensions.IndexOfColMajor(array{{firstIndex, secondIndex, otherIndices...}}); + return m_data[index]; + } + } +#else + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1) const + { + if (PlainObjectType::Options&RowMajor) { + const Index index = i1 + i0 * m_dimensions[1]; + return m_data[index]; + } else { + const Index index = i0 + i1 * m_dimensions[0]; + return m_data[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2) const + { + if (PlainObjectType::Options&RowMajor) { + const Index index = i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0); + return m_data[index]; + } else { + const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * i2); + return m_data[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2, Index i3) const + { + if (PlainObjectType::Options&RowMajor) { + const Index index = i3 + m_dimensions[3] * (i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0)); + return m_data[index]; + } else { + const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * (i2 + m_dimensions[2] * i3)); + return m_data[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2, Index i3, Index i4) const + { + if (PlainObjectType::Options&RowMajor) { + const Index index = i4 + m_dimensions[4] * (i3 + m_dimensions[3] * (i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0))); + return m_data[index]; + } else { + const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * (i2 + m_dimensions[2] * (i3 + m_dimensions[3] * i4))); + return m_data[index]; + } + } +#endif + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(const array& indices) + { + // eigen_assert(checkIndexRange(indices)); + if (PlainObjectType::Options&RowMajor) { + const Index index = m_dimensions.IndexOfRowMajor(indices); + return m_data[index]; + } else { + const Index index = m_dimensions.IndexOfColMajor(indices); + return m_data[index]; + } + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()() + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE) + return m_data[0]; + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index index) + { + eigen_internal_assert(index >= 0 && index < size()); + return m_data[index]; + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index firstIndex, Index secondIndex, IndexTypes... otherIndices) + { + static_assert(sizeof...(otherIndices) + 2 == NumIndices || NumIndices == Dynamic, "Number of indices used to access a tensor coefficient must be equal to the rank of the tensor."); + const std::size_t NumDims = sizeof...(otherIndices) + 2; + if (PlainObjectType::Options&RowMajor) { + const Index index = m_dimensions.IndexOfRowMajor(array{{firstIndex, secondIndex, otherIndices...}}); + return m_data[index]; + } else { + const Index index = m_dimensions.IndexOfColMajor(array{{firstIndex, secondIndex, otherIndices...}}); + return m_data[index]; + } + } +#else + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1) + { + if (PlainObjectType::Options&RowMajor) { + const Index index = i1 + i0 * m_dimensions[1]; + return m_data[index]; + } else { + const Index index = i0 + i1 * m_dimensions[0]; + return m_data[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2) + { + if (PlainObjectType::Options&RowMajor) { + const Index index = i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0); + return m_data[index]; + } else { + const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * i2); + return m_data[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3) + { + if (PlainObjectType::Options&RowMajor) { + const Index index = i3 + m_dimensions[3] * (i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0)); + return m_data[index]; + } else { + const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * (i2 + m_dimensions[2] * i3)); + return m_data[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3, Index i4) + { + if (PlainObjectType::Options&RowMajor) { + const Index index = i4 + m_dimensions[4] * (i3 + m_dimensions[3] * (i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0))); + return m_data[index]; + } else { + const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * (i2 + m_dimensions[2] * (i3 + m_dimensions[3] * i4))); + return m_data[index]; + } + } +#endif + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Self& operator=(const Self& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Self& operator=(const OtherDerived& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + private: + typename MakePointer_::Type m_data; + Dimensions m_dimensions; +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_MAP_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMeta.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMeta.h new file mode 100644 index 00000000..b5ef31d5 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMeta.h @@ -0,0 +1,219 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_META_H +#define EIGEN_CXX11_TENSOR_TENSOR_META_H + +namespace Eigen { + +template struct Cond {}; + +template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +const T1& choose(Cond, const T1& first, const T2&) { + return first; +} + +template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +const T2& choose(Cond, const T1&, const T2& second) { + return second; +} + + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T divup(const X x, const Y y) { + return static_cast((x + y - 1) / y); +} + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T divup(const T x, const T y) { + return static_cast((x + y - 1) / y); +} + +template struct max_n_1 { + static const size_t size = n; +}; +template <> struct max_n_1<0> { + static const size_t size = 1; +}; + + +// Default packet types +template +struct PacketType : internal::packet_traits { + typedef typename internal::packet_traits::type type; +}; + +// For CUDA packet types when using a GpuDevice +#if defined(EIGEN_USE_GPU) && defined(__CUDACC__) && defined(EIGEN_HAS_CUDA_FP16) +template <> +struct PacketType { + typedef half2 type; + static const int size = 2; + enum { + HasAdd = 1, + HasSub = 1, + HasMul = 1, + HasNegate = 1, + HasAbs = 1, + HasArg = 0, + HasAbs2 = 0, + HasMin = 1, + HasMax = 1, + HasConj = 0, + HasSetLinear = 0, + HasBlend = 0, + + HasDiv = 1, + HasSqrt = 1, + HasRsqrt = 1, + HasExp = 1, + HasExpm1 = 0, + HasLog = 1, + HasLog1p = 0, + HasLog10 = 0, + HasPow = 1, + }; +}; +#endif + +#if defined(EIGEN_USE_SYCL) +template + struct PacketType { + typedef T type; + static const int size = 1; + enum { + HasAdd = 0, + HasSub = 0, + HasMul = 0, + HasNegate = 0, + HasAbs = 0, + HasArg = 0, + HasAbs2 = 0, + HasMin = 0, + HasMax = 0, + HasConj = 0, + HasSetLinear = 0, + HasBlend = 0 + }; +}; +#endif + + +// Tuple mimics std::pair but works on e.g. nvcc. +template struct Tuple { + public: + U first; + V second; + + typedef U first_type; + typedef V second_type; + + EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Tuple() : first(), second() {} + + EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Tuple(const U& f, const V& s) : first(f), second(s) {} + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Tuple& operator= (const Tuple& rhs) { + if (&rhs == this) return *this; + first = rhs.first; + second = rhs.second; + return *this; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void swap(Tuple& rhs) { + using numext::swap; + swap(first, rhs.first); + swap(second, rhs.second); + } +}; + +template +EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +bool operator==(const Tuple& x, const Tuple& y) { + return (x.first == y.first && x.second == y.second); +} + +template +EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +bool operator!=(const Tuple& x, const Tuple& y) { + return !(x == y); +} + + +// Can't use std::pairs on cuda devices +template struct IndexPair { + EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE IndexPair() : first(0), second(0) {} + EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE IndexPair(Idx f, Idx s) : first(f), second(s) {} + + EIGEN_DEVICE_FUNC void set(IndexPair val) { + first = val.first; + second = val.second; + } + + Idx first; + Idx second; +}; + + +#ifdef EIGEN_HAS_SFINAE +namespace internal { + + template + EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + array customIndices2Array(IndexType& idx, numeric_list) { + return { idx[Is]... }; + } + template + EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + array customIndices2Array(IndexType&, numeric_list) { + return array(); + } + + /** Make an array (for index/dimensions) out of a custom index */ + template + EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + array customIndices2Array(IndexType& idx) { + return customIndices2Array(idx, typename gen_numeric_list::type{}); + } + + + template + struct is_base_of + { + + typedef char (&yes)[1]; + typedef char (&no)[2]; + + template + struct Host + { + operator BB*() const; + operator DD*(); + }; + + template + static yes check(D*, T); + static no check(B*, int); + + static const bool value = sizeof(check(Host(), int())) == sizeof(yes); + }; + +} +#endif + + + +} // namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_META_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMorphing.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMorphing.h new file mode 100644 index 00000000..6ddd2ca1 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMorphing.h @@ -0,0 +1,921 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_MORPHING_H +#define EIGEN_CXX11_TENSOR_TENSOR_MORPHING_H + +namespace Eigen { + +/** \class TensorReshaping + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor reshaping class. + * + * + */ +namespace internal { +template +struct traits > : public traits +{ + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = array_size::value; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorReshapingOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorReshapingOp type; +}; + +} // end namespace internal + + + +template +class TensorReshapingOp : public TensorBase, WriteAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename internal::remove_const::type CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorReshapingOp(const XprType& expr, const NewDimensions& dims) + : m_xpr(expr), m_dims(dims) {} + + EIGEN_DEVICE_FUNC + const NewDimensions& dimensions() const { return m_dims; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorReshapingOp& operator = (const TensorReshapingOp& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorReshapingOp& operator = (const OtherDerived& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + protected: + typename XprType::Nested m_xpr; + const NewDimensions m_dims; +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorReshapingOp XprType; + typedef NewDimensions Dimensions; + + enum { + IsAligned = TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = TensorEvaluator::RawAccess + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device), m_dimensions(op.dimensions()) + { + // The total size of the reshaped tensor must be equal to the total size + // of the input tensor. + eigen_assert(internal::array_prod(m_impl.dimensions()) == internal::array_prod(op.dimensions())); + } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType* data) { + return m_impl.evalSubExprsIfNeeded(data); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + return m_impl.coeff(index); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + return m_impl.template packet(index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + return m_impl.costPerCoeff(vectorized); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return const_cast(m_impl.data()); } + + EIGEN_DEVICE_FUNC const TensorEvaluator& impl() const { return m_impl; } + + protected: + TensorEvaluator m_impl; + NewDimensions m_dimensions; +}; + + +// Eval as lvalue +template + struct TensorEvaluator, Device> + : public TensorEvaluator, Device> + +{ + typedef TensorEvaluator, Device> Base; + typedef TensorReshapingOp XprType; + typedef NewDimensions Dimensions; + + enum { + IsAligned = TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = TensorEvaluator::RawAccess + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : Base(op, device) + { } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index) + { + return this->m_impl.coeffRef(index); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketReturnType& x) + { + this->m_impl.template writePacket(index, x); + } +}; + + +/** \class TensorSlicing + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor slicing class. + * + * + */ +namespace internal { +template +struct traits > : public traits +{ + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = array_size::value; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorSlicingOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorSlicingOp type; +}; + +} // end namespace internal + + + +template +class TensorSlicingOp : public TensorBase > +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorSlicingOp(const XprType& expr, const StartIndices& indices, const Sizes& sizes) + : m_xpr(expr), m_indices(indices), m_sizes(sizes) {} + + EIGEN_DEVICE_FUNC + const StartIndices& startIndices() const { return m_indices; } + EIGEN_DEVICE_FUNC + const Sizes& sizes() const { return m_sizes; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorSlicingOp& operator = (const OtherDerived& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorSlicingOp& operator = (const TensorSlicingOp& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + + protected: + typename XprType::Nested m_xpr; + const StartIndices m_indices; + const Sizes m_sizes; +}; + + +// Fixme: figure out the exact threshold +namespace { +template struct MemcpyTriggerForSlicing { + EIGEN_DEVICE_FUNC MemcpyTriggerForSlicing(const Device& device) : threshold_(2 * device.numThreads()) { } + EIGEN_DEVICE_FUNC bool operator ()(Index val) const { return val > threshold_; } + + private: + Index threshold_; +}; + +// It is very expensive to start the memcpy kernel on GPU: we therefore only +// use it for large copies. +#ifdef EIGEN_USE_GPU +template struct MemcpyTriggerForSlicing { + EIGEN_DEVICE_FUNC MemcpyTriggerForSlicing(const GpuDevice&) { } + EIGEN_DEVICE_FUNC bool operator ()(Index val) const { return val > 4*1024*1024; } +}; +#endif + +// It is very expensive to start the memcpy kernel on GPU: we therefore only +// use it for large copies. +#ifdef EIGEN_USE_SYCL +template struct MemcpyTriggerForSlicing { + EIGEN_DEVICE_FUNC MemcpyTriggerForSlicing(const SyclDevice&) { } + EIGEN_DEVICE_FUNC bool operator ()(Index val) const { return val > 4*1024*1024; } +}; +#endif + +} + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorSlicingOp XprType; + static const int NumDims = internal::array_size::value; + + enum { + // Alignment can't be guaranteed at compile time since it depends on the + // slice offsets and sizes. + IsAligned = /*TensorEvaluator::IsAligned*/false, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device), m_device(device), m_dimensions(op.sizes()), m_offsets(op.startIndices()) + { + for (std::size_t i = 0; i < internal::array_size::value; ++i) { + eigen_assert(m_impl.dimensions()[i] >= op.sizes()[i] + op.startIndices()[i]); + } + + const typename TensorEvaluator::Dimensions& input_dims = m_impl.dimensions(); + const Sizes& output_dims = op.sizes(); + if (static_cast(Layout) == static_cast(ColMajor)) { + m_inputStrides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1]; + } + + // Don't initialize m_fastOutputStrides[0] since it won't ever be accessed. + m_outputStrides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_outputStrides[i] = m_outputStrides[i-1] * output_dims[i-1]; + m_fastOutputStrides[i] = internal::TensorIntDivisor(m_outputStrides[i]); + } + } else { + m_inputStrides[NumDims-1] = 1; + for (int i = NumDims - 2; i >= 0; --i) { + m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1]; + } + + // Don't initialize m_fastOutputStrides[NumDims-1] since it won't ever be accessed. + m_outputStrides[NumDims-1] = 1; + for (int i = NumDims - 2; i >= 0; --i) { + m_outputStrides[i] = m_outputStrides[i+1] * output_dims[i+1]; + m_fastOutputStrides[i] = internal::TensorIntDivisor(m_outputStrides[i]); + } + } + } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + typedef Sizes Dimensions; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType* data) { + m_impl.evalSubExprsIfNeeded(NULL); + if (!NumTraits::type>::RequireInitialization && data && m_impl.data()) { + Index contiguous_values = 1; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = 0; i < NumDims; ++i) { + contiguous_values *= dimensions()[i]; + if (dimensions()[i] != m_impl.dimensions()[i]) { + break; + } + } + } else { + for (int i = NumDims-1; i >= 0; --i) { + contiguous_values *= dimensions()[i]; + if (dimensions()[i] != m_impl.dimensions()[i]) { + break; + } + } + } + // Use memcpy if it's going to be faster than using the regular evaluation. + const MemcpyTriggerForSlicing trigger(m_device); + if (trigger(contiguous_values)) { + Scalar* src = (Scalar*)m_impl.data(); + for (int i = 0; i < internal::array_prod(dimensions()); i += contiguous_values) { + Index offset = srcCoeff(i); + m_device.memcpy((void*)(data+i), src+offset, contiguous_values * sizeof(Scalar)); + } + return false; + } + } + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + return m_impl.coeff(srcCoeff(index)); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + const int packetSize = internal::unpacket_traits::size; + EIGEN_STATIC_ASSERT((packetSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index+packetSize-1 < internal::array_prod(dimensions())); + + Index inputIndices[] = {0, 0}; + Index indices[] = {index, index + packetSize - 1}; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i > 0; --i) { + const Index idx0 = indices[0] / m_fastOutputStrides[i]; + const Index idx1 = indices[1] / m_fastOutputStrides[i]; + inputIndices[0] += (idx0 + m_offsets[i]) * m_inputStrides[i]; + inputIndices[1] += (idx1 + m_offsets[i]) * m_inputStrides[i]; + indices[0] -= idx0 * m_outputStrides[i]; + indices[1] -= idx1 * m_outputStrides[i]; + } + inputIndices[0] += (indices[0] + m_offsets[0]); + inputIndices[1] += (indices[1] + m_offsets[0]); + } else { + for (int i = 0; i < NumDims - 1; ++i) { + const Index idx0 = indices[0] / m_fastOutputStrides[i]; + const Index idx1 = indices[1] / m_fastOutputStrides[i]; + inputIndices[0] += (idx0 + m_offsets[i]) * m_inputStrides[i]; + inputIndices[1] += (idx1 + m_offsets[i]) * m_inputStrides[i]; + indices[0] -= idx0 * m_outputStrides[i]; + indices[1] -= idx1 * m_outputStrides[i]; + } + inputIndices[0] += (indices[0] + m_offsets[NumDims-1]); + inputIndices[1] += (indices[1] + m_offsets[NumDims-1]); + } + if (inputIndices[1] - inputIndices[0] == packetSize - 1) { + PacketReturnType rslt = m_impl.template packet(inputIndices[0]); + return rslt; + } + else { + EIGEN_ALIGN_MAX typename internal::remove_const::type values[packetSize]; + values[0] = m_impl.coeff(inputIndices[0]); + values[packetSize-1] = m_impl.coeff(inputIndices[1]); + for (int i = 1; i < packetSize-1; ++i) { + values[i] = coeff(index+i); + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + return m_impl.costPerCoeff(vectorized) + TensorOpCost(0, 0, NumDims); + } + + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar* data() const { + Scalar* result = m_impl.data(); + if (result) { + Index offset = 0; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = 0; i < NumDims; ++i) { + if (m_dimensions[i] != m_impl.dimensions()[i]) { + offset += m_offsets[i] * m_inputStrides[i]; + for (int j = i+1; j < NumDims; ++j) { + if (m_dimensions[j] > 1) { + return NULL; + } + offset += m_offsets[j] * m_inputStrides[j]; + } + break; + } + } + } else { + for (int i = NumDims - 1; i >= 0; --i) { + if (m_dimensions[i] != m_impl.dimensions()[i]) { + offset += m_offsets[i] * m_inputStrides[i]; + for (int j = i-1; j >= 0; --j) { + if (m_dimensions[j] > 1) { + return NULL; + } + offset += m_offsets[j] * m_inputStrides[j]; + } + break; + } + } + } + return result + offset; + } + return NULL; + } + /// used by sycl + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const TensorEvaluator& impl() const{ + return m_impl; + } + /// used by sycl + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const StartIndices& startIndices() const{ + return m_offsets; + } + protected: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index srcCoeff(Index index) const + { + Index inputIndex = 0; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i > 0; --i) { + const Index idx = index / m_fastOutputStrides[i]; + inputIndex += (idx + m_offsets[i]) * m_inputStrides[i]; + index -= idx * m_outputStrides[i]; + } + inputIndex += (index + m_offsets[0]); + } else { + for (int i = 0; i < NumDims - 1; ++i) { + const Index idx = index / m_fastOutputStrides[i]; + inputIndex += (idx + m_offsets[i]) * m_inputStrides[i]; + index -= idx * m_outputStrides[i]; + } + inputIndex += (index + m_offsets[NumDims-1]); + } + return inputIndex; + } + + array m_outputStrides; + array, NumDims> m_fastOutputStrides; + array m_inputStrides; + TensorEvaluator m_impl; + const Device& m_device; + Dimensions m_dimensions; + const StartIndices m_offsets; +}; + + +// Eval as lvalue +template +struct TensorEvaluator, Device> + : public TensorEvaluator, Device> +{ + typedef TensorEvaluator, Device> Base; + typedef TensorSlicingOp XprType; + static const int NumDims = internal::array_size::value; + + enum { + IsAligned = /*TensorEvaluator::IsAligned*/false, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : Base(op, device) + { } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + typedef Sizes Dimensions; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index) + { + return this->m_impl.coeffRef(this->srcCoeff(index)); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketReturnType& x) + { + const int packetSize = internal::unpacket_traits::size; + Index inputIndices[] = {0, 0}; + Index indices[] = {index, index + packetSize - 1}; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i > 0; --i) { + const Index idx0 = indices[0] / this->m_fastOutputStrides[i]; + const Index idx1 = indices[1] / this->m_fastOutputStrides[i]; + inputIndices[0] += (idx0 + this->m_offsets[i]) * this->m_inputStrides[i]; + inputIndices[1] += (idx1 + this->m_offsets[i]) * this->m_inputStrides[i]; + indices[0] -= idx0 * this->m_outputStrides[i]; + indices[1] -= idx1 * this->m_outputStrides[i]; + } + inputIndices[0] += (indices[0] + this->m_offsets[0]); + inputIndices[1] += (indices[1] + this->m_offsets[0]); + } else { + for (int i = 0; i < NumDims - 1; ++i) { + const Index idx0 = indices[0] / this->m_fastOutputStrides[i]; + const Index idx1 = indices[1] / this->m_fastOutputStrides[i]; + inputIndices[0] += (idx0 + this->m_offsets[i]) * this->m_inputStrides[i]; + inputIndices[1] += (idx1 + this->m_offsets[i]) * this->m_inputStrides[i]; + indices[0] -= idx0 * this->m_outputStrides[i]; + indices[1] -= idx1 * this->m_outputStrides[i]; + } + inputIndices[0] += (indices[0] + this->m_offsets[NumDims-1]); + inputIndices[1] += (indices[1] + this->m_offsets[NumDims-1]); + } + if (inputIndices[1] - inputIndices[0] == packetSize - 1) { + this->m_impl.template writePacket(inputIndices[0], x); + } + else { + EIGEN_ALIGN_MAX CoeffReturnType values[packetSize]; + internal::pstore(values, x); + this->m_impl.coeffRef(inputIndices[0]) = values[0]; + this->m_impl.coeffRef(inputIndices[1]) = values[packetSize-1]; + for (int i = 1; i < packetSize-1; ++i) { + this->coeffRef(index+i) = values[i]; + } + } + } +}; + + + +namespace internal { +template +struct traits > : public traits +{ + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = array_size::value; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorStridingSlicingOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorStridingSlicingOp type; +}; + +} // end namespace internal + + +template +class TensorStridingSlicingOp : public TensorBase > +{ + public: + typedef typename internal::traits::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename internal::nested::type Nested; + typedef typename internal::traits::StorageKind StorageKind; + typedef typename internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorStridingSlicingOp( + const XprType& expr, const StartIndices& startIndices, + const StopIndices& stopIndices, const Strides& strides) + : m_xpr(expr), m_startIndices(startIndices), m_stopIndices(stopIndices), + m_strides(strides) {} + + EIGEN_DEVICE_FUNC + const StartIndices& startIndices() const { return m_startIndices; } + EIGEN_DEVICE_FUNC + const StartIndices& stopIndices() const { return m_stopIndices; } + EIGEN_DEVICE_FUNC + const StartIndices& strides() const { return m_strides; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorStridingSlicingOp& operator = (const TensorStridingSlicingOp& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run( + assign, DefaultDevice()); + return *this; + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorStridingSlicingOp& operator = (const OtherDerived& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run( + assign, DefaultDevice()); + return *this; + } + + protected: + typename XprType::Nested m_xpr; + const StartIndices m_startIndices; + const StopIndices m_stopIndices; + const Strides m_strides; +}; + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorStridingSlicingOp XprType; + static const int NumDims = internal::array_size::value; + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename internal::remove_const::type ScalarNonConst; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + typedef Strides Dimensions; + + enum { + // Alignment can't be guaranteed at compile time since it depends on the + // slice offsets and sizes. + IsAligned = false, + PacketAccess = false, + BlockAccess = false, + Layout = TensorEvaluator::Layout, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device), m_device(device), m_strides(op.strides()), m_exprStartIndices(op.startIndices()), m_exprStopIndices(op.stopIndices()) + { + // Handle degenerate intervals by gracefully clamping and allowing m_dimensions to be zero + DSizes startIndicesClamped, stopIndicesClamped; + for (size_t i = 0; i < internal::array_size::value; ++i) { + eigen_assert(m_strides[i] != 0 && "0 stride is invalid"); + if(m_strides[i]>0){ + startIndicesClamped[i] = clamp(op.startIndices()[i], 0, m_impl.dimensions()[i]); + stopIndicesClamped[i] = clamp(op.stopIndices()[i], 0, m_impl.dimensions()[i]); + }else{ + /* implies m_strides[i]<0 by assert */ + startIndicesClamped[i] = clamp(op.startIndices()[i], -1, m_impl.dimensions()[i] - 1); + stopIndicesClamped[i] = clamp(op.stopIndices()[i], -1, m_impl.dimensions()[i] - 1); + } + m_startIndices[i] = startIndicesClamped[i]; + } + + const typename TensorEvaluator::Dimensions& input_dims = m_impl.dimensions(); + + // check for degenerate intervals and compute output tensor shape + bool degenerate = false;; + for(int i = 0; i < NumDims; i++){ + Index interval = stopIndicesClamped[i] - startIndicesClamped[i]; + if(interval == 0 || ((interval<0) != (m_strides[i]<0))){ + m_dimensions[i] = 0; + degenerate = true; + }else{ + m_dimensions[i] = interval / m_strides[i] + + (interval % m_strides[i] != 0 ? 1 : 0); + eigen_assert(m_dimensions[i] >= 0); + } + } + Strides output_dims = m_dimensions; + + if (static_cast(Layout) == static_cast(ColMajor)) { + m_inputStrides[0] = m_strides[0]; + m_offsets[0] = startIndicesClamped[0]; + Index previousDimProduct = 1; + for (int i = 1; i < NumDims; ++i) { + previousDimProduct *= input_dims[i-1]; + m_inputStrides[i] = previousDimProduct * m_strides[i]; + m_offsets[i] = startIndicesClamped[i] * previousDimProduct; + } + + // Don't initialize m_fastOutputStrides[0] since it won't ever be accessed. + m_outputStrides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_outputStrides[i] = m_outputStrides[i-1] * output_dims[i-1]; + // NOTE: if tensor is degenerate, we send 1 to prevent TensorIntDivisor constructor crash + m_fastOutputStrides[i] = internal::TensorIntDivisor(degenerate ? 1 : m_outputStrides[i]); + } + } else { + m_inputStrides[NumDims-1] = m_strides[NumDims-1]; + m_offsets[NumDims-1] = startIndicesClamped[NumDims-1]; + Index previousDimProduct = 1; + for (int i = NumDims - 2; i >= 0; --i) { + previousDimProduct *= input_dims[i+1]; + m_inputStrides[i] = previousDimProduct * m_strides[i]; + m_offsets[i] = startIndicesClamped[i] * previousDimProduct; + } + + m_outputStrides[NumDims-1] = 1; + for (int i = NumDims - 2; i >= 0; --i) { + m_outputStrides[i] = m_outputStrides[i+1] * output_dims[i+1]; + // NOTE: if tensor is degenerate, we send 1 to prevent TensorIntDivisor constructor crash + m_fastOutputStrides[i] = internal::TensorIntDivisor(degenerate ? 1 : m_outputStrides[i]); + } + } + m_block_total_size_max = numext::maxi(static_cast(1), + device.lastLevelCacheSize() / + sizeof(Scalar)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType*) { + m_impl.evalSubExprsIfNeeded(NULL); + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + return m_impl.coeff(srcCoeff(index)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + return m_impl.costPerCoeff(vectorized) + TensorOpCost(0, 0, NumDims); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar* data() const { + return NULL; + } + + //use by sycl + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const StartIndices& exprStartIndices() const { return m_exprStartIndices; } + //use by sycl + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const StartIndices& exprStopIndices() const { return m_exprStopIndices; } + //use by sycl + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const StartIndices& strides() const { return m_strides; } + /// used by sycl + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const TensorEvaluator& impl() const{return m_impl;} + + protected: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index srcCoeff(Index index) const + { + Index inputIndex = 0; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i >= 0; --i) { + const Index idx = index / m_fastOutputStrides[i]; + inputIndex += idx * m_inputStrides[i] + m_offsets[i]; + index -= idx * m_outputStrides[i]; + } + } else { + for (int i = 0; i < NumDims; ++i) { + const Index idx = index / m_fastOutputStrides[i]; + inputIndex += idx * m_inputStrides[i] + m_offsets[i]; + index -= idx * m_outputStrides[i]; + } + } + return inputIndex; + } + + static EIGEN_STRONG_INLINE Index clamp(Index value, Index min, Index max) { +#ifndef __SYCL_DEVICE_ONLY__ + return numext::maxi(min, numext::mini(max,value)); +#else + return cl::sycl::clamp(value, min, max); +#endif + } + + array m_outputStrides; + array, NumDims> m_fastOutputStrides; + array m_inputStrides; + TensorEvaluator m_impl; + const Device& m_device; + DSizes m_startIndices; // clamped startIndices + DSizes m_dimensions; + DSizes m_offsets; // offset in a flattened shape + const Strides m_strides; + std::size_t m_block_total_size_max; + //use by sycl + const StartIndices m_exprStartIndices; + //use by sycl + const StopIndices m_exprStopIndices; +}; + +// Eval as lvalue +template +struct TensorEvaluator, Device> + : public TensorEvaluator, Device> +{ + typedef TensorEvaluator, Device> Base; + typedef TensorStridingSlicingOp XprType; + static const int NumDims = internal::array_size::value; + + enum { + IsAligned = false, + PacketAccess = false, + BlockAccess = false, + Layout = TensorEvaluator::Layout, + CoordAccess = TensorEvaluator::CoordAccess, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : Base(op, device) + { } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename internal::remove_const::type ScalarNonConst; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + typedef Strides Dimensions; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index) + { + return this->m_impl.coeffRef(this->srcCoeff(index)); + } +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_MORPHING_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorPadding.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorPadding.h new file mode 100644 index 00000000..a8e25524 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorPadding.h @@ -0,0 +1,404 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_PADDING_H +#define EIGEN_CXX11_TENSOR_TENSOR_PADDING_H + +namespace Eigen { + +/** \class TensorPadding + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor padding class. + * At the moment only padding with a constant value is supported. + * + */ +namespace internal { +template +struct traits > : public traits +{ + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorPaddingOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorPaddingOp type; +}; + +} // end namespace internal + + + +template +class TensorPaddingOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorPaddingOp(const XprType& expr, const PaddingDimensions& padding_dims, const Scalar padding_value) + : m_xpr(expr), m_padding_dims(padding_dims), m_padding_value(padding_value) {} + + EIGEN_DEVICE_FUNC + const PaddingDimensions& padding() const { return m_padding_dims; } + EIGEN_DEVICE_FUNC + Scalar padding_value() const { return m_padding_value; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + protected: + typename XprType::Nested m_xpr; + const PaddingDimensions m_padding_dims; + const Scalar m_padding_value; +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorPaddingOp XprType; + typedef typename XprType::Index Index; + static const int NumDims = internal::array_size::value; + typedef DSizes Dimensions; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = true, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = true, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device), m_padding(op.padding()), m_paddingValue(op.padding_value()) + { + // The padding op doesn't change the rank of the tensor. Directly padding a scalar would lead + // to a vector, which doesn't make sense. Instead one should reshape the scalar into a vector + // of 1 element first and then pad. + EIGEN_STATIC_ASSERT((NumDims > 0), YOU_MADE_A_PROGRAMMING_MISTAKE); + + // Compute dimensions + m_dimensions = m_impl.dimensions(); + for (int i = 0; i < NumDims; ++i) { + m_dimensions[i] += m_padding[i].first + m_padding[i].second; + } + const typename TensorEvaluator::Dimensions& input_dims = m_impl.dimensions(); + if (static_cast(Layout) == static_cast(ColMajor)) { + m_inputStrides[0] = 1; + m_outputStrides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1]; + m_outputStrides[i] = m_outputStrides[i-1] * m_dimensions[i-1]; + } + m_outputStrides[NumDims] = m_outputStrides[NumDims-1] * m_dimensions[NumDims-1]; + } else { + m_inputStrides[NumDims - 1] = 1; + m_outputStrides[NumDims] = 1; + for (int i = NumDims - 2; i >= 0; --i) { + m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1]; + m_outputStrides[i+1] = m_outputStrides[i+2] * m_dimensions[i+1]; + } + m_outputStrides[0] = m_outputStrides[1] * m_dimensions[0]; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar*) { + m_impl.evalSubExprsIfNeeded(NULL); + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + eigen_assert(index < dimensions().TotalSize()); + Index inputIndex = 0; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i > 0; --i) { + const Index idx = index / m_outputStrides[i]; + if (isPaddingAtIndexForDim(idx, i)) { + return m_paddingValue; + } + inputIndex += (idx - m_padding[i].first) * m_inputStrides[i]; + index -= idx * m_outputStrides[i]; + } + if (isPaddingAtIndexForDim(index, 0)) { + return m_paddingValue; + } + inputIndex += (index - m_padding[0].first); + } else { + for (int i = 0; i < NumDims - 1; ++i) { + const Index idx = index / m_outputStrides[i+1]; + if (isPaddingAtIndexForDim(idx, i)) { + return m_paddingValue; + } + inputIndex += (idx - m_padding[i].first) * m_inputStrides[i]; + index -= idx * m_outputStrides[i+1]; + } + if (isPaddingAtIndexForDim(index, NumDims-1)) { + return m_paddingValue; + } + inputIndex += (index - m_padding[NumDims-1].first); + } + return m_impl.coeff(inputIndex); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + if (static_cast(Layout) == static_cast(ColMajor)) { + return packetColMajor(index); + } + return packetRowMajor(index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + TensorOpCost cost = m_impl.costPerCoeff(vectorized); + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = 0; i < NumDims; ++i) + updateCostPerDimension(cost, i, i == 0); + } else { + for (int i = NumDims - 1; i >= 0; --i) + updateCostPerDimension(cost, i, i == NumDims - 1); + } + return cost; + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + /// used by sycl + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const PaddingDimensions& padding() const { return m_padding; } + /// used by sycl + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& padding_value() const { return m_paddingValue; } + /// used by sycl + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const TensorEvaluator& impl() const{return m_impl;} + + private: + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool isPaddingAtIndexForDim( + Index index, int dim_index) const { +#if defined(EIGEN_HAS_INDEX_LIST) + return (!internal::index_pair_first_statically_eq(dim_index, 0) && + index < m_padding[dim_index].first) || + (!internal::index_pair_second_statically_eq(dim_index, 0) && + index >= m_dimensions[dim_index] - m_padding[dim_index].second); +#else + return (index < m_padding[dim_index].first) || + (index >= m_dimensions[dim_index] - m_padding[dim_index].second); +#endif + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool isLeftPaddingCompileTimeZero( + int dim_index) const { +#if defined(EIGEN_HAS_INDEX_LIST) + return internal::index_pair_first_statically_eq(dim_index, 0); +#else + EIGEN_UNUSED_VARIABLE(dim_index); + return false; +#endif + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool isRightPaddingCompileTimeZero( + int dim_index) const { +#if defined(EIGEN_HAS_INDEX_LIST) + return internal::index_pair_second_statically_eq(dim_index, 0); +#else + EIGEN_UNUSED_VARIABLE(dim_index); + return false; +#endif + } + + + void updateCostPerDimension(TensorOpCost& cost, int i, bool first) const { + const double in = static_cast(m_impl.dimensions()[i]); + const double out = in + m_padding[i].first + m_padding[i].second; + if (out == 0) + return; + const double reduction = in / out; + cost *= reduction; + if (first) { + cost += TensorOpCost(0, 0, 2 * TensorOpCost::AddCost() + + reduction * (1 * TensorOpCost::AddCost())); + } else { + cost += TensorOpCost(0, 0, 2 * TensorOpCost::AddCost() + + 2 * TensorOpCost::MulCost() + + reduction * (2 * TensorOpCost::MulCost() + + 1 * TensorOpCost::DivCost())); + } + } + + protected: + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetColMajor(Index index) const + { + EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index+PacketSize-1 < dimensions().TotalSize()); + + const Index initialIndex = index; + Index inputIndex = 0; + for (int i = NumDims - 1; i > 0; --i) { + const Index first = index; + const Index last = index + PacketSize - 1; + const Index lastPaddedLeft = m_padding[i].first * m_outputStrides[i]; + const Index firstPaddedRight = (m_dimensions[i] - m_padding[i].second) * m_outputStrides[i]; + const Index lastPaddedRight = m_outputStrides[i+1]; + + if (!isLeftPaddingCompileTimeZero(i) && last < lastPaddedLeft) { + // all the coefficient are in the padding zone. + return internal::pset1(m_paddingValue); + } + else if (!isRightPaddingCompileTimeZero(i) && first >= firstPaddedRight && last < lastPaddedRight) { + // all the coefficient are in the padding zone. + return internal::pset1(m_paddingValue); + } + else if ((isLeftPaddingCompileTimeZero(i) && isRightPaddingCompileTimeZero(i)) || (first >= lastPaddedLeft && last < firstPaddedRight)) { + // all the coefficient are between the 2 padding zones. + const Index idx = index / m_outputStrides[i]; + inputIndex += (idx - m_padding[i].first) * m_inputStrides[i]; + index -= idx * m_outputStrides[i]; + } + else { + // Every other case + return packetWithPossibleZero(initialIndex); + } + } + + const Index last = index + PacketSize - 1; + const Index first = index; + const Index lastPaddedLeft = m_padding[0].first; + const Index firstPaddedRight = (m_dimensions[0] - m_padding[0].second); + const Index lastPaddedRight = m_outputStrides[1]; + + if (!isLeftPaddingCompileTimeZero(0) && last < lastPaddedLeft) { + // all the coefficient are in the padding zone. + return internal::pset1(m_paddingValue); + } + else if (!isRightPaddingCompileTimeZero(0) && first >= firstPaddedRight && last < lastPaddedRight) { + // all the coefficient are in the padding zone. + return internal::pset1(m_paddingValue); + } + else if ((isLeftPaddingCompileTimeZero(0) && isRightPaddingCompileTimeZero(0)) || (first >= lastPaddedLeft && last < firstPaddedRight)) { + // all the coefficient are between the 2 padding zones. + inputIndex += (index - m_padding[0].first); + return m_impl.template packet(inputIndex); + } + // Every other case + return packetWithPossibleZero(initialIndex); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetRowMajor(Index index) const + { + EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index+PacketSize-1 < dimensions().TotalSize()); + + const Index initialIndex = index; + Index inputIndex = 0; + + for (int i = 0; i < NumDims - 1; ++i) { + const Index first = index; + const Index last = index + PacketSize - 1; + const Index lastPaddedLeft = m_padding[i].first * m_outputStrides[i+1]; + const Index firstPaddedRight = (m_dimensions[i] - m_padding[i].second) * m_outputStrides[i+1]; + const Index lastPaddedRight = m_outputStrides[i]; + + if (!isLeftPaddingCompileTimeZero(i) && last < lastPaddedLeft) { + // all the coefficient are in the padding zone. + return internal::pset1(m_paddingValue); + } + else if (!isRightPaddingCompileTimeZero(i) && first >= firstPaddedRight && last < lastPaddedRight) { + // all the coefficient are in the padding zone. + return internal::pset1(m_paddingValue); + } + else if ((isLeftPaddingCompileTimeZero(i) && isRightPaddingCompileTimeZero(i)) || (first >= lastPaddedLeft && last < firstPaddedRight)) { + // all the coefficient are between the 2 padding zones. + const Index idx = index / m_outputStrides[i+1]; + inputIndex += (idx - m_padding[i].first) * m_inputStrides[i]; + index -= idx * m_outputStrides[i+1]; + } + else { + // Every other case + return packetWithPossibleZero(initialIndex); + } + } + + const Index last = index + PacketSize - 1; + const Index first = index; + const Index lastPaddedLeft = m_padding[NumDims-1].first; + const Index firstPaddedRight = (m_dimensions[NumDims-1] - m_padding[NumDims-1].second); + const Index lastPaddedRight = m_outputStrides[NumDims-1]; + + if (!isLeftPaddingCompileTimeZero(NumDims-1) && last < lastPaddedLeft) { + // all the coefficient are in the padding zone. + return internal::pset1(m_paddingValue); + } + else if (!isRightPaddingCompileTimeZero(NumDims-1) && first >= firstPaddedRight && last < lastPaddedRight) { + // all the coefficient are in the padding zone. + return internal::pset1(m_paddingValue); + } + else if ((isLeftPaddingCompileTimeZero(NumDims-1) && isRightPaddingCompileTimeZero(NumDims-1)) || (first >= lastPaddedLeft && last < firstPaddedRight)) { + // all the coefficient are between the 2 padding zones. + inputIndex += (index - m_padding[NumDims-1].first); + return m_impl.template packet(inputIndex); + } + // Every other case + return packetWithPossibleZero(initialIndex); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetWithPossibleZero(Index index) const + { + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + for (int i = 0; i < PacketSize; ++i) { + values[i] = coeff(index+i); + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + + Dimensions m_dimensions; + array m_outputStrides; + array m_inputStrides; + TensorEvaluator m_impl; + PaddingDimensions m_padding; + + Scalar m_paddingValue; +}; + + + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_PADDING_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorPatch.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorPatch.h new file mode 100644 index 00000000..886a254f --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorPatch.h @@ -0,0 +1,269 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_PATCH_H +#define EIGEN_CXX11_TENSOR_TENSOR_PATCH_H + +namespace Eigen { + +/** \class TensorPatch + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor patch class. + * + * + */ +namespace internal { +template +struct traits > : public traits +{ + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions + 1; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorPatchOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorPatchOp type; +}; + +} // end namespace internal + + + +template +class TensorPatchOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorPatchOp(const XprType& expr, const PatchDim& patch_dims) + : m_xpr(expr), m_patch_dims(patch_dims) {} + + EIGEN_DEVICE_FUNC + const PatchDim& patch_dims() const { return m_patch_dims; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + protected: + typename XprType::Nested m_xpr; + const PatchDim m_patch_dims; +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorPatchOp XprType; + typedef typename XprType::Index Index; + static const int NumDims = internal::array_size::Dimensions>::value + 1; + typedef DSizes Dimensions; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + + enum { + IsAligned = false, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device) + { + Index num_patches = 1; + const typename TensorEvaluator::Dimensions& input_dims = m_impl.dimensions(); + const PatchDim& patch_dims = op.patch_dims(); + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = 0; i < NumDims-1; ++i) { + m_dimensions[i] = patch_dims[i]; + num_patches *= (input_dims[i] - patch_dims[i] + 1); + } + m_dimensions[NumDims-1] = num_patches; + + m_inputStrides[0] = 1; + m_patchStrides[0] = 1; + for (int i = 1; i < NumDims-1; ++i) { + m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1]; + m_patchStrides[i] = m_patchStrides[i-1] * (input_dims[i-1] - patch_dims[i-1] + 1); + } + m_outputStrides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_outputStrides[i] = m_outputStrides[i-1] * m_dimensions[i-1]; + } + } else { + for (int i = 0; i < NumDims-1; ++i) { + m_dimensions[i+1] = patch_dims[i]; + num_patches *= (input_dims[i] - patch_dims[i] + 1); + } + m_dimensions[0] = num_patches; + + m_inputStrides[NumDims-2] = 1; + m_patchStrides[NumDims-2] = 1; + for (int i = NumDims-3; i >= 0; --i) { + m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1]; + m_patchStrides[i] = m_patchStrides[i+1] * (input_dims[i+1] - patch_dims[i+1] + 1); + } + m_outputStrides[NumDims-1] = 1; + for (int i = NumDims-2; i >= 0; --i) { + m_outputStrides[i] = m_outputStrides[i+1] * m_dimensions[i+1]; + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* /*data*/) { + m_impl.evalSubExprsIfNeeded(NULL); + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + Index output_stride_index = (static_cast(Layout) == static_cast(ColMajor)) ? NumDims - 1 : 0; + // Find the location of the first element of the patch. + Index patchIndex = index / m_outputStrides[output_stride_index]; + // Find the offset of the element wrt the location of the first element. + Index patchOffset = index - patchIndex * m_outputStrides[output_stride_index]; + Index inputIndex = 0; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 2; i > 0; --i) { + const Index patchIdx = patchIndex / m_patchStrides[i]; + patchIndex -= patchIdx * m_patchStrides[i]; + const Index offsetIdx = patchOffset / m_outputStrides[i]; + patchOffset -= offsetIdx * m_outputStrides[i]; + inputIndex += (patchIdx + offsetIdx) * m_inputStrides[i]; + } + } else { + for (int i = 0; i < NumDims - 2; ++i) { + const Index patchIdx = patchIndex / m_patchStrides[i]; + patchIndex -= patchIdx * m_patchStrides[i]; + const Index offsetIdx = patchOffset / m_outputStrides[i+1]; + patchOffset -= offsetIdx * m_outputStrides[i+1]; + inputIndex += (patchIdx + offsetIdx) * m_inputStrides[i]; + } + } + inputIndex += (patchIndex + patchOffset); + return m_impl.coeff(inputIndex); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index+PacketSize-1 < dimensions().TotalSize()); + + Index output_stride_index = (static_cast(Layout) == static_cast(ColMajor)) ? NumDims - 1 : 0; + Index indices[2] = {index, index + PacketSize - 1}; + Index patchIndices[2] = {indices[0] / m_outputStrides[output_stride_index], + indices[1] / m_outputStrides[output_stride_index]}; + Index patchOffsets[2] = {indices[0] - patchIndices[0] * m_outputStrides[output_stride_index], + indices[1] - patchIndices[1] * m_outputStrides[output_stride_index]}; + + Index inputIndices[2] = {0, 0}; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 2; i > 0; --i) { + const Index patchIdx[2] = {patchIndices[0] / m_patchStrides[i], + patchIndices[1] / m_patchStrides[i]}; + patchIndices[0] -= patchIdx[0] * m_patchStrides[i]; + patchIndices[1] -= patchIdx[1] * m_patchStrides[i]; + + const Index offsetIdx[2] = {patchOffsets[0] / m_outputStrides[i], + patchOffsets[1] / m_outputStrides[i]}; + patchOffsets[0] -= offsetIdx[0] * m_outputStrides[i]; + patchOffsets[1] -= offsetIdx[1] * m_outputStrides[i]; + + inputIndices[0] += (patchIdx[0] + offsetIdx[0]) * m_inputStrides[i]; + inputIndices[1] += (patchIdx[1] + offsetIdx[1]) * m_inputStrides[i]; + } + } else { + for (int i = 0; i < NumDims - 2; ++i) { + const Index patchIdx[2] = {patchIndices[0] / m_patchStrides[i], + patchIndices[1] / m_patchStrides[i]}; + patchIndices[0] -= patchIdx[0] * m_patchStrides[i]; + patchIndices[1] -= patchIdx[1] * m_patchStrides[i]; + + const Index offsetIdx[2] = {patchOffsets[0] / m_outputStrides[i+1], + patchOffsets[1] / m_outputStrides[i+1]}; + patchOffsets[0] -= offsetIdx[0] * m_outputStrides[i+1]; + patchOffsets[1] -= offsetIdx[1] * m_outputStrides[i+1]; + + inputIndices[0] += (patchIdx[0] + offsetIdx[0]) * m_inputStrides[i]; + inputIndices[1] += (patchIdx[1] + offsetIdx[1]) * m_inputStrides[i]; + } + } + inputIndices[0] += (patchIndices[0] + patchOffsets[0]); + inputIndices[1] += (patchIndices[1] + patchOffsets[1]); + + if (inputIndices[1] - inputIndices[0] == PacketSize - 1) { + PacketReturnType rslt = m_impl.template packet(inputIndices[0]); + return rslt; + } + else { + EIGEN_ALIGN_MAX CoeffReturnType values[PacketSize]; + values[0] = m_impl.coeff(inputIndices[0]); + values[PacketSize-1] = m_impl.coeff(inputIndices[1]); + for (int i = 1; i < PacketSize-1; ++i) { + values[i] = coeff(index+i); + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + const double compute_cost = NumDims * (TensorOpCost::DivCost() + + TensorOpCost::MulCost() + + 2 * TensorOpCost::AddCost()); + return m_impl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, compute_cost, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + protected: + Dimensions m_dimensions; + array m_outputStrides; + array m_inputStrides; + array m_patchStrides; + + TensorEvaluator m_impl; +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_PATCH_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorRandom.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorRandom.h new file mode 100644 index 00000000..1655a813 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorRandom.h @@ -0,0 +1,276 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2016 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_RANDOM_H +#define EIGEN_CXX11_TENSOR_TENSOR_RANDOM_H + +namespace Eigen { +namespace internal { + +namespace { + +EIGEN_DEVICE_FUNC uint64_t get_random_seed() { +#ifdef __CUDA_ARCH__ + // We don't support 3d kernels since we currently only use 1 and + // 2d kernels. + assert(threadIdx.z == 0); + return clock64() + + blockIdx.x * blockDim.x + threadIdx.x + + gridDim.x * blockDim.x * (blockIdx.y * blockDim.y + threadIdx.y); + +#elif defined _WIN32 + // Use the current time as a baseline. + SYSTEMTIME st; + GetSystemTime(&st); + int time = st.wSecond + 1000 * st.wMilliseconds; + // Mix in a random number to make sure that we get different seeds if + // we try to generate seeds faster than the clock resolution. + // We need 2 random values since the generator only generate 16 bits at + // a time (https://msdn.microsoft.com/en-us/library/398ax69y.aspx) + int rnd1 = ::rand(); + int rnd2 = ::rand(); + uint64_t rnd = (rnd1 | rnd2 << 16) ^ time; + return rnd; + +#elif defined __APPLE__ + // Same approach as for win32, except that the random number generator + // is better (// https://developer.apple.com/legacy/library/documentation/Darwin/Reference/ManPages/man3/random.3.html#//apple_ref/doc/man/3/random). + uint64_t rnd = ::random() ^ mach_absolute_time(); + return rnd; + +#else + // Augment the current time with pseudo random number generation + // to ensure that we get different seeds if we try to generate seeds + // faster than the clock resolution. + timespec ts; + clock_gettime(CLOCK_REALTIME, &ts); + uint64_t rnd = ::random() ^ ts.tv_nsec; + return rnd; +#endif +} + +static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE unsigned PCG_XSH_RS_generator(uint64_t* state) { + // TODO: Unify with the implementation in the non blocking thread pool. + uint64_t current = *state; + // Update the internal state + *state = current * 6364136223846793005ULL + 0xda3e39cb94b95bdbULL; + // Generate the random output (using the PCG-XSH-RS scheme) + return static_cast((current ^ (current >> 22)) >> (22 + (current >> 61))); +} + +static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE uint64_t PCG_XSH_RS_state(uint64_t seed) { + seed = seed ? seed : get_random_seed(); + return seed * 6364136223846793005ULL + 0xda3e39cb94b95bdbULL; +} + +} // namespace + + +template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +T RandomToTypeUniform(uint64_t* state) { + unsigned rnd = PCG_XSH_RS_generator(state); + return static_cast(rnd); +} + + +template <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +Eigen::half RandomToTypeUniform(uint64_t* state) { + Eigen::half result; + // Generate 10 random bits for the mantissa + unsigned rnd = PCG_XSH_RS_generator(state); + result.x = static_cast(rnd & 0x3ffu); + // Set the exponent + result.x |= (static_cast(15) << 10); + // Return the final result + return result - Eigen::half(1.0f); +} + + +template <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +float RandomToTypeUniform(uint64_t* state) { + typedef union { + uint32_t raw; + float fp; + } internal; + internal result; + // Generate 23 random bits for the mantissa mantissa + const unsigned rnd = PCG_XSH_RS_generator(state); + result.raw = rnd & 0x7fffffu; + // Set the exponent + result.raw |= (static_cast(127) << 23); + // Return the final result + return result.fp - 1.0f; +} + +template <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +double RandomToTypeUniform(uint64_t* state) { + typedef union { + uint64_t raw; + double dp; + } internal; + internal result; + result.raw = 0; + // Generate 52 random bits for the mantissa + // First generate the upper 20 bits + unsigned rnd1 = PCG_XSH_RS_generator(state) & 0xfffffu; + // The generate the lower 32 bits + unsigned rnd2 = PCG_XSH_RS_generator(state); + result.raw = (static_cast(rnd1) << 32) | rnd2; + // Set the exponent + result.raw |= (static_cast(1023) << 52); + // Return the final result + return result.dp - 1.0; +} + +template <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +std::complex RandomToTypeUniform >(uint64_t* state) { + return std::complex(RandomToTypeUniform(state), + RandomToTypeUniform(state)); +} +template <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +std::complex RandomToTypeUniform >(uint64_t* state) { + return std::complex(RandomToTypeUniform(state), + RandomToTypeUniform(state)); +} + +template class UniformRandomGenerator { + public: + static const bool PacketAccess = true; + + // Uses the given "seed" if non-zero, otherwise uses a random seed. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE UniformRandomGenerator( + uint64_t seed = 0) { + m_state = PCG_XSH_RS_state(seed); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE UniformRandomGenerator( + const UniformRandomGenerator& other) { + m_state = other.m_state; + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + T operator()(Index i) const { + uint64_t local_state = m_state + i; + T result = RandomToTypeUniform(&local_state); + m_state = local_state; + return result; + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Packet packetOp(Index i) const { + const int packetSize = internal::unpacket_traits::size; + EIGEN_ALIGN_MAX T values[packetSize]; + uint64_t local_state = m_state + i; + for (int j = 0; j < packetSize; ++j) { + values[j] = RandomToTypeUniform(&local_state); + } + m_state = local_state; + return internal::pload(values); + } + + private: + mutable uint64_t m_state; +}; + +template +struct functor_traits > { + enum { + // Rough estimate for floating point, multiplied by ceil(sizeof(T) / sizeof(float)). + Cost = 12 * NumTraits::AddCost * + ((sizeof(Scalar) + sizeof(float) - 1) / sizeof(float)), + PacketAccess = UniformRandomGenerator::PacketAccess + }; +}; + + + +template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +T RandomToTypeNormal(uint64_t* state) { + // Use the ratio of uniform method to generate numbers following a normal + // distribution. See for example Numerical Recipes chapter 7.3.9 for the + // details. + T u, v, q; + do { + u = RandomToTypeUniform(state); + v = T(1.7156) * (RandomToTypeUniform(state) - T(0.5)); + const T x = u - T(0.449871); + const T y = numext::abs(v) + T(0.386595); + q = x*x + y * (T(0.196)*y - T(0.25472)*x); + } while (q > T(0.27597) && + (q > T(0.27846) || v*v > T(-4) * numext::log(u) * u*u)); + + return v/u; +} + +template <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +std::complex RandomToTypeNormal >(uint64_t* state) { + return std::complex(RandomToTypeNormal(state), + RandomToTypeNormal(state)); +} +template <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +std::complex RandomToTypeNormal >(uint64_t* state) { + return std::complex(RandomToTypeNormal(state), + RandomToTypeNormal(state)); +} + + +template class NormalRandomGenerator { + public: + static const bool PacketAccess = true; + + // Uses the given "seed" if non-zero, otherwise uses a random seed. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE NormalRandomGenerator(uint64_t seed = 0) { + m_state = PCG_XSH_RS_state(seed); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE NormalRandomGenerator( + const NormalRandomGenerator& other) { + m_state = other.m_state; + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + T operator()(Index i) const { + uint64_t local_state = m_state + i; + T result = RandomToTypeNormal(&local_state); + m_state = local_state; + return result; + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Packet packetOp(Index i) const { + const int packetSize = internal::unpacket_traits::size; + EIGEN_ALIGN_MAX T values[packetSize]; + uint64_t local_state = m_state + i; + for (int j = 0; j < packetSize; ++j) { + values[j] = RandomToTypeNormal(&local_state); + } + m_state = local_state; + return internal::pload(values); + } + + private: + mutable uint64_t m_state; +}; + + +template +struct functor_traits > { + enum { + // On average, we need to generate about 3 random numbers + // 15 mul, 8 add, 1.5 logs + Cost = 3 * functor_traits >::Cost + + 15 * NumTraits::AddCost + 8 * NumTraits::AddCost + + 3 * functor_traits >::Cost / 2, + PacketAccess = NormalRandomGenerator::PacketAccess + }; +}; + + +} // end namespace internal +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_RANDOM_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReduction.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReduction.h new file mode 100644 index 00000000..e341e2e9 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReduction.h @@ -0,0 +1,799 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// Copyright (C) 2016 Mehdi Goli, Codeplay Software Ltd +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_H +#define EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_H + +// clang is incompatible with the CUDA syntax wrt making a kernel a class friend, +// so we'll use a macro to make clang happy. +#ifndef KERNEL_FRIEND +#if defined(__clang__) && defined(__CUDA__) +#define KERNEL_FRIEND friend __global__ +#else +#define KERNEL_FRIEND friend +#endif +#endif + + +namespace Eigen { + + +/** \class TensorReduction + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor reduction class. + * + */ + +namespace internal { + template class MakePointer_ > + struct traits > + : traits +{ + typedef traits XprTraits; + typedef typename XprTraits::Scalar Scalar; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + static const int NumDimensions = XprTraits::NumDimensions - array_size::value; + static const int Layout = XprTraits::Layout; + + template struct MakePointer { + // Intermediate typedef to workaround MSVC issue. + typedef MakePointer_ MakePointerT; + typedef typename MakePointerT::Type Type; + }; +}; + +template class MakePointer_> +struct eval, Eigen::Dense> +{ + typedef const TensorReductionOp& type; +}; + +template class MakePointer_> +struct nested, 1, typename eval >::type> +{ + typedef TensorReductionOp type; +}; + + +template struct DimInitializer { + template EIGEN_DEVICE_FUNC + static void run(const InputDims& input_dims, + const array::value>& reduced, + OutputDims* output_dims, ReducedDims* reduced_dims) { + const int NumInputDims = internal::array_size::value; + int outputIndex = 0; + int reduceIndex = 0; + for (int i = 0; i < NumInputDims; ++i) { + if (reduced[i]) { + (*reduced_dims)[reduceIndex] = input_dims[i]; + ++reduceIndex; + } else { + (*output_dims)[outputIndex] = input_dims[i]; + ++outputIndex; + } + } + } +}; + +template <> struct DimInitializer > { + template EIGEN_DEVICE_FUNC + static void run(const InputDims& input_dims, const array&, + Sizes<>*, array* reduced_dims) { + const int NumInputDims = internal::array_size::value; + for (int i = 0; i < NumInputDims; ++i) { + (*reduced_dims)[i] = input_dims[i]; + } + } +}; + + +template +struct are_inner_most_dims { + static const bool value = false; +}; +template +struct preserve_inner_most_dims { + static const bool value = false; +}; + +#if EIGEN_HAS_CONSTEXPR && EIGEN_HAS_VARIADIC_TEMPLATES +template +struct are_inner_most_dims{ + static const bool tmp1 = indices_statically_known_to_increase(); + static const bool tmp2 = index_statically_eq(0, 0); + static const bool tmp3 = index_statically_eq(array_size::value-1, array_size::value-1); + static const bool value = tmp1 & tmp2 & tmp3; +}; +template +struct are_inner_most_dims{ + static const bool tmp1 = indices_statically_known_to_increase(); + static const bool tmp2 = index_statically_eq(0, NumTensorDims - array_size::value); + static const bool tmp3 = index_statically_eq(array_size::value - 1, NumTensorDims - 1); + static const bool value = tmp1 & tmp2 & tmp3; + +}; +template +struct preserve_inner_most_dims{ + static const bool tmp1 = indices_statically_known_to_increase(); + static const bool tmp2 = index_statically_gt(0, 0); + static const bool value = tmp1 & tmp2; + +}; +template +struct preserve_inner_most_dims{ + static const bool tmp1 = indices_statically_known_to_increase(); + static const bool tmp2 = index_statically_lt(array_size::value - 1, NumTensorDims - 1); + static const bool value = tmp1 & tmp2; +}; +#endif + + +template +struct GenericDimReducer { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self& self, typename Self::Index firstIndex, Op& reducer, typename Self::CoeffReturnType* accum) { + EIGEN_STATIC_ASSERT((DimIndex > 0), YOU_MADE_A_PROGRAMMING_MISTAKE); + for (int j = 0; j < self.m_reducedDims[DimIndex]; ++j) { + const typename Self::Index input = firstIndex + j * self.m_reducedStrides[DimIndex]; + GenericDimReducer::reduce(self, input, reducer, accum); + } + } +}; +template +struct GenericDimReducer<0, Self, Op> { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self& self, typename Self::Index firstIndex, Op& reducer, typename Self::CoeffReturnType* accum) { + for (int j = 0; j < self.m_reducedDims[0]; ++j) { + const typename Self::Index input = firstIndex + j * self.m_reducedStrides[0]; + reducer.reduce(self.m_impl.coeff(input), accum); + } + } +}; +template +struct GenericDimReducer<-1, Self, Op> { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self& self, typename Self::Index index, Op& reducer, typename Self::CoeffReturnType* accum) { + reducer.reduce(self.m_impl.coeff(index), accum); + } +}; + +template +struct InnerMostDimReducer { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Self::CoeffReturnType reduce(const Self& self, typename Self::Index firstIndex, typename Self::Index numValuesToReduce, Op& reducer) { + typename Self::CoeffReturnType accum = reducer.initialize(); + for (typename Self::Index j = 0; j < numValuesToReduce; ++j) { + reducer.reduce(self.m_impl.coeff(firstIndex + j), &accum); + } + return reducer.finalize(accum); + } +}; + +template +struct InnerMostDimReducer { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Self::CoeffReturnType reduce(const Self& self, typename Self::Index firstIndex, typename Self::Index numValuesToReduce, Op& reducer) { + const int packetSize = internal::unpacket_traits::size; + const typename Self::Index VectorizedSize = (numValuesToReduce / packetSize) * packetSize; + typename Self::PacketReturnType p = reducer.template initializePacket(); + for (typename Self::Index j = 0; j < VectorizedSize; j += packetSize) { + reducer.reducePacket(self.m_impl.template packet(firstIndex + j), &p); + } + typename Self::CoeffReturnType accum = reducer.initialize(); + for (typename Self::Index j = VectorizedSize; j < numValuesToReduce; ++j) { + reducer.reduce(self.m_impl.coeff(firstIndex + j), &accum); + } + return reducer.finalizeBoth(accum, p); + } +}; + +template +struct InnerMostDimPreserver { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self&, typename Self::Index, Op&, typename Self::PacketReturnType*) { + eigen_assert(false && "should never be called"); + } +}; + +template +struct InnerMostDimPreserver { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self& self, typename Self::Index firstIndex, Op& reducer, typename Self::PacketReturnType* accum) { + EIGEN_STATIC_ASSERT((DimIndex > 0), YOU_MADE_A_PROGRAMMING_MISTAKE); + for (typename Self::Index j = 0; j < self.m_reducedDims[DimIndex]; ++j) { + const typename Self::Index input = firstIndex + j * self.m_reducedStrides[DimIndex]; + InnerMostDimPreserver::reduce(self, input, reducer, accum); + } + } +}; + +template +struct InnerMostDimPreserver<0, Self, Op, true> { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self& self, typename Self::Index firstIndex, Op& reducer, typename Self::PacketReturnType* accum) { + for (typename Self::Index j = 0; j < self.m_reducedDims[0]; ++j) { + const typename Self::Index input = firstIndex + j * self.m_reducedStrides[0]; + reducer.reducePacket(self.m_impl.template packet(input), accum); + } + } +}; +template +struct InnerMostDimPreserver<-1, Self, Op, true> { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self&, typename Self::Index, Op&, typename Self::PacketReturnType*) { + eigen_assert(false && "should never be called"); + } +}; + +// Default full reducer +template +struct FullReducer { + static const bool HasOptimizedImplementation = false; + + static EIGEN_DEVICE_FUNC void run(const Self& self, Op& reducer, const Device&, typename Self::CoeffReturnType* output) { + const typename Self::Index num_coeffs = array_prod(self.m_impl.dimensions()); + *output = InnerMostDimReducer::reduce(self, 0, num_coeffs, reducer); + } +}; + + +#ifdef EIGEN_USE_THREADS +// Multithreaded full reducers +template +struct FullReducerShard { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(const Self& self, typename Self::Index firstIndex, + typename Self::Index numValuesToReduce, Op& reducer, + typename Self::CoeffReturnType* output) { + *output = InnerMostDimReducer::reduce( + self, firstIndex, numValuesToReduce, reducer); + } +}; + +// Multithreaded full reducer +template +struct FullReducer { + static const bool HasOptimizedImplementation = !Op::IsStateful; + static const int PacketSize = + unpacket_traits::size; + + // launch one reducer per thread and accumulate the result. + static void run(const Self& self, Op& reducer, const ThreadPoolDevice& device, + typename Self::CoeffReturnType* output) { + typedef typename Self::Index Index; + const Index num_coeffs = array_prod(self.m_impl.dimensions()); + if (num_coeffs == 0) { + *output = reducer.finalize(reducer.initialize()); + return; + } + const TensorOpCost cost = + self.m_impl.costPerCoeff(Vectorizable) + + TensorOpCost(0, 0, internal::functor_traits::Cost, Vectorizable, + PacketSize); + const int num_threads = TensorCostModel::numThreads( + num_coeffs, cost, device.numThreads()); + if (num_threads == 1) { + *output = + InnerMostDimReducer::reduce(self, 0, num_coeffs, reducer); + return; + } + const Index blocksize = + std::floor(static_cast(num_coeffs) / num_threads); + const Index numblocks = blocksize > 0 ? num_coeffs / blocksize : 0; + eigen_assert(num_coeffs >= numblocks * blocksize); + + Barrier barrier(internal::convert_index(numblocks)); + MaxSizeVector shards(numblocks, reducer.initialize()); + for (Index i = 0; i < numblocks; ++i) { + device.enqueue_with_barrier(&barrier, &FullReducerShard::run, + self, i * blocksize, blocksize, reducer, + &shards[i]); + } + typename Self::CoeffReturnType finalShard; + if (numblocks * blocksize < num_coeffs) { + finalShard = InnerMostDimReducer::reduce( + self, numblocks * blocksize, num_coeffs - numblocks * blocksize, + reducer); + } else { + finalShard = reducer.initialize(); + } + barrier.Wait(); + + for (Index i = 0; i < numblocks; ++i) { + reducer.reduce(shards[i], &finalShard); + } + *output = reducer.finalize(finalShard); + } +}; + +#endif + + +// Default inner reducer +template +struct InnerReducer { + static const bool HasOptimizedImplementation = false; + + EIGEN_DEVICE_FUNC static bool run(const Self&, Op&, const Device&, typename Self::CoeffReturnType*, typename Self::Index, typename Self::Index) { + eigen_assert(false && "Not implemented"); + return true; + } +}; + +// Default outer reducer +template +struct OuterReducer { + static const bool HasOptimizedImplementation = false; + + EIGEN_DEVICE_FUNC static bool run(const Self&, Op&, const Device&, typename Self::CoeffReturnType*, typename Self::Index, typename Self::Index) { + eigen_assert(false && "Not implemented"); + return true; + } +}; + + +#if defined(EIGEN_USE_GPU) && defined(__CUDACC__) +template +__global__ void FullReductionKernel(R, const S, I, typename S::CoeffReturnType*, unsigned int*); + + +#ifdef EIGEN_HAS_CUDA_FP16 +template +__global__ void ReductionInitFullReduxKernelHalfFloat(R, const S, I, half2*); +template +__global__ void FullReductionKernelHalfFloat(R, const S, I, half*, half2*); +template +__global__ void InnerReductionKernelHalfFloat(R, const S, I, I, half*); + +#endif + +template +__global__ void InnerReductionKernel(R, const S, I, I, typename S::CoeffReturnType*); + +template +__global__ void OuterReductionKernel(R, const S, I, I, typename S::CoeffReturnType*); +#endif + +} // end namespace internal + + +template class MakePointer_> +class TensorReductionOp : public TensorBase, ReadOnlyAccessors> { + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename internal::remove_const::type CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorReductionOp(const XprType& expr, const Dims& dims) : m_expr(expr), m_dims(dims) + { } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorReductionOp(const XprType& expr, const Dims& dims, const Op& reducer) : m_expr(expr), m_dims(dims), m_reducer(reducer) + { } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const XprType& expression() const { return m_expr; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const Dims& dims() const { return m_dims; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const Op& reducer() const { return m_reducer; } + + protected: + typename XprType::Nested m_expr; + const Dims m_dims; + const Op m_reducer; +}; + + +// Eval as rvalue +template class MakePointer_, typename Device> +struct TensorEvaluator, Device> +{ + typedef TensorReductionOp XprType; + typedef typename XprType::Index Index; + typedef ArgType ChildType; + typedef typename TensorEvaluator::Dimensions InputDimensions; + static const int NumInputDims = internal::array_size::value; + static const int NumReducedDims = internal::array_size::value; + static const int NumOutputDims = NumInputDims - NumReducedDims; + typedef typename internal::conditional, DSizes >::type Dimensions; + typedef typename XprType::Scalar Scalar; + typedef TensorEvaluator, Device> Self; + static const bool InputPacketAccess = TensorEvaluator::PacketAccess; + typedef typename internal::remove_const::type CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = false, + PacketAccess = Self::InputPacketAccess && Op::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + static const bool ReducingInnerMostDims = internal::are_inner_most_dims::value; + static const bool PreservingInnerMostDims = internal::preserve_inner_most_dims::value; + static const bool RunningFullReduction = (NumOutputDims==0); + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device), m_reducer(op.reducer()), m_result(NULL), m_device(device), m_xpr_dims(op.dims()) + { + EIGEN_STATIC_ASSERT((NumInputDims >= NumReducedDims), YOU_MADE_A_PROGRAMMING_MISTAKE); + EIGEN_STATIC_ASSERT((!ReducingInnerMostDims | !PreservingInnerMostDims | (NumReducedDims == NumInputDims)), + YOU_MADE_A_PROGRAMMING_MISTAKE); + + // Build the bitmap indicating if an input dimension is reduced or not. + for (int i = 0; i < NumInputDims; ++i) { + m_reduced[i] = false; + } + for (int i = 0; i < NumReducedDims; ++i) { + eigen_assert(op.dims()[i] >= 0); + eigen_assert(op.dims()[i] < NumInputDims); + m_reduced[op.dims()[i]] = true; + } + + const typename TensorEvaluator::Dimensions& input_dims = m_impl.dimensions(); + internal::DimInitializer::run(input_dims, m_reduced, &m_dimensions, &m_reducedDims); + + // Precompute output strides. + if (NumOutputDims > 0) { + if (static_cast(Layout) == static_cast(ColMajor)) { + m_outputStrides[0] = 1; + for (int i = 1; i < NumOutputDims; ++i) { + m_outputStrides[i] = m_outputStrides[i - 1] * m_dimensions[i - 1]; + } + } else { + m_outputStrides.back() = 1; + for (int i = NumOutputDims - 2; i >= 0; --i) { + m_outputStrides[i] = m_outputStrides[i + 1] * m_dimensions[i + 1]; + } + } + } + + // Precompute input strides. + if (NumInputDims > 0) { + array input_strides; + if (static_cast(Layout) == static_cast(ColMajor)) { + input_strides[0] = 1; + for (int i = 1; i < NumInputDims; ++i) { + input_strides[i] = input_strides[i-1] * input_dims[i-1]; + } + } else { + input_strides.back() = 1; + for (int i = NumInputDims - 2; i >= 0; --i) { + input_strides[i] = input_strides[i + 1] * input_dims[i + 1]; + } + } + + int outputIndex = 0; + int reduceIndex = 0; + for (int i = 0; i < NumInputDims; ++i) { + if (m_reduced[i]) { + m_reducedStrides[reduceIndex] = input_strides[i]; + ++reduceIndex; + } else { + m_preservedStrides[outputIndex] = input_strides[i]; + ++outputIndex; + } + } + } + + // Special case for full reductions + if (NumOutputDims == 0) { + m_preservedStrides[0] = internal::array_prod(input_dims); + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool evalSubExprsIfNeeded(typename MakePointer_::Type data) { + m_impl.evalSubExprsIfNeeded(NULL); + + // Use the FullReducer if possible. + if ((RunningFullReduction && RunningOnSycl) ||(RunningFullReduction && + internal::FullReducer::HasOptimizedImplementation && + ((RunningOnGPU && (m_device.majorDeviceVersion() >= 3)) || + !RunningOnGPU))) { + bool need_assign = false; + if (!data) { + m_result = static_cast(m_device.allocate(sizeof(CoeffReturnType))); + data = m_result; + need_assign = true; + } + Op reducer(m_reducer); + internal::FullReducer::run(*this, reducer, m_device, data); + return need_assign; + } + else if(RunningOnSycl){ + const Index num_values_to_reduce = internal::array_prod(m_reducedDims); + const Index num_coeffs_to_preserve = internal::array_prod(m_dimensions); + if (!data) { + data = static_cast(m_device.allocate(sizeof(CoeffReturnType) * num_coeffs_to_preserve)); + m_result = data; + } + Op reducer(m_reducer); + internal::InnerReducer::run(*this, reducer, m_device, data, num_values_to_reduce, num_coeffs_to_preserve); + return (m_result != NULL); + } + + // Attempt to use an optimized reduction. + else if (RunningOnGPU && (m_device.majorDeviceVersion() >= 3)) { + bool reducing_inner_dims = true; + for (int i = 0; i < NumReducedDims; ++i) { + if (static_cast(Layout) == static_cast(ColMajor)) { + reducing_inner_dims &= m_reduced[i]; + } else { + reducing_inner_dims &= m_reduced[NumInputDims - 1 - i]; + } + } + if (internal::InnerReducer::HasOptimizedImplementation && + (reducing_inner_dims || ReducingInnerMostDims)) { + const Index num_values_to_reduce = internal::array_prod(m_reducedDims); + const Index num_coeffs_to_preserve = internal::array_prod(m_dimensions); + if (!data) { + if (num_coeffs_to_preserve < 1024 && num_values_to_reduce > num_coeffs_to_preserve && num_values_to_reduce > 128) { + data = static_cast(m_device.allocate(sizeof(CoeffReturnType) * num_coeffs_to_preserve)); + m_result = data; + } + else { + return true; + } + } + Op reducer(m_reducer); + if (internal::InnerReducer::run(*this, reducer, m_device, data, num_values_to_reduce, num_coeffs_to_preserve)) { + if (m_result) { + m_device.deallocate(m_result); + m_result = NULL; + } + return true; + } else { + return (m_result != NULL); + } + } + + bool preserving_inner_dims = true; + for (int i = 0; i < NumReducedDims; ++i) { + if (static_cast(Layout) == static_cast(ColMajor)) { + preserving_inner_dims &= m_reduced[NumInputDims - 1 - i]; + } else { + preserving_inner_dims &= m_reduced[i]; + } + } + if (internal::OuterReducer::HasOptimizedImplementation && + preserving_inner_dims) { + const Index num_values_to_reduce = internal::array_prod(m_reducedDims); + const Index num_coeffs_to_preserve = internal::array_prod(m_dimensions); + if (!data) { + if (num_coeffs_to_preserve < 1024 && num_values_to_reduce > num_coeffs_to_preserve && num_values_to_reduce > 32) { + data = static_cast(m_device.allocate(sizeof(CoeffReturnType) * num_coeffs_to_preserve)); + m_result = data; + } + else { + return true; + } + } + Op reducer(m_reducer); + if (internal::OuterReducer::run(*this, reducer, m_device, data, num_values_to_reduce, num_coeffs_to_preserve)) { + if (m_result) { + m_device.deallocate(m_result); + m_result = NULL; + } + return true; + } else { + return (m_result != NULL); + } + } + } + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + if (m_result) { + m_device.deallocate(m_result); + m_result = NULL; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + if ((RunningOnSycl || RunningFullReduction || RunningOnGPU) && m_result) { + return *(m_result + index); + } + Op reducer(m_reducer); + if (ReducingInnerMostDims || RunningFullReduction) { + const Index num_values_to_reduce = + (static_cast(Layout) == static_cast(ColMajor)) ? m_preservedStrides[0] : m_preservedStrides[NumPreservedStrides - 1]; + return internal::InnerMostDimReducer::reduce(*this, firstInput(index), + num_values_to_reduce, reducer); + } else { + typename Self::CoeffReturnType accum = reducer.initialize(); + internal::GenericDimReducer::reduce(*this, firstInput(index), reducer, &accum); + return reducer.finalize(accum); + } + } + + // TODO(bsteiner): provide a more efficient implementation. + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index + PacketSize - 1 < Index(internal::array_prod(dimensions()))); + + if (RunningOnGPU && m_result) { + return internal::pload(m_result + index); + } + + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + if (ReducingInnerMostDims) { + const Index num_values_to_reduce = + (static_cast(Layout) == static_cast(ColMajor)) ? m_preservedStrides[0] : m_preservedStrides[NumPreservedStrides - 1]; + const Index firstIndex = firstInput(index); + for (Index i = 0; i < PacketSize; ++i) { + Op reducer(m_reducer); + values[i] = internal::InnerMostDimReducer::reduce(*this, firstIndex + i * num_values_to_reduce, + num_values_to_reduce, reducer); + } + } else if (PreservingInnerMostDims) { + const Index firstIndex = firstInput(index); + const int innermost_dim = (static_cast(Layout) == static_cast(ColMajor)) ? 0 : NumOutputDims - 1; + // TBD: extend this the the n innermost dimensions that we preserve. + if (((firstIndex % m_dimensions[innermost_dim]) + PacketSize - 1) < m_dimensions[innermost_dim]) { + Op reducer(m_reducer); + typename Self::PacketReturnType accum = reducer.template initializePacket(); + internal::InnerMostDimPreserver::reduce(*this, firstIndex, reducer, &accum); + return reducer.finalizePacket(accum); + } else { + for (int i = 0; i < PacketSize; ++i) { + values[i] = coeff(index + i); + } + } + } else { + for (int i = 0; i < PacketSize; ++i) { + values[i] = coeff(index + i); + } + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + + // Must be called after evalSubExprsIfNeeded(). + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + if (RunningFullReduction && m_result) { + return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, PacketSize); + } else { + const Index num_values_to_reduce = internal::array_prod(m_reducedDims); + const double compute_cost = num_values_to_reduce * internal::functor_traits::Cost; + return m_impl.costPerCoeff(vectorized) * num_values_to_reduce + + TensorOpCost(0, 0, compute_cost, vectorized, PacketSize); + } + } + + EIGEN_DEVICE_FUNC typename MakePointer_::Type data() const { return m_result; } + /// required by sycl in order to extract the accessor + const TensorEvaluator& impl() const { return m_impl; } + /// added for sycl in order to construct the buffer from the sycl device + const Device& device() const{return m_device;} + /// added for sycl in order to re-construct the reduction eval on the device for the sub-kernel + const Dims& xprDims() const {return m_xpr_dims;} + + + private: + template friend struct internal::GenericDimReducer; + template friend struct internal::InnerMostDimReducer; + template friend struct internal::InnerMostDimPreserver; + template friend struct internal::FullReducer; +#ifdef EIGEN_USE_THREADS + template friend struct internal::FullReducerShard; +#endif +#if defined(EIGEN_USE_GPU) && defined(__CUDACC__) + template KERNEL_FRIEND void internal::FullReductionKernel(R, const S, I, typename S::CoeffReturnType*, unsigned int*); +#ifdef EIGEN_HAS_CUDA_FP16 + template KERNEL_FRIEND void internal::ReductionInitFullReduxKernelHalfFloat(R, const S, I, half2*); + template KERNEL_FRIEND void internal::FullReductionKernelHalfFloat(R, const S, I, half*, half2*); + template KERNEL_FRIEND void internal::InnerReductionKernelHalfFloat(R, const S, I, I, half*); +#endif + template KERNEL_FRIEND void internal::InnerReductionKernel(R, const S, I, I, typename S::CoeffReturnType*); + + template KERNEL_FRIEND void internal::OuterReductionKernel(R, const S, I, I, typename S::CoeffReturnType*); +#endif + +#if defined(EIGEN_USE_SYCL) + template < typename HostExpr_, typename FunctorExpr_, typename Tuple_of_Acc_, typename Dims_, typename Op_, typename Index_> friend class TensorSycl::internal::ReductionFunctor; + template friend class TensorSycl::internal::FullReductionKernelFunctor; +#endif + + + template friend struct internal::InnerReducer; + + // Returns the Index in the input tensor of the first value that needs to be + // used to compute the reduction at output index "index". + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index firstInput(Index index) const { + if (ReducingInnerMostDims) { + if (static_cast(Layout) == static_cast(ColMajor)) { + return index * m_preservedStrides[0]; + } else { + return index * m_preservedStrides[NumPreservedStrides - 1]; + } + } + // TBD: optimize the case where we preserve the innermost dimensions. + Index startInput = 0; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumOutputDims - 1; i > 0; --i) { + // This is index_i in the output tensor. + const Index idx = index / m_outputStrides[i]; + startInput += idx * m_preservedStrides[i]; + index -= idx * m_outputStrides[i]; + } + if (PreservingInnerMostDims) { + eigen_assert(m_preservedStrides[0] == 1); + startInput += index; + } else { + startInput += index * m_preservedStrides[0]; + } + } else { + for (int i = 0; i < NumOutputDims - 1; ++i) { + // This is index_i in the output tensor. + const Index idx = index / m_outputStrides[i]; + startInput += idx * m_preservedStrides[i]; + index -= idx * m_outputStrides[i]; + } + if (PreservingInnerMostDims) { + eigen_assert(m_preservedStrides[NumPreservedStrides - 1] == 1); + startInput += index; + } else { + startInput += index * m_preservedStrides[NumPreservedStrides - 1]; + } + } + return startInput; + } + + // Bitmap indicating if an input dimension is reduced or not. + array m_reduced; + // Dimensions of the output of the operation. + Dimensions m_dimensions; + // Precomputed strides for the output tensor. + array m_outputStrides; + // Subset of strides of the input tensor for the non-reduced dimensions. + // Indexed by output dimensions. + static const int NumPreservedStrides = max_n_1::size; + array m_preservedStrides; + + // Subset of strides of the input tensor for the reduced dimensions. + // Indexed by reduced dimensions. + array m_reducedStrides; + // Size of the input dimensions that are reduced. + // Indexed by reduced dimensions. + array m_reducedDims; + + // Evaluator for the input expression. + TensorEvaluator m_impl; + + // Operation to apply for computing the reduction. + Op m_reducer; + + // For full reductions +#if defined(EIGEN_USE_GPU) && defined(__CUDACC__) + static const bool RunningOnGPU = internal::is_same::value; + static const bool RunningOnSycl = false; +#elif defined(EIGEN_USE_SYCL) +static const bool RunningOnSycl = internal::is_same::type, Eigen::SyclDevice>::value; +static const bool RunningOnGPU = false; +#else + static const bool RunningOnGPU = false; + static const bool RunningOnSycl = false; +#endif + typename MakePointer_::Type m_result; + + const Device& m_device; + const Dims& m_xpr_dims; +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_H diff --git a/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReductionCuda.h b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReductionCuda.h new file mode 100644 index 00000000..edb0ab28 --- /dev/null +++ b/testbed/nanogui/ext/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReductionCuda.h @@ -0,0 +1,749 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_CUDA_H +#define EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_CUDA_H + +namespace Eigen { +namespace internal { + + +#if defined(EIGEN_USE_GPU) && defined(__CUDACC__) +// Full reducers for GPU, don't vectorize for now + +// Reducer function that enables multiple cuda thread to safely accumulate at the same +// output address. It basically reads the current value of the output variable, and +// attempts to update it with the new value. If in the meantime another cuda thread +// updated the content of the output address it will try again. +template +__device__ EIGEN_ALWAYS_INLINE void atomicReduce(T* output, T accum, R& reducer) { +#if __CUDA_ARCH__ >= 300 + if (sizeof(T) == 4) + { + unsigned int oldval = *reinterpret_cast(output); + unsigned int newval = oldval; + reducer.reduce(accum, reinterpret_cast(&newval)); + if (newval == oldval) { + return; + } + unsigned int readback; + while ((readback = atomicCAS((unsigned int*)output, oldval, newval)) != oldval) { + oldval = readback; + newval = oldval; + reducer.reduce(accum, reinterpret_cast(&newval)); + if (newval == oldval) { + return; + } + } + } + else if (sizeof(T) == 8) { + unsigned long long oldval = *reinterpret_cast(output); + unsigned long long newval = oldval; + reducer.reduce(accum, reinterpret_cast(&newval)); + if (newval == oldval) { + return; + } + unsigned long long readback; + while ((readback = atomicCAS((unsigned long long*)output, oldval, newval)) != oldval) { + oldval = readback; + newval = oldval; + reducer.reduce(accum, reinterpret_cast(&newval)); + if (newval == oldval) { + return; + } + } + } + else { + assert(0 && "Wordsize not supported"); + } +#else + assert(0 && "Shouldn't be called on unsupported device"); +#endif +} + +// We extend atomicExch to support extra data types +template +__device__ inline Type atomicExchCustom(Type* address, Type val) { + return atomicExch(address, val); +} + +template <> +__device__ inline double atomicExchCustom(double* address, double val) { + unsigned long long int* address_as_ull = reinterpret_cast(address); + return __longlong_as_double(atomicExch(address_as_ull, __double_as_longlong(val))); +} + +#ifdef EIGEN_HAS_CUDA_FP16 +template