Start working on triangular meshes collision detection

This commit is contained in:
Daniel Chappuis 2015-08-27 22:31:05 +02:00
parent c76e5247aa
commit 0ddec3f842
21 changed files with 857 additions and 11 deletions

View File

@ -72,6 +72,8 @@ SET (REACTPHYSICS3D_SOURCES
"src/collision/narrowphase/NarrowPhaseAlgorithm.cpp"
"src/collision/narrowphase/SphereVsSphereAlgorithm.h"
"src/collision/narrowphase/SphereVsSphereAlgorithm.cpp"
"src/collision/narrowphase/ConcaveVsConvexAlgorithm.h"
"src/collision/narrowphase/ConcaveVsConvexAlgorithm.cpp"
"src/collision/shapes/AABB.h"
"src/collision/shapes/AABB.cpp"
"src/collision/shapes/BoxShape.h"
@ -88,10 +90,18 @@ SET (REACTPHYSICS3D_SOURCES
"src/collision/shapes/CylinderShape.cpp"
"src/collision/shapes/SphereShape.h"
"src/collision/shapes/SphereShape.cpp"
"src/collision/shapes/TriangleShape.h"
"src/collision/shapes/TriangleShape.cpp"
"src/collision/shapes/ConcaveMeshShape.h"
"src/collision/shapes/ConcaveMeshShape.cpp"
"src/collision/RaycastInfo.h"
"src/collision/RaycastInfo.cpp"
"src/collision/ProxyShape.h"
"src/collision/ProxyShape.cpp"
"src/collision/TriangleVertexArray.h"
"src/collision/TriangleVertexArray.cpp"
"src/collision/TriangleMesh.h"
"src/collision/TriangleMesh.cpp"
"src/collision/CollisionDetection.h"
"src/collision/CollisionDetection.cpp"
"src/constraint/BallAndSocketJoint.h"

View File

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

View File

@ -0,0 +1,87 @@
/********************************************************************************
* ReactPhysics3D physics library, http://www.reactphysics3d.com *
* Copyright (c) 2010-2015 Daniel Chappuis *
*********************************************************************************
* *
* This software is provided 'as-is', without any express or implied warranty. *
* In no event will the authors be held liable for any damages arising from the *
* use of this software. *
* *
* Permission is granted to anyone to use this software for any purpose, *
* including commercial applications, and to alter it and redistribute it *
* freely, subject to the following restrictions: *
* *
* 1. The origin of this software must not be misrepresented; you must not claim *
* that you wrote the original software. If you use this software in a *
* product, an acknowledgment in the product documentation would be *
* appreciated but is not required. *
* *
* 2. Altered source versions must be plainly marked as such, and must not be *
* misrepresented as being the original software. *
* *
* 3. This notice may not be removed or altered from any source distribution. *
* *
********************************************************************************/
#ifndef REACTPHYSICS3D_TRIANGLE_MESH_H
#define REACTPHYSICS3D_TRIANGLE_MESH_H
// Libraries
#include <vector>
#include "TriangleVertexArray.h"
namespace reactphysics3d {
// Class TriangleMesh
/**
* 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
* mesh for instance.
*/
class TriangleMesh {
protected:
/// All the triangle arrays of the mesh (one triangle array per part)
std::vector<TriangleVertexArray*> mTriangleArrays;
public:
/// Constructor
TriangleMesh();
/// Destructor
~TriangleMesh();
/// Add a subpart of the mesh
void addSubpart(TriangleVertexArray* triangleVertexArray);
/// Return a pointer to a given subpart (triangle vertex array) of the mesh
TriangleVertexArray* getSubpart(uint indexSubpart) const;
/// Return the number of subparts of the mesh
uint getNbSubparts() const;
};
// Add a subpart of the mesh
inline void TriangleMesh::addSubpart(TriangleVertexArray* triangleVertexArray) {
mTriangleArrays.push_back(triangleVertexArray );
}
// Return a pointer to a given subpart (triangle vertex array) of the mesh
inline TriangleVertexArray* TriangleMesh::getSubpart(uint indexSubpart) const {
assert(indexSubpart < mTriangleArrays.size());
return mTriangleArrays[indexSubpart];
}
// Return the number of subparts of the mesh
inline uint TriangleMesh::getNbSubparts() const {
return mTriangleArrays.size();
}
}
#endif

View File

@ -0,0 +1,45 @@
/********************************************************************************
* ReactPhysics3D physics library, http://www.reactphysics3d.com *
* Copyright (c) 2010-2015 Daniel Chappuis *
*********************************************************************************
* *
* This software is provided 'as-is', without any express or implied warranty. *
* In no event will the authors be held liable for any damages arising from the *
* use of this software. *
* *
* Permission is granted to anyone to use this software for any purpose, *
* including commercial applications, and to alter it and redistribute it *
* freely, subject to the following restrictions: *
* *
* 1. The origin of this software must not be misrepresented; you must not claim *
* that you wrote the original software. If you use this software in a *
* product, an acknowledgment in the product documentation would be *
* appreciated but is not required. *
* *
* 2. Altered source versions must be plainly marked as such, and must not be *
* misrepresented as being the original software. *
* *
* 3. This notice may not be removed or altered from any source distribution. *
* *
********************************************************************************/
// Libraries
#include "TriangleVertexArray.h"
using namespace reactphysics3d;
// Constructor
TriangleVertexArray::TriangleVertexArray(uint nbVertices, void* verticesStart, int verticesStride,
uint nbTriangles, void* indexesStart, int indexesStride) {
mNbVertices = nbVertices;
mVerticesStart = reinterpret_cast<unsigned char*>(verticesStart);
mVerticesStride = verticesStride;
mNbTriangles = nbTriangles;
mIndexesStart = reinterpret_cast<unsigned char*>(indexesStart);
mIndexesStride = indexesStride;
}
// Destructor
TriangleVertexArray::~TriangleVertexArray() {
}

View File

@ -0,0 +1,84 @@
/********************************************************************************
* ReactPhysics3D physics library, http://www.reactphysics3d.com *
* Copyright (c) 2010-2015 Daniel Chappuis *
*********************************************************************************
* *
* This software is provided 'as-is', without any express or implied warranty. *
* In no event will the authors be held liable for any damages arising from the *
* use of this software. *
* *
* Permission is granted to anyone to use this software for any purpose, *
* including commercial applications, and to alter it and redistribute it *
* freely, subject to the following restrictions: *
* *
* 1. The origin of this software must not be misrepresented; you must not claim *
* that you wrote the original software. If you use this software in a *
* product, an acknowledgment in the product documentation would be *
* appreciated but is not required. *
* *
* 2. Altered source versions must be plainly marked as such, and must not be *
* misrepresented as being the original software. *
* *
* 3. This notice may not be removed or altered from any source distribution. *
* *
********************************************************************************/
#ifndef REACTPHYSICS3D_TRIANGLE_VERTEX_ARRAY_H
#define REACTPHYSICS3D_TRIANGLE_VERTEX_ARRAY_H
// Libraries
namespace reactphysics3d {
// Class TriangleVertexArray
/**
* This class is used to describe the vertices and faces of a triangular mesh.
* A TriangleVertexArray represents a continuous array of vertices and indexes
* of a triangular mesh. When you create a TriangleVertexArray, no data is copied
* into the array. It only stores pointer to the da. The purpose is to allow
* the user to share vertices data between the physics engine and the rendering
* part. Therefore, make sure that the data pointed by a TriangleVertexArray
* remain valid during the TriangleVertexArray life.
*/
class TriangleVertexArray {
protected:
/// Number of vertices in the array
uint mNbVertices;
/// Pointer to the first vertex value in the array
unsigned char* mVerticesStart;
/// Stride (number of bytes) between the beginning of two vertices
/// values in the array
int mVerticesStride;
/// Number of triangles in the array
uint mNbTriangles;
/// Pointer to the first vertex index of the array
unsigned char* mIndexesStart;
/// Stride (number of bytes) between the beginning of two indexes in
/// the array
int mIndexesStride;
public:
/// Constructor
TriangleVertexArray(uint nbVertices, void* verticesStart, int verticesStride,
uint nbTriangles, void* indexesStart, int indexesStride);
/// Destructor
~TriangleVertexArray();
};
}
#endif

View File

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

View File

@ -0,0 +1,71 @@
/********************************************************************************
* ReactPhysics3D physics library, http://www.reactphysics3d.com *
* Copyright (c) 2010-2015 Daniel Chappuis *
*********************************************************************************
* *
* This software is provided 'as-is', without any express or implied warranty. *
* In no event will the authors be held liable for any damages arising from the *
* use of this software. *
* *
* Permission is granted to anyone to use this software for any purpose, *
* including commercial applications, and to alter it and redistribute it *
* freely, subject to the following restrictions: *
* *
* 1. The origin of this software must not be misrepresented; you must not claim *
* that you wrote the original software. If you use this software in a *
* product, an acknowledgment in the product documentation would be *
* appreciated but is not required. *
* *
* 2. Altered source versions must be plainly marked as such, and must not be *
* misrepresented as being the original software. *
* *
* 3. This notice may not be removed or altered from any source distribution. *
* *
********************************************************************************/
#ifndef REACTPHYSICS3D_CONCAVE_VS_CONVEX_ALGORITHM_H
#define REACTPHYSICS3D_CONCAVE_VS_CONVEX_ALGORITHM_H
// Libraries
/// Namespace ReactPhysics3D
namespace reactphysics3d {
// Class ConcaveVsConvexAlgorithm
/**
* This class is used to compute the narrow-phase collision detection
* between a concave collision shape and a convex collision shape. The idea is
* to use the GJK collision detection algorithm to compute the collision between
* the convex shape and each of the triangles in the concave shape.
*/
class ConcaveVsConvexAlgorithm : public NarrowPhaseAlgorithm {
protected :
// -------------------- Methods -------------------- //
/// Private copy-constructor
ConcaveVsConvexAlgorithm(const ConcaveVsConvexAlgorithm& algorithm);
/// Private assignment operator
ConcaveVsConvexAlgorithm& operator=(const ConcaveVsConvexAlgorithm& algorithm);
public :
// -------------------- Methods -------------------- //
/// Constructor
ConcaveVsConvexAlgorithm();
/// Destructor
virtual ~ConcaveVsConvexAlgorithm();
/// Return true and compute a contact info if the two bounding volume collide
virtual bool testCollision(ProxyShape* collisionShape1, ProxyShape* collisionShape2,
ContactPointInfo*& contactInfo);
};
}
#endif

View File

@ -52,7 +52,7 @@ namespace reactphysics3d {
*/
class BoxShape : public CollisionShape {
private :
protected :
// -------------------- Attributes -------------------- //

View File

@ -46,7 +46,7 @@ namespace reactphysics3d {
*/
class CapsuleShape : public CollisionShape {
private :
protected :
// -------------------- Attributes -------------------- //

View File

@ -40,8 +40,8 @@
namespace reactphysics3d {
/// Type of the collision shape
enum CollisionShapeType {BOX, SPHERE, CONE, CYLINDER, CAPSULE, CONVEX_MESH};
const int NB_COLLISION_SHAPE_TYPES = 6;
enum CollisionShapeType {TRIANGLE, BOX, SPHERE, CONE, CYLINDER, CAPSULE, CONVEX_MESH, CONCAVE_MESH};
const int NB_COLLISION_SHAPE_TYPES = 8;
// Declarations
class ProxyShape;

View File

@ -0,0 +1,48 @@
/********************************************************************************
* ReactPhysics3D physics library, http://www.reactphysics3d.com *
* Copyright (c) 2010-2015 Daniel Chappuis *
*********************************************************************************
* *
* This software is provided 'as-is', without any express or implied warranty. *
* In no event will the authors be held liable for any damages arising from the *
* use of this software. *
* *
* Permission is granted to anyone to use this software for any purpose, *
* including commercial applications, and to alter it and redistribute it *
* freely, subject to the following restrictions: *
* *
* 1. The origin of this software must not be misrepresented; you must not claim *
* that you wrote the original software. If you use this software in a *
* product, an acknowledgment in the product documentation would be *
* appreciated but is not required. *
* *
* 2. Altered source versions must be plainly marked as such, and must not be *
* misrepresented as being the original software. *
* *
* 3. This notice may not be removed or altered from any source distribution. *
* *
********************************************************************************/
// Libraries
#include "ConcaveMeshShape.h"
using namespace reactphysics3d;
// Constructor
ConcaveMeshShape::ConcaveMeshShape(TriangleMesh* triangleMesh) {
}
// Destructor
ConcaveMeshShape::~ConcaveMeshShape() {
}
// Raycast method with feedback information
bool ConcaveMeshShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const {
// TODO : Implement this
return false;
}

View File

@ -0,0 +1,172 @@
/********************************************************************************
* ReactPhysics3D physics library, http://www.reactphysics3d.com *
* Copyright (c) 2010-2015 Daniel Chappuis *
*********************************************************************************
* *
* This software is provided 'as-is', without any express or implied warranty. *
* In no event will the authors be held liable for any damages arising from the *
* use of this software. *
* *
* Permission is granted to anyone to use this software for any purpose, *
* including commercial applications, and to alter it and redistribute it *
* freely, subject to the following restrictions: *
* *
* 1. The origin of this software must not be misrepresented; you must not claim *
* that you wrote the original software. If you use this software in a *
* product, an acknowledgment in the product documentation would be *
* appreciated but is not required. *
* *
* 2. Altered source versions must be plainly marked as such, and must not be *
* misrepresented as being the original software. *
* *
* 3. This notice may not be removed or altered from any source distribution. *
* *
********************************************************************************/
#ifndef REACTPHYSICS3D_CONCAVE_MESH_SHAPE_H
#define REACTPHYSICS3D_CONCAVE_MESH_SHAPE_H
namespace reactphysics3d {
// TODO : Implement raycasting with this collision shape
// Class ConcaveMeshShape
/**
* This class represents a concave mesh shape. Note that collision detection
* with a concave mesh shape can be very expensive. You should use only use
* this shape for a static mesh.
*/
class ConcaveMeshShape : public CollisionShape {
protected:
// -------------------- Methods -------------------- //
/// Private copy-constructor
ConcaveMeshShape(const ConcaveMeshShape& shape);
/// Private assignment operator
ConcaveMeshShape& operator=(const ConcaveMeshShape& shape);
/// Return a local support point in a given direction with the object margin
virtual Vector3 getLocalSupportPointWithMargin(const Vector3& direction,
void** cachedCollisionData) const;
/// Return a local support point in a given direction without the object margin
virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction,
void** cachedCollisionData) const;
/// Return true if a point is inside the collision shape
virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const;
/// Raycast method with feedback information
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const;
/// Allocate and return a copy of the object
virtual ConcaveMeshShape* clone(void* allocatedMemory) const;
/// Return the number of bytes used by the collision shape
virtual size_t getSizeInBytes() const;
public:
/// Constructor
ConcaveMeshShape(TriangleMesh* triangleMesh);
/// Destructor
~ConcaveMeshShape();
/// Return the local bounds of the shape in x, y and z directions.
virtual void getLocalBounds(Vector3& min, Vector3& max) const;
/// Return the local inertia tensor of the collision shape
virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const;
/// Update the AABB of a body using its collision shape
virtual void computeAABB(AABB& aabb, const Transform& transform);
/// Test equality between two sphere shapes
virtual bool isEqualTo(const CollisionShape& otherCollisionShape) const;
};
/// Allocate and return a copy of the object
inline ConcaveMeshShape* ConcaveMeshShape::clone(void* allocatedMemory) const {
return new (allocatedMemory) ConcaveMeshShape(*this);
}
// Return the number of bytes used by the collision shape
inline size_t ConcaveMeshShape::getSizeInBytes() const {
return sizeof(ConcaveMeshShape);
}
// Return a local support point in a given direction with the object margin
inline Vector3 ConcaveMeshShape::getLocalSupportPointWithMargin(const Vector3& direction,
void** cachedCollisionData) const {
// TODO : Implement this
return Vector3(0, 0, 0);
}
// Return a local support point in a given direction without the object margin
inline Vector3 ConcaveMeshShape::getLocalSupportPointWithoutMargin(const Vector3& direction,
void** cachedCollisionData) const {
// TODO : Implement this
return Vector3(0.0, 0.0, 0.0);
}
// Return the local bounds of the shape in x, y and z directions.
// This method is used to compute the AABB of the box
/**
* @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 ConcaveMeshShape::getLocalBounds(Vector3& min, Vector3& max) const {
// TODO : Implement this
}
// Return the local inertia tensor of the sphere
/**
* @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 ConcaveMeshShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const {
// TODO : Implement this
decimal diag = decimal(0.4) * mass * mRadius * mRadius;
tensor.setAllValues(diag, 0.0, 0.0,
0.0, diag, 0.0,
0.0, 0.0, diag);
}
// Update the AABB of a body using its collision shape
/**
* @param[out] aabb The axis-aligned bounding box (AABB) of the collision shape
* computed in world-space coordinates
* @param transform Transform used to compute the AABB of the collision shape
*/
inline void ConcaveMeshShape::computeAABB(AABB& aabb, const Transform& transform) {
// TODO : Implement this
}
// Test equality between two sphere shapes
inline bool ConcaveMeshShape::isEqualTo(const CollisionShape& otherCollisionShape) const {
const ConcaveMeshShape& otherShape = dynamic_cast<const ConcaveMeshShape&>(otherCollisionShape);
// TODO : Implement this
return false;
}
// Return true if a point is inside the collision shape
inline bool ConcaveMeshShape::testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const {
// TODO : Implement this
return false;
}
}
#endif

View File

@ -51,7 +51,7 @@ namespace reactphysics3d {
*/
class ConeShape : public CollisionShape {
private :
protected :
// -------------------- Attributes -------------------- //

View File

@ -41,6 +41,9 @@ namespace reactphysics3d {
// Declaration
class CollisionWorld;
// TODO : Make possible to create a ConvexMeshShape using a TriangleMesh as for
// the ConcaveMeshShape
// Class ConvexMeshShape
/**
* This class represents a convex mesh shape. In order to create a convex mesh shape, you
@ -59,7 +62,7 @@ class CollisionWorld;
*/
class ConvexMeshShape : public CollisionShape {
private :
protected :
// -------------------- Attributes -------------------- //

View File

@ -51,7 +51,7 @@ namespace reactphysics3d {
*/
class CylinderShape : public CollisionShape {
private :
protected :
// -------------------- Attributes -------------------- //

View File

@ -44,7 +44,7 @@ namespace reactphysics3d {
*/
class SphereShape : public CollisionShape {
private :
protected :
// -------------------- Attributes -------------------- //

View File

@ -0,0 +1,69 @@
/********************************************************************************
* ReactPhysics3D physics library, http://www.reactphysics3d.com *
* Copyright (c) 2010-2015 Daniel Chappuis *
*********************************************************************************
* *
* This software is provided 'as-is', without any express or implied warranty. *
* In no event will the authors be held liable for any damages arising from the *
* use of this software. *
* *
* Permission is granted to anyone to use this software for any purpose, *
* including commercial applications, and to alter it and redistribute it *
* freely, subject to the following restrictions: *
* *
* 1. The origin of this software must not be misrepresented; you must not claim *
* that you wrote the original software. If you use this software in a *
* product, an acknowledgment in the product documentation would be *
* appreciated but is not required. *
* *
* 2. Altered source versions must be plainly marked as such, and must not be *
* misrepresented as being the original software. *
* *
* 3. This notice may not be removed or altered from any source distribution. *
* *
********************************************************************************/
// Libraries
#include "TriangleShape.h"
#include "collision/ProxyShape.h"
#include "configuration.h"
#include <cassert>
using namespace reactphysics3d;
// Constructor
/**
* @param point1 First point of the triangle
* @param point2 Second point of the triangle
* @param point3 Third point of the triangle
* @param margin The collision margin (in meters) around the collision shape
*/
TriangleShape::TriangleShape(const Vector3& point1, const Vector3& point2,
const Vector3& point3, decimal margin)
: CollisionShape(TRIANGLE, margin) {
mPoints[0] = point1;
mPoints[1] = point2;
mPoints[2] = point3;
}
// Private copy-constructor
TriangleShape::TriangleShape(const TriangleShape& shape)
: CollisionShape(shape) {
mPoints[0] = shape.mPoints[0];
mPoints[1] = shape.mPoints[1];
mPoints[2] = shape.mPoints[2];
}
// Destructor
TriangleShape::~TriangleShape() {
}
// Raycast method with feedback information
bool TriangleShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const {
// TODO : Implement this
return false;
}

View File

@ -0,0 +1,191 @@
/********************************************************************************
* ReactPhysics3D physics library, http://www.reactphysics3d.com *
* Copyright (c) 2010-2015 Daniel Chappuis *
*********************************************************************************
* *
* This software is provided 'as-is', without any express or implied warranty. *
* In no event will the authors be held liable for any damages arising from the *
* use of this software. *
* *
* Permission is granted to anyone to use this software for any purpose, *
* including commercial applications, and to alter it and redistribute it *
* freely, subject to the following restrictions: *
* *
* 1. The origin of this software must not be misrepresented; you must not claim *
* that you wrote the original software. If you use this software in a *
* product, an acknowledgment in the product documentation would be *
* appreciated but is not required. *
* *
* 2. Altered source versions must be plainly marked as such, and must not be *
* misrepresented as being the original software. *
* *
* 3. This notice may not be removed or altered from any source distribution. *
* *
********************************************************************************/
#ifndef REACTPHYSICS3D_TRIANGLE_SHAPE_H
#define REACTPHYSICS3D_TRIANGLE_SHAPE_H
// Libraries
#include "mathematics/mathematics.h"
#include "CollisionShape.h"
/// ReactPhysics3D namespace
namespace reactphysics3d {
// Class TriangleShape
/**
* This class represents a triangle collision shape that is centered
* at the origin and defined three points.
*/
class TriangleShape : public CollisionShape {
protected:
// -------------------- Attribute -------------------- //
/// Three points of the triangle
Vector3 mPoints[3];
// -------------------- Methods -------------------- //
/// Private copy-constructor
TriangleShape(const TriangleShape& shape);
/// Private assignment operator
TriangleShape& operator=(const TriangleShape& shape);
/// Return a local support point in a given direction with the object margin
virtual Vector3 getLocalSupportPointWithMargin(const Vector3& direction,
void** cachedCollisionData) const;
/// Return a local support point in a given direction without the object margin
virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction,
void** cachedCollisionData) const;
/// Return true if a point is inside the collision shape
virtual bool testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const;
/// Raycast method with feedback information
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const;
/// Allocate and return a copy of the object
virtual TriangleShape* clone(void* allocatedMemory) const;
/// Return the number of bytes used by the collision shape
virtual size_t getSizeInBytes() const;
public:
// -------------------- Methods -------------------- //
/// Constructor
TriangleShape(const Vector3& point1, const Vector3& point2,
const Vector3& point3, decimal margin);
/// Destructor
virtual ~TriangleShape();
/// Return the local bounds of the shape in x, y and z directions.
virtual void getLocalBounds(Vector3& min, Vector3& max) const;
/// Return the local inertia tensor of the collision shape
virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const;
/// Update the AABB of a body using its collision shape
virtual void computeAABB(AABB& aabb, const Transform& transform);
/// Test equality between two triangle shapes
virtual bool isEqualTo(const CollisionShape& otherCollisionShape) const;
};
/// Allocate and return a copy of the object
inline TriangleShape* TriangleShape::clone(void* allocatedMemory) const {
return new (allocatedMemory) TriangleShape(*this);
}
// Return the number of bytes used by the collision shape
inline size_t TriangleShape::getSizeInBytes() const {
return sizeof(TriangleShape);
}
// Return a local support point in a given direction with the object margin
inline Vector3 TriangleShape::getLocalSupportPointWithMargin(const Vector3& direction,
void** cachedCollisionData) const {
// TODO : Do we need to use margin for triangle support point ?
return getLocalSupportPointWithoutMargin(direction, cachedCollisionData);
}
// Return a local support point in a given direction without the object margin
inline Vector3 TriangleShape::getLocalSupportPointWithoutMargin(const Vector3& direction,
void** cachedCollisionData) const {
Vector3 dotProducts(direction.dot(mPoints[0]), direction.dot(mPoints[1], direction.dot(mPoints[2])));
return mPoints[dotProducts.getMaxAxis()];
}
// Return the local bounds of the shape in x, y and z directions.
// This method is used to compute the AABB of the box
/**
* @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 TriangleShape::getLocalBounds(Vector3& min, Vector3& max) const {
// TODO :This code is wrong
const Vector3 xAxis(worldPoint1.X, worldPoint2.X, worldPoint3.X);
const Vector3 yAxis(worldPoint1.Y, worldPoint2.Y, worldPoint3.Y);
const Vector3 zAxis(worldPoint1.Z, worldPoint2.Z, worldPoint3.Z);
min.setAllValues(xAxis.getMinAxis(), yAxis.getMinAxis(), zAxis.getMinAxis());
max.setAllValues(xAxis.getMaxAxis(), yAxis.getMaxAxis(), zAxis.getMaxAxis());
}
// Return the local inertia tensor of the triangle 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 TriangleShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const {
tensor.setToZero();
}
// Update the AABB of a body using its collision shape
/**
* @param[out] aabb The axis-aligned bounding box (AABB) of the collision shape
* computed in world-space coordinates
* @param transform Transform used to compute the AABB of the collision shape
*/
inline void TriangleShape::computeAABB(AABB& aabb, const Transform& transform) {
// TODO :This code is wrong
const Vector3 worldPoint1 = transform * mPoints[0];
const Vector3 worldPoint2 = transform * mPoints[1];
const Vector3 worldPoint3 = transform * mPoints[2];
const Vector3 xAxis(worldPoint1.X, worldPoint2.X, worldPoint3.X);
const Vector3 yAxis(worldPoint1.Y, worldPoint2.Y, worldPoint3.Y);
const Vector3 zAxis(worldPoint1.Z, worldPoint2.Z, worldPoint3.Z);
aabb.setMin(Vector3(xAxis.getMinAxis(), yAxis.getMinAxis(), zAxis.getMinAxis()));
aabb.setMax(Vector3(xAxis.getMaxAxis(), yAxis.getMaxAxis(), zAxis.getMaxAxis()));
}
// Test equality between two triangle shapes
inline bool TriangleShape::isEqualTo(const CollisionShape& otherCollisionShape) const {
const TriangleShape& otherShape = dynamic_cast<const TriangleShape&>(otherCollisionShape);
return (mPoints[0] == otherShape.mPoints[0] &&
mPoints[1] == otherShape.mPoints[1] &&
mPoints[2] == otherShape.mPoints[2]);
}
// Return true if a point is inside the collision shape
inline bool TriangleShape::testPointInside(const Vector3& localPoint, ProxyShape* proxyShape) const {
return false;
}
}
#endif

View File

@ -26,7 +26,7 @@ FILE(COPY "imgui/DroidSans.ttf" DESTINATION "${EXECUTABLE_OUTPUT_PATH}")
SET(CMAKE_CXX_FLAGS "-Wall -std=c++0x")
# Headers
INCLUDE_DIRECTORIES(${GLEW_INCLUDE_PATH} "src/" "opengl-framework/src/" "glfw/include/" "common/" "scenes/" "imgui/")
INCLUDE_DIRECTORIES("src/" "opengl-framework/src/" "glfw/include/" "common/" "scenes/" "imgui/")
# Testbed source files
SET(TESTBED_SOURCES

View File

@ -238,7 +238,7 @@ void Capsule::createVBOAndVAO() {
// Create th VBO for the indices data
mVBOIndices.create();
mVBOIndices.bind();
size_t sizeIndices = mIndices[0].size() * sizeof(uint);
size_t sizeIndices = mIndices[0].size() * sizeof(unsigned int);
mVBOIndices.copyDataIntoVBO(sizeIndices, getIndicesPointer(), GL_STATIC_DRAW);
mVBOIndices.unbind();

View File

@ -236,7 +236,7 @@ void Sphere::createVBOAndVAO() {
// Create th VBO for the indices data
mVBOIndices.create();
mVBOIndices.bind();
size_t sizeIndices = mIndices[0].size() * sizeof(uint);
size_t sizeIndices = mIndices[0].size() * sizeof(unsigned int);
mVBOIndices.copyDataIntoVBO(sizeIndices, getIndicesPointer(), GL_STATIC_DRAW);
mVBOIndices.unbind();