Continue working on SAT, remove Cone and Cylinder shapes

This commit is contained in:
Daniel Chappuis 2017-02-02 22:58:40 +01:00
parent adeac94506
commit e9f2f94f64
47 changed files with 792 additions and 3999 deletions

View File

@ -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"

View File

@ -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<int>(shape1Type);
const int shape2Index = static_cast<int>(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<const uint>(shape1->getCollisionShape()->getType());
const uint shape2TypeIndex = static_cast<const uint>(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<int>(shape1Type);
const int shape2Index = static_cast<int>(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<int>(shape1Type);
const int shape2Index = static_cast<int>(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<int>(shape1Type);
const int shape2Index = static_cast<int>(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<int>(shape1Type);
const int shape2Index = static_cast<int>(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<int>(shape1Type);
const int shape2Index = static_cast<int>(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) {

View File

@ -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<int>(shape1Type)][static_cast<int>(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<unsigned int>(shape1Type);
const unsigned int shape2Index = static_cast<unsigned int>(shape2Type);
assert(shape1Index <= shape2Index);
return mCollisionMatrix[shape1Index][shape2Index];
}
// Ray casting method
inline void CollisionDetection::raycast(RaycastCallback* raycastCallback,
const Ray& ray,

View File

@ -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 <map>
using namespace reactphysics3d;
// Initialize the structure
void HalfEdgeStructure::init(std::vector<const Vector3> vertices, std::vector<std::vector<uint>> faces) {
using edgeKey = std::pair<uint, uint>;
std::map<edgeKey, Edge> edges;
std::map<edgeKey, edgeKey> nextEdges;
std::map<edgeKey, uint> mapEdgeToStartVertex;
// For each vertices
for (uint v=0; v<vertices.size(); v++) {
Vertex vertex(vertices[v]);
mVertices.push_back(vertex);
}
// For each face
for (uint f=0; f<faces.size(); f++) {
// Create a new face
Face face;
mFaces.push_back(face);
// Vertices of the current face
std::vector<uint>& faceVertices = faces[f];
std::vector<edgeKey> 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 =
}
}
}

View File

@ -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 <vector>
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<Face> mFaces;
/// All the vertices
std::vector<Vertex> mVertices;
/// All the half-edges
std::vector<Edge> mEdges;
public:
/// Constructor
HalfEdgeStructure() = default;
/// Destructor
~HalfEdgeStructure() = default;
/// Initialize the structure
void init(std::vector<const Vector3> vertices, std::vector<std::vector<uint>> 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

View File

@ -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<uint> 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;
}

View File

@ -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 <vector>
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<const Vector3> mVertices;
/// All the indexes of the face vertices
std::vector<std::vector<uint>> 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<uint> 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

View File

@ -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 {

View File

@ -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) {
}

View File

@ -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

View File

@ -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<CollisionShapeType>(type1);
CollisionShapeType shape2Type = static_cast<CollisionShapeType>(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;
}

View File

@ -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;

View File

@ -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<const ConvexShape*>(narrowPhaseInfo->collisionShape1);
const ConvexShape* shape2 = static_cast<const ConvexShape*>(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;
}

View File

@ -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 <algorithm>
/// 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

View File

@ -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 <cassert>
// 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;
}

View File

@ -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;
}

View File

@ -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 <cassert>
/// 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

View File

@ -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 <cassert>
/// 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

View File

@ -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<const ConvexShape*>(narrowPhaseInfo->collisionShape1);
const ConvexShape* shape2 = static_cast<const ConvexShape*>(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

View File

@ -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);
};
}

View File

@ -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 <algorithm>
#include <cmath>
#include <cfloat>
#include <cassert>
// We want to use the ReactPhysics3D namespace
using namespace reactphysics3d;
bool SATAlgorithm::testCollision(const NarrowPhaseInfo* narrowPhaseInfo,
ContactPointInfo& contactPointInfo) {
}

View File

@ -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

View File

@ -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;
}

View File

@ -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

View File

@ -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

View File

@ -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 <complex>
#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;
}

View File

@ -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

View File

@ -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;
}

View File

@ -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

View File

@ -24,15 +24,17 @@
********************************************************************************/
// Libraries
#include <cassert>
#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<uint>(shape1->getCollisionShape()->getType()) <=
static_cast<uint>(shape2->getCollisionShape()->getType()));
}

View File

@ -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

View File

@ -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"

View File

@ -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

View File

@ -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)));

View File

@ -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));

View File

@ -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

View File

@ -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; i<getNbParts(); i++) {
glDrawElements(GL_TRIANGLES, getNbFaces(i) * 3, 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();
if (wireframe) {
glPolygonMode(GL_FRONT_AND_BACK, GL_FILL);
}
}
// Create the Vertex Buffer Objects used to render with OpenGL.
/// We create two VBOs (one for vertices and one for indices)
void Cone::createVBOAndVAO() {
// Create the VBO for the vertices data
mVBOVertices.create();
mVBOVertices.bind();
size_t sizeVertices = mVertices.size() * sizeof(openglframework::Vector3);
mVBOVertices.copyDataIntoVBO(sizeVertices, getVerticesPointer(), GL_STATIC_DRAW);
mVBOVertices.unbind();
// Create the VBO for the normals data
mVBONormals.create();
mVBONormals.bind();
size_t sizeNormals = mNormals.size() * sizeof(openglframework::Vector3);
mVBONormals.copyDataIntoVBO(sizeNormals, getNormalsPointer(), GL_STATIC_DRAW);
mVBONormals.unbind();
if (hasTexture()) {
// Create the VBO for the texture co data
mVBOTextureCoords.create();
mVBOTextureCoords.bind();
size_t sizeTextureCoords = mUVs.size() * sizeof(openglframework::Vector2);
mVBOTextureCoords.copyDataIntoVBO(sizeTextureCoords, getUVTextureCoordinatesPointer(), GL_STATIC_DRAW);
mVBOTextureCoords.unbind();
}
// Create th VBO for the indices data
mVBOIndices.create();
mVBOIndices.bind();
size_t sizeIndices = mIndices[0].size() * sizeof(unsigned int);
mVBOIndices.copyDataIntoVBO(sizeIndices, getIndicesPointer(), 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();
if (hasTexture()) {
// Bind the VBO of texture coords
mVBOTextureCoords.bind();
}
// Bind the VBO of indices
mVBOIndices.bind();
// Unbind the VAO
mVAO.unbind();
}
// Set the scaling of the object
void Cone::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, 0, 0,
0, 0, mRadius * scaling.z, 0,
0, 0, 0, 1);
}

View File

@ -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

View File

@ -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; i<getNbParts(); i++) {
glDrawElements(GL_TRIANGLES, getNbFaces(i) * 3, 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();
if (wireframe) {
glPolygonMode(GL_FRONT_AND_BACK, GL_FILL);
}
}
// Create the Vertex Buffer Objects used to render with OpenGL.
/// We create two VBOs (one for vertices and one for indices)
void Cylinder::createVBOAndVAO() {
// Create the VBO for the vertices data
mVBOVertices.create();
mVBOVertices.bind();
size_t sizeVertices = mVertices.size() * sizeof(openglframework::Vector3);
mVBOVertices.copyDataIntoVBO(sizeVertices, getVerticesPointer(), GL_STATIC_DRAW);
mVBOVertices.unbind();
// Create the VBO for the normals data
mVBONormals.create();
mVBONormals.bind();
size_t sizeNormals = mNormals.size() * sizeof(openglframework::Vector3);
mVBONormals.copyDataIntoVBO(sizeNormals, getNormalsPointer(), GL_STATIC_DRAW);
mVBONormals.unbind();
if (hasTexture()) {
// Create the VBO for the texture co data
mVBOTextureCoords.create();
mVBOTextureCoords.bind();
size_t sizeTextureCoords = mUVs.size() * sizeof(openglframework::Vector2);
mVBOTextureCoords.copyDataIntoVBO(sizeTextureCoords, getUVTextureCoordinatesPointer(), GL_STATIC_DRAW);
mVBOTextureCoords.unbind();
}
// Create th VBO for the indices data
mVBOIndices.create();
mVBOIndices.bind();
size_t sizeIndices = mIndices[0].size() * sizeof(unsigned int);
mVBOIndices.copyDataIntoVBO(sizeIndices, getIndicesPointer(), 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();
if (hasTexture()) {
// Bind the VBO of texture coords
mVBOTextureCoords.bind();
}
// Bind the VBO of indices
mVBOIndices.bind();
// Unbind the VAO
mVAO.unbind();
}
// Set the scaling of the object
void Cylinder::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, 0, 0,
0, 0, mRadius * scaling.z, 0,
0, 0, 0, 1);
}

View File

@ -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

View File

@ -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);

View File

@ -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;

View File

@ -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"

View File

@ -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; i<NB_CONES; i++) {
// Position
float angle = i * 50.0f;
openglframework::Vector3 position(radius * cos(angle),
35 + i * (CONE_HEIGHT + 0.3f),
radius * sin(angle));
// Create a cone and a corresponding rigid in the dynamics world
Cone* cone = new Cone(CONE_RADIUS, CONE_HEIGHT, position, CONE_MASS, mDynamicsWorld,
meshFolderPath);
// Add some rolling resistance
cone->getRigidBody()->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; i<NB_CYLINDERS; i++) {
// Position
float angle = i * 35.0f;
openglframework::Vector3 position(radius * cos(angle),
25 + i * (CYLINDER_HEIGHT + 0.3f),
radius * sin(angle));
// Create a cylinder and a corresponding rigid in the dynamics world
Cylinder* cylinder = new Cylinder(CYLINDER_RADIUS, CYLINDER_HEIGHT, position ,
CYLINDER_MASS, mDynamicsWorld, meshFolderPath);
// Add some rolling resistance
cylinder->getRigidBody()->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<NB_CAPSULES; i++) {
@ -306,26 +250,6 @@ CollisionShapesScene::~CollisionShapesScene() {
delete (*it);
}
// Destroy all the cones of the scene
for (std::vector<Cone*>::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<Cylinder*>::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<Capsule*>::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<Cone*>::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<Cylinder*>::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<Capsule*>::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<Cone*>::iterator it = mCones.begin(); it != mCones.end(); ++it) {
(*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled);
}
// Render all the cylinders of the scene
for (std::vector<Cylinder*>::iterator it = mCylinders.begin(); it != mCylinders.end(); ++it) {
(*it)->render(shader, worldToCameraMatrix, mIsWireframeEnabled);
}
// Render all the capsules of the scene
for (std::vector<Capsule*>::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; i<NB_CONES; i++) {
// Position
float angle = i * 50.0f;
openglframework::Vector3 position(radius * cos(angle),
35 + i * (CONE_HEIGHT + 0.3f),
radius * sin(angle));
// 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);
// Reset the transform
mCones[i]->setTransform(transform);
}
// Create all the cylinders of the scene
for (int i=0; i<NB_CYLINDERS; i++) {
// Position
float angle = i * 35.0f;
openglframework::Vector3 position(radius * cos(angle),
25 + i * (CYLINDER_HEIGHT + 0.3f),
radius * sin(angle));
// 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);
// Reset the transform
mCylinders[i]->setTransform(transform);
}
// Create all the capsules of the scene
for (int i=0; i<NB_CAPSULES; i++) {

View File

@ -32,8 +32,6 @@
#include "SceneDemo.h"
#include "Sphere.h"
#include "Box.h"
#include "Cone.h"
#include "Cylinder.h"
#include "Capsule.h"
#include "ConvexMesh.h"
#include "ConcaveMesh.h"
@ -46,8 +44,6 @@ namespace collisionshapesscene {
const float SCENE_RADIUS = 30.0f;
const int NB_BOXES = 5;
const int NB_SPHERES = 5;
const int NB_CONES = 5;
const int NB_CYLINDERS = 5;
const int NB_CAPSULES = 5;
const int NB_MESHES = 3;
const int NB_COMPOUND_SHAPES = 3;
@ -80,10 +76,6 @@ class CollisionShapesScene : public SceneDemo {
std::vector<Sphere*> mSpheres;
std::vector<Cone*> mCones;
std::vector<Cylinder*> mCylinders;
std::vector<Capsule*> mCapsules;
/// All the convex meshes of the scene

View File

@ -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);

View File

@ -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;