Use the name CollisionShape instead of Collider for the collision shapes

This commit is contained in:
Daniel Chappuis 2012-08-04 00:34:30 +02:00
parent c7faae9b20
commit 29e5f2b7b4
30 changed files with 209 additions and 209 deletions

View File

@ -25,16 +25,16 @@
// Libraries
#include "Body.h"
#include "../colliders/Collider.h"
#include "../collision/shapes/CollisionShape.h"
// We want to use the ReactPhysics3D namespace
using namespace reactphysics3d;
// Constructor
Body::Body(const Transform& transform, Collider* collider, decimal mass, bodyindex id)
: collider(collider), mass(mass), transform(transform), isActive(true), id(id), hasMoved(false) {
Body::Body(const Transform& transform, CollisionShape *collisionShape, decimal mass, bodyindex id)
: collisionShape(collisionShape), mass(mass), transform(transform), isActive(true), id(id), hasMoved(false) {
assert(mass > 0.0);
assert(collider);
assert(collisionShape);
isMotionEnabled = true;
isCollisionEnabled = true;
@ -44,7 +44,7 @@ Body::Body(const Transform& transform, Collider* collider, decimal mass, bodyind
oldTransform = transform;
// Create the AABB for broad-phase collision detection
aabb = new AABB(transform, collider->getLocalExtents(OBJECT_MARGIN));
aabb = new AABB(transform, collisionShape->getLocalExtents(OBJECT_MARGIN));
}
// Destructor

View File

@ -30,8 +30,8 @@
#include <stdexcept>
#include <cassert>
#include "../mathematics/Transform.h"
#include "../colliders/AABB.h"
#include "../colliders/Collider.h"
#include "../collision/shapes/AABB.h"
#include "../collision/shapes/CollisionShape.h"
#include "../configuration.h"
// Namespace reactphysics3d
@ -46,7 +46,7 @@ namespace reactphysics3d {
*/
class Body {
protected :
Collider* collider; // Collider of the body
CollisionShape* collisionShape; // Collision shape of the body
decimal mass; // Mass of the body
Transform transform; // Position and orientation of the body
Transform oldTransform; // Last position and orientation of the body
@ -59,14 +59,14 @@ class Body {
bool hasMoved; // True if the body has moved during the last frame
public :
Body(const Transform& transform, Collider* collider, decimal mass, bodyindex id); // Constructor
virtual ~Body(); // Destructor
Body(const Transform& transform, CollisionShape* collisionShape, decimal mass, bodyindex id); // Constructor
virtual ~Body(); // Destructor
bodyindex getID() const; // Return the id of the body
bool getHasMoved() const; // Return true if the body has moved during the last frame
void setHasMoved(bool hasMoved); // Set the hasMoved variable (true if the body has moved during the last frame)
Collider* getCollider() const; // Return the collision collider
void setCollider(Collider* collider); // Set the collision collider
CollisionShape* getCollisionShape() const; // Return the collision shape
void setCollisionShape(CollisionShape* collisionShape); // Set the collision shape
decimal getMass() const; // Return the mass of the body
void setMass(decimal mass); // Set the mass of the body
bool getIsActive() const; // Return true if the body is active
@ -105,16 +105,16 @@ inline void Body::setHasMoved(bool hasMoved) {
this->hasMoved = hasMoved;
}
// Return the collider
inline Collider* Body::getCollider() const {
assert(collider);
return collider;
// Return the collision shape
inline CollisionShape *Body::getCollisionShape() const {
assert(collisionShape);
return collisionShape;
}
// Set the collider
inline void Body::setCollider(Collider* collider) {
assert(collider);
this->collider = collider;
// Set the collision shape
inline void Body::setCollisionShape(CollisionShape *collisionShape) {
assert(collisionShape);
this->collisionShape = collisionShape;
}
// Method that return the mass of the body
@ -201,7 +201,7 @@ inline void Body::updateAABB() {
// TODO : An AABB should not be updated every frame but only if the body has moved
// Update the AABB
aabb->update(transform, collider->getLocalExtents(OBJECT_MARGIN));
aabb->update(transform, collisionShape->getLocalExtents(OBJECT_MARGIN));
}
// Smaller than operator

View File

@ -25,22 +25,22 @@
// Libraries
#include "RigidBody.h"
#include "../colliders/Collider.h"
#include "../collision/shapes/CollisionShape.h"
// We want to use the ReactPhysics3D namespace
using namespace reactphysics3d;
// Constructor
RigidBody::RigidBody(const Transform& transform, decimal mass, const Matrix3x3& inertiaTensorLocal, Collider* collider, bodyindex id)
: Body(transform, collider, mass, id), inertiaTensorLocal(inertiaTensorLocal),
RigidBody::RigidBody(const Transform& transform, decimal mass, const Matrix3x3& inertiaTensorLocal, CollisionShape *collisionShape, bodyindex id)
: Body(transform, collisionShape, mass, id), inertiaTensorLocal(inertiaTensorLocal),
inertiaTensorLocalInverse(inertiaTensorLocal.getInverse()), massInverse(1.0/mass) {
restitution = 1.0;
// Set the body pointer of the AABB and the collider
// Set the body pointer of the AABB and the collision shape
aabb->setBodyPointer(this);
assert(collider);
assert(collisionShape);
assert(aabb);
}

View File

@ -29,7 +29,7 @@
// Libraries
#include <cassert>
#include "Body.h"
#include "../colliders/Collider.h"
#include "../collision/shapes/CollisionShape.h"
#include "../mathematics/mathematics.h"
// Namespace reactphysics3d
@ -55,7 +55,7 @@ class RigidBody : public Body {
public :
RigidBody(const Transform& transform, decimal mass, const Matrix3x3& inertiaTensorLocal,
Collider* collider, bodyindex id); // Constructor // Copy-constructor
CollisionShape* collisionShape, bodyindex id); // Constructor // Copy-constructor
virtual ~RigidBody(); // Destructor
Vector3 getLinearVelocity() const; // Return the linear velocity

View File

@ -29,7 +29,7 @@
#include "broadphase/SweepAndPruneAlgorithm.h"
#include "broadphase/NoBroadPhaseAlgorithm.h"
#include "../body/Body.h"
#include "../colliders/BoxCollider.h"
#include "../collision/shapes/BoxShape.h"
#include "../body/RigidBody.h"
#include "../configuration.h"
#include <cassert>
@ -129,15 +129,15 @@ bool CollisionDetection::computeNarrowPhase() {
// Update the contact cache of the overlapping pair
(*it).second->update();
// Select the narrow phase algorithm to use according to the two colliders
NarrowPhaseAlgorithm& narrowPhaseAlgorithm = SelectNarrowPhaseAlgorithm(body1->getCollider(), body2->getCollider());
// Select the narrow phase algorithm to use according to the two collision shapes
NarrowPhaseAlgorithm& narrowPhaseAlgorithm = SelectNarrowPhaseAlgorithm(body1->getCollisionShape(), body2->getCollisionShape());
// Notify the narrow-phase algorithm about the overlapping pair we are going to test
narrowPhaseAlgorithm.setCurrentOverlappingPair((*it).second);
// Use the narrow-phase collision detection algorithm to check if there really is a collision
if (narrowPhaseAlgorithm.testCollision(body1->getCollider(), body1->getTransform(),
body2->getCollider(), body2->getTransform(), contactInfo)) {
if (narrowPhaseAlgorithm.testCollision(body1->getCollisionShape(), body1->getTransform(),
body2->getCollisionShape(), body2->getTransform(), contactInfo)) {
assert(contactInfo);
collisionExists = true;

View File

@ -71,8 +71,8 @@ class CollisionDetection {
void computeBroadPhase(); // Compute the broad-phase collision detection
bool computeNarrowPhase(); // Compute the narrow-phase collision detection
NarrowPhaseAlgorithm& SelectNarrowPhaseAlgorithm(Collider* collider1,
Collider* collider2); // Select the narrow phase algorithm to use given two colliders
NarrowPhaseAlgorithm& SelectNarrowPhaseAlgorithm(CollisionShape* collisionShape1,
CollisionShape* collisionShape2); // Select the narrow phase algorithm to use given two collision shapes
public :
CollisionDetection(PhysicsWorld* physicsWorld); // Constructor
@ -96,11 +96,11 @@ inline OverlappingPair* CollisionDetection::getOverlappingPair(bodyindex body1ID
return 0;
}
// Select the narrow-phase collision algorithm to use given two colliders
inline NarrowPhaseAlgorithm& CollisionDetection::SelectNarrowPhaseAlgorithm(Collider* collider1, Collider* collider2) {
// Select the narrow-phase collision algorithm to use given two collision shapes
inline NarrowPhaseAlgorithm& CollisionDetection::SelectNarrowPhaseAlgorithm(CollisionShape* collisionShape1, CollisionShape* collisionShape2) {
// Sphere vs Sphere algorithm
if (collider1->getType() == SPHERE && collider2->getType() == SPHERE) {
if (collisionShape1->getType() == SPHERE && collisionShape2->getType() == SPHERE) {
return narrowPhaseSphereVsSphereAlgorithm;
}
else { // GJK algorithm

View File

@ -27,7 +27,7 @@
#define CONTACT_INFO_H
// Libraries
#include "../colliders/BoxCollider.h"
#include "../collision/shapes/BoxShape.h"
#include "../mathematics/mathematics.h"
// ReactPhysics3D namespace

View File

@ -28,7 +28,7 @@
// Libraries
#include "BroadPhaseAlgorithm.h"
#include "../../colliders/AABB.h"
#include "../../collision/shapes/AABB.h"
#include <map>
#include <vector>

View File

@ -81,8 +81,8 @@ int EPAAlgorithm::isOriginInTetrahedron(const Vector3& p1, const Vector3& p2, co
// 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
bool EPAAlgorithm::computePenetrationDepthAndContactPoints(Simplex simplex, const Collider* collider1, const Transform& transform1,
const Collider* collider2, const Transform& transform2,
bool EPAAlgorithm::computePenetrationDepthAndContactPoints(Simplex simplex, const CollisionShape* collisionShape1, const Transform& transform1,
const CollisionShape* collisionShape2, const Transform& transform2,
Vector3& v, ContactInfo*& contactInfo) {
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
@ -148,18 +148,18 @@ bool EPAAlgorithm::computePenetrationDepthAndContactPoints(Simplex simplex, cons
Vector3 v3 = rotationMat * v2;
// Compute the support point in the direction of v1
suppPointsA[2] = collider1->getLocalSupportPoint(v1, OBJECT_MARGIN);
suppPointsB[2] = body2Tobody1 * collider2->getLocalSupportPoint(rotateToBody2 * (-v1), OBJECT_MARGIN);
suppPointsA[2] = collisionShape1->getLocalSupportPoint(v1, OBJECT_MARGIN);
suppPointsB[2] = body2Tobody1 * collisionShape2->getLocalSupportPoint(rotateToBody2 * (-v1), OBJECT_MARGIN);
points[2] = suppPointsA[2] - suppPointsB[2];
// Compute the support point in the direction of v2
suppPointsA[3] = collider1->getLocalSupportPoint(v2, OBJECT_MARGIN);
suppPointsB[3] = body2Tobody1 * collider2->getLocalSupportPoint(rotateToBody2 * (-v2), OBJECT_MARGIN);
suppPointsA[3] = collisionShape1->getLocalSupportPoint(v2, OBJECT_MARGIN);
suppPointsB[3] = body2Tobody1 * collisionShape2->getLocalSupportPoint(rotateToBody2 * (-v2), OBJECT_MARGIN);
points[3] = suppPointsA[3] - suppPointsB[3];
// Compute the support point in the direction of v3
suppPointsA[4] = collider1->getLocalSupportPoint(v3, OBJECT_MARGIN);
suppPointsB[4] = body2Tobody1 * collider2->getLocalSupportPoint(rotateToBody2 * (-v3), OBJECT_MARGIN);
suppPointsA[4] = collisionShape1->getLocalSupportPoint(v3, OBJECT_MARGIN);
suppPointsB[4] = body2Tobody1 * collisionShape2->getLocalSupportPoint(rotateToBody2 * (-v3), OBJECT_MARGIN);
points[4] = suppPointsA[4] - suppPointsB[4];
// Now we have an hexahedron (two tetrahedron glued together). We can simply keep the
@ -253,11 +253,11 @@ bool EPAAlgorithm::computePenetrationDepthAndContactPoints(Simplex simplex, cons
Vector3 n = v1.cross(v2);
// Compute the two new vertices to obtain a hexahedron
suppPointsA[3] = collider1->getLocalSupportPoint(n, OBJECT_MARGIN);
suppPointsB[3] = body2Tobody1 * collider2->getLocalSupportPoint(rotateToBody2 * (-n), OBJECT_MARGIN);
suppPointsA[3] = collisionShape1->getLocalSupportPoint(n, OBJECT_MARGIN);
suppPointsB[3] = body2Tobody1 * collisionShape2->getLocalSupportPoint(rotateToBody2 * (-n), OBJECT_MARGIN);
points[3] = suppPointsA[3] - suppPointsB[3];
suppPointsA[4] = collider1->getLocalSupportPoint(-n, OBJECT_MARGIN);
suppPointsB[4] = body2Tobody1 * collider2->getLocalSupportPoint(rotateToBody2 * n, OBJECT_MARGIN);
suppPointsA[4] = collisionShape1->getLocalSupportPoint(-n, OBJECT_MARGIN);
suppPointsB[4] = body2Tobody1 * collisionShape2->getLocalSupportPoint(rotateToBody2 * n, OBJECT_MARGIN);
points[4] = suppPointsA[4] - suppPointsB[4];
// Construct the triangle faces
@ -326,8 +326,8 @@ bool EPAAlgorithm::computePenetrationDepthAndContactPoints(Simplex simplex, cons
}
// Compute the support point of the Minkowski difference (A-B) in the closest point direction
suppPointsA[nbVertices] = collider1->getLocalSupportPoint(triangle->getClosestPoint(), OBJECT_MARGIN);
suppPointsB[nbVertices] = body2Tobody1 * collider2->getLocalSupportPoint(rotateToBody2 * (-triangle->getClosestPoint()), OBJECT_MARGIN);
suppPointsA[nbVertices] = collisionShape1->getLocalSupportPoint(triangle->getClosestPoint(), OBJECT_MARGIN);
suppPointsB[nbVertices] = body2Tobody1 * collisionShape2->getLocalSupportPoint(rotateToBody2 * (-triangle->getClosestPoint()), OBJECT_MARGIN);
points[nbVertices] = suppPointsA[nbVertices] - suppPointsB[nbVertices];
int indexNewVertex = nbVertices;

View File

@ -28,7 +28,7 @@
// Libraries
#include "../GJK/Simplex.h"
#include "../../../colliders/Collider.h"
#include "../../shapes/CollisionShape.h"
#include "../../ContactInfo.h"
#include "../../../mathematics/mathematics.h"
#include "TriangleEPA.h"
@ -85,8 +85,8 @@ class EPAAlgorithm {
EPAAlgorithm(MemoryPool<ContactInfo>& memoryPoolContactInfos); // Constructor
~EPAAlgorithm(); // Destructor
bool computePenetrationDepthAndContactPoints(Simplex simplex, const Collider* collider1, const Transform& transform1,
const Collider* collider2, const Transform& transform2,
bool computePenetrationDepthAndContactPoints(Simplex simplex, const CollisionShape* collisionShape1, const Transform& transform1,
const CollisionShape* collisionShape2, const Transform& transform2,
Vector3& v, ContactInfo*& contactInfo); // Compute the penetration depth with EPA algorithm
};

View File

@ -60,8 +60,8 @@ GJKAlgorithm::~GJKAlgorithm() {
// 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 Collider* collider1, const Transform& transform1,
const Collider* collider2, const Transform& transform2,
bool GJKAlgorithm::testCollision(const CollisionShape* collisionShape1, const Transform& transform1,
const CollisionShape* collisionShape2, const Transform& transform2,
ContactInfo*& contactInfo) {
Vector3 suppA; // Support point of object A
@ -95,8 +95,8 @@ bool GJKAlgorithm::testCollision(const Collider* collider1, const Transform& tra
do {
// Compute the support points for original objects (without margins) A and B
suppA = collider1->getLocalSupportPoint(-v);
suppB = body2Tobody1 * collider2->getLocalSupportPoint(rotateToBody2 * v);
suppA = collisionShape1->getLocalSupportPoint(-v);
suppB = body2Tobody1 * collisionShape2->getLocalSupportPoint(rotateToBody2 * v);
// Compute the support point for the Minkowski difference A-B
w = suppA - suppB;
@ -235,7 +235,7 @@ bool GJKAlgorithm::testCollision(const Collider* collider1, const Transform& tra
// enlarged objects to compute a simplex polytope that contains the origin. Then, we give that simplex
// polytope to the EPA algorithm to compute the correct penetration depth and contact points between
// the enlarged objects.
return computePenetrationDepthForEnlargedObjects(collider1, transform1, collider2, transform2, contactInfo, v);
return computePenetrationDepthForEnlargedObjects(collisionShape1, transform1, collisionShape2, transform2, contactInfo, v);
}
// This method runs the GJK algorithm on the two enlarged objects (with margin)
@ -243,8 +243,8 @@ bool GJKAlgorithm::testCollision(const Collider* collider1, const Transform& tra
// 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 Collider* const collider1, const Transform& transform1,
const Collider* const collider2, const Transform& transform2,
bool GJKAlgorithm::computePenetrationDepthForEnlargedObjects(const CollisionShape* const collisionShape1, const Transform& transform1,
const CollisionShape* const collisionShape2, const Transform& transform2,
ContactInfo*& contactInfo, Vector3& v) {
Simplex simplex;
Vector3 suppA;
@ -262,8 +262,8 @@ bool GJKAlgorithm::computePenetrationDepthForEnlargedObjects(const Collider* con
do {
// Compute the support points for the enlarged object A and B
suppA = collider1->getLocalSupportPoint(-v, OBJECT_MARGIN);
suppB = body2ToBody1 * collider2->getLocalSupportPoint(rotateToBody2 * v, OBJECT_MARGIN);
suppA = collisionShape1->getLocalSupportPoint(-v, OBJECT_MARGIN);
suppB = body2ToBody1 * collisionShape2->getLocalSupportPoint(rotateToBody2 * v, OBJECT_MARGIN);
// Compute the support point for the Minkowski difference A-B
w = suppA - suppB;
@ -299,5 +299,5 @@ bool GJKAlgorithm::computePenetrationDepthForEnlargedObjects(const Collider* con
// 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 algoEPA.computePenetrationDepthAndContactPoints(simplex, collider1, transform1, collider2, transform2, v, contactInfo);
return algoEPA.computePenetrationDepthAndContactPoints(simplex, collisionShape1, transform1, collisionShape2, transform2, v, contactInfo);
}

View File

@ -29,7 +29,7 @@
// Libraries
#include "../NarrowPhaseAlgorithm.h"
#include "../../ContactInfo.h"
#include "../../../colliders/Collider.h"
#include "../../../collision/shapes/CollisionShape.h"
#include "../EPA/EPAAlgorithm.h"
@ -61,16 +61,16 @@ class GJKAlgorithm : public NarrowPhaseAlgorithm {
private :
EPAAlgorithm algoEPA; // EPA Algorithm
bool computePenetrationDepthForEnlargedObjects(const Collider* collider1, const Transform& transform1,
const Collider* collider2, const Transform& transform2,
bool computePenetrationDepthForEnlargedObjects(const CollisionShape* collisionShape1, const Transform& transform1,
const CollisionShape* collisionShape2, const Transform& transform2,
ContactInfo*& contactInfo, Vector3& v); // Compute the penetration depth for enlarged objects
public :
GJKAlgorithm(MemoryPool<ContactInfo>& memoryPoolContactInfos); // Constructor
~GJKAlgorithm(); // Destructor
virtual bool testCollision(const Collider* collider1, const Transform& transform1,
const Collider* collider2, const Transform& transform2,
virtual bool testCollision(const CollisionShape* collisionShape1, const Transform& transform1,
const CollisionShape* collisionShape2, const Transform& transform2,
ContactInfo*& contactInfo); // Return true and compute a contact info if the two bounding volume collide
};

View File

@ -53,8 +53,8 @@ class NarrowPhaseAlgorithm {
virtual ~NarrowPhaseAlgorithm(); // Destructor
void setCurrentOverlappingPair(OverlappingPair* overlappingPair); // Set the current overlapping pair of bodies
virtual bool testCollision(const Collider* collider1, const Transform& transform1,
const Collider* collider2, const Transform& transform2,
virtual bool testCollision(const CollisionShape* collisionShape1, const Transform& transform1,
const CollisionShape* collisionShape2, const Transform& transform2,
ContactInfo*& contactInfo)=0; // Return true and compute a contact info if the two bounding volume collide
};

View File

@ -25,7 +25,7 @@
// Libraries
#include "SphereVsSphereAlgorithm.h"
#include "../../colliders/SphereCollider.h"
#include "../../collision/shapes/SphereShape.h"
// We want to use the ReactPhysics3D namespace
using namespace reactphysics3d;
@ -41,26 +41,26 @@ SphereVsSphereAlgorithm::~SphereVsSphereAlgorithm() {
}
bool SphereVsSphereAlgorithm::testCollision(const Collider* collider1, const Transform& transform1,
const Collider* collider2, const Transform& transform2, ContactInfo*& contactInfo) {
bool SphereVsSphereAlgorithm::testCollision(const CollisionShape* collisionShape1, const Transform& transform1,
const CollisionShape* collisionShape2, const Transform& transform2, ContactInfo*& contactInfo) {
// Get the sphere colliders
const SphereCollider* sphereCollider1 = dynamic_cast<const SphereCollider*>(collider1);
const SphereCollider* sphereCollider2 = dynamic_cast<const SphereCollider*>(collider2);
// Get the sphere collision shapes
const SphereShape* sphereShape1 = dynamic_cast<const SphereShape*>(collisionShape1);
const SphereShape* sphereShape2 = dynamic_cast<const SphereShape*>(collisionShape2);
// Compute the distance between the centers
Vector3 vectorBetweenCenters = transform2.getPosition() - transform1.getPosition();
decimal squaredDistanceBetweenCenters = vectorBetweenCenters.lengthSquare();
// Compute the sum of the radius
decimal sumRadius = sphereCollider1->getRadius() + sphereCollider2->getRadius();
decimal sumRadius = sphereShape1->getRadius() + sphereShape2->getRadius();
// If the sphere colliders intersect
// If the sphere collision shapes intersect
if (squaredDistanceBetweenCenters <= sumRadius * sumRadius) {
Vector3 centerSphere2InBody1LocalSpace = transform1.inverse() * transform2.getPosition();
Vector3 centerSphere1InBody2LocalSpace = transform2.inverse() * transform1.getPosition();
Vector3 intersectionOnBody1 = sphereCollider1->getRadius() * centerSphere2InBody1LocalSpace.getUnit();
Vector3 intersectionOnBody2 = sphereCollider2->getRadius() * centerSphere1InBody2LocalSpace.getUnit();
Vector3 intersectionOnBody1 = sphereShape1->getRadius() * centerSphere2InBody1LocalSpace.getUnit();
Vector3 intersectionOnBody2 = sphereShape2->getRadius() * centerSphere1InBody2LocalSpace.getUnit();
decimal penetrationDepth = sumRadius - std::sqrt(squaredDistanceBetweenCenters);
// Create the contact info object
@ -71,4 +71,4 @@ bool SphereVsSphereAlgorithm::testCollision(const Collider* collider1, const Tra
}
return false;
}
}

View File

@ -38,7 +38,7 @@ namespace reactphysics3d {
/* -------------------------------------------------------------------
Class SphereVsSphereAlgorithm :
This class is used to compute the narrow-phase collision detection
between two sphere colliders.
between two sphere collision shapes.
-------------------------------------------------------------------
*/
class SphereVsSphereAlgorithm : public NarrowPhaseAlgorithm {
@ -48,8 +48,8 @@ class SphereVsSphereAlgorithm : public NarrowPhaseAlgorithm {
SphereVsSphereAlgorithm(MemoryPool<ContactInfo>& memoryPoolContactInfos); // Constructor
virtual ~SphereVsSphereAlgorithm(); // Destructor
virtual bool testCollision(const Collider* collider1, const Transform& transform1,
const Collider* collider2, const Transform& transform2,
virtual bool testCollision(const CollisionShape* collisionShape1, const Transform& transform1,
const CollisionShape* collisionShape2, const Transform& transform2,
ContactInfo*& contactInfo); // Return true and compute a contact info if the two bounding volume collide
};

View File

@ -25,7 +25,7 @@
// Libraries
#include "AABB.h"
#include "../configuration.h"
#include "../../configuration.h"
#include <cassert>
#if defined(VISUAL_DEBUG)

View File

@ -27,7 +27,7 @@
#define AABB_H
// Libraries
#include "../mathematics/mathematics.h"
#include "../../mathematics/mathematics.h"
// ReactPhysics3D namespace
namespace reactphysics3d {

View File

@ -24,8 +24,8 @@
********************************************************************************/
// Libraries
#include "BoxCollider.h"
#include "../configuration.h"
#include "BoxShape.h"
#include "../../configuration.h"
#include <vector>
#include <cassert>
@ -46,17 +46,17 @@ using namespace reactphysics3d;
using namespace std;
// Constructor
BoxCollider::BoxCollider(const Vector3& extent) : Collider(BOX), extent(extent) {
BoxShape::BoxShape(const Vector3& extent) : CollisionShape(BOX), extent(extent) {
}
// Destructor
BoxCollider::~BoxCollider() {
BoxShape::~BoxShape() {
}
// Return the local inertia tensor of the collider
void BoxCollider::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const {
// Return the local inertia tensor of the collision shape
void BoxShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const {
decimal factor = (1.0 / 3.0) * mass;
decimal xSquare = extent.getX() * extent.getX();
decimal ySquare = extent.getY() * extent.getY();
@ -68,7 +68,7 @@ void BoxCollider::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) con
#ifdef VISUAL_DEBUG
// Draw the Box (only for testing purpose)
void BoxCollider::draw() const {
void BoxShape::draw() const {
decimal e1 = extent.getX();
decimal e2 = extent.getY();
decimal e3 = extent.getZ();

View File

@ -23,39 +23,39 @@
* *
********************************************************************************/
#ifndef BOX_COLLIDER_H
#define BOX_COLLIDER_H
#ifndef BOX_SHAPE_H
#define BOX_SHAPE_H
// Libraries
#include <cfloat>
#include "Collider.h"
#include "../mathematics/mathematics.h"
#include "CollisionShape.h"
#include "../../mathematics/mathematics.h"
// ReactPhysics3D namespace
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class BoxCollider :
This class represents a 3D box collider. Those axis are unit length.
Class BoxShape :
This class represents a 3D box shape. Those axis are unit length.
The three extents are half-widths of the box along the three
axis x, y, z local axis. The "transform" of the corresponding
rigid body gives an orientation and a position to the box.
-------------------------------------------------------------------
*/
class BoxCollider : public Collider {
class BoxShape : public CollisionShape {
private :
Vector3 extent; // Extent sizes of the box in the x, y and z direction
public :
BoxCollider(const Vector3& extent); // Constructor
virtual ~BoxCollider(); // Destructor
BoxShape(const Vector3& extent); // Constructor
virtual ~BoxShape(); // Destructor
const Vector3& getExtent() const; // Return the extents of the box
void setExtent(const Vector3& extent); // Set the extents of the box
virtual Vector3 getLocalExtents(decimal margin=0.0) const; // Return the local extents in x,y and z direction
virtual Vector3 getLocalSupportPoint(const Vector3& direction, decimal margin=0.0) const; // Return a local support point in a given direction
virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; // Return the local inertia tensor of the collider
virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; // Return the local inertia tensor of the collision shape
#ifdef VISUAL_DEBUG
virtual void draw() const; // Draw the Box (only for testing purpose)
@ -63,23 +63,23 @@ class BoxCollider : public Collider {
};
// Return the extents of the box
inline const Vector3& BoxCollider::getExtent() const {
inline const Vector3& BoxShape::getExtent() const {
return extent;
}
// Set the extents of the box
inline void BoxCollider::setExtent(const Vector3& extent) {
inline void BoxShape::setExtent(const Vector3& extent) {
this->extent = extent;
}
// Return the local extents of the box (half-width) in x,y and z local direction
// This method is used to compute the AABB of the box
inline Vector3 BoxCollider::getLocalExtents(decimal margin) const {
inline Vector3 BoxShape::getLocalExtents(decimal margin) const {
return extent + Vector3(margin, margin, margin);
}
// Return a local support point in a given direction
inline Vector3 BoxCollider::getLocalSupportPoint(const Vector3& direction, decimal margin) const {
inline Vector3 BoxShape::getLocalSupportPoint(const Vector3& direction, decimal margin) const {
assert(margin >= 0.0);
return Vector3(direction.getX() < 0.0 ? -extent.getX()-margin : extent.getX()+margin,

View File

@ -24,17 +24,17 @@
********************************************************************************/
// Libraries
#include "Collider.h"
#include "CollisionShape.h"
// We want to use the ReactPhysics3D namespace
using namespace reactphysics3d;
// Constructor
Collider::Collider(ColliderType type) : type(type) {
CollisionShape::CollisionShape(CollisionShapeType type) : type(type) {
}
// Destructor
Collider::~Collider() {
CollisionShape::~CollisionShape() {
}

View File

@ -23,49 +23,49 @@
* *
********************************************************************************/
#ifndef COLLIDER_H
#define COLLIDER_H
#ifndef COLLISION_SHAPE_H
#define COLLISION_SHAPE_H
// Libraries
#include <cassert>
#include "../mathematics/Vector3.h"
#include "../mathematics/Matrix3x3.h"
#include "../../mathematics/Vector3.h"
#include "../../mathematics/Matrix3x3.h"
// ReactPhysics3D namespace
namespace reactphysics3d {
// Enumeration
enum ColliderType {BOX, SPHERE, CONE, CYLINDER}; // Type of the collider
enum CollisionShapeType {BOX, SPHERE, CONE, CYLINDER}; // Type of the collision shape
// Declarations
class Body;
/* -------------------------------------------------------------------
Class Collider :
This abstract class represents the collider associated with a
Class CollisionShape :
This abstract class represents the collision shape associated with a
body that is used during the narrow-phase collision detection.
-------------------------------------------------------------------
*/
class Collider {
class CollisionShape {
protected :
ColliderType type; // Type of the collider
CollisionShapeType type; // Type of the collision shape
public :
Collider(ColliderType type); // Constructor
virtual ~Collider(); // Destructor
CollisionShape(CollisionShapeType type); // Constructor
virtual ~CollisionShape(); // Destructor
ColliderType getType() const; // Return the type of the collider
CollisionShapeType getType() const; // Return the type of the collision shapes
virtual Vector3 getLocalSupportPoint(const Vector3& direction, decimal margin=0.0) const=0; // Return a local support point in a given direction
virtual Vector3 getLocalExtents(decimal margin=0.0) const=0; // Return the local extents in x,y and z direction
virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const=0; // Return the local inertia tensor of the collider
virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const=0; // Return the local inertia tensor of the collision shapes
};
// Return the type of the collider
inline ColliderType Collider::getType() const {
// Return the type of the collision shape
inline CollisionShapeType CollisionShape::getType() const {
return type;
}
}
#endif
#endif

View File

@ -25,8 +25,8 @@
// Libraries
#include <complex>
#include "../configuration.h"
#include "ConeCollider.h"
#include "../../configuration.h"
#include "ConeShape.h"
#if defined(VISUAL_DEBUG)
#if defined(APPLE_OS)
@ -44,7 +44,7 @@
using namespace reactphysics3d;
// Constructor
ConeCollider::ConeCollider(decimal radius, decimal height) : Collider(CONE), radius(radius), halfHeight(height/2.0) {
ConeShape::ConeShape(decimal radius, decimal height) : CollisionShape(CONE), radius(radius), halfHeight(height/2.0) {
assert(radius > 0.0);
assert(halfHeight > 0.0);
@ -53,12 +53,12 @@ ConeCollider::ConeCollider(decimal radius, decimal height) : Collider(CONE), rad
}
// Destructor
ConeCollider::~ConeCollider() {
ConeShape::~ConeShape() {
}
// Return a local support point in a given direction
inline Vector3 ConeCollider::getLocalSupportPoint(const Vector3& direction, decimal margin) const {
inline Vector3 ConeShape::getLocalSupportPoint(const Vector3& direction, decimal margin) const {
assert(margin >= 0.0);
const Vector3& v = direction;
@ -93,7 +93,7 @@ inline Vector3 ConeCollider::getLocalSupportPoint(const Vector3& direction, deci
#ifdef VISUAL_DEBUG
// Draw the cone (only for debuging purpose)
void ConeCollider::draw() const {
void ConeShape::draw() const {
// Draw in red
glColor3f(1.0, 0.0, 0.0);

View File

@ -23,19 +23,19 @@
* *
********************************************************************************/
#ifndef CONE_COLLIDER_H
#define CONE_COLLIDER_H
#ifndef CONE_SHAPE_H
#define CONE_SHAPE_H
// Libraries
#include "Collider.h"
#include "../mathematics/mathematics.h"
#include "CollisionShape.h"
#include "../../mathematics/mathematics.h"
// ReactPhysics3D namespace
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class ConeCollider :
This class represents a cone collider centered at the
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
@ -43,15 +43,15 @@ namespace reactphysics3d {
to the cone.
-------------------------------------------------------------------
*/
class ConeCollider : public Collider {
class ConeShape : public CollisionShape {
private :
decimal radius; // Radius of the base
decimal halfHeight; // Half height of the cone
decimal sinTheta; // sine of the semi angle at the apex point
public :
ConeCollider(decimal radius, decimal height); // Constructor
virtual ~ConeCollider(); // Destructor
ConeShape(decimal radius, decimal height); // Constructor
virtual ~ConeShape(); // Destructor
decimal getRadius() const; // Return the radius
void setRadius(decimal radius); // Set the radius
@ -59,7 +59,7 @@ class ConeCollider : public Collider {
void setHeight(decimal height); // Set the height
virtual Vector3 getLocalSupportPoint(const Vector3& direction, decimal margin=0.0) const; // Return a support point in a given direction
virtual Vector3 getLocalExtents(decimal margin=0.0) const; // Return the local extents in x,y and z direction
virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; // Return the local inertia tensor of the collider
virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; // Return the local inertia tensor of the collision shape
#ifdef VISUAL_DEBUG
@ -68,12 +68,12 @@ class ConeCollider : public Collider {
};
// Return the radius
inline decimal ConeCollider::getRadius() const {
inline decimal ConeShape::getRadius() const {
return radius;
}
// Set the radius
inline void ConeCollider::setRadius(decimal radius) {
inline void ConeShape::setRadius(decimal radius) {
this->radius = radius;
// Update sine of the semi-angle at the apex point
@ -81,12 +81,12 @@ inline void ConeCollider::setRadius(decimal radius) {
}
// Return the height
inline decimal ConeCollider::getHeight() const {
inline decimal ConeShape::getHeight() const {
return 2.0 * halfHeight;
}
// Set the height
inline void ConeCollider::setHeight(decimal height) {
inline void ConeShape::setHeight(decimal height) {
this->halfHeight = height / 2.0;
// Update the sine of the semi-angle at the apex point
@ -94,12 +94,12 @@ inline void ConeCollider::setHeight(decimal height) {
}
// Return the local extents in x,y and z direction
inline Vector3 ConeCollider::getLocalExtents(decimal margin) const {
inline Vector3 ConeShape::getLocalExtents(decimal margin) const {
return Vector3(radius + margin, halfHeight + margin, radius + margin);
}
// Return the local inertia tensor of the collider
inline void ConeCollider::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const {
// Return the local inertia tensor of the collision shape
inline void ConeShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const {
decimal rSquare = radius * radius;
decimal diagXZ = 0.15 * mass * (rSquare + halfHeight);
tensor.setAllValues(diagXZ, 0.0, 0.0, 0.0, 0.3 * mass * rSquare, 0.0, 0.0, 0.0, diagXZ);
@ -107,4 +107,4 @@ inline void ConeCollider::computeLocalInertiaTensor(Matrix3x3& tensor, decimal m
}; // End of the ReactPhysics3D namespace
#endif
#endif

View File

@ -24,8 +24,8 @@
********************************************************************************/
// Libraries
#include "CylinderCollider.h"
#include "../configuration.h"
#include "CylinderShape.h"
#include "../../configuration.h"
#if defined(VISUAL_DEBUG)
#if defined(APPLE_OS)
@ -43,18 +43,18 @@
using namespace reactphysics3d;
// Constructor
CylinderCollider::CylinderCollider(decimal radius, decimal height)
: Collider(CYLINDER), radius(radius), halfHeight(height/2.0) {
CylinderShape::CylinderShape(decimal radius, decimal height)
: CollisionShape(CYLINDER), radius(radius), halfHeight(height/2.0) {
}
// Destructor
CylinderCollider::~CylinderCollider() {
CylinderShape::~CylinderShape() {
}
// Return a local support point in a given direction
Vector3 CylinderCollider::getLocalSupportPoint(const Vector3& direction, decimal margin) const {
Vector3 CylinderShape::getLocalSupportPoint(const Vector3& direction, decimal margin) const {
assert(margin >= 0.0);
Vector3 supportPoint(0.0, 0.0, 0.0);
@ -86,7 +86,7 @@ Vector3 CylinderCollider::getLocalSupportPoint(const Vector3& direction, decimal
#ifdef VISUAL_DEBUG
// Draw the cone (only for debuging purpose)
void CylinderCollider::draw() const {
void CylinderShape::draw() const {
// Draw in red
glColor3f(1.0, 0.0, 0.0);

View File

@ -23,33 +23,33 @@
* *
********************************************************************************/
#ifndef CYLINDER_COLLIDER_H
#define CYLINDER_COLLIDER_H
#ifndef CYLINDER_SHAPE_H
#define CYLINDER_SHAPE_H
// Libraries
#include "Collider.h"
#include "../mathematics/mathematics.h"
#include "CollisionShape.h"
#include "../../mathematics/mathematics.h"
// ReactPhysics3D namespace
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class CylinderCollider :
This class represents a cylinder collision collider around the Y axis
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.
-------------------------------------------------------------------
*/
class CylinderCollider : public Collider {
class CylinderShape : public CollisionShape {
private :
decimal radius; // Radius of the base
decimal halfHeight; // Half height of the cone
public :
CylinderCollider(decimal radius, decimal height); // Constructor
virtual ~CylinderCollider(); // Destructor
CylinderShape(decimal radius, decimal height); // Constructor
virtual ~CylinderShape(); // Destructor
decimal getRadius() const; // Return the radius
void setRadius(decimal radius); // Set the radius
@ -57,7 +57,7 @@ class CylinderCollider : public Collider {
void setHeight(decimal height); // Set the height
virtual Vector3 getLocalSupportPoint(const Vector3& direction, decimal margin=0.0) const; // Return a support point in a given direction
virtual Vector3 getLocalExtents(decimal margin=0.0) const; // Return the local extents in x,y and z direction
virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; // Return the local inertia tensor of the collider
virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; // Return the local inertia tensor of the collision shape
#ifdef VISUAL_DEBUG
virtual void draw() const; // Draw the sphere (only for testing purpose)
@ -65,32 +65,32 @@ class CylinderCollider : public Collider {
};
// Return the radius
inline decimal CylinderCollider::getRadius() const {
inline decimal CylinderShape::getRadius() const {
return radius;
}
// Set the radius
inline void CylinderCollider::setRadius(decimal radius) {
inline void CylinderShape::setRadius(decimal radius) {
this->radius = radius;
}
// Return the height
inline decimal CylinderCollider::getHeight() const {
inline decimal CylinderShape::getHeight() const {
return halfHeight * 2.0;
}
// Set the height
inline void CylinderCollider::setHeight(decimal height) {
inline void CylinderShape::setHeight(decimal height) {
this->halfHeight = height / 2.0;
}
// Return the local extents in x,y and z direction
inline Vector3 CylinderCollider::getLocalExtents(decimal margin) const {
inline Vector3 CylinderShape::getLocalExtents(decimal margin) const {
return Vector3(radius + margin, halfHeight + margin, radius + margin);
}
// Return the local inertia tensor of the cylinder
inline void CylinderCollider::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const {
inline void CylinderShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const {
decimal height = 2.0 * halfHeight;
decimal diag = (1.0 / 12.0) * mass * (3 * radius * radius + height * height);
tensor.setAllValues(diag, 0.0, 0.0, 0.0, 0.5 * mass * radius * radius, 0.0, 0.0, 0.0, diag);

View File

@ -24,8 +24,8 @@
********************************************************************************/
// Libraries
#include "SphereCollider.h"
#include "../configuration.h"
#include "SphereShape.h"
#include "../../configuration.h"
#include <cassert>
#if defined(VISUAL_DEBUG)
@ -45,18 +45,18 @@ using namespace reactphysics3d;
using namespace std;
// Constructor
SphereCollider::SphereCollider(decimal radius) : Collider(SPHERE), radius(radius) {
SphereShape::SphereShape(decimal radius) : CollisionShape(SPHERE), radius(radius) {
}
// Destructor
SphereCollider::~SphereCollider() {
SphereShape::~SphereShape() {
}
#ifdef VISUAL_DEBUG
// Draw the sphere (only for testing purpose)
void SphereCollider::draw() const {
void SphereShape::draw() const {
// Draw in red
glColor3f(1.0, 0.0, 0.0);
@ -64,4 +64,4 @@ void SphereCollider::draw() const {
// Draw the sphere
glutWireSphere(radius, 50, 50);
}
#endif
#endif

View File

@ -23,35 +23,35 @@
* *
********************************************************************************/
#ifndef SPHERE_COLLIDER_H
#define SPHERE_COLLIDER_H
#ifndef SPHERE_SHAPE_H
#define SPHERE_SHAPE_H
// Libraries
#include "Collider.h"
#include "../mathematics/mathematics.h"
#include "CollisionShape.h"
#include "../../mathematics/mathematics.h"
// ReactPhysics3D namespace
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class SphereCollider :
This class represents a sphere collider that is centered
Class SphereShape :
This class represents a sphere collision shape that is centered
at the origin and defined by its radius.
-------------------------------------------------------------------
*/
class SphereCollider : public Collider {
class SphereShape : public CollisionShape {
private :
decimal radius; // Radius of the sphere
public :
SphereCollider(decimal radius); // Constructor
virtual ~SphereCollider(); // Destructor
SphereShape(decimal radius); // Constructor
virtual ~SphereShape(); // Destructor
decimal getRadius() const; // Return the radius of the sphere
void setRadius(decimal radius); // Set the radius of the sphere
virtual Vector3 getLocalSupportPoint(const Vector3& direction, decimal margin=0.0) const; // Return a local support point in a given direction
virtual Vector3 getLocalExtents(decimal margin=0.0) const; // Return the local extents in x,y and z direction
virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; // Return the local inertia tensor of the collider
virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; // Return the local inertia tensor of the collision shape
#ifdef VISUAL_DEBUG
virtual void draw() const; // Draw the sphere (only for testing purpose)
@ -59,17 +59,17 @@ class SphereCollider : public Collider {
};
// Get the radius of the sphere
inline decimal SphereCollider::getRadius() const {
inline decimal SphereShape::getRadius() const {
return radius;
}
// Set the radius of the sphere
inline void SphereCollider::setRadius(decimal radius) {
inline void SphereShape::setRadius(decimal radius) {
this->radius = radius;
}
// Return a local support point in a given direction
inline Vector3 SphereCollider::getLocalSupportPoint(const Vector3& direction, decimal margin) const {
inline Vector3 SphereShape::getLocalSupportPoint(const Vector3& direction, decimal margin) const {
assert(margin >= 0.0);
decimal length = direction.length();
@ -84,18 +84,18 @@ inline Vector3 SphereCollider::getLocalSupportPoint(const Vector3& direction, de
return Vector3(0, radius + margin, 0);
}
// Return the local extents of the collider (half-width) in x,y and z local direction
// Return the local extents of the collision shape (half-width) in x,y and z local direction
// This method is used to compute the AABB of the box
inline Vector3 SphereCollider::getLocalExtents(decimal margin) const {
inline Vector3 SphereShape::getLocalExtents(decimal margin) const {
return Vector3(radius + margin, radius + margin, radius + margin);
}
// Return the local inertia tensor of the sphere
inline void SphereCollider::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const {
inline void SphereShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const {
decimal diag = 0.4 * mass * radius * radius;
tensor.setAllValues(diag, 0.0, 0.0, 0.0, diag, 0.0, 0.0, 0.0, diag);
}
}; // End of the ReactPhysics3D namespace
#endif
#endif

View File

@ -43,7 +43,7 @@ PhysicsWorld::~PhysicsWorld() {
}
// Create a rigid body into the physics world
RigidBody* PhysicsWorld::createRigidBody(const Transform& transform, decimal mass, const Matrix3x3& inertiaTensorLocal, Collider* collider) {
RigidBody* PhysicsWorld::createRigidBody(const Transform& transform, decimal mass, const Matrix3x3& inertiaTensorLocal, CollisionShape* collisionShape) {
// Compute the body ID
bodyindex bodyID;
@ -57,7 +57,7 @@ RigidBody* PhysicsWorld::createRigidBody(const Transform& transform, decimal mas
}
// Create the rigid body
RigidBody* rigidBody = new (memoryPoolRigidBodies.allocateObject()) RigidBody(transform, mass, inertiaTensorLocal, collider, bodyID);
RigidBody* rigidBody = new (memoryPoolRigidBodies.allocateObject()) RigidBody(transform, mass, inertiaTensorLocal, collisionShape, bodyID);
// Add the rigid body to the physics world
bodies.insert(rigidBody);

View File

@ -65,7 +65,7 @@ class PhysicsWorld {
virtual ~PhysicsWorld(); // Destructor
RigidBody* createRigidBody(const Transform& transform, decimal mass,
const Matrix3x3& inertiaTensorLocal, Collider* collider); // Create a rigid body into the physics world
const Matrix3x3& inertiaTensorLocal, CollisionShape* collisionShape); // Create a rigid body into the physics world
void destroyRigidBody(RigidBody* rigidBody); // Destroy a rigid body
Vector3 getGravity() const; // Return the gravity vector of the world
bool getIsGravityOn() const; // Return if the gravity is on

View File

@ -40,12 +40,12 @@
#include "body/RigidBody.h"
#include "engine/PhysicsWorld.h"
#include "engine/PhysicsEngine.h"
#include "colliders/Collider.h"
#include "colliders/BoxCollider.h"
#include "colliders/SphereCollider.h"
#include "colliders/ConeCollider.h"
#include "colliders/CylinderCollider.h"
#include "colliders/AABB.h"
#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/AABB.h"
// Alias to the ReactPhysics3D namespace
namespace rp3d = reactphysics3d;