Merge branch optimization into develop

This commit is contained in:
Daniel Chappuis 2021-01-04 21:50:09 +01:00
commit afe8f100d6
181 changed files with 6707 additions and 6418 deletions

View File

@ -7,19 +7,31 @@ do not hesitate to take a look at the user manual.
### Added
- Method RigidBody::resetForce() to reset the accumulated external force on a rigid body has beend added
- Method RigidBody::resetTorque() to reset the accumulated external torque on a rigid body has beend added
- Method RigidBody::resetForce() to reset the accumulated external force on a rigid body has been added
- Method RigidBody::resetTorque() to reset the accumulated external torque on a rigid body has been added
- Constructors with local-space anchor/axis have been added to BallAndSocketJointInfo, HingeJointInfo, FixedJointInfo and SliderJointInfo classes
- Robustness of polyhedron vs polyhedron collision detection has been improved in SAT algorithm (face contacts are favored over edge-edge contacts for better stability)
- Method HingeJoint::getAngle() to get the current angle of the hinge joint has been added
### Changed
- The PhysicsWorld::setGravity() method now takes a const parameter
- Rolling resistance constraint is not solved anymore in the solver. Angular damping needs to be used instead to simulate this
- The List class has been renamed to Array
- The default number of iterations for the velocity solver is now 6 instead of 10
- The default number of iterations for the position solver is now 3 instead of 5
- The raycasting broad-phase performance has been improved
- The raycasting performance against HeighFieldShape has been improved (better middle-phase algorithm)
### Removed
- Method Material::getRollingResistance() has been removed (angular damping has to be used instead of rolling resistance)
- Method Material::setRollingResistance() has been removed (angular damping has to be used instead of rolling resistance)
### Fixed
- Issue [#165](https://github.com/DanielChappuis/reactphysics3d/issues/165) with order of contact manifolds in islands creation has been fixed
- Issue [#179](https://github.com/DanielChappuis/reactphysics3d/issues/179) with FixedJoint constraint
- Issue with concave vs convex shape collision detection has been fixed
- Issue with edge vs edge collision has been fixed in SAT algorithm (wrong contact normal was computed)
- Issue with sphere radius in DebugRenderer

View File

@ -63,9 +63,6 @@ set (REACTPHYSICS3D_HEADERS
"include/reactphysics3d/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.h"
"include/reactphysics3d/collision/narrowphase/NarrowPhaseInput.h"
"include/reactphysics3d/collision/narrowphase/NarrowPhaseInfoBatch.h"
"include/reactphysics3d/collision/narrowphase/SphereVsSphereNarrowPhaseInfoBatch.h"
"include/reactphysics3d/collision/narrowphase/CapsuleVsCapsuleNarrowPhaseInfoBatch.h"
"include/reactphysics3d/collision/narrowphase/SphereVsCapsuleNarrowPhaseInfoBatch.h"
"include/reactphysics3d/collision/shapes/AABB.h"
"include/reactphysics3d/collision/shapes/ConvexShape.h"
"include/reactphysics3d/collision/shapes/ConvexPolyhedronShape.h"
@ -124,6 +121,7 @@ set (REACTPHYSICS3D_HEADERS
"include/reactphysics3d/collision/CollisionCallback.h"
"include/reactphysics3d/collision/OverlapCallback.h"
"include/reactphysics3d/mathematics/mathematics.h"
"include/reactphysics3d/mathematics/mathematics_common.h"
"include/reactphysics3d/mathematics/mathematics_functions.h"
"include/reactphysics3d/mathematics/Matrix2x2.h"
"include/reactphysics3d/mathematics/Matrix3x3.h"
@ -140,7 +138,7 @@ set (REACTPHYSICS3D_HEADERS
"include/reactphysics3d/memory/MemoryManager.h"
"include/reactphysics3d/containers/Stack.h"
"include/reactphysics3d/containers/LinkedList.h"
"include/reactphysics3d/containers/List.h"
"include/reactphysics3d/containers/Array.h"
"include/reactphysics3d/containers/Map.h"
"include/reactphysics3d/containers/Set.h"
"include/reactphysics3d/containers/Pair.h"
@ -168,9 +166,6 @@ set (REACTPHYSICS3D_SOURCES
"src/collision/narrowphase/ConvexPolyhedronVsConvexPolyhedronAlgorithm.cpp"
"src/collision/narrowphase/NarrowPhaseInput.cpp"
"src/collision/narrowphase/NarrowPhaseInfoBatch.cpp"
"src/collision/narrowphase/SphereVsSphereNarrowPhaseInfoBatch.cpp"
"src/collision/narrowphase/CapsuleVsCapsuleNarrowPhaseInfoBatch.cpp"
"src/collision/narrowphase/SphereVsCapsuleNarrowPhaseInfoBatch.cpp"
"src/collision/shapes/AABB.cpp"
"src/collision/shapes/ConvexShape.cpp"
"src/collision/shapes/ConvexPolyhedronShape.cpp"
@ -226,7 +221,6 @@ set (REACTPHYSICS3D_SOURCES
"src/components/SliderJointComponents.cpp"
"src/collision/CollisionCallback.cpp"
"src/collision/OverlapCallback.cpp"
"src/mathematics/mathematics_functions.cpp"
"src/mathematics/Matrix2x2.cpp"
"src/mathematics/Matrix3x3.cpp"
"src/mathematics/Quaternion.cpp"

View File

@ -1201,7 +1201,7 @@ indices[16]=2; indices[17]=3; indices[18]=7; indices[19]=6;
indices[20]=0; indices[21]=4; indices[22]=7; indices[23]=3;
// Description of the six faces of the convex mesh
polygonFaces = new PolygonVertexArray::PolygonFace[6];
PolygonVertexArray::PolygonFace* polygonFaces = new PolygonVertexArray::PolygonFace[6];
PolygonVertexArray::PolygonFace* face = polygonFaces;
for (int f = 0; f < 6; f++) {
@ -1236,6 +1236,9 @@ ConvexMeshShape* convexMeshShape = physicsCommon.createConvexMeshShape(polyhedro
that you need to avoid coplanar faces in your convex mesh shape. Coplanar faces have to be merged together. Remember that convex meshes are
not limited to triangular faces, you can create faces with more than three vertices. \\
Also note that meshes with duplicated vertices are not supported. The number of vertices you pass to create the PolygonVertexArray must be exactly
the number of vertices in your convex mesh. \\
When you specify the vertices for each face of your convex mesh, be careful with their order. The vertices of a face must be specified in
counter clockwise order as seen from the outside of your convex mesh. \\
@ -1316,8 +1319,11 @@ ConcaveMeshShape* concaveMesh = physicsCommon.createConcaveMeshShape(triangleMes
\texttt{TriangleMesh} for multiple \texttt{ConcaveMeshShape} with a different scaling factor each time. \\
\end{sloppypar}
In the previous example, the vertex normals that are needed for collision detection are automatically computed. However, if you want to specify your own
vertex normals, you can do it by using another constructor for the \texttt{TriangleVertexArray}. \\
In the previous example, the vertices normals that are needed for collision detection are automatically computed. However, you can specify your own
vertices normals by using another constructor for the \texttt{TriangleVertexArray}. Note that each vertex normal is computed as weighted average
of the face normals of all the neighboring triangle faces. Therefore, if you specify your mesh with duplicated vertices when you create the
\emph{TriangleVertexArray}, the automatic vertices normals computation will not give correct normals because each vertex of the mesh will only be
part of a single triangle face. In this case, you should provide your own vertices normals when you create the \emph{TriangleVertexArray}. \\
\subsubsection{Heightfield Shape}
@ -1440,14 +1446,13 @@ colliderBody4->setCollideWithMaskBits(CATEGORY2);
\subsection{Material}
\label{sec:material}
The material of a rigid body is used to describe the physical properties it is made of. This is represented by the \texttt{Material} class. Each body that
you create will have a default material. You can get the material of the rigid body using the \texttt{RigidBody::\allowbreak getMaterial()} method. \\
The material of a collider is used to describe the physical properties it is made of. This is represented by the \texttt{Material} class. Each collider that you create will have a default material. You can get the material of the collider using the \texttt{Collider::\allowbreak getMaterial()} method. \\
You can use the material to set those physical properties. \\
For instance, you can change the bounciness of the rigid body. The bounciness is a value between 0 and 1. The value 1 is used for a very bouncy
object and the value 0 means that the body will not be bouncy at all. To change the bounciness of the material, you can use the
\texttt{Material::\allowbreak setBounciness()} method. \\
For instance, you can change the bounciness of the collider. The bounciness is a value between 0 and 1. The value 1 is used for
a very bouncy object and the value 0 means that the collider will not be bouncy at all. To change the bounciness of the material,
you can use the \texttt{Material::\allowbreak setBounciness()} method. \\
\begin{sloppypar}
It is also possible to set the mass density of the collider which has a default value of 1. As described in section \ref{sec:rigidbodymass}, the
@ -1455,25 +1460,20 @@ colliderBody4->setCollideWithMaskBits(CATEGORY2);
mass density of a collider, you need to use the \texttt{Material::setMassDensity()} method. \\
\end{sloppypar}
You are also able to change the friction coefficient of the body. This value needs to be between 0 and 1. If the value is 0, no friction will be
applied when the body is in contact with another body. However, if the value is 1, the friction force will be high. You can change the
friction coefficient of the material with the \texttt{Material::\allowbreak setFrictionCoefficient()} method. \\
You are also able to change the friction coefficient of the collider. This value needs to be between 0 and 1. If the value is 0,
no friction will be applied when the collider is in contact with another collider. However, if the value is 1, the friction force will be high. You can
change the friction coefficient of the material with the \texttt{Material::\allowbreak setFrictionCoefficient()} method. \\
You can use the material to add rolling resistance to a rigid body. Rolling resistance can be used to stop
a rolling object on a flat surface for instance. You should use this only with SphereShape or
CapsuleShape collision shapes. By default, rolling resistance is zero but you can
set a positive value using the \texttt{Material::\allowbreak setRollingResistance()} method to increase resistance. \\
Here is how to get the material of a rigid body and how to modify some of its properties: \\
Here is how to get the material of a collider and how to modify some of its properties: \\
\begin{lstlisting}
// Get the current material of the body
Material& material = rigidBody->getMaterial();
// Get the current material of the collider
Material& material = collider->getMaterial();
// Change the bounciness of the body
// Change the bounciness of the collider
material.setBounciness(0.4);
// Change the friction coefficient of the body
// Change the friction coefficient of the collider
material.setFrictionCoefficient(0.2);
\end{lstlisting}

View File

@ -143,7 +143,7 @@ class CollisionBody {
Collider* getCollider(uint colliderIndex);
/// Return the number of colliders associated with this body
uint getNbColliders() const;
uint32 getNbColliders() const;
/// Return the world-space coordinates of a point given the local-space coordinates of the body
Vector3 getWorldPoint(const Vector3& localPoint) const;
@ -178,7 +178,7 @@ class CollisionBody {
* @param worldAABB The AABB (in world-space coordinates) that will be used to test overlap
* @return True if the given AABB overlaps with the AABB of the collision body
*/
inline bool CollisionBody::testAABBOverlap(const AABB& worldAABB) const {
RP3D_FORCE_INLINE bool CollisionBody::testAABBOverlap(const AABB& worldAABB) const {
return worldAABB.testCollision(getAABB());
}
@ -186,14 +186,14 @@ inline bool CollisionBody::testAABBOverlap(const AABB& worldAABB) const {
/**
* @return The entity of the body
*/
inline Entity CollisionBody::getEntity() const {
RP3D_FORCE_INLINE Entity CollisionBody::getEntity() const {
return mEntity;
}
#ifdef IS_RP3D_PROFILING_ENABLED
// Set the profiler
inline void CollisionBody::setProfiler(Profiler* profiler) {
RP3D_FORCE_INLINE void CollisionBody::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}

View File

@ -57,7 +57,7 @@ class RigidBody : public CollisionBody {
void setIsSleeping(bool isSleeping);
/// Update whether the current overlapping pairs where this body is involed are active or not
void updateOverlappingPairs();
void resetOverlappingPairs();
/// Compute and return the local-space center of mass of the body using its colliders
Vector3 computeCenterOfMass() const;
@ -65,8 +65,8 @@ class RigidBody : public CollisionBody {
/// Compute the local-space inertia tensor and total mass of the body using its colliders
void computeMassAndInertiaTensorLocal(Vector3& inertiaTensorLocal, decimal& totalMass) const;
/// Return the inverse of the inertia tensor in world coordinates.
static const Matrix3x3 getWorldInertiaTensorInverse(PhysicsWorld& world, Entity bodyEntity);
/// Compute the inverse of the inertia tensor in world coordinates.
static void computeWorldInertiaTensorInverse(const Matrix3x3& orientation, const Vector3& inverseInertiaTensorLocal, Matrix3x3& outInverseInertiaTensorWorld);
public :
@ -212,6 +212,24 @@ class RigidBody : public CollisionBody {
friend class Joint;
};
/// Compute the inverse of the inertia tensor in world coordinates.
RP3D_FORCE_INLINE void RigidBody::computeWorldInertiaTensorInverse(const Matrix3x3& orientation, const Vector3& inverseInertiaTensorLocal, Matrix3x3& outInverseInertiaTensorWorld) {
outInverseInertiaTensorWorld[0][0] = orientation[0][0] * inverseInertiaTensorLocal.x;
outInverseInertiaTensorWorld[0][1] = orientation[1][0] * inverseInertiaTensorLocal.x;
outInverseInertiaTensorWorld[0][2] = orientation[2][0] * inverseInertiaTensorLocal.x;
outInverseInertiaTensorWorld[1][0] = orientation[0][1] * inverseInertiaTensorLocal.y;
outInverseInertiaTensorWorld[1][1] = orientation[1][1] * inverseInertiaTensorLocal.y;
outInverseInertiaTensorWorld[1][2] = orientation[2][1] * inverseInertiaTensorLocal.y;
outInverseInertiaTensorWorld[2][0] = orientation[0][2] * inverseInertiaTensorLocal.z;
outInverseInertiaTensorWorld[2][1] = orientation[1][2] * inverseInertiaTensorLocal.z;
outInverseInertiaTensorWorld[2][2] = orientation[2][2] * inverseInertiaTensorLocal.z;
outInverseInertiaTensorWorld = orientation * outInverseInertiaTensorWorld;
}
}
#endif

View File

@ -59,9 +59,6 @@ class Collider {
/// Pointer to the parent body
CollisionBody* mBody;
/// Material properties of the rigid body
Material mMaterial;
/// Pointer to user data
void* mUserData;
@ -188,7 +185,7 @@ class Collider {
/**
* @return The entity of the collider
*/
inline Entity Collider::getEntity() const {
RP3D_FORCE_INLINE Entity Collider::getEntity() const {
return mEntity;
}
@ -196,7 +193,7 @@ inline Entity Collider::getEntity() const {
/**
* @return Pointer to the parent body
*/
inline CollisionBody* Collider::getBody() const {
RP3D_FORCE_INLINE CollisionBody* Collider::getBody() const {
return mBody;
}
@ -204,7 +201,7 @@ inline CollisionBody* Collider::getBody() const {
/**
* @return A pointer to the user data stored into the collider
*/
inline void* Collider::getUserData() const {
RP3D_FORCE_INLINE void* Collider::getUserData() const {
return mUserData;
}
@ -212,7 +209,7 @@ inline void* Collider::getUserData() const {
/**
* @param userData Pointer to the user data you want to store within the collider
*/
inline void Collider::setUserData(void* userData) {
RP3D_FORCE_INLINE void Collider::setUserData(void* userData) {
mUserData = userData;
}
@ -221,18 +218,10 @@ inline void Collider::setUserData(void* userData) {
* @param worldAABB The AABB (in world-space coordinates) that will be used to test overlap
* @return True if the given AABB overlaps with the AABB of the collision body
*/
inline bool Collider::testAABBOverlap(const AABB& worldAABB) const {
RP3D_FORCE_INLINE bool Collider::testAABBOverlap(const AABB& worldAABB) const {
return worldAABB.testCollision(getWorldAABB());
}
// Return a reference to the material properties of the collider
/**
* @return A reference to the material of the body
*/
inline Material& Collider::getMaterial() {
return mMaterial;
}
}
#endif

View File

@ -27,7 +27,7 @@
#define REACTPHYSICS3D_COLLISION_CALLBACK_H
// Libraries
#include <reactphysics3d/containers/List.h>
#include <reactphysics3d/containers/Array.h>
#include <reactphysics3d/collision/ContactPair.h>
#include <reactphysics3d/constraint/ContactPoint.h>
@ -114,7 +114,7 @@ class CollisionCallback {
// Class ContactPair
/**
* This class represents the contact between two colliders of the physics world.
* A contact pair contains a list of contact points.
* A contact pair contains an array of contact points.
*/
class ContactPair {
@ -141,7 +141,7 @@ class CollisionCallback {
const reactphysics3d::ContactPair& mContactPair;
/// Pointer to the contact points
List<reactphysics3d::ContactPoint>* mContactPoints;
Array<reactphysics3d::ContactPoint>* mContactPoints;
/// Reference to the physics world
PhysicsWorld& mWorld;
@ -152,7 +152,7 @@ class CollisionCallback {
// -------------------- Methods -------------------- //
/// Constructor
ContactPair(const reactphysics3d::ContactPair& contactPair, List<reactphysics3d::ContactPoint>* contactPoints,
ContactPair(const reactphysics3d::ContactPair& contactPair, Array<reactphysics3d::ContactPoint>* contactPoints,
PhysicsWorld& world, bool mIsLostContactPair);
public:
@ -226,23 +226,23 @@ class CollisionCallback {
// -------------------- Attributes -------------------- //
/// Pointer to the list of contact pairs (contains contacts and triggers events)
List<reactphysics3d::ContactPair>* mContactPairs;
/// Pointer to the array of contact pairs (contains contacts and triggers events)
Array<reactphysics3d::ContactPair>* mContactPairs;
/// Pointer to the list of contact manifolds
List<ContactManifold>* mContactManifolds;
/// Pointer to the array of contact manifolds
Array<ContactManifold>* mContactManifolds;
/// Pointer to the contact points
List<reactphysics3d::ContactPoint>* mContactPoints;
Array<reactphysics3d::ContactPoint>* mContactPoints;
/// Pointer to the list of lost contact pairs (contains contacts and triggers events)
List<reactphysics3d::ContactPair>& mLostContactPairs;
/// Pointer to the array of lost contact pairs (contains contacts and triggers events)
Array<reactphysics3d::ContactPair>& mLostContactPairs;
/// List of indices of the mContactPairs list that are contact events (not overlap/triggers)
List<uint> mContactPairsIndices;
/// Array of indices in the mContactPairs array that are contact events (not overlap/triggers)
Array<uint> mContactPairsIndices;
/// List of indices of the mLostContactPairs list that are contact events (not overlap/triggers)
List<uint> mLostContactPairsIndices;
/// Array of indices in the mLostContactPairs array that are contact events (not overlap/triggers)
Array<uint> mLostContactPairsIndices;
/// Reference to the physics world
PhysicsWorld& mWorld;
@ -250,8 +250,8 @@ class CollisionCallback {
// -------------------- Methods -------------------- //
/// Constructor
CallbackData(List<reactphysics3d::ContactPair>* contactPairs, List<ContactManifold>* manifolds,
List<reactphysics3d::ContactPoint>* contactPoints, List<reactphysics3d::ContactPair>& lostContactPairs,
CallbackData(Array<reactphysics3d::ContactPair>* contactPairs, Array<ContactManifold>* manifolds,
Array<reactphysics3d::ContactPoint>* contactPoints, Array<reactphysics3d::ContactPair>& lostContactPairs,
PhysicsWorld& world);
/// Deleted copy constructor
@ -278,7 +278,7 @@ class CollisionCallback {
* @param index Index of the contact pair to retrieve
* @return A contact pair object
*/
ContactPair getContactPair(uint index) const;
ContactPair getContactPair(uint32 index) const;
// -------------------- Friendship -------------------- //
@ -296,7 +296,7 @@ class CollisionCallback {
/**
* @return The number of contact pairs
*/
inline uint CollisionCallback::CallbackData::getNbContactPairs() const {
RP3D_FORCE_INLINE uint32 CollisionCallback::CallbackData::getNbContactPairs() const {
return mContactPairsIndices.size() + mLostContactPairsIndices.size();
}
@ -304,7 +304,7 @@ inline uint CollisionCallback::CallbackData::getNbContactPairs() const {
/**
* @return The number of contact points
*/
inline uint CollisionCallback::ContactPair::getNbContactPoints() const {
RP3D_FORCE_INLINE uint CollisionCallback::ContactPair::getNbContactPoints() const {
return mContactPair.nbToTalContactPoints;
}
@ -312,7 +312,7 @@ inline uint CollisionCallback::ContactPair::getNbContactPoints() const {
/**
* @return The penetration depth (larger than zero)
*/
inline decimal CollisionCallback::ContactPoint::getPenetrationDepth() const {
RP3D_FORCE_INLINE decimal CollisionCallback::ContactPoint::getPenetrationDepth() const {
return mContactPoint.getPenetrationDepth();
}
@ -320,7 +320,7 @@ inline decimal CollisionCallback::ContactPoint::getPenetrationDepth() const {
/**
* @return The contact normal direction at the contact point (in world-space)
*/
inline const Vector3& CollisionCallback::ContactPoint::getWorldNormal() const {
RP3D_FORCE_INLINE const Vector3& CollisionCallback::ContactPoint::getWorldNormal() const {
return mContactPoint.getNormal();
}
@ -328,7 +328,7 @@ inline const Vector3& CollisionCallback::ContactPoint::getWorldNormal() const {
/**
* @return The contact point in the local-space of the first collider (from body1) in contact
*/
inline const Vector3& CollisionCallback::ContactPoint::getLocalPointOnCollider1() const {
RP3D_FORCE_INLINE const Vector3& CollisionCallback::ContactPoint::getLocalPointOnCollider1() const {
return mContactPoint.getLocalPointOnShape1();
}
@ -336,7 +336,7 @@ inline const Vector3& CollisionCallback::ContactPoint::getLocalPointOnCollider1(
/**
* @return The contact point in the local-space of the second collider (from body2) in contact
*/
inline const Vector3& CollisionCallback::ContactPoint::getLocalPointOnCollider2() const {
RP3D_FORCE_INLINE const Vector3& CollisionCallback::ContactPoint::getLocalPointOnCollider2() const {
return mContactPoint.getLocalPointOnShape2();
}

View File

@ -58,11 +58,11 @@ class ContactManifold {
// -------------------- Constants -------------------- //
/// Maximum number of contact points in a reduced contact manifold
const int MAX_CONTACT_POINTS_IN_MANIFOLD = 4;
static constexpr int MAX_CONTACT_POINTS_IN_MANIFOLD = 4;
// -------------------- Attributes -------------------- //
/// Index of the first contact point of the manifold in the list of contact points
/// Index of the first contact point of the manifold in the array of contact points
uint contactPointsIndex;
/// Entity of the first body in contact
@ -78,7 +78,7 @@ class ContactManifold {
Entity colliderEntity2;
/// Number of contacts in the cache
int8 nbContactPoints;
uint8 nbContactPoints;
/// First friction vector of the contact manifold
Vector3 frictionVector1;
@ -95,9 +95,6 @@ class ContactManifold {
/// Twist friction constraint accumulated impulse
decimal frictionTwistImpulse;
/// Accumulated rolling resistance impulse
Vector3 rollingResistanceImpulse;
/// True if the contact manifold has already been added into an island
bool isAlreadyInIsland;
@ -107,16 +104,7 @@ class ContactManifold {
/// Constructor
ContactManifold(Entity bodyEntity1, Entity bodyEntity2, Entity colliderEntity1, Entity colliderEntity2,
uint contactPointsIndex, int8 nbContactPoints);
/// Destructor
~ContactManifold();
/// Copy-constructor
ContactManifold(const ContactManifold& contactManifold) = default;
/// Assignment operator
ContactManifold& operator=(const ContactManifold& contactManifold) = default;
uint contactPointsIndex, uint8 nbContactPoints);
// -------------------- Friendship -------------------- //

View File

@ -45,8 +45,12 @@ struct ContactManifoldInfo {
// -------------------- Attributes -------------------- //
/// Number of potential contact points
uint8 nbPotentialContactPoints;
/// Indices of the contact points in the mPotentialContactPoints array
List<uint> potentialContactPointsIndices;
uint potentialContactPointsIndices[NB_MAX_CONTACT_POINTS_IN_POTENTIAL_MANIFOLD];
/// Overlapping pair id
uint64 pairId;
@ -54,8 +58,7 @@ struct ContactManifoldInfo {
// -------------------- Methods -------------------- //
/// Constructor
ContactManifoldInfo(uint64 pairId, MemoryAllocator& allocator)
: potentialContactPointsIndices(allocator), pairId(pairId) {
ContactManifoldInfo(uint64 pairId) : nbPotentialContactPoints(0), pairId(pairId) {
}

View File

@ -47,8 +47,11 @@ struct ContactPair {
/// Overlapping pair Id
uint64 pairId;
/// Number of potential contact manifolds
uint8 nbPotentialContactManifolds;
/// Indices of the potential contact manifolds
List<uint> potentialContactManifoldsIndices;
uint potentialContactManifoldsIndices[NB_MAX_POTENTIAL_CONTACT_MANIFOLDS];
/// Entity of the first body of the contact
Entity body1Entity;
@ -66,19 +69,19 @@ struct ContactPair {
bool isAlreadyInIsland;
/// Index of the contact pair in the array of pairs
uint contactPairIndex;
uint32 contactPairIndex;
/// Index of the first contact manifold in the array
uint contactManifoldsIndex;
uint32 contactManifoldsIndex;
/// Number of contact manifolds
int8 nbContactManifolds;
/// Index of the first contact point in the array of contact points
uint contactPointsIndex;
uint32 contactPointsIndex;
/// Total number of contact points in all the manifolds of the contact pair
uint nbToTalContactPoints;
uint32 nbToTalContactPoints;
/// True if the colliders of the pair were already colliding in the previous frame
bool collidingInPreviousFrame;
@ -90,13 +93,21 @@ struct ContactPair {
/// Constructor
ContactPair(uint64 pairId, Entity body1Entity, Entity body2Entity, Entity collider1Entity,
Entity collider2Entity, uint contactPairIndex, bool collidingInPreviousFrame, bool isTrigger, MemoryAllocator& allocator)
: pairId(pairId), potentialContactManifoldsIndices(allocator), body1Entity(body1Entity), body2Entity(body2Entity),
Entity collider2Entity, uint contactPairIndex, bool collidingInPreviousFrame, bool isTrigger)
: pairId(pairId), nbPotentialContactManifolds(0), body1Entity(body1Entity), body2Entity(body2Entity),
collider1Entity(collider1Entity), collider2Entity(collider2Entity),
isAlreadyInIsland(false), contactPairIndex(contactPairIndex), contactManifoldsIndex(0), nbContactManifolds(0),
contactPointsIndex(0), nbToTalContactPoints(0), collidingInPreviousFrame(collidingInPreviousFrame), isTrigger(isTrigger) {
}
// Remove a potential manifold at a given index in the array
void removePotentialManifoldAtIndex(uint index) {
assert(index < nbPotentialContactManifolds);
potentialContactManifoldsIndices[index] = potentialContactManifoldsIndices[nbPotentialContactManifolds - 1];
nbPotentialContactManifolds--;
}
};
}

View File

@ -45,10 +45,6 @@ class CollisionBody;
*/
struct ContactPointInfo {
private:
// -------------------- Methods -------------------- //
public:
// -------------------- Attributes -------------------- //
@ -56,29 +52,15 @@ struct ContactPointInfo {
/// Normalized normal vector of the collision contact in world space
Vector3 normal;
/// Penetration depth of the contact
decimal penetrationDepth;
/// Contact point of body 1 in local space of body 1
Vector3 localPoint1;
/// Contact point of body 2 in local space of body 2
Vector3 localPoint2;
// -------------------- Methods -------------------- //
/// Penetration depth of the contact
decimal penetrationDepth;
/// Constructor
ContactPointInfo(const Vector3& contactNormal, decimal penDepth,
const Vector3& localPt1, const Vector3& localPt2)
: normal(contactNormal), penetrationDepth(penDepth),
localPoint1(localPt1), localPoint2(localPt2) {
assert(contactNormal.lengthSquare() > decimal(0.8));
assert(penDepth > decimal(0.0));
}
/// Destructor
~ContactPointInfo() = default;
};
}

View File

@ -54,22 +54,22 @@ class HalfEdgeStructure {
/// Face
struct Face {
uint edgeIndex; // Index of an half-edge of the face
List<uint> faceVertices; // Index of the vertices of the face
Array<uint> faceVertices; // Index of the vertices of the face
/// Constructor
Face(MemoryAllocator& allocator) : faceVertices(allocator) {}
/// Constructor
Face(List<uint> vertices) : faceVertices(vertices) {}
Face(Array<uint> vertices) : faceVertices(vertices) {}
};
/// Vertex
struct Vertex {
uint vertexPointIndex; // Index of the vertex point in the origin vertex array
uint edgeIndex; // Index of one edge emanting from this vertex
uint32 vertexPointIndex; // Index of the vertex point in the origin vertex array
uint32 edgeIndex; // Index of one edge emanting from this vertex
/// Constructor
Vertex(uint vertexCoordsIndex) : vertexPointIndex(vertexCoordsIndex) { }
Vertex(uint32 vertexCoordsIndex) : vertexPointIndex(vertexCoordsIndex) { }
};
private:
@ -78,13 +78,13 @@ class HalfEdgeStructure {
MemoryAllocator& mAllocator;
/// All the faces
List<Face> mFaces;
Array<Face> mFaces;
/// All the vertices
List<Vertex> mVertices;
Array<Vertex> mVertices;
/// All the half-edges
List<Edge> mEdges;
Array<Edge> mEdges;
public:
@ -103,7 +103,7 @@ class HalfEdgeStructure {
uint addVertex(uint vertexPointIndex);
/// Add a face
void addFace(List<uint> faceVertices);
void addFace(Array<uint> faceVertices);
/// Return the number of faces
uint getNbFaces() const;
@ -129,7 +129,7 @@ class HalfEdgeStructure {
/**
* @param vertexPointIndex Index of the vertex in the vertex data array
*/
inline uint HalfEdgeStructure::addVertex(uint vertexPointIndex) {
RP3D_FORCE_INLINE uint32 HalfEdgeStructure::addVertex(uint32 vertexPointIndex) {
Vertex vertex(vertexPointIndex);
mVertices.add(vertex);
return mVertices.size() - 1;
@ -137,10 +137,10 @@ inline uint HalfEdgeStructure::addVertex(uint vertexPointIndex) {
// Add a face
/**
* @param faceVertices List of the vertices in a face (ordered in CCW order as seen from outside
* @param faceVertices Array of the vertices in a face (ordered in CCW order as seen from outside
* the polyhedron
*/
inline void HalfEdgeStructure::addFace(List<uint> faceVertices) {
RP3D_FORCE_INLINE void HalfEdgeStructure::addFace(Array<uint> faceVertices) {
// Create a new face
Face face(faceVertices);
@ -151,31 +151,31 @@ inline void HalfEdgeStructure::addFace(List<uint> faceVertices) {
/**
* @return The number of faces in the polyhedron
*/
inline uint HalfEdgeStructure::getNbFaces() const {
return static_cast<uint>(mFaces.size());
RP3D_FORCE_INLINE uint32 HalfEdgeStructure::getNbFaces() const {
return mFaces.size();
}
// Return the number of edges
/**
* @return The number of edges in the polyhedron
*/
inline uint HalfEdgeStructure::getNbHalfEdges() const {
return static_cast<uint>(mEdges.size());
RP3D_FORCE_INLINE uint32 HalfEdgeStructure::getNbHalfEdges() const {
return mEdges.size();
}
// Return the number of vertices
/**
* @return The number of vertices in the polyhedron
*/
inline uint HalfEdgeStructure::getNbVertices() const {
return static_cast<uint>(mVertices.size());
RP3D_FORCE_INLINE uint32 HalfEdgeStructure::getNbVertices() const {
return mVertices.size();
}
// Return a given face
/**
* @return A given face of the polyhedron
*/
inline const HalfEdgeStructure::Face& HalfEdgeStructure::getFace(uint index) const {
RP3D_FORCE_INLINE const HalfEdgeStructure::Face& HalfEdgeStructure::getFace(uint32 index) const {
assert(index < mFaces.size());
return mFaces[index];
}
@ -184,7 +184,7 @@ inline const HalfEdgeStructure::Face& HalfEdgeStructure::getFace(uint index) con
/**
* @return A given edge of the polyhedron
*/
inline const HalfEdgeStructure::Edge& HalfEdgeStructure::getHalfEdge(uint index) const {
RP3D_FORCE_INLINE const HalfEdgeStructure::Edge& HalfEdgeStructure::getHalfEdge(uint32 index) const {
assert(index < mEdges.size());
return mEdges[index];
}
@ -193,7 +193,7 @@ inline const HalfEdgeStructure::Edge& HalfEdgeStructure::getHalfEdge(uint index)
/**
* @return A given vertex of the polyhedron
*/
inline const HalfEdgeStructure::Vertex& HalfEdgeStructure::getVertex(uint index) const {
RP3D_FORCE_INLINE const HalfEdgeStructure::Vertex& HalfEdgeStructure::getVertex(uint32 index) const {
assert(index < mVertices.size());
return mVertices[index];
}

View File

@ -27,7 +27,7 @@
#define REACTPHYSICS3D_OVERLAP_CALLBACK_H
// Libraries
#include <reactphysics3d/containers/List.h>
#include <reactphysics3d/containers/Array.h>
#include <reactphysics3d/collision/ContactPair.h>
/// ReactPhysics3D namespace
@ -131,17 +131,17 @@ class OverlapCallback {
// -------------------- Attributes -------------------- //
/// Reference to the list of contact pairs (contains contacts and triggers events)
List<ContactPair>& mContactPairs;
/// Reference to the array of contact pairs (contains contacts and triggers events)
Array<ContactPair>& mContactPairs;
/// Reference to the list of lost contact pairs (contains contacts and triggers events)
List<ContactPair>& mLostContactPairs;
/// Reference to the array of lost contact pairs (contains contacts and triggers events)
Array<ContactPair>& mLostContactPairs;
/// List of indices of the mContactPairs list that are overlap/triggers events (not contact events)
List<uint> mContactPairsIndices;
/// Array of indices of the mContactPairs array that are overlap/triggers events (not contact events)
Array<uint> mContactPairsIndices;
/// List of indices of the mLostContactPairs list that are overlap/triggers events (not contact events)
List<uint> mLostContactPairsIndices;
/// Array of indices of the mLostContactPairs array that are overlap/triggers events (not contact events)
Array<uint> mLostContactPairsIndices;
/// Reference to the physics world
PhysicsWorld& mWorld;
@ -149,7 +149,7 @@ class OverlapCallback {
// -------------------- Methods -------------------- //
/// Constructor
CallbackData(List<ContactPair>& contactPairs, List<ContactPair>& lostContactPairs, bool onlyReportTriggers, PhysicsWorld& world);
CallbackData(Array<ContactPair>& contactPairs, Array<ContactPair>& lostContactPairs, bool onlyReportTriggers, PhysicsWorld& world);
/// Deleted copy constructor
CallbackData(const CallbackData& callbackData) = delete;
@ -165,10 +165,10 @@ class OverlapCallback {
// -------------------- Methods -------------------- //
/// Return the number of overlapping pairs of bodies
uint getNbOverlappingPairs() const;
uint32 getNbOverlappingPairs() const;
/// Return a given overlapping pair of bodies
OverlapPair getOverlappingPair(uint index) const;
OverlapPair getOverlappingPair(uint32 index) const;
// -------------------- Friendship -------------------- //
@ -185,7 +185,7 @@ class OverlapCallback {
};
// Return the number of overlapping pairs of bodies
inline uint OverlapCallback::CallbackData::getNbOverlappingPairs() const {
RP3D_FORCE_INLINE uint32 OverlapCallback::CallbackData::getNbOverlappingPairs() const {
return mContactPairsIndices.size() + mLostContactPairsIndices.size();
}
@ -193,7 +193,7 @@ inline uint OverlapCallback::CallbackData::getNbOverlappingPairs() const {
/// Note that the returned OverlapPair object is only valid during the call of the CollisionCallback::onOverlap()
/// method. Therefore, you need to get contact data from it and make a copy. Do not make a copy of the OverlapPair
/// object itself because it won't be valid after the CollisionCallback::onOverlap() call.
inline OverlapCallback::OverlapPair OverlapCallback::CallbackData::getOverlappingPair(uint index) const {
RP3D_FORCE_INLINE OverlapCallback::OverlapPair OverlapCallback::CallbackData::getOverlappingPair(uint32 index) const {
assert(index < getNbOverlappingPairs());

View File

@ -140,7 +140,7 @@ class PolygonVertexArray {
/**
* @return The data type of the vertices in the array
*/
inline PolygonVertexArray::VertexDataType PolygonVertexArray::getVertexDataType() const {
RP3D_FORCE_INLINE PolygonVertexArray::VertexDataType PolygonVertexArray::getVertexDataType() const {
return mVertexDataType;
}
@ -148,7 +148,7 @@ inline PolygonVertexArray::VertexDataType PolygonVertexArray::getVertexDataType(
/**
* @return The data type of the indices in the array
*/
inline PolygonVertexArray::IndexDataType PolygonVertexArray::getIndexDataType() const {
RP3D_FORCE_INLINE PolygonVertexArray::IndexDataType PolygonVertexArray::getIndexDataType() const {
return mIndexDataType;
}
@ -156,7 +156,7 @@ inline PolygonVertexArray::IndexDataType PolygonVertexArray::getIndexDataType()
/**
* @return The number of vertices in the array
*/
inline uint PolygonVertexArray::getNbVertices() const {
RP3D_FORCE_INLINE uint PolygonVertexArray::getNbVertices() const {
return mNbVertices;
}
@ -164,7 +164,7 @@ inline uint PolygonVertexArray::getNbVertices() const {
/**
* @return The number of faces in the array
*/
inline uint PolygonVertexArray::getNbFaces() const {
RP3D_FORCE_INLINE uint PolygonVertexArray::getNbFaces() const {
return mNbFaces;
}
@ -172,7 +172,7 @@ inline uint PolygonVertexArray::getNbFaces() const {
/**
* @return The number of bytes between two vertices
*/
inline int PolygonVertexArray::getVerticesStride() const {
RP3D_FORCE_INLINE int PolygonVertexArray::getVerticesStride() const {
return mVerticesStride;
}
@ -180,7 +180,7 @@ inline int PolygonVertexArray::getVerticesStride() const {
/**
* @return The number of bytes between two consecutive face indices
*/
inline int PolygonVertexArray::getIndicesStride() const {
RP3D_FORCE_INLINE int PolygonVertexArray::getIndicesStride() const {
return mIndicesStride;
}
@ -189,7 +189,7 @@ inline int PolygonVertexArray::getIndicesStride() const {
* @param faceIndex Index of a given face
* @return A polygon face
*/
inline PolygonVertexArray::PolygonFace* PolygonVertexArray::getPolygonFace(uint faceIndex) const {
RP3D_FORCE_INLINE PolygonVertexArray::PolygonFace* PolygonVertexArray::getPolygonFace(uint faceIndex) const {
assert(faceIndex < mNbFaces);
return &mPolygonFacesStart[faceIndex];
}
@ -198,7 +198,7 @@ inline PolygonVertexArray::PolygonFace* PolygonVertexArray::getPolygonFace(uint
/**
* @return A pointer to the start of the vertex array of the polyhedron
*/
inline const unsigned char* PolygonVertexArray::getVerticesStart() const {
RP3D_FORCE_INLINE const unsigned char* PolygonVertexArray::getVerticesStart() const {
return mVerticesStart;
}
@ -206,7 +206,7 @@ inline const unsigned char* PolygonVertexArray::getVerticesStart() const {
/**
* @return A pointer to the start of the face indices array of the polyhedron
*/
inline const unsigned char* PolygonVertexArray::getIndicesStart() const {
RP3D_FORCE_INLINE const unsigned char* PolygonVertexArray::getIndicesStart() const {
return mIndicesStart;
}

View File

@ -28,6 +28,7 @@
// Libraries
#include <reactphysics3d/mathematics/mathematics.h>
#include <reactphysics3d/containers/Array.h>
#include "HalfEdgeStructure.h"
namespace reactphysics3d {
@ -69,7 +70,7 @@ class PolyhedronMesh {
PolyhedronMesh(PolygonVertexArray* polygonVertexArray, MemoryAllocator& allocator);
/// Create the half-edge structure of the mesh
void createHalfEdgeStructure();
bool createHalfEdgeStructure();
/// Compute the faces normals
void computeFacesNormals();
@ -80,6 +81,9 @@ class PolyhedronMesh {
/// Compute and return the area of a face
decimal getFaceArea(uint faceIndex) const;
/// Static factory method to create a polyhedron mesh
static PolyhedronMesh* create(PolygonVertexArray* polygonVertexArray, MemoryAllocator& polyhedronMeshAllocator, MemoryAllocator& dataAllocator);
public:
// -------------------- Methods -------------------- //
@ -117,7 +121,7 @@ class PolyhedronMesh {
/**
* @return The number of vertices in the mesh
*/
inline uint PolyhedronMesh::getNbVertices() const {
RP3D_FORCE_INLINE uint PolyhedronMesh::getNbVertices() const {
return mHalfEdgeStructure.getNbVertices();
}
@ -125,7 +129,7 @@ inline uint PolyhedronMesh::getNbVertices() const {
/**
* @return The number of faces in the mesh
*/
inline uint PolyhedronMesh::getNbFaces() const {
RP3D_FORCE_INLINE uint PolyhedronMesh::getNbFaces() const {
return mHalfEdgeStructure.getNbFaces();
}
@ -134,7 +138,7 @@ inline uint PolyhedronMesh::getNbFaces() const {
* @param faceIndex The index of a given face of the mesh
* @return The normal vector of a given face of the mesh
*/
inline Vector3 PolyhedronMesh::getFaceNormal(uint faceIndex) const {
RP3D_FORCE_INLINE Vector3 PolyhedronMesh::getFaceNormal(uint faceIndex) const {
assert(faceIndex < mHalfEdgeStructure.getNbFaces());
return mFacesNormals[faceIndex];
}
@ -143,7 +147,7 @@ inline Vector3 PolyhedronMesh::getFaceNormal(uint faceIndex) const {
/**
* @return The Half-Edge structure of the mesh
*/
inline const HalfEdgeStructure& PolyhedronMesh::getHalfEdgeStructure() const {
RP3D_FORCE_INLINE const HalfEdgeStructure& PolyhedronMesh::getHalfEdgeStructure() const {
return mHalfEdgeStructure;
}
@ -151,7 +155,7 @@ inline const HalfEdgeStructure& PolyhedronMesh::getHalfEdgeStructure() const {
/**
* @return The centroid of the mesh
*/
inline Vector3 PolyhedronMesh::getCentroid() const {
RP3D_FORCE_INLINE Vector3 PolyhedronMesh::getCentroid() const {
return mCentroid;
}

View File

@ -137,6 +137,7 @@ struct RaycastTest {
/// Constructor
RaycastTest(RaycastCallback* callback) {
userCallback = callback;
}
/// Ray cast test against a collider

View File

@ -28,7 +28,7 @@
// Libraries
#include <cassert>
#include <reactphysics3d/containers/List.h>
#include <reactphysics3d/containers/Array.h>
#include <reactphysics3d/memory/MemoryAllocator.h>
namespace reactphysics3d {
@ -49,7 +49,7 @@ class TriangleMesh {
protected:
/// All the triangle arrays of the mesh (one triangle array per part)
List<TriangleVertexArray*> mTriangleArrays;
Array<TriangleVertexArray*> mTriangleArrays;
/// Constructor
TriangleMesh(reactphysics3d::MemoryAllocator& allocator);
@ -78,7 +78,7 @@ class TriangleMesh {
/**
* @param triangleVertexArray Pointer to the TriangleVertexArray to add into the mesh
*/
inline void TriangleMesh::addSubpart(TriangleVertexArray* triangleVertexArray) {
RP3D_FORCE_INLINE void TriangleMesh::addSubpart(TriangleVertexArray* triangleVertexArray) {
mTriangleArrays.add(triangleVertexArray );
}
@ -87,7 +87,7 @@ inline void TriangleMesh::addSubpart(TriangleVertexArray* triangleVertexArray) {
* @param indexSubpart The index of the sub-part of the mesh
* @return A pointer to the triangle vertex array of a given sub-part of the mesh
*/
inline TriangleVertexArray* TriangleMesh::getSubpart(uint indexSubpart) const {
RP3D_FORCE_INLINE TriangleVertexArray* TriangleMesh::getSubpart(uint32 indexSubpart) const {
assert(indexSubpart < mTriangleArrays.size());
return mTriangleArrays[indexSubpart];
}
@ -96,7 +96,7 @@ inline TriangleVertexArray* TriangleMesh::getSubpart(uint indexSubpart) const {
/**
* @return The number of sub-parts of the mesh
*/
inline uint TriangleMesh::getNbSubparts() const {
RP3D_FORCE_INLINE uint32 TriangleMesh::getNbSubparts() const {
return mTriangleArrays.size();
}

View File

@ -182,7 +182,7 @@ class TriangleVertexArray {
/**
* @return The data type of the vertices in the array
*/
inline TriangleVertexArray::VertexDataType TriangleVertexArray::getVertexDataType() const {
RP3D_FORCE_INLINE TriangleVertexArray::VertexDataType TriangleVertexArray::getVertexDataType() const {
return mVertexDataType;
}
@ -190,7 +190,7 @@ inline TriangleVertexArray::VertexDataType TriangleVertexArray::getVertexDataTyp
/**
* @return The data type of the normals in the array
*/
inline TriangleVertexArray::NormalDataType TriangleVertexArray::getVertexNormalDataType() const {
RP3D_FORCE_INLINE TriangleVertexArray::NormalDataType TriangleVertexArray::getVertexNormalDataType() const {
return mVertexNormaldDataType;
}
@ -198,7 +198,7 @@ inline TriangleVertexArray::NormalDataType TriangleVertexArray::getVertexNormalD
/**
* @return The data type of the face indices in the array
*/
inline TriangleVertexArray::IndexDataType TriangleVertexArray::getIndexDataType() const {
RP3D_FORCE_INLINE TriangleVertexArray::IndexDataType TriangleVertexArray::getIndexDataType() const {
return mIndexDataType;
}
@ -206,7 +206,7 @@ inline TriangleVertexArray::IndexDataType TriangleVertexArray::getIndexDataType(
/**
* @return The number of vertices in the array
*/
inline uint TriangleVertexArray::getNbVertices() const {
RP3D_FORCE_INLINE uint TriangleVertexArray::getNbVertices() const {
return mNbVertices;
}
@ -214,7 +214,7 @@ inline uint TriangleVertexArray::getNbVertices() const {
/**
* @return The number of triangles in the array
*/
inline uint TriangleVertexArray::getNbTriangles() const {
RP3D_FORCE_INLINE uint TriangleVertexArray::getNbTriangles() const {
return mNbTriangles;
}
@ -222,7 +222,7 @@ inline uint TriangleVertexArray::getNbTriangles() const {
/**
* @return The number of bytes separating two consecutive vertices in the array
*/
inline uint TriangleVertexArray::getVerticesStride() const {
RP3D_FORCE_INLINE uint TriangleVertexArray::getVerticesStride() const {
return mVerticesStride;
}
@ -230,7 +230,7 @@ inline uint TriangleVertexArray::getVerticesStride() const {
/**
* @return The number of bytes separating two consecutive normals in the array
*/
inline uint TriangleVertexArray::getVerticesNormalsStride() const {
RP3D_FORCE_INLINE uint TriangleVertexArray::getVerticesNormalsStride() const {
return mVerticesNormalsStride;
}
@ -238,7 +238,7 @@ inline uint TriangleVertexArray::getVerticesNormalsStride() const {
/**
* @return The number of bytes separating two consecutive face indices in the array
*/
inline uint TriangleVertexArray::getIndicesStride() const {
RP3D_FORCE_INLINE uint TriangleVertexArray::getIndicesStride() const {
return mIndicesStride;
}
@ -246,7 +246,7 @@ inline uint TriangleVertexArray::getIndicesStride() const {
/**
* @return A pointer to the start of the vertices data in the array
*/
inline const void* TriangleVertexArray::getVerticesStart() const {
RP3D_FORCE_INLINE const void* TriangleVertexArray::getVerticesStart() const {
return mVerticesStart;
}
@ -254,7 +254,7 @@ inline const void* TriangleVertexArray::getVerticesStart() const {
/**
* @return A pointer to the start of the normals data in the array
*/
inline const void* TriangleVertexArray::getVerticesNormalsStart() const {
RP3D_FORCE_INLINE const void* TriangleVertexArray::getVerticesNormalsStart() const {
return mVerticesNormalsStart;
}
@ -262,7 +262,7 @@ inline const void* TriangleVertexArray::getVerticesNormalsStart() const {
/**
* @return A pointer to the start of the face indices data in the array
*/
inline const void* TriangleVertexArray::getIndicesStart() const {
RP3D_FORCE_INLINE const void* TriangleVertexArray::getIndicesStart() const {
return mIndicesStart;
}

View File

@ -58,7 +58,7 @@ struct TreeNode {
// -------------------- Attributes -------------------- //
// A node is either in the tree (has a parent) or in the free nodes list
// A node is either in the tree (has a parent) or in the free nodes array
// (has a next node)
union {
@ -149,7 +149,7 @@ class DynamicAABBTree {
/// ID of the root node of the tree
int32 mRootNodeID;
/// ID of the first node of the list of free (allocated) nodes in the tree that we can use
/// ID of the first node of the array of free (allocated) nodes in the tree that we can use
int32 mFreeNodeID;
/// Number of allocated nodes in the tree
@ -236,11 +236,11 @@ class DynamicAABBTree {
void* getNodeDataPointer(int32 nodeID) const;
/// Report all shapes overlapping with all the shapes in the map in parameter
void reportAllShapesOverlappingWithShapes(const List<int32>& nodesToTest, size_t startIndex,
size_t endIndex, List<Pair<int32, int32>>& outOverlappingNodes) const;
void reportAllShapesOverlappingWithShapes(const Array<int32>& nodesToTest, size_t startIndex,
size_t endIndex, Array<Pair<int32, int32>>& outOverlappingNodes) const;
/// Report all shapes overlapping with the AABB given in parameter.
void reportAllShapesOverlappingWithAABB(const AABB& aabb, List<int>& overlappingNodes) const;
void reportAllShapesOverlappingWithAABB(const AABB& aabb, Array<int>& overlappingNodes) const;
/// Ray casting method
void raycast(const Ray& ray, DynamicAABBTreeRaycastCallback& callback) const;
@ -264,38 +264,38 @@ class DynamicAABBTree {
};
// Return true if the node is a leaf of the tree
inline bool TreeNode::isLeaf() const {
RP3D_FORCE_INLINE bool TreeNode::isLeaf() const {
return (height == 0);
}
// Return the fat AABB corresponding to a given node ID
inline const AABB& DynamicAABBTree::getFatAABB(int32 nodeID) const {
RP3D_FORCE_INLINE const AABB& DynamicAABBTree::getFatAABB(int32 nodeID) const {
assert(nodeID >= 0 && nodeID < mNbAllocatedNodes);
return mNodes[nodeID].aabb;
}
// Return the pointer to the data array of a given leaf node of the tree
inline int32* DynamicAABBTree::getNodeDataInt(int32 nodeID) const {
RP3D_FORCE_INLINE int32* DynamicAABBTree::getNodeDataInt(int32 nodeID) const {
assert(nodeID >= 0 && nodeID < mNbAllocatedNodes);
assert(mNodes[nodeID].isLeaf());
return mNodes[nodeID].dataInt;
}
// Return the pointer to the data pointer of a given leaf node of the tree
inline void* DynamicAABBTree::getNodeDataPointer(int32 nodeID) const {
RP3D_FORCE_INLINE void* DynamicAABBTree::getNodeDataPointer(int32 nodeID) const {
assert(nodeID >= 0 && nodeID < mNbAllocatedNodes);
assert(mNodes[nodeID].isLeaf());
return mNodes[nodeID].dataPointer;
}
// Return the root AABB of the tree
inline AABB DynamicAABBTree::getRootAABB() const {
RP3D_FORCE_INLINE AABB DynamicAABBTree::getRootAABB() const {
return getFatAABB(mRootNodeID);
}
// Add an object into the tree. This method creates a new leaf node in the tree and
// returns the ID of the corresponding node.
inline int32 DynamicAABBTree::addObject(const AABB& aabb, int32 data1, int32 data2) {
RP3D_FORCE_INLINE int32 DynamicAABBTree::addObject(const AABB& aabb, int32 data1, int32 data2) {
int32 nodeId = addObjectInternal(aabb);
@ -307,7 +307,7 @@ inline int32 DynamicAABBTree::addObject(const AABB& aabb, int32 data1, int32 dat
// Add an object into the tree. This method creates a new leaf node in the tree and
// returns the ID of the corresponding node.
inline int32 DynamicAABBTree::addObject(const AABB& aabb, void* data) {
RP3D_FORCE_INLINE int32 DynamicAABBTree::addObject(const AABB& aabb, void* data) {
int32 nodeId = addObjectInternal(aabb);
@ -319,7 +319,7 @@ inline int32 DynamicAABBTree::addObject(const AABB& aabb, void* data) {
#ifdef IS_RP3D_PROFILING_ENABLED
// Set the profiler
inline void DynamicAABBTree::setProfiler(Profiler* profiler) {
RP3D_FORCE_INLINE void DynamicAABBTree::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}

View File

@ -34,7 +34,7 @@
namespace reactphysics3d {
// Declarations
struct CapsuleVsCapsuleNarrowPhaseInfoBatch;
struct NarrowPhaseInfoBatch;
class ContactPoint;
// Class CapsuleVsCapsuleAlgorithm
@ -66,7 +66,7 @@ class CapsuleVsCapsuleAlgorithm : public NarrowPhaseAlgorithm {
CapsuleVsCapsuleAlgorithm& operator=(const CapsuleVsCapsuleAlgorithm& algorithm) = delete;
/// Compute the narrow-phase collision detection between two capsules
bool testCollision(CapsuleVsCapsuleNarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchStartIndex,
bool testCollision(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchStartIndex,
uint batchNbItems, MemoryAllocator& memoryAllocator);
};

View File

@ -34,6 +34,7 @@ namespace reactphysics3d {
// Declarations
class ContactPoint;
struct NarrowPhaseInfoBatch;
// Class CapsuleVsConvexPolyhedronAlgorithm
/**

View File

@ -173,39 +173,39 @@ class CollisionDispatch {
};
// Get the Sphere vs Sphere narrow-phase collision detection algorithm
inline SphereVsSphereAlgorithm* CollisionDispatch::getSphereVsSphereAlgorithm() {
RP3D_FORCE_INLINE SphereVsSphereAlgorithm* CollisionDispatch::getSphereVsSphereAlgorithm() {
return mSphereVsSphereAlgorithm;
}
// Get the Sphere vs Capsule narrow-phase collision detection algorithm
inline SphereVsCapsuleAlgorithm* CollisionDispatch::getSphereVsCapsuleAlgorithm() {
RP3D_FORCE_INLINE SphereVsCapsuleAlgorithm* CollisionDispatch::getSphereVsCapsuleAlgorithm() {
return mSphereVsCapsuleAlgorithm;
}
// Get the Capsule vs Capsule narrow-phase collision detection algorithm
inline CapsuleVsCapsuleAlgorithm* CollisionDispatch::getCapsuleVsCapsuleAlgorithm() {
RP3D_FORCE_INLINE CapsuleVsCapsuleAlgorithm* CollisionDispatch::getCapsuleVsCapsuleAlgorithm() {
return mCapsuleVsCapsuleAlgorithm;
}
// Get the Sphere vs Convex Polyhedron narrow-phase collision detection algorithm
inline SphereVsConvexPolyhedronAlgorithm* CollisionDispatch::getSphereVsConvexPolyhedronAlgorithm() {
RP3D_FORCE_INLINE SphereVsConvexPolyhedronAlgorithm* CollisionDispatch::getSphereVsConvexPolyhedronAlgorithm() {
return mSphereVsConvexPolyhedronAlgorithm;
}
// Get the Capsule vs Convex Polyhedron narrow-phase collision detection algorithm
inline CapsuleVsConvexPolyhedronAlgorithm* CollisionDispatch::getCapsuleVsConvexPolyhedronAlgorithm() {
RP3D_FORCE_INLINE CapsuleVsConvexPolyhedronAlgorithm* CollisionDispatch::getCapsuleVsConvexPolyhedronAlgorithm() {
return mCapsuleVsConvexPolyhedronAlgorithm;
}
// Get the Convex Polyhedron vs Convex Polyhedron narrow-phase collision detection algorithm
inline ConvexPolyhedronVsConvexPolyhedronAlgorithm* CollisionDispatch::getConvexPolyhedronVsConvexPolyhedronAlgorithm() {
RP3D_FORCE_INLINE ConvexPolyhedronVsConvexPolyhedronAlgorithm* CollisionDispatch::getConvexPolyhedronVsConvexPolyhedronAlgorithm() {
return mConvexPolyhedronVsConvexPolyhedronAlgorithm;
}
#ifdef IS_RP3D_PROFILING_ENABLED
// Set the profiler
inline void CollisionDispatch::setProfiler(Profiler* profiler) {
RP3D_FORCE_INLINE void CollisionDispatch::setProfiler(Profiler* profiler) {
mProfiler = profiler;
mSphereVsSphereAlgorithm->setProfiler(profiler);

View File

@ -34,6 +34,7 @@ namespace reactphysics3d {
// Declarations
class ContactPoint;
struct NarrowPhaseInfoBatch;
// Class ConvexPolyhedronVsConvexPolyhedronAlgorithm
/**

View File

@ -39,7 +39,7 @@ struct NarrowPhaseInfoBatch;
class ConvexShape;
class Profiler;
class VoronoiSimplex;
template<typename T> class List;
template<typename T> class Array;
// Constants
constexpr decimal REL_ERROR = decimal(1.0e-3);
@ -98,7 +98,7 @@ class GJKAlgorithm {
/// Compute a contact info if the two bounding volumes collide.
void testCollision(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchStartIndex,
uint batchNbItems, List<GJKResult>& gjkResults);
uint batchNbItems, Array<GJKResult>& gjkResults);
#ifdef IS_RP3D_PROFILING_ENABLED
@ -112,7 +112,7 @@ class GJKAlgorithm {
#ifdef IS_RP3D_PROFILING_ENABLED
// Set the profiler
inline void GJKAlgorithm::setProfiler(Profiler* profiler) {
RP3D_FORCE_INLINE void GJKAlgorithm::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}

View File

@ -28,6 +28,7 @@
// Libraries
#include <reactphysics3d/mathematics/Vector3.h>
#include <reactphysics3d/mathematics/Vector2.h>
/// ReactPhysics3D namespace
namespace reactphysics3d {
@ -171,17 +172,17 @@ class VoronoiSimplex {
};
// Return true if the simplex contains 4 points
inline bool VoronoiSimplex::isFull() const {
RP3D_FORCE_INLINE bool VoronoiSimplex::isFull() const {
return mNbPoints == 4;
}
// Return true if the simple is empty
inline bool VoronoiSimplex::isEmpty() const {
RP3D_FORCE_INLINE bool VoronoiSimplex::isEmpty() const {
return mNbPoints == 0;
}
// Set the barycentric coordinates of the closest point
inline void VoronoiSimplex::setBarycentricCoords(decimal a, decimal b, decimal c, decimal d) {
RP3D_FORCE_INLINE void VoronoiSimplex::setBarycentricCoords(decimal a, decimal b, decimal c, decimal d) {
mBarycentricCoords[0] = a;
mBarycentricCoords[1] = b;
mBarycentricCoords[2] = c;
@ -189,7 +190,7 @@ inline void VoronoiSimplex::setBarycentricCoords(decimal a, decimal b, decimal c
}
// Compute the closest point "v" to the origin of the current simplex.
inline bool VoronoiSimplex::computeClosestPoint(Vector3& v) {
RP3D_FORCE_INLINE bool VoronoiSimplex::computeClosestPoint(Vector3& v) {
bool isValid = recomputeClosestPoint();
v = mClosestPoint;
@ -197,7 +198,7 @@ inline bool VoronoiSimplex::computeClosestPoint(Vector3& v) {
}
// Return true if the
inline bool VoronoiSimplex::checkClosestPointValid() const {
RP3D_FORCE_INLINE bool VoronoiSimplex::checkClosestPointValid() const {
return mBarycentricCoords[0] >= decimal(0.0) && mBarycentricCoords[1] >= decimal(0.0) &&
mBarycentricCoords[2] >= decimal(0.0) && mBarycentricCoords[3] >= decimal(0.0);
}

View File

@ -106,7 +106,7 @@ class NarrowPhaseAlgorithm {
#ifdef IS_RP3D_PROFILING_ENABLED
// Set the profiler
inline void NarrowPhaseAlgorithm::setProfiler(Profiler* profiler) {
RP3D_FORCE_INLINE void NarrowPhaseAlgorithm::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}

View File

@ -28,6 +28,8 @@
// Libraries
#include <reactphysics3d/engine/OverlappingPairs.h>
#include <reactphysics3d/collision/ContactPointInfo.h>
#include <reactphysics3d/configuration.h>
/// Namespace ReactPhysics3D
namespace reactphysics3d {
@ -40,93 +42,143 @@ struct ContactPointInfo;
// Struct NarrowPhaseInfoBatch
/**
* This abstract structure collects all the potential collisions from the middle-phase algorithm
* that have to be tested during narrow-phase collision detection. There is an implementation of
* this class for each kind of collision detection test. For instance, one for sphere vs sphere,
* one for sphere vs capsule, ...
* This structure collects all the potential collisions from the middle-phase algorithm
* that have to be tested during narrow-phase collision detection.
*/
struct NarrowPhaseInfoBatch {
struct NarrowPhaseInfo {
/// Broadphase overlapping pairs ids
uint64 overlappingPairId;
/// Entity of the first collider to test collision with
Entity colliderEntity1;
/// Entity of the second collider to test collision with
Entity colliderEntity2;
/// Collision info of the previous frame
LastFrameCollisionInfo* lastFrameCollisionInfo;
/// Memory allocator for the collision shape (Used to release TriangleShape memory in destructor)
MemoryAllocator* collisionShapeAllocator;
/// Shape local to world transform of sphere 1
Transform shape1ToWorldTransform;
/// Shape local to world transform of sphere 2
Transform shape2ToWorldTransform;
/// Pointer to the first collision shapes to test collision with
CollisionShape* collisionShape1;
/// Pointer to the second collision shapes to test collision with
CollisionShape* collisionShape2;
/// True if we need to report contacts (false for triggers for instance)
bool reportContacts;
/// Result of the narrow-phase collision detection test
bool isColliding;
/// Number of contact points
uint8 nbContactPoints;
/// Array of contact points created during the narrow-phase
ContactPointInfo contactPoints[NB_MAX_CONTACT_POINTS_IN_NARROWPHASE_INFO];
/// Constructor
NarrowPhaseInfo(uint64 pairId, Entity collider1, Entity collider2, LastFrameCollisionInfo* lastFrameInfo, MemoryAllocator& shapeAllocator,
const Transform& shape1ToWorldTransform, const Transform& shape2ToWorldTransform, CollisionShape* shape1,
CollisionShape* shape2, bool needToReportContacts)
: overlappingPairId(pairId), colliderEntity1(collider1), colliderEntity2(collider2), lastFrameCollisionInfo(lastFrameInfo),
collisionShapeAllocator(&shapeAllocator), shape1ToWorldTransform(shape1ToWorldTransform),
shape2ToWorldTransform(shape2ToWorldTransform), collisionShape1(shape1),
collisionShape2(shape2), reportContacts(needToReportContacts), isColliding(false), nbContactPoints(0) {
}
};
protected:
/// Memory allocator
/// Reference to the memory allocator
MemoryAllocator& mMemoryAllocator;
/// Reference to all the broad-phase overlapping pairs
OverlappingPairs& mOverlappingPairs;
/// Cached capacity
uint mCachedCapacity = 0;
uint32 mCachedCapacity = 0;
public:
/// List of Broadphase overlapping pairs ids
List<uint64> overlappingPairIds;
/// List of pointers to the first colliders to test collision with
List<Entity> colliderEntities1;
/// List of pointers to the second colliders to test collision with
List<Entity> colliderEntities2;
/// List of pointers to the first collision shapes to test collision with
List<CollisionShape*> collisionShapes1;
/// List of pointers to the second collision shapes to test collision with
List<CollisionShape*> collisionShapes2;
/// List of transforms that maps from collision shape 1 local-space to world-space
List<Transform> shape1ToWorldTransforms;
/// List of transforms that maps from collision shape 2 local-space to world-space
List<Transform> shape2ToWorldTransforms;
/// True for each pair of objects that we need to report contacts (false for triggers for instance)
List<bool> reportContacts;
/// Result of the narrow-phase collision detection test
List<bool> isColliding;
/// List of contact points created during the narrow-phase
List<List<ContactPointInfo*>> contactPoints;
/// Memory allocators for the collision shape (Used to release TriangleShape memory in destructor)
List<MemoryAllocator*> collisionShapeAllocators;
/// Collision infos of the previous frame
List<LastFrameCollisionInfo*> lastFrameCollisionInfos;
/// For each collision test, we keep some meta data
Array<NarrowPhaseInfo> narrowPhaseInfos;
/// Constructor
NarrowPhaseInfoBatch(MemoryAllocator& allocator, OverlappingPairs& overlappingPairs);
NarrowPhaseInfoBatch(OverlappingPairs& overlappingPairs, MemoryAllocator& allocator);
/// Destructor
virtual ~NarrowPhaseInfoBatch();
/// Return the number of objects in the batch
uint getNbObjects() const;
~NarrowPhaseInfoBatch();
/// Add shapes to be tested during narrow-phase collision detection into the batch
virtual void addNarrowPhaseInfo(uint64 pairId, uint64 pairIndex, Entity collider1, Entity collider2, CollisionShape* shape1,
CollisionShape* shape2, const Transform& shape1Transform,
const Transform& shape2Transform, bool needToReportContacts, MemoryAllocator& shapeAllocator);
void addNarrowPhaseInfo(uint64 pairId, Entity collider1, Entity collider2, CollisionShape* shape1,
CollisionShape* shape2, const Transform& shape1Transform, const Transform& shape2Transform,
bool needToReportContacts, LastFrameCollisionInfo* lastFrameInfo, MemoryAllocator& shapeAllocator);
/// Return the number of objects in the batch
uint32 getNbObjects() const;
/// Add a new contact point
virtual void addContactPoint(uint index, const Vector3& contactNormal, decimal penDepth,
void addContactPoint(uint32 index, const Vector3& contactNormal, decimal penDepth,
const Vector3& localPt1, const Vector3& localPt2);
/// Reset the remaining contact points
void resetContactPoints(uint index);
// Initialize the containers using cached capacity
virtual void reserveMemory();
void reserveMemory();
/// Clear all the objects in the batch
virtual void clear();
void clear();
};
/// Return the number of objects in the batch
inline uint NarrowPhaseInfoBatch::getNbObjects() const {
return overlappingPairIds.size();
RP3D_FORCE_INLINE uint32 NarrowPhaseInfoBatch::getNbObjects() const {
return narrowPhaseInfos.size();
}
// Add shapes to be tested during narrow-phase collision detection into the batch
RP3D_FORCE_INLINE void NarrowPhaseInfoBatch::addNarrowPhaseInfo(uint64 pairId, Entity collider1, Entity collider2, CollisionShape* shape1,
CollisionShape* shape2, const Transform& shape1Transform, const Transform& shape2Transform,
bool needToReportContacts, LastFrameCollisionInfo* lastFrameInfo, MemoryAllocator& shapeAllocator) {
// Create a meta data object
narrowPhaseInfos.emplace(pairId, collider1, collider2, lastFrameInfo, shapeAllocator, shape1Transform, shape2Transform, shape1, shape2, needToReportContacts);
}
// Add a new contact point
RP3D_FORCE_INLINE void NarrowPhaseInfoBatch::addContactPoint(uint index, const Vector3& contactNormal, decimal penDepth, const Vector3& localPt1, const Vector3& localPt2) {
assert(penDepth > decimal(0.0));
if (narrowPhaseInfos[index].nbContactPoints < NB_MAX_CONTACT_POINTS_IN_NARROWPHASE_INFO) {
assert(contactNormal.length() > 0.8f);
// Add it into the array of contact points
narrowPhaseInfos[index].contactPoints[narrowPhaseInfos[index].nbContactPoints].normal = contactNormal;
narrowPhaseInfos[index].contactPoints[narrowPhaseInfos[index].nbContactPoints].penetrationDepth = penDepth;
narrowPhaseInfos[index].contactPoints[narrowPhaseInfos[index].nbContactPoints].localPoint1 = localPt1;
narrowPhaseInfos[index].contactPoints[narrowPhaseInfos[index].nbContactPoints].localPoint2 = localPt2;
narrowPhaseInfos[index].nbContactPoints++;
}
}
// Reset the remaining contact points
RP3D_FORCE_INLINE void NarrowPhaseInfoBatch::resetContactPoints(uint index) {
narrowPhaseInfos[index].nbContactPoints = 0;
}
}

View File

@ -27,11 +27,9 @@
#define REACTPHYSICS3D_NARROW_PHASE_INPUT_H
// Libraries
#include <reactphysics3d/containers/List.h>
#include <reactphysics3d/containers/Array.h>
#include <reactphysics3d/collision/narrowphase/NarrowPhaseInfoBatch.h>
#include <reactphysics3d/collision/narrowphase/SphereVsSphereNarrowPhaseInfoBatch.h>
#include <reactphysics3d/collision/narrowphase/CapsuleVsCapsuleNarrowPhaseInfoBatch.h>
#include <reactphysics3d/collision/narrowphase/SphereVsCapsuleNarrowPhaseInfoBatch.h>
#include <reactphysics3d/collision/narrowphase/CollisionDispatch.h>
/// Namespace ReactPhysics3D
namespace reactphysics3d {
@ -55,9 +53,9 @@ class NarrowPhaseInput {
private:
SphereVsSphereNarrowPhaseInfoBatch mSphereVsSphereBatch;
SphereVsCapsuleNarrowPhaseInfoBatch mSphereVsCapsuleBatch;
CapsuleVsCapsuleNarrowPhaseInfoBatch mCapsuleVsCapsuleBatch;
NarrowPhaseInfoBatch mSphereVsSphereBatch;
NarrowPhaseInfoBatch mSphereVsCapsuleBatch;
NarrowPhaseInfoBatch mCapsuleVsCapsuleBatch;
NarrowPhaseInfoBatch mSphereVsConvexPolyhedronBatch;
NarrowPhaseInfoBatch mCapsuleVsConvexPolyhedronBatch;
NarrowPhaseInfoBatch mConvexPolyhedronVsConvexPolyhedronBatch;
@ -68,19 +66,19 @@ class NarrowPhaseInput {
NarrowPhaseInput(MemoryAllocator& allocator, OverlappingPairs& overlappingPairs);
/// Add shapes to be tested during narrow-phase collision detection into the batch
void addNarrowPhaseTest(uint64 pairId, uint64 pairIndex, Entity collider1, Entity collider2, CollisionShape* shape1,
void addNarrowPhaseTest(uint64 pairId, Entity collider1, Entity collider2, CollisionShape* shape1,
CollisionShape* shape2, const Transform& shape1Transform,
const Transform& shape2Transform, NarrowPhaseAlgorithmType narrowPhaseAlgorithmType, bool reportContacts,
MemoryAllocator& shapeAllocator);
LastFrameCollisionInfo* lastFrameInfo, MemoryAllocator& shapeAllocator);
/// Get a reference to the sphere vs sphere batch
SphereVsSphereNarrowPhaseInfoBatch& getSphereVsSphereBatch();
NarrowPhaseInfoBatch& getSphereVsSphereBatch();
/// Get a reference to the sphere vs capsule batch
SphereVsCapsuleNarrowPhaseInfoBatch& getSphereVsCapsuleBatch();
NarrowPhaseInfoBatch& getSphereVsCapsuleBatch();
/// Get a reference to the capsule vs capsule batch
CapsuleVsCapsuleNarrowPhaseInfoBatch& getCapsuleVsCapsuleBatch();
NarrowPhaseInfoBatch& getCapsuleVsCapsuleBatch();
/// Get a reference to the sphere vs convex polyhedron batch
NarrowPhaseInfoBatch& getSphereVsConvexPolyhedronBatch();
@ -100,34 +98,65 @@ class NarrowPhaseInput {
// Get a reference to the sphere vs sphere batch contacts
inline SphereVsSphereNarrowPhaseInfoBatch& NarrowPhaseInput::getSphereVsSphereBatch() {
RP3D_FORCE_INLINE NarrowPhaseInfoBatch& NarrowPhaseInput::getSphereVsSphereBatch() {
return mSphereVsSphereBatch;
}
// Get a reference to the sphere vs capsule batch contacts
inline SphereVsCapsuleNarrowPhaseInfoBatch& NarrowPhaseInput::getSphereVsCapsuleBatch() {
RP3D_FORCE_INLINE NarrowPhaseInfoBatch& NarrowPhaseInput::getSphereVsCapsuleBatch() {
return mSphereVsCapsuleBatch;
}
// Get a reference to the capsule vs capsule batch contacts
inline CapsuleVsCapsuleNarrowPhaseInfoBatch& NarrowPhaseInput::getCapsuleVsCapsuleBatch() {
RP3D_FORCE_INLINE NarrowPhaseInfoBatch& NarrowPhaseInput::getCapsuleVsCapsuleBatch() {
return mCapsuleVsCapsuleBatch;
}
// Get a reference to the sphere vs convex polyhedron batch contacts
inline NarrowPhaseInfoBatch& NarrowPhaseInput::getSphereVsConvexPolyhedronBatch() {
RP3D_FORCE_INLINE NarrowPhaseInfoBatch& NarrowPhaseInput::getSphereVsConvexPolyhedronBatch() {
return mSphereVsConvexPolyhedronBatch;
}
// Get a reference to the capsule vs convex polyhedron batch contacts
inline NarrowPhaseInfoBatch& NarrowPhaseInput::getCapsuleVsConvexPolyhedronBatch() {
RP3D_FORCE_INLINE NarrowPhaseInfoBatch& NarrowPhaseInput::getCapsuleVsConvexPolyhedronBatch() {
return mCapsuleVsConvexPolyhedronBatch;
}
// Get a reference to the convex polyhedron vs convex polyhedron batch contacts
inline NarrowPhaseInfoBatch& NarrowPhaseInput::getConvexPolyhedronVsConvexPolyhedronBatch() {
RP3D_FORCE_INLINE NarrowPhaseInfoBatch &NarrowPhaseInput::getConvexPolyhedronVsConvexPolyhedronBatch() {
return mConvexPolyhedronVsConvexPolyhedronBatch;
}
// Add shapes to be tested during narrow-phase collision detection into the batch
RP3D_FORCE_INLINE void NarrowPhaseInput::addNarrowPhaseTest(uint64 pairId, Entity collider1, Entity collider2, CollisionShape* shape1, CollisionShape* shape2,
const Transform& shape1Transform, const Transform& shape2Transform,
NarrowPhaseAlgorithmType narrowPhaseAlgorithmType, bool reportContacts, LastFrameCollisionInfo* lastFrameInfo,
MemoryAllocator& shapeAllocator) {
switch (narrowPhaseAlgorithmType) {
case NarrowPhaseAlgorithmType::SphereVsSphere:
mSphereVsSphereBatch.addNarrowPhaseInfo(pairId, collider1, collider2, shape1, shape2, shape1Transform, shape2Transform, reportContacts, lastFrameInfo, shapeAllocator);
break;
case NarrowPhaseAlgorithmType::SphereVsCapsule:
mSphereVsCapsuleBatch.addNarrowPhaseInfo(pairId, collider1, collider2, shape1, shape2, shape1Transform, shape2Transform, reportContacts, lastFrameInfo, shapeAllocator);
break;
case NarrowPhaseAlgorithmType::CapsuleVsCapsule:
mCapsuleVsCapsuleBatch.addNarrowPhaseInfo(pairId, collider1, collider2, shape1, shape2, shape1Transform, shape2Transform, reportContacts, lastFrameInfo, shapeAllocator);
break;
case NarrowPhaseAlgorithmType::SphereVsConvexPolyhedron:
mSphereVsConvexPolyhedronBatch.addNarrowPhaseInfo(pairId, collider1, collider2, shape1, shape2, shape1Transform, shape2Transform, reportContacts, lastFrameInfo, shapeAllocator);
break;
case NarrowPhaseAlgorithmType::CapsuleVsConvexPolyhedron:
mCapsuleVsConvexPolyhedronBatch.addNarrowPhaseInfo(pairId, collider1, collider2, shape1, shape2, shape1Transform, shape2Transform, reportContacts, lastFrameInfo, shapeAllocator);
break;
case NarrowPhaseAlgorithmType::ConvexPolyhedronVsConvexPolyhedron:
mConvexPolyhedronVsConvexPolyhedronBatch.addNarrowPhaseInfo(pairId, collider1, collider2, shape1, shape2, shape1Transform, shape2Transform, reportContacts, lastFrameInfo, shapeAllocator);
break;
case NarrowPhaseAlgorithmType::None:
// Must never happen
assert(false);
break;
}
}
}
#endif

View File

@ -185,7 +185,7 @@ class SATAlgorithm {
#ifdef IS_RP3D_PROFILING_ENABLED
// Set the profiler
inline void SATAlgorithm::setProfiler(Profiler* profiler) {
RP3D_FORCE_INLINE void SATAlgorithm::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}

View File

@ -34,7 +34,7 @@ namespace reactphysics3d {
// Declarations
class ContactPoint;
struct SphereVsCapsuleNarrowPhaseInfoBatch;
struct NarrowPhaseInfoBatch;
// Class SphereVsCapsuleAlgorithm
/**
@ -65,7 +65,7 @@ class SphereVsCapsuleAlgorithm : public NarrowPhaseAlgorithm {
SphereVsCapsuleAlgorithm& operator=(const SphereVsCapsuleAlgorithm& algorithm) = delete;
/// Compute the narrow-phase collision detection between a sphere and a capsule
bool testCollision(SphereVsCapsuleNarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchStartIndex,
bool testCollision(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchStartIndex,
uint batchNbItems, MemoryAllocator& memoryAllocator);
};

View File

@ -34,6 +34,7 @@ namespace reactphysics3d {
// Declarations
class ContactPoint;
struct NarrowPhaseInfoBatch;
// Class SphereVsConvexPolyhedronAlgorithm
/**

View File

@ -34,7 +34,7 @@ namespace reactphysics3d {
// Declarations
class ContactPoint;
struct SphereVsSphereNarrowPhaseInfoBatch;
struct NarrowPhaseInfoBatch;
// Class SphereVsSphereAlgorithm
/**
@ -65,7 +65,7 @@ class SphereVsSphereAlgorithm : public NarrowPhaseAlgorithm {
SphereVsSphereAlgorithm& operator=(const SphereVsSphereAlgorithm& algorithm) = delete;
/// Compute a contact info if the two bounding volume collide
bool testCollision(SphereVsSphereNarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchStartIndex,
bool testCollision(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchStartIndex,
uint batchNbItems, MemoryAllocator& memoryAllocator);
};

View File

@ -110,7 +110,10 @@ class AABB {
bool testCollisionTriangleAABB(const Vector3* trianglePoints) const;
/// Return true if the ray intersects the AABB
bool testRayIntersect(const Ray& ray) const;
bool testRayIntersect(const Vector3& rayOrigin, const Vector3& rayDirectionInv, decimal rayMaxFraction) const;
/// Compute the intersection of a ray and the AABB
bool raycast(const Ray& ray, Vector3& hitPoint) const;
/// Apply a scale factor to the AABB
void applyScale(const Vector3& scale);
@ -127,44 +130,44 @@ class AABB {
};
// Return the center point of the AABB in world coordinates
inline Vector3 AABB::getCenter() const {
RP3D_FORCE_INLINE Vector3 AABB::getCenter() const {
return (mMinCoordinates + mMaxCoordinates) * decimal(0.5);
}
// Return the minimum coordinates of the AABB
inline const Vector3& AABB::getMin() const {
RP3D_FORCE_INLINE const Vector3& AABB::getMin() const {
return mMinCoordinates;
}
// Set the minimum coordinates of the AABB
inline void AABB::setMin(const Vector3& min) {
RP3D_FORCE_INLINE void AABB::setMin(const Vector3& min) {
mMinCoordinates = min;
}
// Return the maximum coordinates of the AABB
inline const Vector3& AABB::getMax() const {
RP3D_FORCE_INLINE const Vector3& AABB::getMax() const {
return mMaxCoordinates;
}
// Set the maximum coordinates of the AABB
inline void AABB::setMax(const Vector3& max) {
RP3D_FORCE_INLINE void AABB::setMax(const Vector3& max) {
mMaxCoordinates = max;
}
// Return the size of the AABB in the three dimension x, y and z
inline Vector3 AABB::getExtent() const {
RP3D_FORCE_INLINE Vector3 AABB::getExtent() const {
return mMaxCoordinates - mMinCoordinates;
}
// Inflate each side of the AABB by a given size
inline void AABB::inflate(decimal dx, decimal dy, decimal dz) {
RP3D_FORCE_INLINE void AABB::inflate(decimal dx, decimal dy, decimal dz) {
mMaxCoordinates += Vector3(dx, dy, dz);
mMinCoordinates -= Vector3(dx, dy, dz);
}
// Return true if the current AABB is overlapping with the AABB in argument.
/// Two AABBs overlap if they overlap in the three x, y and z axis at the same time
inline bool AABB::testCollision(const AABB& aabb) const {
RP3D_FORCE_INLINE bool AABB::testCollision(const AABB& aabb) const {
if (mMaxCoordinates.x < aabb.mMinCoordinates.x ||
aabb.mMaxCoordinates.x < mMinCoordinates.x) return false;
if (mMaxCoordinates.y < aabb.mMinCoordinates.y ||
@ -175,13 +178,13 @@ inline bool AABB::testCollision(const AABB& aabb) const {
}
// Return the volume of the AABB
inline decimal AABB::getVolume() const {
RP3D_FORCE_INLINE decimal AABB::getVolume() const {
const Vector3 diff = mMaxCoordinates - mMinCoordinates;
return (diff.x * diff.y * diff.z);
}
// Return true if the AABB of a triangle intersects the AABB
inline bool AABB::testCollisionTriangleAABB(const Vector3* trianglePoints) const {
RP3D_FORCE_INLINE bool AABB::testCollisionTriangleAABB(const Vector3* trianglePoints) const {
if (min3(trianglePoints[0].x, trianglePoints[1].x, trianglePoints[2].x) > mMaxCoordinates.x) return false;
if (min3(trianglePoints[0].y, trianglePoints[1].y, trianglePoints[2].y) > mMaxCoordinates.y) return false;
@ -195,7 +198,7 @@ inline bool AABB::testCollisionTriangleAABB(const Vector3* trianglePoints) const
}
// Return true if a point is inside the AABB
inline bool AABB::contains(const Vector3& point) const {
RP3D_FORCE_INLINE bool AABB::contains(const Vector3& point) const {
return (point.x >= mMinCoordinates.x - MACHINE_EPSILON && point.x <= mMaxCoordinates.x + MACHINE_EPSILON &&
point.y >= mMinCoordinates.y - MACHINE_EPSILON && point.y <= mMaxCoordinates.y + MACHINE_EPSILON &&
@ -203,13 +206,13 @@ inline bool AABB::contains(const Vector3& point) const {
}
// Apply a scale factor to the AABB
inline void AABB::applyScale(const Vector3& scale) {
RP3D_FORCE_INLINE void AABB::applyScale(const Vector3& scale) {
mMinCoordinates = mMinCoordinates * scale;
mMaxCoordinates = mMaxCoordinates * scale;
}
// Assignment operator
inline AABB& AABB::operator=(const AABB& aabb) {
RP3D_FORCE_INLINE AABB& AABB::operator=(const AABB& aabb) {
if (this != &aabb) {
mMinCoordinates = aabb.mMinCoordinates;
mMaxCoordinates = aabb.mMaxCoordinates;
@ -217,6 +220,147 @@ inline AABB& AABB::operator=(const AABB& aabb) {
return *this;
}
// Merge the AABB in parameter with the current one
RP3D_FORCE_INLINE void AABB::mergeWithAABB(const AABB& aabb) {
mMinCoordinates.x = std::min(mMinCoordinates.x, aabb.mMinCoordinates.x);
mMinCoordinates.y = std::min(mMinCoordinates.y, aabb.mMinCoordinates.y);
mMinCoordinates.z = std::min(mMinCoordinates.z, aabb.mMinCoordinates.z);
mMaxCoordinates.x = std::max(mMaxCoordinates.x, aabb.mMaxCoordinates.x);
mMaxCoordinates.y = std::max(mMaxCoordinates.y, aabb.mMaxCoordinates.y);
mMaxCoordinates.z = std::max(mMaxCoordinates.z, aabb.mMaxCoordinates.z);
}
// Replace the current AABB with a new AABB that is the union of two AABBs in parameters
RP3D_FORCE_INLINE void AABB::mergeTwoAABBs(const AABB& aabb1, const AABB& aabb2) {
mMinCoordinates.x = std::min(aabb1.mMinCoordinates.x, aabb2.mMinCoordinates.x);
mMinCoordinates.y = std::min(aabb1.mMinCoordinates.y, aabb2.mMinCoordinates.y);
mMinCoordinates.z = std::min(aabb1.mMinCoordinates.z, aabb2.mMinCoordinates.z);
mMaxCoordinates.x = std::max(aabb1.mMaxCoordinates.x, aabb2.mMaxCoordinates.x);
mMaxCoordinates.y = std::max(aabb1.mMaxCoordinates.y, aabb2.mMaxCoordinates.y);
mMaxCoordinates.z = std::max(aabb1.mMaxCoordinates.z, aabb2.mMaxCoordinates.z);
}
// Return true if the current AABB contains the AABB given in parameter
RP3D_FORCE_INLINE bool AABB::contains(const AABB& aabb) const {
bool isInside = true;
isInside = isInside && mMinCoordinates.x <= aabb.mMinCoordinates.x;
isInside = isInside && mMinCoordinates.y <= aabb.mMinCoordinates.y;
isInside = isInside && mMinCoordinates.z <= aabb.mMinCoordinates.z;
isInside = isInside && mMaxCoordinates.x >= aabb.mMaxCoordinates.x;
isInside = isInside && mMaxCoordinates.y >= aabb.mMaxCoordinates.y;
isInside = isInside && mMaxCoordinates.z >= aabb.mMaxCoordinates.z;
return isInside;
}
// Create and return an AABB for a triangle
RP3D_FORCE_INLINE AABB AABB::createAABBForTriangle(const Vector3* trianglePoints) {
Vector3 minCoords(trianglePoints[0].x, trianglePoints[0].y, trianglePoints[0].z);
Vector3 maxCoords(trianglePoints[0].x, trianglePoints[0].y, trianglePoints[0].z);
if (trianglePoints[1].x < minCoords.x) minCoords.x = trianglePoints[1].x;
if (trianglePoints[1].y < minCoords.y) minCoords.y = trianglePoints[1].y;
if (trianglePoints[1].z < minCoords.z) minCoords.z = trianglePoints[1].z;
if (trianglePoints[2].x < minCoords.x) minCoords.x = trianglePoints[2].x;
if (trianglePoints[2].y < minCoords.y) minCoords.y = trianglePoints[2].y;
if (trianglePoints[2].z < minCoords.z) minCoords.z = trianglePoints[2].z;
if (trianglePoints[1].x > maxCoords.x) maxCoords.x = trianglePoints[1].x;
if (trianglePoints[1].y > maxCoords.y) maxCoords.y = trianglePoints[1].y;
if (trianglePoints[1].z > maxCoords.z) maxCoords.z = trianglePoints[1].z;
if (trianglePoints[2].x > maxCoords.x) maxCoords.x = trianglePoints[2].x;
if (trianglePoints[2].y > maxCoords.y) maxCoords.y = trianglePoints[2].y;
if (trianglePoints[2].z > maxCoords.z) maxCoords.z = trianglePoints[2].z;
return AABB(minCoords, maxCoords);
}
// Return true if the ray intersects the AABB
RP3D_FORCE_INLINE bool AABB::testRayIntersect(const Vector3& rayOrigin, const Vector3& rayDirectionInverse, decimal rayMaxFraction) const {
// This algorithm relies on the IEE floating point properties (division by zero). If the rayDirection is zero, rayDirectionInverse and
// therfore t1 and t2 will be +-INFINITY. If the i coordinate of the ray's origin is inside the AABB (mMinCoordinates[i] < rayOrigin[i] < mMaxCordinates[i)), we have
// t1 = -t2 = +- INFINITY. Since max(n, -INFINITY) = min(n, INFINITY) = n for all n, tMin and tMax will stay unchanged. Secondly, if the i
// coordinate of the ray's origin is outside the box (rayOrigin[i] < mMinCoordinates[i] or rayOrigin[i] > mMaxCoordinates[i]) we have
// t1 = t2 = +- INFINITY and therefore either tMin = +INFINITY or tMax = -INFINITY. One of those values will stay until the end and make the
// method to return false. Unfortunately, if the ray lies exactly on a slab (rayOrigin[i] = mMinCoordinates[i] or rayOrigin[i] = mMaxCoordinates[i]) we
// have t1 = (mMinCoordinates[i] - rayOrigin[i]) * rayDirectionInverse[i] = 0 * INFINITY = NaN which is a problem for the remaining of the algorithm.
// This will cause the method to return true when the ray is not intersecting the AABB and therefore cause to traverse more nodes than necessary in
// the BVH tree. Because this should be rare, it is not really a big issue.
// Reference: https://tavianator.com/2011/ray_box.html
decimal t1 = (mMinCoordinates[0] - rayOrigin[0]) * rayDirectionInverse[0];
decimal t2 = (mMaxCoordinates[0] - rayOrigin[0]) * rayDirectionInverse[0];
decimal tMin = std::min(t1, t2);
decimal tMax = std::max(t1, t2);
tMax = std::min(tMax, rayMaxFraction);
for (uint i = 1; i < 3; i++) {
t1 = (mMinCoordinates[i] - rayOrigin[i]) * rayDirectionInverse[i];
t2 = (mMaxCoordinates[i] - rayOrigin[i]) * rayDirectionInverse[i];
tMin = std::max(tMin, std::min(t1, t2));
tMax = std::min(tMax, std::max(t1, t2));
}
return tMax >= std::max(tMin, decimal(0.0));
}
// Compute the intersection of a ray and the AABB
RP3D_FORCE_INLINE bool AABB::raycast(const Ray& ray, Vector3& hitPoint) const {
decimal tMin = decimal(0.0);
decimal tMax = DECIMAL_LARGEST;
const decimal epsilon = 0.00001;
const Vector3 rayDirection = ray.point2 - ray.point1;
// For all three slabs
for (int i=0; i < 3; i++) {
// If the ray is parallel to the slab
if (std::abs(rayDirection[i]) < epsilon) {
// If origin of the ray is not inside the slab, no hit
if (ray.point1[i] < mMinCoordinates[i] || ray.point1[i] > mMaxCoordinates[i]) return false;
}
else {
decimal rayDirectionInverse = decimal(1.0) / rayDirection[i];
decimal t1 = (mMinCoordinates[i] - ray.point1[i]) * rayDirectionInverse;
decimal t2 = (mMaxCoordinates[i] - ray.point1[i]) * rayDirectionInverse;
if (t1 > t2) {
// Swap t1 and t2
decimal tTemp = t2;
t2 = t1;
t1 = tTemp;
}
tMin = std::max(tMin, t1);
tMax = std::min(tMax, t2);
// Exit with no collision
if (tMin > tMax) return false;
}
}
// Compute the hit point
hitPoint = ray.point1 + tMin * rayDirection;
return true;
}
}
#endif

View File

@ -36,6 +36,7 @@ namespace reactphysics3d {
// Declarations
class CollisionBody;
class DefaultAllocator;
class PhysicsCommon;
// Class BoxShape
/**
@ -53,13 +54,13 @@ class BoxShape : public ConvexPolyhedronShape {
/// Half-extents of the box in the x, y and z direction
Vector3 mHalfExtents;
/// Half-edge structure of the polyhedron
HalfEdgeStructure mHalfEdgeStructure;
/// Reference to the physics common object
PhysicsCommon& mPhysicsCommon;
// -------------------- Methods -------------------- //
/// Constructor
BoxShape(const Vector3& halfExtents, MemoryAllocator& allocator);
BoxShape(const Vector3& halfExtents, MemoryAllocator& allocator, PhysicsCommon& physicsCommon);
/// Return a local support point in a given direction without the object margin
virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction) const override;
@ -140,7 +141,7 @@ class BoxShape : public ConvexPolyhedronShape {
/**
* @return The vector with the three half-extents of the box shape
*/
inline Vector3 BoxShape::getHalfExtents() const {
RP3D_FORCE_INLINE Vector3 BoxShape::getHalfExtents() const {
return mHalfExtents;
}
@ -150,7 +151,7 @@ inline Vector3 BoxShape::getHalfExtents() const {
/**
* @param halfExtents The vector with the three half-extents of the box
*/
inline void BoxShape::setHalfExtents(const Vector3& halfExtents) {
RP3D_FORCE_INLINE void BoxShape::setHalfExtents(const Vector3& halfExtents) {
mHalfExtents = halfExtents;
notifyColliderAboutChangedSize();
@ -162,7 +163,7 @@ inline void BoxShape::setHalfExtents(const Vector3& halfExtents) {
* @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 BoxShape::getLocalBounds(Vector3& min, Vector3& max) const {
RP3D_FORCE_INLINE void BoxShape::getLocalBounds(Vector3& min, Vector3& max) const {
// Maximum bounds
max = mHalfExtents;
@ -172,12 +173,12 @@ inline void BoxShape::getLocalBounds(Vector3& min, Vector3& max) const {
}
// Return the number of bytes used by the collision shape
inline size_t BoxShape::getSizeInBytes() const {
RP3D_FORCE_INLINE size_t BoxShape::getSizeInBytes() const {
return sizeof(BoxShape);
}
// Return a local support point in a given direction without the object margin
inline Vector3 BoxShape::getLocalSupportPointWithoutMargin(const Vector3& direction) const {
RP3D_FORCE_INLINE Vector3 BoxShape::getLocalSupportPointWithoutMargin(const Vector3& direction) const {
return Vector3(direction.x < decimal(0.0) ? -mHalfExtents.x : mHalfExtents.x,
direction.y < decimal(0.0) ? -mHalfExtents.y : mHalfExtents.y,
@ -185,49 +186,35 @@ inline Vector3 BoxShape::getLocalSupportPointWithoutMargin(const Vector3& direct
}
// Return true if a point is inside the collision shape
inline bool BoxShape::testPointInside(const Vector3& localPoint, Collider* collider) const {
RP3D_FORCE_INLINE bool BoxShape::testPointInside(const Vector3& localPoint, Collider* collider) const {
return (localPoint.x < mHalfExtents[0] && localPoint.x > -mHalfExtents[0] &&
localPoint.y < mHalfExtents[1] && localPoint.y > -mHalfExtents[1] &&
localPoint.z < mHalfExtents[2] && localPoint.z > -mHalfExtents[2]);
}
// Return the number of faces of the polyhedron
inline uint BoxShape::getNbFaces() const {
RP3D_FORCE_INLINE uint BoxShape::getNbFaces() const {
return 6;
}
// Return a given face of the polyhedron
inline const HalfEdgeStructure::Face& BoxShape::getFace(uint faceIndex) const {
assert(faceIndex < mHalfEdgeStructure.getNbFaces());
return mHalfEdgeStructure.getFace(faceIndex);
}
// Return the number of vertices of the polyhedron
inline uint BoxShape::getNbVertices() const {
RP3D_FORCE_INLINE uint BoxShape::getNbVertices() const {
return 8;
}
// Return a given vertex of the polyhedron
inline HalfEdgeStructure::Vertex BoxShape::getVertex(uint vertexIndex) const {
assert(vertexIndex < getNbVertices());
return mHalfEdgeStructure.getVertex(vertexIndex);
}
// Return the position of a given vertex
inline Vector3 BoxShape::getVertexPosition(uint vertexIndex) const {
RP3D_FORCE_INLINE Vector3 BoxShape::getVertexPosition(uint vertexIndex) const {
assert(vertexIndex < getNbVertices());
Vector3 extent = getHalfExtents();
switch(vertexIndex) {
case 0: return Vector3(-extent.x, -extent.y, extent.z);
case 1: return Vector3(extent.x, -extent.y, extent.z);
case 2: return Vector3(extent.x, extent.y, extent.z);
case 3: return Vector3(-extent.x, extent.y, extent.z);
case 4: return Vector3(-extent.x, -extent.y, -extent.z);
case 5: return Vector3(extent.x, -extent.y, -extent.z);
case 6: return Vector3(extent.x, extent.y, -extent.z);
case 7: return Vector3(-extent.x, extent.y, -extent.z);
case 0: return Vector3(-mHalfExtents.x, -mHalfExtents.y, mHalfExtents.z);
case 1: return Vector3(mHalfExtents.x, -mHalfExtents.y, mHalfExtents.z);
case 2: return Vector3(mHalfExtents.x, mHalfExtents.y, mHalfExtents.z);
case 3: return Vector3(-mHalfExtents.x, mHalfExtents.y, mHalfExtents.z);
case 4: return Vector3(-mHalfExtents.x, -mHalfExtents.y, -mHalfExtents.z);
case 5: return Vector3(mHalfExtents.x, -mHalfExtents.y, -mHalfExtents.z);
case 6: return Vector3(mHalfExtents.x, mHalfExtents.y, -mHalfExtents.z);
case 7: return Vector3(-mHalfExtents.x, mHalfExtents.y, -mHalfExtents.z);
}
assert(false);
@ -235,7 +222,7 @@ inline Vector3 BoxShape::getVertexPosition(uint vertexIndex) const {
}
// Return the normal vector of a given face of the polyhedron
inline Vector3 BoxShape::getFaceNormal(uint faceIndex) const {
RP3D_FORCE_INLINE Vector3 BoxShape::getFaceNormal(uint faceIndex) const {
assert(faceIndex < getNbFaces());
switch(faceIndex) {
@ -252,31 +239,25 @@ inline Vector3 BoxShape::getFaceNormal(uint faceIndex) const {
}
// Return the centroid of the box
inline Vector3 BoxShape::getCentroid() const {
RP3D_FORCE_INLINE Vector3 BoxShape::getCentroid() const {
return Vector3::zero();
}
// Compute and return the volume of the collision shape
inline decimal BoxShape::getVolume() const {
RP3D_FORCE_INLINE decimal BoxShape::getVolume() const {
return 8 * mHalfExtents.x * mHalfExtents.y * mHalfExtents.z;
}
// Return the string representation of the shape
inline std::string BoxShape::to_string() const {
RP3D_FORCE_INLINE std::string BoxShape::to_string() const {
return "BoxShape{extents=" + mHalfExtents.to_string() + "}";
}
// Return the number of half-edges of the polyhedron
inline uint BoxShape::getNbHalfEdges() const {
RP3D_FORCE_INLINE uint BoxShape::getNbHalfEdges() const {
return 24;
}
// Return a given half-edge of the polyhedron
inline const HalfEdgeStructure::Edge& BoxShape::getHalfEdge(uint edgeIndex) const {
assert(edgeIndex < getNbHalfEdges());
return mHalfEdgeStructure.getHalfEdge(edgeIndex);
}
}
#endif

View File

@ -126,7 +126,7 @@ class CapsuleShape : public ConvexShape {
/**
* @return The radius of the capsule shape (in meters)
*/
inline decimal CapsuleShape::getRadius() const {
RP3D_FORCE_INLINE decimal CapsuleShape::getRadius() const {
return mMargin;
}
@ -136,7 +136,7 @@ inline decimal CapsuleShape::getRadius() const {
/**
* @param radius The radius of the capsule (in meters)
*/
inline void CapsuleShape::setRadius(decimal radius) {
RP3D_FORCE_INLINE void CapsuleShape::setRadius(decimal radius) {
assert(radius > decimal(0.0));
mMargin = radius;
@ -148,7 +148,7 @@ inline void CapsuleShape::setRadius(decimal radius) {
/**
* @return The height of the capsule shape (in meters)
*/
inline decimal CapsuleShape::getHeight() const {
RP3D_FORCE_INLINE decimal CapsuleShape::getHeight() const {
return mHalfHeight + mHalfHeight;
}
@ -158,7 +158,7 @@ inline decimal CapsuleShape::getHeight() const {
/**
* @param height The height of the capsule (in meters)
*/
inline void CapsuleShape::setHeight(decimal height) {
RP3D_FORCE_INLINE void CapsuleShape::setHeight(decimal height) {
assert(height > decimal(0.0));
mHalfHeight = height * decimal(0.5);
@ -167,7 +167,7 @@ inline void CapsuleShape::setHeight(decimal height) {
}
// Return the number of bytes used by the collision shape
inline size_t CapsuleShape::getSizeInBytes() const {
RP3D_FORCE_INLINE size_t CapsuleShape::getSizeInBytes() const {
return sizeof(CapsuleShape);
}
@ -177,7 +177,7 @@ inline size_t CapsuleShape::getSizeInBytes() const {
* @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 CapsuleShape::getLocalBounds(Vector3& min, Vector3& max) const {
RP3D_FORCE_INLINE void CapsuleShape::getLocalBounds(Vector3& min, Vector3& max) const {
// Maximum bounds
max.x = mMargin;
@ -191,12 +191,12 @@ inline void CapsuleShape::getLocalBounds(Vector3& min, Vector3& max) const {
}
// Compute and return the volume of the collision shape
inline decimal CapsuleShape::getVolume() const {
RP3D_FORCE_INLINE decimal CapsuleShape::getVolume() const {
return reactphysics3d::PI_RP3D * mMargin * mMargin * (decimal(4.0) * mMargin / decimal(3.0) + decimal(2.0) * mHalfHeight);
}
// Return true if the collision shape is a polyhedron
inline bool CapsuleShape::isPolyhedron() const {
RP3D_FORCE_INLINE bool CapsuleShape::isPolyhedron() const {
return false;
}
@ -207,7 +207,7 @@ inline bool CapsuleShape::isPolyhedron() const {
/// Therefore, in this method, we compute the support points of both top and bottom spheres of
/// the capsule and return the point with the maximum dot product with the direction vector. Note
/// that the object margin is implicitly the radius and height of the capsule.
inline Vector3 CapsuleShape::getLocalSupportPointWithoutMargin(const Vector3& direction) const {
RP3D_FORCE_INLINE Vector3 CapsuleShape::getLocalSupportPointWithoutMargin(const Vector3& direction) const {
// Support point top sphere
decimal dotProductTop = mHalfHeight * direction.y;
@ -225,7 +225,7 @@ inline Vector3 CapsuleShape::getLocalSupportPointWithoutMargin(const Vector3& di
}
// Return the string representation of the shape
inline std::string CapsuleShape::to_string() const {
RP3D_FORCE_INLINE std::string CapsuleShape::to_string() const {
return "CapsuleShape{halfHeight=" + std::to_string(mHalfHeight) + ", radius=" + std::to_string(getRadius()) + "}";
}

View File

@ -30,7 +30,7 @@
#include <cassert>
#include <reactphysics3d/configuration.h>
#include <reactphysics3d/utils/Profiler.h>
#include <reactphysics3d/containers/List.h>
#include <reactphysics3d/containers/Array.h>
/// ReactPhysics3D namespace
namespace reactphysics3d {
@ -76,8 +76,8 @@ class CollisionShape {
/// Unique identifier of the shape inside an overlapping pair
uint32 mId;
/// List of the colliders associated with this shape
List<Collider*> mColliders;
/// Array of the colliders associated with this shape
Array<Collider*> mColliders;
#ifdef IS_RP3D_PROFILING_ENABLED
@ -172,7 +172,7 @@ class CollisionShape {
/**
* @return The name of the collision shape (box, sphere, triangle, ...)
*/
inline CollisionShapeName CollisionShape::getName() const {
RP3D_FORCE_INLINE CollisionShapeName CollisionShape::getName() const {
return mName;
}
@ -180,29 +180,29 @@ inline CollisionShapeName CollisionShape::getName() const {
/**
* @return The type of the collision shape (sphere, capsule, convex polyhedron, concave mesh)
*/
inline CollisionShapeType CollisionShape::getType() const {
RP3D_FORCE_INLINE CollisionShapeType CollisionShape::getType() const {
return mType;
}
// Return the id of the shape
inline uint32 CollisionShape::getId() const {
RP3D_FORCE_INLINE uint32 CollisionShape::getId() const {
return mId;
}
// Assign a new collider to the collision shape
inline void CollisionShape::addCollider(Collider* collider) {
RP3D_FORCE_INLINE void CollisionShape::addCollider(Collider* collider) {
mColliders.add(collider);
}
// Remove an assigned collider from the collision shape
inline void CollisionShape::removeCollider(Collider* collider) {
RP3D_FORCE_INLINE void CollisionShape::removeCollider(Collider* collider) {
mColliders.remove(collider);
}
#ifdef IS_RP3D_PROFILING_ENABLED
// Set the profiler
inline void CollisionShape::setProfiler(Profiler* profiler) {
RP3D_FORCE_INLINE void CollisionShape::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}

View File

@ -29,7 +29,7 @@
// Libraries
#include <reactphysics3d/collision/shapes/ConcaveShape.h>
#include <reactphysics3d/collision/broadphase/DynamicAABBTree.h>
#include <reactphysics3d/containers/List.h>
#include <reactphysics3d/containers/Array.h>
namespace reactphysics3d {
@ -72,7 +72,7 @@ class ConcaveMeshRaycastCallback : public DynamicAABBTreeRaycastCallback {
private :
List<int32> mHitAABBNodes;
Array<int32> mHitAABBNodes;
const DynamicAABBTree& mDynamicAABBTree;
const ConcaveMeshShape& mConcaveMeshShape;
Collider* mCollider;
@ -142,10 +142,13 @@ class ConcaveMeshShape : public ConcaveShape {
/// if the user did not provide its own vertices normals)
Vector3** mComputedVerticesNormals;
/// Reference to the triangle half-edge structure
HalfEdgeStructure& mTriangleHalfEdgeStructure;
// -------------------- Methods -------------------- //
/// Constructor
ConcaveMeshShape(TriangleMesh* triangleMesh, MemoryAllocator& allocator, const Vector3& scaling = Vector3(1, 1, 1));
ConcaveMeshShape(TriangleMesh* triangleMesh, MemoryAllocator& allocator, HalfEdgeStructure& triangleHalfEdgeStructure, const Vector3& scaling = Vector3(1, 1, 1));
/// Raycast method with feedback information
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, Collider* collider, MemoryAllocator& allocator) const override;
@ -156,7 +159,7 @@ class ConcaveMeshShape : public ConcaveShape {
/// Insert all the triangles into the dynamic AABB tree
void initBVHTree();
/// Return the three vertices coordinates (in the list outTriangleVertices) of a triangle
/// Return the three vertices coordinates (in the array outTriangleVertices) of a triangle
void getTriangleVertices(uint subPart, uint triangleIndex, Vector3* outTriangleVertices) const;
/// Return the three vertex normals (in the array outVerticesNormals) of a triangle
@ -166,8 +169,8 @@ class ConcaveMeshShape : public ConcaveShape {
uint computeTriangleShapeId(uint subPart, uint triangleIndex) const;
/// Compute all the triangles of the mesh that are overlapping with the AABB in parameter
virtual void computeOverlappingTriangles(const AABB& localAABB, List<Vector3>& triangleVertices,
List<Vector3> &triangleVerticesNormals, List<uint>& shapeIds,
virtual void computeOverlappingTriangles(const AABB& localAABB, Array<Vector3>& triangleVertices,
Array<Vector3> &triangleVerticesNormals, Array<uint>& shapeIds,
MemoryAllocator& allocator) const override;
/// Destructor
@ -212,7 +215,7 @@ class ConcaveMeshShape : public ConcaveShape {
};
// Return the number of bytes used by the collision shape
inline size_t ConcaveMeshShape::getSizeInBytes() const {
RP3D_FORCE_INLINE size_t ConcaveMeshShape::getSizeInBytes() const {
return sizeof(ConcaveMeshShape);
}
@ -222,7 +225,7 @@ inline size_t ConcaveMeshShape::getSizeInBytes() const {
* @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 {
RP3D_FORCE_INLINE void ConcaveMeshShape::getLocalBounds(Vector3& min, Vector3& max) const {
// Get the AABB of the whole tree
AABB treeAABB = mDynamicAABBTree.getRootAABB();
@ -233,7 +236,7 @@ inline void ConcaveMeshShape::getLocalBounds(Vector3& min, Vector3& max) const {
// Called when a overlapping node has been found during the call to
// DynamicAABBTree:reportAllShapesOverlappingWithAABB()
inline void ConvexTriangleAABBOverlapCallback::notifyOverlappingNode(int nodeId) {
RP3D_FORCE_INLINE void ConvexTriangleAABBOverlapCallback::notifyOverlappingNode(int nodeId) {
// Get the node data (triangle index and mesh subpart index)
int32* data = mDynamicAABBTree.getNodeDataInt(nodeId);
@ -253,7 +256,7 @@ inline void ConvexTriangleAABBOverlapCallback::notifyOverlappingNode(int nodeId)
#ifdef IS_RP3D_PROFILING_ENABLED
// Set the profiler
inline void ConcaveMeshShape::setProfiler(Profiler* profiler) {
RP3D_FORCE_INLINE void ConcaveMeshShape::setProfiler(Profiler* profiler) {
CollisionShape::setProfiler(profiler);

View File

@ -111,8 +111,8 @@ class ConcaveShape : public CollisionShape {
virtual bool isPolyhedron() const override;
/// Use a callback method on all triangles of the concave shape inside a given AABB
virtual void computeOverlappingTriangles(const AABB& localAABB, List<Vector3>& triangleVertices,
List<Vector3>& triangleVerticesNormals, List<uint>& shapeIds,
virtual void computeOverlappingTriangles(const AABB& localAABB, Array<Vector3>& triangleVertices,
Array<Vector3>& triangleVerticesNormals, Array<uint>& shapeIds,
MemoryAllocator& allocator) const=0;
/// Compute and return the volume of the collision shape
@ -120,22 +120,22 @@ class ConcaveShape : public CollisionShape {
};
// Return true if the collision shape is convex, false if it is concave
inline bool ConcaveShape::isConvex() const {
RP3D_FORCE_INLINE bool ConcaveShape::isConvex() const {
return false;
}
// Return true if the collision shape is a polyhedron
inline bool ConcaveShape::isPolyhedron() const {
RP3D_FORCE_INLINE bool ConcaveShape::isPolyhedron() const {
return true;
}
// Return true if a point is inside the collision shape
inline bool ConcaveShape::testPointInside(const Vector3& localPoint, Collider* collider) const {
RP3D_FORCE_INLINE bool ConcaveShape::testPointInside(const Vector3& localPoint, Collider* collider) const {
return false;
}
// Return the raycast test type (front, back, front-back)
inline TriangleRaycastSide ConcaveShape::getRaycastTestType() const {
RP3D_FORCE_INLINE TriangleRaycastSide ConcaveShape::getRaycastTestType() const {
return mRaycastTestType;
}
@ -143,19 +143,19 @@ inline TriangleRaycastSide ConcaveShape::getRaycastTestType() const {
/**
* @param testType Raycast test type for the triangle (front, back, front-back)
*/
inline void ConcaveShape::setRaycastTestType(TriangleRaycastSide testType) {
RP3D_FORCE_INLINE void ConcaveShape::setRaycastTestType(TriangleRaycastSide testType) {
mRaycastTestType = testType;
}
// Return the scale of the shape
inline const Vector3& ConcaveShape::getScale() const {
RP3D_FORCE_INLINE const Vector3& ConcaveShape::getScale() const {
return mScale;
}
// Set the scale of the shape
/// Note that you might want to recompute the inertia tensor and center of mass of the body
/// after changing the scale of a collision shape
inline void ConcaveShape::setScale(const Vector3& scale) {
RP3D_FORCE_INLINE void ConcaveShape::setScale(const Vector3& scale) {
mScale = scale;
notifyColliderAboutChangedSize();
@ -165,7 +165,7 @@ inline void ConcaveShape::setScale(const Vector3& scale) {
/**
* @param mass Mass to use to compute the inertia tensor of the collision shape
*/
inline Vector3 ConcaveShape::getLocalInertiaTensor(decimal mass) const {
RP3D_FORCE_INLINE Vector3 ConcaveShape::getLocalInertiaTensor(decimal mass) const {
// Default inertia tensor
// Note that this is not very realistic for a concave triangle mesh.

View File

@ -147,19 +147,19 @@ class ConvexMeshShape : public ConvexPolyhedronShape {
};
// Return the number of bytes used by the collision shape
inline size_t ConvexMeshShape::getSizeInBytes() const {
RP3D_FORCE_INLINE size_t ConvexMeshShape::getSizeInBytes() const {
return sizeof(ConvexMeshShape);
}
// Return the scaling vector
inline const Vector3& ConvexMeshShape::getScale() const {
RP3D_FORCE_INLINE const Vector3& ConvexMeshShape::getScale() const {
return mScale;
}
// Set the scale
/// Note that you might want to recompute the inertia tensor and center of mass of the body
/// after changing the scale of a collision shape
inline void ConvexMeshShape::setScale(const Vector3& scale) {
RP3D_FORCE_INLINE void ConvexMeshShape::setScale(const Vector3& scale) {
mScale = scale;
recalculateBounds();
notifyColliderAboutChangedSize();
@ -170,7 +170,7 @@ inline void ConvexMeshShape::setScale(const Vector3& scale) {
* @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 ConvexMeshShape::getLocalBounds(Vector3& min, Vector3& max) const {
RP3D_FORCE_INLINE void ConvexMeshShape::getLocalBounds(Vector3& min, Vector3& max) const {
min = mMinBounds;
max = mMaxBounds;
}
@ -181,7 +181,7 @@ inline void ConvexMeshShape::getLocalBounds(Vector3& min, Vector3& max) const {
/**
* @param mass Mass to use to compute the inertia tensor of the collision shape
*/
inline Vector3 ConvexMeshShape::getLocalInertiaTensor(decimal mass) const {
RP3D_FORCE_INLINE Vector3 ConvexMeshShape::getLocalInertiaTensor(decimal mass) const {
const decimal factor = (decimal(1.0) / decimal(3.0)) * mass;
const Vector3 realExtent = decimal(0.5) * (mMaxBounds - mMinBounds);
assert(realExtent.x > 0 && realExtent.y > 0 && realExtent.z > 0);
@ -192,58 +192,58 @@ inline Vector3 ConvexMeshShape::getLocalInertiaTensor(decimal mass) const {
}
// Return the number of faces of the polyhedron
inline uint ConvexMeshShape::getNbFaces() const {
RP3D_FORCE_INLINE uint ConvexMeshShape::getNbFaces() const {
return mPolyhedronMesh->getHalfEdgeStructure().getNbFaces();
}
// Return a given face of the polyhedron
inline const HalfEdgeStructure::Face& ConvexMeshShape::getFace(uint faceIndex) const {
RP3D_FORCE_INLINE const HalfEdgeStructure::Face& ConvexMeshShape::getFace(uint faceIndex) const {
assert(faceIndex < getNbFaces());
return mPolyhedronMesh->getHalfEdgeStructure().getFace(faceIndex);
}
// Return the number of vertices of the polyhedron
inline uint ConvexMeshShape::getNbVertices() const {
RP3D_FORCE_INLINE uint ConvexMeshShape::getNbVertices() const {
return mPolyhedronMesh->getHalfEdgeStructure().getNbVertices();
}
// Return a given vertex of the polyhedron
inline HalfEdgeStructure::Vertex ConvexMeshShape::getVertex(uint vertexIndex) const {
RP3D_FORCE_INLINE HalfEdgeStructure::Vertex ConvexMeshShape::getVertex(uint vertexIndex) const {
assert(vertexIndex < getNbVertices());
return mPolyhedronMesh->getHalfEdgeStructure().getVertex(vertexIndex);
}
// Return the number of half-edges of the polyhedron
inline uint ConvexMeshShape::getNbHalfEdges() const {
RP3D_FORCE_INLINE uint ConvexMeshShape::getNbHalfEdges() const {
return mPolyhedronMesh->getHalfEdgeStructure().getNbHalfEdges();
}
// Return a given half-edge of the polyhedron
inline const HalfEdgeStructure::Edge& ConvexMeshShape::getHalfEdge(uint edgeIndex) const {
RP3D_FORCE_INLINE const HalfEdgeStructure::Edge& ConvexMeshShape::getHalfEdge(uint edgeIndex) const {
assert(edgeIndex < getNbHalfEdges());
return mPolyhedronMesh->getHalfEdgeStructure().getHalfEdge(edgeIndex);
}
// Return the position of a given vertex
inline Vector3 ConvexMeshShape::getVertexPosition(uint vertexIndex) const {
RP3D_FORCE_INLINE Vector3 ConvexMeshShape::getVertexPosition(uint vertexIndex) const {
assert(vertexIndex < getNbVertices());
return mPolyhedronMesh->getVertex(vertexIndex) * mScale;
}
// Return the normal vector of a given face of the polyhedron
inline Vector3 ConvexMeshShape::getFaceNormal(uint faceIndex) const {
RP3D_FORCE_INLINE Vector3 ConvexMeshShape::getFaceNormal(uint faceIndex) const {
assert(faceIndex < getNbFaces());
return mPolyhedronMesh->getFaceNormal(faceIndex);
}
// Return the centroid of the polyhedron
inline Vector3 ConvexMeshShape::getCentroid() const {
RP3D_FORCE_INLINE Vector3 ConvexMeshShape::getCentroid() const {
return mPolyhedronMesh->getCentroid() * mScale;
}
// Compute and return the volume of the collision shape
inline decimal ConvexMeshShape::getVolume() const {
RP3D_FORCE_INLINE decimal ConvexMeshShape::getVolume() const {
return mPolyhedronMesh->getVolume();
}

View File

@ -94,11 +94,34 @@ class ConvexPolyhedronShape : public ConvexShape {
};
// Return true if the collision shape is a polyhedron
inline bool ConvexPolyhedronShape::isPolyhedron() const {
RP3D_FORCE_INLINE bool ConvexPolyhedronShape::isPolyhedron() const {
return true;
}
// Find and return the index of the polyhedron face with the most anti-parallel face
// normal given a direction vector. This is used to find the incident face on
// a polyhedron of a given reference face of another polyhedron
RP3D_FORCE_INLINE uint ConvexPolyhedronShape::findMostAntiParallelFace(const Vector3& direction) const {
decimal minDotProduct = DECIMAL_LARGEST;
uint mostAntiParallelFace = 0;
// For each face of the polyhedron
const uint32 nbFaces = getNbFaces();
for (uint32 i=0; i < nbFaces; i++) {
// Get the face normal
const decimal dotProduct = getFaceNormal(i).dot(direction);
if (dotProduct < minDotProduct) {
minDotProduct = dotProduct;
mostAntiParallelFace = i;
}
}
return mostAntiParallelFace;
}
}
#endif

View File

@ -83,7 +83,7 @@ class ConvexShape : public CollisionShape {
};
// Return true if the collision shape is convex, false if it is concave
inline bool ConvexShape::isConvex() const {
RP3D_FORCE_INLINE bool ConvexShape::isConvex() const {
return true;
}
@ -91,7 +91,7 @@ inline bool ConvexShape::isConvex() const {
/**
* @return The margin (in meters) around the collision shape
*/
inline decimal ConvexShape::getMargin() const {
RP3D_FORCE_INLINE decimal ConvexShape::getMargin() const {
return mMargin;
}

View File

@ -91,14 +91,21 @@ class HeightFieldShape : public ConcaveShape {
/// Local AABB of the height field (without scaling)
AABB mAABB;
/// Reference to the half-edge structure
HalfEdgeStructure& mTriangleHalfEdgeStructure;
// -------------------- Methods -------------------- //
/// Constructor
HeightFieldShape(int nbGridColumns, int nbGridRows, decimal minHeight, decimal maxHeight,
const void* heightFieldData, HeightDataType dataType, MemoryAllocator& allocator,
int upAxis = 1, decimal integerHeightScale = 1.0f,
HalfEdgeStructure& triangleHalfEdgeStructure, int upAxis = 1, decimal integerHeightScale = 1.0f,
const Vector3& scaling = Vector3(1,1,1));
/// Raycast a single triangle of the height-field
bool raycastTriangle(const Ray& ray, const Vector3& p1, const Vector3& p2, const Vector3& p3, uint shapeId,
Collider *collider, RaycastInfo& raycastInfo, decimal &smallestHitFraction, MemoryAllocator& allocator) const;
/// Raycast method with feedback information
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, Collider* collider, MemoryAllocator& allocator) const override;
@ -122,6 +129,9 @@ class HeightFieldShape : public ConcaveShape {
/// Compute the shape Id for a given triangle
uint computeTriangleShapeId(uint iIndex, uint jIndex, uint secondTriangleIncrement) const;
/// Compute the first grid cell of the heightfield intersected by a ray
bool computeEnteringRayGridCoordinates(const Ray& ray, int& i, int& j, Vector3& outHitPoint) const;
/// Destructor
virtual ~HeightFieldShape() override = default;
@ -152,8 +162,8 @@ class HeightFieldShape : public ConcaveShape {
virtual void getLocalBounds(Vector3& min, Vector3& max) const override;
/// Use a callback method on all triangles of the concave shape inside a given AABB
virtual void computeOverlappingTriangles(const AABB& localAABB, List<Vector3>& triangleVertices,
List<Vector3>& triangleVerticesNormals, List<uint>& shapeIds,
virtual void computeOverlappingTriangles(const AABB& localAABB, Array<Vector3>& triangleVertices,
Array<Vector3>& triangleVerticesNormals, Array<uint>& shapeIds,
MemoryAllocator& allocator) const override;
/// Return the string representation of the shape
@ -167,27 +177,27 @@ class HeightFieldShape : public ConcaveShape {
};
// Return the number of rows in the height field
inline int HeightFieldShape::getNbRows() const {
RP3D_FORCE_INLINE int HeightFieldShape::getNbRows() const {
return mNbRows;
}
// Return the number of columns in the height field
inline int HeightFieldShape::getNbColumns() const {
RP3D_FORCE_INLINE int HeightFieldShape::getNbColumns() const {
return mNbColumns;
}
// Return the type of height value in the height field
inline HeightFieldShape::HeightDataType HeightFieldShape::getHeightDataType() const {
RP3D_FORCE_INLINE HeightFieldShape::HeightDataType HeightFieldShape::getHeightDataType() const {
return mHeightDataType;
}
// Return the number of bytes used by the collision shape
inline size_t HeightFieldShape::getSizeInBytes() const {
RP3D_FORCE_INLINE size_t HeightFieldShape::getSizeInBytes() const {
return sizeof(HeightFieldShape);
}
// Return the height of a given (x,y) point in the height field
inline decimal HeightFieldShape::getHeightAt(int x, int y) const {
RP3D_FORCE_INLINE decimal HeightFieldShape::getHeightAt(int x, int y) const {
assert(x >= 0 && x < mNbColumns);
assert(y >= 0 && y < mNbRows);
@ -201,12 +211,12 @@ inline decimal HeightFieldShape::getHeightAt(int x, int y) const {
}
// Return the closest inside integer grid value of a given floating grid value
inline int HeightFieldShape::computeIntegerGridValue(decimal value) const {
RP3D_FORCE_INLINE int HeightFieldShape::computeIntegerGridValue(decimal value) const {
return (value < decimal(0.0)) ? value - decimal(0.5) : value + decimal(0.5);
}
// Compute the shape Id for a given triangle
inline uint HeightFieldShape::computeTriangleShapeId(uint iIndex, uint jIndex, uint secondTriangleIncrement) const {
RP3D_FORCE_INLINE uint HeightFieldShape::computeTriangleShapeId(uint iIndex, uint jIndex, uint secondTriangleIncrement) const {
return (jIndex * (mNbColumns - 1) + iIndex) * 2 + secondTriangleIncrement;
}

View File

@ -111,7 +111,7 @@ class SphereShape : public ConvexShape {
/**
* @return Radius of the sphere
*/
inline decimal SphereShape::getRadius() const {
RP3D_FORCE_INLINE decimal SphereShape::getRadius() const {
return mMargin;
}
@ -121,7 +121,7 @@ inline decimal SphereShape::getRadius() const {
/**
* @param radius Radius of the sphere
*/
inline void SphereShape::setRadius(decimal radius) {
RP3D_FORCE_INLINE void SphereShape::setRadius(decimal radius) {
assert(radius > decimal(0.0));
mMargin = radius;
@ -132,7 +132,7 @@ inline void SphereShape::setRadius(decimal radius) {
/**
* @return False because the sphere shape is not a polyhedron
*/
inline bool SphereShape::isPolyhedron() const {
RP3D_FORCE_INLINE bool SphereShape::isPolyhedron() const {
return false;
}
@ -140,12 +140,12 @@ inline bool SphereShape::isPolyhedron() const {
/**
* @return The size (in bytes) of the sphere shape
*/
inline size_t SphereShape::getSizeInBytes() const {
RP3D_FORCE_INLINE size_t SphereShape::getSizeInBytes() const {
return sizeof(SphereShape);
}
// Return a local support point in a given direction without the object margin
inline Vector3 SphereShape::getLocalSupportPointWithoutMargin(const Vector3& direction) const {
RP3D_FORCE_INLINE Vector3 SphereShape::getLocalSupportPointWithoutMargin(const Vector3& direction) const {
// Return the center of the sphere (the radius is taken into account in the object margin)
return Vector3(0.0, 0.0, 0.0);
@ -157,7 +157,7 @@ inline Vector3 SphereShape::getLocalSupportPointWithoutMargin(const Vector3& dir
* @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 SphereShape::getLocalBounds(Vector3& min, Vector3& max) const {
RP3D_FORCE_INLINE void SphereShape::getLocalBounds(Vector3& min, Vector3& max) const {
// Maximum bounds
max.x = mMargin;
@ -174,23 +174,23 @@ inline void SphereShape::getLocalBounds(Vector3& min, Vector3& max) const {
/**
* @param mass Mass to use to compute the inertia tensor of the collision shape
*/
inline Vector3 SphereShape::getLocalInertiaTensor(decimal mass) const {
RP3D_FORCE_INLINE Vector3 SphereShape::getLocalInertiaTensor(decimal mass) const {
decimal diag = decimal(0.4) * mass * mMargin * mMargin;
return Vector3(diag, diag, diag);
}
// Compute and return the volume of the collision shape
inline decimal SphereShape::getVolume() const {
RP3D_FORCE_INLINE decimal SphereShape::getVolume() const {
return decimal(4.0) / decimal(3.0) * reactphysics3d::PI_RP3D * mMargin * mMargin * mMargin;
}
// Return true if a point is inside the collision shape
inline bool SphereShape::testPointInside(const Vector3& localPoint, Collider* collider) const {
RP3D_FORCE_INLINE bool SphereShape::testPointInside(const Vector3& localPoint, Collider* collider) const {
return (localPoint.lengthSquare() < mMargin * mMargin);
}
// Return the string representation of the shape
inline std::string SphereShape::to_string() const {
RP3D_FORCE_INLINE std::string SphereShape::to_string() const {
return "SphereShape{radius=" + std::to_string(getRadius()) + "}";
}

View File

@ -33,6 +33,9 @@
/// ReactPhysics3D namespace
namespace reactphysics3d {
// Forward declarations
class PhysicsCommon;
/// Raycast test side for the triangle
enum class TriangleRaycastSide {
@ -73,11 +76,8 @@ class TriangleShape : public ConvexPolyhedronShape {
/// Raycast test type for the triangle (front, back, front-back)
TriangleRaycastSide mRaycastTestType;
/// Faces information for the two faces of the triangle
HalfEdgeStructure::Face mFaces[2];
/// Edges information for the six edges of the triangle
HalfEdgeStructure::Edge mEdges[6];
/// Reference to triangle half-edge structure
HalfEdgeStructure& mTriangleHalfEdgeStructure;
// -------------------- Methods -------------------- //
@ -91,8 +91,7 @@ class TriangleShape : public ConvexPolyhedronShape {
virtual bool testPointInside(const Vector3& localPoint, Collider* collider) const override;
/// Raycast method with feedback information
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, Collider* collider,
MemoryAllocator& allocator) const override;
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, Collider* collider, MemoryAllocator& allocator) const override;
/// Return the number of bytes used by the collision shape
virtual size_t getSizeInBytes() const override;
@ -108,8 +107,11 @@ class TriangleShape : public ConvexPolyhedronShape {
Vector3& outNewLocalContactPointOtherShape, Vector3& outSmoothWorldContactTriangleNormal) const;
/// Constructor
TriangleShape(const Vector3* vertices, const Vector3* verticesNormals,
uint shapeId, MemoryAllocator& allocator);
TriangleShape(const Vector3* vertices, const Vector3* verticesNormals, uint shapeId, HalfEdgeStructure& triangleHalfEdgeStructure,
MemoryAllocator& allocator);
/// Constructor
TriangleShape(const Vector3* vertices, uint shapeId, HalfEdgeStructure& triangleHalfEdgeStructure, MemoryAllocator& allocator);
/// Destructor
virtual ~TriangleShape() override = default;
@ -188,12 +190,12 @@ class TriangleShape : public ConvexPolyhedronShape {
};
// Return the number of bytes used by the collision shape
inline size_t TriangleShape::getSizeInBytes() const {
RP3D_FORCE_INLINE size_t TriangleShape::getSizeInBytes() const {
return sizeof(TriangleShape);
}
// Return a local support point in a given direction without the object margin
inline Vector3 TriangleShape::getLocalSupportPointWithoutMargin(const Vector3& direction) const {
RP3D_FORCE_INLINE Vector3 TriangleShape::getLocalSupportPointWithoutMargin(const Vector3& direction) const {
Vector3 dotProducts(direction.dot(mPoints[0]), direction.dot(mPoints[1]), direction.dot(mPoints[2]));
return mPoints[dotProducts.getMaxAxis()];
}
@ -204,7 +206,7 @@ inline Vector3 TriangleShape::getLocalSupportPointWithoutMargin(const Vector3& d
* @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 {
RP3D_FORCE_INLINE void TriangleShape::getLocalBounds(Vector3& min, Vector3& max) const {
const Vector3 xAxis(mPoints[0].x, mPoints[1].x, mPoints[2].x);
const Vector3 yAxis(mPoints[0].y, mPoints[1].y, mPoints[2].y);
@ -222,33 +224,27 @@ inline void TriangleShape::getLocalBounds(Vector3& min, Vector3& max) const {
* coordinates
* @param mass Mass to use to compute the inertia tensor of the collision shape
*/
inline Vector3 TriangleShape::getLocalInertiaTensor(decimal mass) const {
RP3D_FORCE_INLINE Vector3 TriangleShape::getLocalInertiaTensor(decimal mass) const {
return Vector3(0, 0, 0);
}
// Return true if a point is inside the collision shape
inline bool TriangleShape::testPointInside(const Vector3& localPoint, Collider* collider) const {
RP3D_FORCE_INLINE bool TriangleShape::testPointInside(const Vector3& localPoint, Collider* collider) const {
return false;
}
// Return the number of faces of the polyhedron
inline uint TriangleShape::getNbFaces() const {
RP3D_FORCE_INLINE uint TriangleShape::getNbFaces() const {
return 2;
}
// Return a given face of the polyhedron
inline const HalfEdgeStructure::Face& TriangleShape::getFace(uint faceIndex) const {
assert(faceIndex < 2);
return mFaces[faceIndex];
}
// Return the number of vertices of the polyhedron
inline uint TriangleShape::getNbVertices() const {
RP3D_FORCE_INLINE uint TriangleShape::getNbVertices() const {
return 3;
}
// Return a given vertex of the polyhedron
inline HalfEdgeStructure::Vertex TriangleShape::getVertex(uint vertexIndex) const {
RP3D_FORCE_INLINE HalfEdgeStructure::Vertex TriangleShape::getVertex(uint vertexIndex) const {
assert(vertexIndex < 3);
HalfEdgeStructure::Vertex vertex(vertexIndex);
@ -260,36 +256,31 @@ inline HalfEdgeStructure::Vertex TriangleShape::getVertex(uint vertexIndex) cons
return vertex;
}
// Return a given half-edge of the polyhedron
inline const HalfEdgeStructure::Edge& TriangleShape::getHalfEdge(uint edgeIndex) const {
assert(edgeIndex < getNbHalfEdges());
return mEdges[edgeIndex];
}
// Return the position of a given vertex
inline Vector3 TriangleShape::getVertexPosition(uint vertexIndex) const {
RP3D_FORCE_INLINE Vector3 TriangleShape::getVertexPosition(uint vertexIndex) const {
assert(vertexIndex < 3);
return mPoints[vertexIndex];
}
// Return the normal vector of a given face of the polyhedron
inline Vector3 TriangleShape::getFaceNormal(uint faceIndex) const {
RP3D_FORCE_INLINE Vector3 TriangleShape::getFaceNormal(uint faceIndex) const {
assert(faceIndex < 2);
assert(mNormal.length() > decimal(0.0));
return faceIndex == 0 ? mNormal : -mNormal;
}
// Return the centroid of the box
inline Vector3 TriangleShape::getCentroid() const {
RP3D_FORCE_INLINE Vector3 TriangleShape::getCentroid() const {
return (mPoints[0] + mPoints[1] + mPoints[2]) / decimal(3.0);
}
// Return the number of half-edges of the polyhedron
inline uint TriangleShape::getNbHalfEdges() const {
RP3D_FORCE_INLINE uint TriangleShape::getNbHalfEdges() const {
return 6;
}
// Return the raycast test type (front, back, front-back)
inline TriangleRaycastSide TriangleShape::getRaycastTestType() const {
RP3D_FORCE_INLINE TriangleRaycastSide TriangleShape::getRaycastTestType() const {
return mRaycastTestType;
}
@ -297,21 +288,100 @@ inline TriangleRaycastSide TriangleShape::getRaycastTestType() const {
/**
* @param testType Raycast test type for the triangle (front, back, front-back)
*/
inline void TriangleShape::setRaycastTestType(TriangleRaycastSide testType) {
RP3D_FORCE_INLINE void TriangleShape::setRaycastTestType(TriangleRaycastSide testType) {
mRaycastTestType = testType;
}
// Return the string representation of the shape
inline std::string TriangleShape::to_string() const {
RP3D_FORCE_INLINE std::string TriangleShape::to_string() const {
return "TriangleShape{v1=" + mPoints[0].to_string() + ", v2=" + mPoints[1].to_string() + "," +
"v3=" + mPoints[2].to_string() + "}";
}
// Compute and return the volume of the collision shape
inline decimal TriangleShape::getVolume() const {
RP3D_FORCE_INLINE decimal TriangleShape::getVolume() const {
return decimal(0.0);
}
// Get a smooth contact normal for collision for a triangle of the mesh
/// This is used to avoid the internal edges issue that occurs when a shape is colliding with
/// several triangles of a concave mesh. If the shape collide with an edge of the triangle for instance,
/// the computed contact normal from this triangle edge is not necessarily in the direction of the surface
/// normal of the mesh at this point. The idea to solve this problem is to use the real (smooth) surface
/// normal of the mesh at this point as the contact normal. This technique is described in the chapter 5
/// of the Game Physics Pearl book by Gino van der Bergen and Dirk Gregorius. The vertices normals of the
/// mesh are either provided by the user or precomputed if the user did not provide them. Note that we only
/// use the interpolated normal if the contact point is on an edge of the triangle. If the contact is in the
/// middle of the triangle, we return the true triangle normal.
RP3D_FORCE_INLINE Vector3 TriangleShape::computeSmoothLocalContactNormalForTriangle(const Vector3& localContactPoint) const {
assert(mNormal.length() > decimal(0.0));
// Compute the barycentric coordinates of the point in the triangle
decimal u, v, w;
computeBarycentricCoordinatesInTriangle(mPoints[0], mPoints[1], mPoints[2], localContactPoint, u, v, w);
// If the contact is in the middle of the triangle face (not on the edges)
if (u > MACHINE_EPSILON && v > MACHINE_EPSILON && w > MACHINE_EPSILON) {
// We return the true triangle face normal (not the interpolated one)
return mNormal;
}
// We compute the contact normal as the barycentric interpolation of the three vertices normals
const Vector3 interpolatedNormal = u * mVerticesNormals[0] + v * mVerticesNormals[1] + w * mVerticesNormals[2];
// If the interpolated normal is degenerated
if (interpolatedNormal.lengthSquare() < MACHINE_EPSILON) {
// Return the original normal
return mNormal;
}
return interpolatedNormal.getUnit();
}
// This method compute the smooth mesh contact with a triangle in case one of the two collision
// shapes is a triangle. The idea in this case is to use a smooth vertex normal of the triangle mesh
// at the contact point instead of the triangle normal to avoid the internal edge collision issue.
// This method will return the new smooth world contact
// normal of the triangle and the the local contact point on the other shape.
RP3D_FORCE_INLINE void TriangleShape::computeSmoothTriangleMeshContact(const CollisionShape* shape1, const CollisionShape* shape2,
Vector3& localContactPointShape1, Vector3& localContactPointShape2,
const Transform& shape1ToWorld, const Transform& shape2ToWorld,
decimal penetrationDepth, Vector3& outSmoothVertexNormal) {
assert(shape1->getName() != CollisionShapeName::TRIANGLE || shape2->getName() != CollisionShapeName::TRIANGLE);
// If one the shape is a triangle
bool isShape1Triangle = shape1->getName() == CollisionShapeName::TRIANGLE;
if (isShape1Triangle || shape2->getName() == CollisionShapeName::TRIANGLE) {
const TriangleShape* triangleShape = isShape1Triangle ? static_cast<const TriangleShape*>(shape1):
static_cast<const TriangleShape*>(shape2);
// Compute the smooth triangle mesh contact normal and recompute the local contact point on the other shape
triangleShape->computeSmoothMeshContact(isShape1Triangle ? localContactPointShape1 : localContactPointShape2,
isShape1Triangle ? shape1ToWorld : shape2ToWorld,
isShape1Triangle ? shape2ToWorld.getInverse() : shape1ToWorld.getInverse(),
penetrationDepth, isShape1Triangle,
isShape1Triangle ? localContactPointShape2 : localContactPointShape1,
outSmoothVertexNormal);
}
}
// Return a given face of the polyhedron
RP3D_FORCE_INLINE const HalfEdgeStructure::Face& TriangleShape::getFace(uint faceIndex) const {
assert(faceIndex < 2);
return mTriangleHalfEdgeStructure.getFace(faceIndex);
}
// Return a given half-edge of the polyhedron
RP3D_FORCE_INLINE const HalfEdgeStructure::Edge& TriangleShape::getHalfEdge(uint edgeIndex) const {
assert(edgeIndex < getNbHalfEdges());
return mTriangleHalfEdgeStructure.getHalfEdge(edgeIndex);
}
}
#endif

View File

@ -188,140 +188,140 @@ class BallAndSocketJointComponents : public Components {
};
// Return a pointer to a given joint
inline BallAndSocketJoint* BallAndSocketJointComponents::getJoint(Entity jointEntity) const {
RP3D_FORCE_INLINE BallAndSocketJoint* BallAndSocketJointComponents::getJoint(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mJoints[mMapEntityToComponentIndex[jointEntity]];
}
// Set the joint pointer to a given joint
inline void BallAndSocketJointComponents::setJoint(Entity jointEntity, BallAndSocketJoint* joint) const {
RP3D_FORCE_INLINE void BallAndSocketJointComponents::setJoint(Entity jointEntity, BallAndSocketJoint* joint) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mJoints[mMapEntityToComponentIndex[jointEntity]] = joint;
}
// Return the local anchor point of body 1 for a given joint
inline const Vector3& BallAndSocketJointComponents::getLocalAnchorPointBody1(Entity jointEntity) const {
RP3D_FORCE_INLINE const Vector3& BallAndSocketJointComponents::getLocalAnchorPointBody1(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]];
}
// Set the local anchor point of body 1 for a given joint
inline void BallAndSocketJointComponents::setLocalAnchorPointBody1(Entity jointEntity, const Vector3& localAnchoirPointBody1) {
RP3D_FORCE_INLINE void BallAndSocketJointComponents::setLocalAnchorPointBody1(Entity jointEntity, const Vector3& localAnchoirPointBody1) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]] = localAnchoirPointBody1;
}
// Return the local anchor point of body 2 for a given joint
inline const Vector3& BallAndSocketJointComponents::getLocalAnchorPointBody2(Entity jointEntity) const {
RP3D_FORCE_INLINE const Vector3& BallAndSocketJointComponents::getLocalAnchorPointBody2(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]];
}
// Set the local anchor point of body 2 for a given joint
inline void BallAndSocketJointComponents::setLocalAnchorPointBody2(Entity jointEntity, const Vector3& localAnchoirPointBody2) {
RP3D_FORCE_INLINE void BallAndSocketJointComponents::setLocalAnchorPointBody2(Entity jointEntity, const Vector3& localAnchoirPointBody2) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]] = localAnchoirPointBody2;
}
// Return the vector from center of body 1 to anchor point in world-space
inline const Vector3& BallAndSocketJointComponents::getR1World(Entity jointEntity) const {
RP3D_FORCE_INLINE const Vector3& BallAndSocketJointComponents::getR1World(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mR1World[mMapEntityToComponentIndex[jointEntity]];
}
// Set the vector from center of body 1 to anchor point in world-space
inline void BallAndSocketJointComponents::setR1World(Entity jointEntity, const Vector3& r1World) {
RP3D_FORCE_INLINE void BallAndSocketJointComponents::setR1World(Entity jointEntity, const Vector3& r1World) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mR1World[mMapEntityToComponentIndex[jointEntity]] = r1World;
}
// Return the vector from center of body 2 to anchor point in world-space
inline const Vector3& BallAndSocketJointComponents::getR2World(Entity jointEntity) const {
RP3D_FORCE_INLINE const Vector3& BallAndSocketJointComponents::getR2World(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mR2World[mMapEntityToComponentIndex[jointEntity]];
}
// Set the vector from center of body 2 to anchor point in world-space
inline void BallAndSocketJointComponents::setR2World(Entity jointEntity, const Vector3& r2World) {
RP3D_FORCE_INLINE void BallAndSocketJointComponents::setR2World(Entity jointEntity, const Vector3& r2World) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mR2World[mMapEntityToComponentIndex[jointEntity]] = r2World;
}
// Return the inertia tensor of body 1 (in world-space coordinates)
inline const Matrix3x3& BallAndSocketJointComponents::getI1(Entity jointEntity) const {
RP3D_FORCE_INLINE const Matrix3x3& BallAndSocketJointComponents::getI1(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mI1[mMapEntityToComponentIndex[jointEntity]];
}
// Set the inertia tensor of body 1 (in world-space coordinates)
inline void BallAndSocketJointComponents::setI1(Entity jointEntity, const Matrix3x3& i1) {
RP3D_FORCE_INLINE void BallAndSocketJointComponents::setI1(Entity jointEntity, const Matrix3x3& i1) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mI1[mMapEntityToComponentIndex[jointEntity]] = i1;
}
// Return the inertia tensor of body 2 (in world-space coordinates)
inline const Matrix3x3& BallAndSocketJointComponents::getI2(Entity jointEntity) const {
RP3D_FORCE_INLINE const Matrix3x3& BallAndSocketJointComponents::getI2(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mI2[mMapEntityToComponentIndex[jointEntity]];
}
// Set the inertia tensor of body 2 (in world-space coordinates)
inline void BallAndSocketJointComponents::setI2(Entity jointEntity, const Matrix3x3& i2) {
RP3D_FORCE_INLINE void BallAndSocketJointComponents::setI2(Entity jointEntity, const Matrix3x3& i2) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mI2[mMapEntityToComponentIndex[jointEntity]] = i2;
}
// Return the bias vector for the constraint
inline Vector3 &BallAndSocketJointComponents::getBiasVector(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3 &BallAndSocketJointComponents::getBiasVector(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mBiasVector[mMapEntityToComponentIndex[jointEntity]];
}
// Set the bias vector for the constraint
inline void BallAndSocketJointComponents::setBiasVector(Entity jointEntity, const Vector3& biasVector) {
RP3D_FORCE_INLINE void BallAndSocketJointComponents::setBiasVector(Entity jointEntity, const Vector3& biasVector) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mBiasVector[mMapEntityToComponentIndex[jointEntity]] = biasVector;
}
// Return the inverse mass matrix K=JM^-1J^-t of the constraint
inline Matrix3x3& BallAndSocketJointComponents::getInverseMassMatrix(Entity jointEntity) {
RP3D_FORCE_INLINE Matrix3x3& BallAndSocketJointComponents::getInverseMassMatrix(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mInverseMassMatrix[mMapEntityToComponentIndex[jointEntity]];
}
// Set the inverse mass matrix K=JM^-1J^-t of the constraint
inline void BallAndSocketJointComponents::setInverseMassMatrix(Entity jointEntity, const Matrix3x3& inverseMassMatrix) {
RP3D_FORCE_INLINE void BallAndSocketJointComponents::setInverseMassMatrix(Entity jointEntity, const Matrix3x3& inverseMassMatrix) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mInverseMassMatrix[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
}
// Return the accumulated impulse
inline Vector3 &BallAndSocketJointComponents::getImpulse(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3 &BallAndSocketJointComponents::getImpulse(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mImpulse[mMapEntityToComponentIndex[jointEntity]];
}
// Set the accumulated impulse
inline void BallAndSocketJointComponents::setImpulse(Entity jointEntity, const Vector3& impulse) {
RP3D_FORCE_INLINE void BallAndSocketJointComponents::setImpulse(Entity jointEntity, const Vector3& impulse) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mImpulse[mMapEntityToComponentIndex[jointEntity]] = impulse;

View File

@ -32,6 +32,7 @@
#include <reactphysics3d/containers/Map.h>
#include <reactphysics3d/collision/shapes/AABB.h>
#include <reactphysics3d/components/Components.h>
#include <reactphysics3d/engine/Material.h>
// ReactPhysics3D namespace
namespace reactphysics3d {
@ -89,8 +90,8 @@ class ColliderComponents : public Components {
/// Array with the local-to-world transforms of the colliders
Transform* mLocalToWorldTransforms;
/// Array with the list of involved overlapping pairs for each collider
List<uint64>* mOverlappingPairs;
/// Array with the involved overlapping pairs for each collider
Array<uint64>* mOverlappingPairs;
/// True if the size of the collision shape associated with the collider
/// has been changed by the user
@ -99,6 +100,9 @@ class ColliderComponents : public Components {
/// True if the collider is a trigger
bool* mIsTrigger;
/// Array with the material of each collider
Material* mMaterials;
// -------------------- Methods -------------------- //
@ -127,14 +131,15 @@ class ColliderComponents : public Components {
unsigned short collisionCategoryBits;
unsigned short collideWithMaskBits;
const Transform& localToWorldTransform;
const Material& material;
/// Constructor
ColliderComponent(Entity bodyEntity, Collider* collider, AABB localBounds, const Transform& localToBodyTransform,
CollisionShape* collisionShape, unsigned short collisionCategoryBits,
unsigned short collideWithMaskBits, const Transform& localToWorldTransform)
unsigned short collideWithMaskBits, const Transform& localToWorldTransform, const Material& material)
:bodyEntity(bodyEntity), collider(collider), localBounds(localBounds), localToBodyTransform(localToBodyTransform),
collisionShape(collisionShape), collisionCategoryBits(collisionCategoryBits), collideWithMaskBits(collideWithMaskBits),
localToWorldTransform(localToWorldTransform) {
localToWorldTransform(localToWorldTransform), material(material) {
}
};
@ -189,8 +194,8 @@ class ColliderComponents : public Components {
/// Set the local-to-world transform of a collider
void setLocalToWorldTransform(Entity colliderEntity, const Transform& transform);
/// Return a reference to the list of overlapping pairs for a given collider
List<uint64>& getOverlappingPairs(Entity colliderEntity);
/// Return a reference to the array of overlapping pairs for a given collider
Array<uint64>& getOverlappingPairs(Entity colliderEntity);
/// Return true if the size of collision shape of the collider has been changed by the user
bool getHasCollisionShapeChangedSize(Entity colliderEntity) const;
@ -204,16 +209,24 @@ class ColliderComponents : public Components {
/// Set whether a collider is a trigger
void setIsTrigger(Entity colliderEntity, bool isTrigger);
/// Return a reference to the material of a collider
Material& getMaterial(Entity colliderEntity);
/// Set the material of a collider
void setMaterial(Entity colliderEntity, const Material& material);
// -------------------- Friendship -------------------- //
friend class BroadPhaseSystem;
friend class CollisionDetectionSystem;
friend class ContactSolverSystem;
friend class DynamicsSystem;
friend class OverlappingPairs;
friend class RigidBody;
};
// Return the body entity of a given collider
inline Entity ColliderComponents::getBody(Entity colliderEntity) const {
RP3D_FORCE_INLINE Entity ColliderComponents::getBody(Entity colliderEntity) const {
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
@ -221,7 +234,7 @@ inline Entity ColliderComponents::getBody(Entity colliderEntity) const {
}
// Return a pointer to a given collider
inline Collider *ColliderComponents::getCollider(Entity colliderEntity) const {
RP3D_FORCE_INLINE Collider *ColliderComponents::getCollider(Entity colliderEntity) const {
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
@ -229,7 +242,7 @@ inline Collider *ColliderComponents::getCollider(Entity colliderEntity) const {
}
// Return the local-to-body transform of a collider
inline const Transform& ColliderComponents::getLocalToBodyTransform(Entity colliderEntity) const {
RP3D_FORCE_INLINE const Transform& ColliderComponents::getLocalToBodyTransform(Entity colliderEntity) const {
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
@ -237,7 +250,7 @@ inline const Transform& ColliderComponents::getLocalToBodyTransform(Entity colli
}
// Set the local-to-body transform of a collider
inline void ColliderComponents::setLocalToBodyTransform(Entity colliderEntity, const Transform& transform) {
RP3D_FORCE_INLINE void ColliderComponents::setLocalToBodyTransform(Entity colliderEntity, const Transform& transform) {
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
@ -245,7 +258,7 @@ inline void ColliderComponents::setLocalToBodyTransform(Entity colliderEntity, c
}
// Return a pointer to the collision shape of a collider
inline CollisionShape* ColliderComponents::getCollisionShape(Entity colliderEntity) const {
RP3D_FORCE_INLINE CollisionShape* ColliderComponents::getCollisionShape(Entity colliderEntity) const {
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
@ -253,7 +266,7 @@ inline CollisionShape* ColliderComponents::getCollisionShape(Entity colliderEnti
}
// Return the broad-phase id of a given collider
inline int32 ColliderComponents::getBroadPhaseId(Entity colliderEntity) const {
RP3D_FORCE_INLINE int32 ColliderComponents::getBroadPhaseId(Entity colliderEntity) const {
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
@ -261,7 +274,7 @@ inline int32 ColliderComponents::getBroadPhaseId(Entity colliderEntity) const {
}
// Set the broad-phase id of a given collider
inline void ColliderComponents::setBroadPhaseId(Entity colliderEntity, int32 broadPhaseId) {
RP3D_FORCE_INLINE void ColliderComponents::setBroadPhaseId(Entity colliderEntity, int32 broadPhaseId) {
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
@ -269,7 +282,7 @@ inline void ColliderComponents::setBroadPhaseId(Entity colliderEntity, int32 bro
}
// Return the collision category bits of a given collider
inline unsigned short ColliderComponents::getCollisionCategoryBits(Entity colliderEntity) const {
RP3D_FORCE_INLINE unsigned short ColliderComponents::getCollisionCategoryBits(Entity colliderEntity) const {
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
@ -277,7 +290,7 @@ inline unsigned short ColliderComponents::getCollisionCategoryBits(Entity collid
}
// Return the "collide with" mask bits of a given collider
inline unsigned short ColliderComponents::getCollideWithMaskBits(Entity colliderEntity) const {
RP3D_FORCE_INLINE unsigned short ColliderComponents::getCollideWithMaskBits(Entity colliderEntity) const {
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
@ -285,7 +298,7 @@ inline unsigned short ColliderComponents::getCollideWithMaskBits(Entity collider
}
// Set the collision category bits of a given collider
inline void ColliderComponents::setCollisionCategoryBits(Entity colliderEntity, unsigned short collisionCategoryBits) {
RP3D_FORCE_INLINE void ColliderComponents::setCollisionCategoryBits(Entity colliderEntity, unsigned short collisionCategoryBits) {
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
@ -293,7 +306,7 @@ inline void ColliderComponents::setCollisionCategoryBits(Entity colliderEntity,
}
// Set the "collide with" mask bits of a given collider
inline void ColliderComponents::setCollideWithMaskBits(Entity colliderEntity, unsigned short collideWithMaskBits) {
RP3D_FORCE_INLINE void ColliderComponents::setCollideWithMaskBits(Entity colliderEntity, unsigned short collideWithMaskBits) {
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
@ -301,7 +314,7 @@ inline void ColliderComponents::setCollideWithMaskBits(Entity colliderEntity, un
}
// Return the local-to-world transform of a collider
inline const Transform& ColliderComponents::getLocalToWorldTransform(Entity colliderEntity) const {
RP3D_FORCE_INLINE const Transform& ColliderComponents::getLocalToWorldTransform(Entity colliderEntity) const {
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
@ -309,15 +322,15 @@ inline const Transform& ColliderComponents::getLocalToWorldTransform(Entity coll
}
// Set the local-to-world transform of a collider
inline void ColliderComponents::setLocalToWorldTransform(Entity colliderEntity, const Transform& transform) {
RP3D_FORCE_INLINE void ColliderComponents::setLocalToWorldTransform(Entity colliderEntity, const Transform& transform) {
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
mLocalToWorldTransforms[mMapEntityToComponentIndex[colliderEntity]] = transform;
}
// Return a reference to the list of overlapping pairs for a given collider
inline List<uint64>& ColliderComponents::getOverlappingPairs(Entity colliderEntity) {
// Return a reference to the array of overlapping pairs for a given collider
RP3D_FORCE_INLINE Array<uint64>& ColliderComponents::getOverlappingPairs(Entity colliderEntity) {
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
@ -325,7 +338,7 @@ inline List<uint64>& ColliderComponents::getOverlappingPairs(Entity colliderEnti
}
// Return true if the size of collision shape of the collider has been changed by the user
inline bool ColliderComponents::getHasCollisionShapeChangedSize(Entity colliderEntity) const {
RP3D_FORCE_INLINE bool ColliderComponents::getHasCollisionShapeChangedSize(Entity colliderEntity) const {
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
@ -333,7 +346,7 @@ inline bool ColliderComponents::getHasCollisionShapeChangedSize(Entity colliderE
}
// Return true if the size of collision shape of the collider has been changed by the user
inline void ColliderComponents::setHasCollisionShapeChangedSize(Entity colliderEntity, bool hasCollisionShapeChangedSize) {
RP3D_FORCE_INLINE void ColliderComponents::setHasCollisionShapeChangedSize(Entity colliderEntity, bool hasCollisionShapeChangedSize) {
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
@ -342,7 +355,7 @@ inline void ColliderComponents::setHasCollisionShapeChangedSize(Entity colliderE
// Return true if a collider is a trigger
inline bool ColliderComponents::getIsTrigger(Entity colliderEntity) const {
RP3D_FORCE_INLINE bool ColliderComponents::getIsTrigger(Entity colliderEntity) const {
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
@ -350,13 +363,29 @@ inline bool ColliderComponents::getIsTrigger(Entity colliderEntity) const {
}
// Set whether a collider is a trigger
inline void ColliderComponents::setIsTrigger(Entity colliderEntity, bool isTrigger) {
RP3D_FORCE_INLINE void ColliderComponents::setIsTrigger(Entity colliderEntity, bool isTrigger) {
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
mIsTrigger[mMapEntityToComponentIndex[colliderEntity]] = isTrigger;
}
// Return a reference to the material of a collider
RP3D_FORCE_INLINE Material& ColliderComponents::getMaterial(Entity colliderEntity) {
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
return mMaterials[mMapEntityToComponentIndex[colliderEntity]];
}
// Set the material of a collider
RP3D_FORCE_INLINE void ColliderComponents::setMaterial(Entity colliderEntity, const Material& material) {
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
mMaterials[mMapEntityToComponentIndex[colliderEntity]] = material;
}
}
#endif

View File

@ -57,8 +57,8 @@ class CollisionBodyComponents : public Components {
/// Array of pointers to the corresponding bodies
CollisionBody** mBodies;
/// Array with the list of colliders of each body
List<Entity>* mColliders;
/// Array with the colliders of each body
Array<Entity>* mColliders;
/// Array of boolean values to know if the body is active.
bool* mIsActive;
@ -113,8 +113,8 @@ class CollisionBodyComponents : public Components {
/// Return a pointer to a body
CollisionBody* getBody(Entity bodyEntity);
/// Return the list of colliders of a body
const List<Entity>& getColliders(Entity bodyEntity) const;
/// Return the array of colliders of a body
const Array<Entity>& getColliders(Entity bodyEntity) const;
/// Return true if the body is active
bool getIsActive(Entity bodyEntity) const;
@ -130,7 +130,7 @@ class CollisionBodyComponents : public Components {
};
// Add a collider to a body component
inline void CollisionBodyComponents::addColliderToBody(Entity bodyEntity, Entity colliderEntity) {
RP3D_FORCE_INLINE void CollisionBodyComponents::addColliderToBody(Entity bodyEntity, Entity colliderEntity) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -138,7 +138,7 @@ inline void CollisionBodyComponents::addColliderToBody(Entity bodyEntity, Entity
}
// Remove a collider from a body component
inline void CollisionBodyComponents::removeColliderFromBody(Entity bodyEntity, Entity colliderEntity) {
RP3D_FORCE_INLINE void CollisionBodyComponents::removeColliderFromBody(Entity bodyEntity, Entity colliderEntity) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -146,15 +146,15 @@ inline void CollisionBodyComponents::removeColliderFromBody(Entity bodyEntity, E
}
// Return a pointer to a body
inline CollisionBody *CollisionBodyComponents::getBody(Entity bodyEntity) {
RP3D_FORCE_INLINE CollisionBody *CollisionBodyComponents::getBody(Entity bodyEntity) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
return mBodies[mMapEntityToComponentIndex[bodyEntity]];
}
// Return the list of colliders of a body
inline const List<Entity>& CollisionBodyComponents::getColliders(Entity bodyEntity) const {
// Return the array of colliders of a body
RP3D_FORCE_INLINE const Array<Entity>& CollisionBodyComponents::getColliders(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -162,7 +162,7 @@ inline const List<Entity>& CollisionBodyComponents::getColliders(Entity bodyEnti
}
// Return true if the body is active
inline bool CollisionBodyComponents::getIsActive(Entity bodyEntity) const {
RP3D_FORCE_INLINE bool CollisionBodyComponents::getIsActive(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -170,7 +170,7 @@ inline bool CollisionBodyComponents::getIsActive(Entity bodyEntity) const {
}
// Set the value to know if the body is active
inline void CollisionBodyComponents::setIsActive(Entity bodyEntity, bool isActive) const {
RP3D_FORCE_INLINE void CollisionBodyComponents::setIsActive(Entity bodyEntity, bool isActive) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -178,7 +178,7 @@ inline void CollisionBodyComponents::setIsActive(Entity bodyEntity, bool isActiv
}
// Return the user data associated with the body
inline void* CollisionBodyComponents::getUserData(Entity bodyEntity) const {
RP3D_FORCE_INLINE void* CollisionBodyComponents::getUserData(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -186,7 +186,7 @@ inline void* CollisionBodyComponents::getUserData(Entity bodyEntity) const {
}
// Set the user data associated with the body
inline void CollisionBodyComponents::setUserData(Entity bodyEntity, void* userData) const {
RP3D_FORCE_INLINE void CollisionBodyComponents::setUserData(Entity bodyEntity, void* userData) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));

View File

@ -113,6 +113,9 @@ class Components {
/// Return true if there is a component for a given entity
bool hasComponent(Entity entity) const;
/// Return true if there is a component for a given entiy and if so set the entity index
bool hasComponentGetIndex(Entity entity, uint32& entityIndex) const;
/// Return the number of components
uint32 getNbComponents() const;
@ -124,28 +127,41 @@ class Components {
};
// Return true if an entity is sleeping
inline bool Components::getIsEntityDisabled(Entity entity) const {
RP3D_FORCE_INLINE bool Components::getIsEntityDisabled(Entity entity) const {
assert(hasComponent(entity));
return mMapEntityToComponentIndex[entity] >= mDisabledStartIndex;
}
// Return true if there is a component for a given entity
inline bool Components::hasComponent(Entity entity) const {
RP3D_FORCE_INLINE bool Components::hasComponent(Entity entity) const {
return mMapEntityToComponentIndex.containsKey(entity);
}
// Return true if there is a component for a given entiy and if so set the entity index
RP3D_FORCE_INLINE bool Components::hasComponentGetIndex(Entity entity, uint32& entityIndex) const {
auto it = mMapEntityToComponentIndex.find(entity);
if (it != mMapEntityToComponentIndex.end()) {
entityIndex = it->second;
return true;
}
return false;
}
// Return the number of components
inline uint32 Components::getNbComponents() const {
RP3D_FORCE_INLINE uint32 Components::getNbComponents() const {
return mNbComponents;
}
// Return the number of enabled components
inline uint32 Components::getNbEnabledComponents() const {
RP3D_FORCE_INLINE uint32 Components::getNbEnabledComponents() const {
return mDisabledStartIndex;
}
// Return the index in the arrays for a given entity
inline uint32 Components::getEntityIndex(Entity entity) const {
RP3D_FORCE_INLINE uint32 Components::getEntityIndex(Entity entity) const {
assert(hasComponent(entity));
return mMapEntityToComponentIndex[entity];
}

View File

@ -224,133 +224,133 @@ class FixedJointComponents : public Components {
};
// Return a pointer to a given joint
inline FixedJoint* FixedJointComponents::getJoint(Entity jointEntity) const {
RP3D_FORCE_INLINE FixedJoint* FixedJointComponents::getJoint(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mJoints[mMapEntityToComponentIndex[jointEntity]];
}
// Set the joint pointer to a given joint
inline void FixedJointComponents::setJoint(Entity jointEntity, FixedJoint* joint) const {
RP3D_FORCE_INLINE void FixedJointComponents::setJoint(Entity jointEntity, FixedJoint* joint) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mJoints[mMapEntityToComponentIndex[jointEntity]] = joint;
}
// Return the local anchor point of body 1 for a given joint
inline const Vector3& FixedJointComponents::getLocalAnchorPointBody1(Entity jointEntity) const {
RP3D_FORCE_INLINE const Vector3& FixedJointComponents::getLocalAnchorPointBody1(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]];
}
// Set the local anchor point of body 1 for a given joint
inline void FixedJointComponents::setLocalAnchorPointBody1(Entity jointEntity, const Vector3& localAnchorPointBody1) {
RP3D_FORCE_INLINE void FixedJointComponents::setLocalAnchorPointBody1(Entity jointEntity, const Vector3& localAnchorPointBody1) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]] = localAnchorPointBody1;
}
// Return the local anchor point of body 2 for a given joint
inline const Vector3& FixedJointComponents::getLocalAnchorPointBody2(Entity jointEntity) const {
RP3D_FORCE_INLINE const Vector3& FixedJointComponents::getLocalAnchorPointBody2(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]];
}
// Set the local anchor point of body 2 for a given joint
inline void FixedJointComponents::setLocalAnchorPointBody2(Entity jointEntity, const Vector3& localAnchorPointBody2) {
RP3D_FORCE_INLINE void FixedJointComponents::setLocalAnchorPointBody2(Entity jointEntity, const Vector3& localAnchorPointBody2) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]] = localAnchorPointBody2;
}
// Return the vector from center of body 1 to anchor point in world-space
inline const Vector3& FixedJointComponents::getR1World(Entity jointEntity) const {
RP3D_FORCE_INLINE const Vector3& FixedJointComponents::getR1World(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mR1World[mMapEntityToComponentIndex[jointEntity]];
}
// Set the vector from center of body 1 to anchor point in world-space
inline void FixedJointComponents::setR1World(Entity jointEntity, const Vector3& r1World) {
RP3D_FORCE_INLINE void FixedJointComponents::setR1World(Entity jointEntity, const Vector3& r1World) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mR1World[mMapEntityToComponentIndex[jointEntity]] = r1World;
}
// Return the vector from center of body 2 to anchor point in world-space
inline const Vector3& FixedJointComponents::getR2World(Entity jointEntity) const {
RP3D_FORCE_INLINE const Vector3& FixedJointComponents::getR2World(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mR2World[mMapEntityToComponentIndex[jointEntity]];
}
// Set the vector from center of body 2 to anchor point in world-space
inline void FixedJointComponents::setR2World(Entity jointEntity, const Vector3& r2World) {
RP3D_FORCE_INLINE void FixedJointComponents::setR2World(Entity jointEntity, const Vector3& r2World) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mR2World[mMapEntityToComponentIndex[jointEntity]] = r2World;
}
// Return the inertia tensor of body 1 (in world-space coordinates)
inline const Matrix3x3& FixedJointComponents::getI1(Entity jointEntity) const {
RP3D_FORCE_INLINE const Matrix3x3& FixedJointComponents::getI1(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mI1[mMapEntityToComponentIndex[jointEntity]];
}
// Set the inertia tensor of body 1 (in world-space coordinates)
inline void FixedJointComponents::setI1(Entity jointEntity, const Matrix3x3& i1) {
RP3D_FORCE_INLINE void FixedJointComponents::setI1(Entity jointEntity, const Matrix3x3& i1) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mI1[mMapEntityToComponentIndex[jointEntity]] = i1;
}
// Return the inertia tensor of body 2 (in world-space coordinates)
inline const Matrix3x3& FixedJointComponents::getI2(Entity jointEntity) const {
RP3D_FORCE_INLINE const Matrix3x3& FixedJointComponents::getI2(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mI2[mMapEntityToComponentIndex[jointEntity]];
}
// Set the inertia tensor of body 2 (in world-space coordinates)
inline void FixedJointComponents::setI2(Entity jointEntity, const Matrix3x3& i2) {
RP3D_FORCE_INLINE void FixedJointComponents::setI2(Entity jointEntity, const Matrix3x3& i2) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mI2[mMapEntityToComponentIndex[jointEntity]] = i2;
}
// Return the translation impulse
inline Vector3& FixedJointComponents::getImpulseTranslation(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& FixedJointComponents::getImpulseTranslation(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mImpulseTranslation[mMapEntityToComponentIndex[jointEntity]];
}
// Set the translation impulse
inline void FixedJointComponents::setImpulseTranslation(Entity jointEntity, const Vector3& impulseTranslation) {
RP3D_FORCE_INLINE void FixedJointComponents::setImpulseTranslation(Entity jointEntity, const Vector3& impulseTranslation) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mImpulseTranslation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
}
// Return the translation impulse
inline Vector3& FixedJointComponents::getImpulseRotation(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& FixedJointComponents::getImpulseRotation(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mImpulseRotation[mMapEntityToComponentIndex[jointEntity]];
}
// Set the translation impulse
inline void FixedJointComponents::setImpulseRotation(Entity jointEntity, const Vector3& impulseTranslation) {
RP3D_FORCE_INLINE void FixedJointComponents::setImpulseRotation(Entity jointEntity, const Vector3& impulseTranslation) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mImpulseRotation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
}
// Return the translation inverse mass matrix of the constraint
inline Matrix3x3& FixedJointComponents::getInverseMassMatrixTranslation(Entity jointEntity) {
RP3D_FORCE_INLINE Matrix3x3& FixedJointComponents::getInverseMassMatrixTranslation(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mInverseMassMatrixTranslation[mMapEntityToComponentIndex[jointEntity]];
@ -358,63 +358,63 @@ inline Matrix3x3& FixedJointComponents::getInverseMassMatrixTranslation(Entity j
// Set the translation inverse mass matrix of the constraint
inline void FixedJointComponents::setInverseMassMatrixTranslation(Entity jointEntity, const Matrix3x3& inverseMassMatrix) {
RP3D_FORCE_INLINE void FixedJointComponents::setInverseMassMatrixTranslation(Entity jointEntity, const Matrix3x3& inverseMassMatrix) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mInverseMassMatrixTranslation[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
}
// Return the rotation inverse mass matrix of the constraint
inline Matrix3x3& FixedJointComponents::getInverseMassMatrixRotation(Entity jointEntity) {
RP3D_FORCE_INLINE Matrix3x3& FixedJointComponents::getInverseMassMatrixRotation(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mInverseMassMatrixRotation[mMapEntityToComponentIndex[jointEntity]];
}
// Set the rotation inverse mass matrix of the constraint
inline void FixedJointComponents::setInverseMassMatrixRotation(Entity jointEntity, const Matrix3x3& inverseMassMatrix) {
RP3D_FORCE_INLINE void FixedJointComponents::setInverseMassMatrixRotation(Entity jointEntity, const Matrix3x3& inverseMassMatrix) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mInverseMassMatrixRotation[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
}
// Return the translation bias
inline Vector3& FixedJointComponents::getBiasTranslation(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& FixedJointComponents::getBiasTranslation(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mBiasTranslation[mMapEntityToComponentIndex[jointEntity]];
}
// Set the translation impulse
inline void FixedJointComponents::setBiasTranslation(Entity jointEntity, const Vector3 &impulseTranslation) {
RP3D_FORCE_INLINE void FixedJointComponents::setBiasTranslation(Entity jointEntity, const Vector3 &impulseTranslation) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mBiasTranslation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
}
// Return the rotation bias
inline Vector3& FixedJointComponents::getBiasRotation(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& FixedJointComponents::getBiasRotation(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mBiasRotation[mMapEntityToComponentIndex[jointEntity]];
}
// Set the rotation impulse
inline void FixedJointComponents::setBiasRotation(Entity jointEntity, const Vector3& impulseRotation) {
RP3D_FORCE_INLINE void FixedJointComponents::setBiasRotation(Entity jointEntity, const Vector3& impulseRotation) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mBiasRotation[mMapEntityToComponentIndex[jointEntity]] = impulseRotation;
}
// Return the initial orientation difference
inline Quaternion& FixedJointComponents::getInitOrientationDifferenceInv(Entity jointEntity) {
RP3D_FORCE_INLINE Quaternion& FixedJointComponents::getInitOrientationDifferenceInv(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mInitOrientationDifferenceInv[mMapEntityToComponentIndex[jointEntity]];
}
// Set the rotation impulse
inline void FixedJointComponents::setInitOrientationDifferenceInv(Entity jointEntity, const Quaternion& initOrientationDifferenceInv) {
RP3D_FORCE_INLINE void FixedJointComponents::setInitOrientationDifferenceInv(Entity jointEntity, const Quaternion& initOrientationDifferenceInv) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mInitOrientationDifferenceInv[mMapEntityToComponentIndex[jointEntity]] = initOrientationDifferenceInv;

View File

@ -415,133 +415,133 @@ class HingeJointComponents : public Components {
};
// Return a pointer to a given joint
inline HingeJoint* HingeJointComponents::getJoint(Entity jointEntity) const {
RP3D_FORCE_INLINE HingeJoint* HingeJointComponents::getJoint(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mJoints[mMapEntityToComponentIndex[jointEntity]];
}
// Set the joint pointer to a given joint
inline void HingeJointComponents::setJoint(Entity jointEntity, HingeJoint* joint) const {
RP3D_FORCE_INLINE void HingeJointComponents::setJoint(Entity jointEntity, HingeJoint* joint) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mJoints[mMapEntityToComponentIndex[jointEntity]] = joint;
}
// Return the local anchor point of body 1 for a given joint
inline const Vector3& HingeJointComponents::getLocalAnchorPointBody1(Entity jointEntity) const {
RP3D_FORCE_INLINE const Vector3& HingeJointComponents::getLocalAnchorPointBody1(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]];
}
// Set the local anchor point of body 1 for a given joint
inline void HingeJointComponents::setLocalAnchorPointBody1(Entity jointEntity, const Vector3& localAnchoirPointBody1) {
RP3D_FORCE_INLINE void HingeJointComponents::setLocalAnchorPointBody1(Entity jointEntity, const Vector3& localAnchoirPointBody1) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]] = localAnchoirPointBody1;
}
// Return the local anchor point of body 2 for a given joint
inline const Vector3& HingeJointComponents::getLocalAnchorPointBody2(Entity jointEntity) const {
RP3D_FORCE_INLINE const Vector3& HingeJointComponents::getLocalAnchorPointBody2(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]];
}
// Set the local anchor point of body 2 for a given joint
inline void HingeJointComponents::setLocalAnchorPointBody2(Entity jointEntity, const Vector3& localAnchoirPointBody2) {
RP3D_FORCE_INLINE void HingeJointComponents::setLocalAnchorPointBody2(Entity jointEntity, const Vector3& localAnchoirPointBody2) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]] = localAnchoirPointBody2;
}
// Return the vector from center of body 1 to anchor point in world-space
inline const Vector3& HingeJointComponents::getR1World(Entity jointEntity) const {
RP3D_FORCE_INLINE const Vector3& HingeJointComponents::getR1World(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mR1World[mMapEntityToComponentIndex[jointEntity]];
}
// Set the vector from center of body 1 to anchor point in world-space
inline void HingeJointComponents::setR1World(Entity jointEntity, const Vector3& r1World) {
RP3D_FORCE_INLINE void HingeJointComponents::setR1World(Entity jointEntity, const Vector3& r1World) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mR1World[mMapEntityToComponentIndex[jointEntity]] = r1World;
}
// Return the vector from center of body 2 to anchor point in world-space
inline const Vector3& HingeJointComponents::getR2World(Entity jointEntity) const {
RP3D_FORCE_INLINE const Vector3& HingeJointComponents::getR2World(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mR2World[mMapEntityToComponentIndex[jointEntity]];
}
// Set the vector from center of body 2 to anchor point in world-space
inline void HingeJointComponents::setR2World(Entity jointEntity, const Vector3& r2World) {
RP3D_FORCE_INLINE void HingeJointComponents::setR2World(Entity jointEntity, const Vector3& r2World) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mR2World[mMapEntityToComponentIndex[jointEntity]] = r2World;
}
// Return the inertia tensor of body 1 (in world-space coordinates)
inline const Matrix3x3& HingeJointComponents::getI1(Entity jointEntity) const {
RP3D_FORCE_INLINE const Matrix3x3& HingeJointComponents::getI1(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mI1[mMapEntityToComponentIndex[jointEntity]];
}
// Set the inertia tensor of body 1 (in world-space coordinates)
inline void HingeJointComponents::setI1(Entity jointEntity, const Matrix3x3& i1) {
RP3D_FORCE_INLINE void HingeJointComponents::setI1(Entity jointEntity, const Matrix3x3& i1) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mI1[mMapEntityToComponentIndex[jointEntity]] = i1;
}
// Return the inertia tensor of body 2 (in world-space coordinates)
inline const Matrix3x3& HingeJointComponents::getI2(Entity jointEntity) const {
RP3D_FORCE_INLINE const Matrix3x3& HingeJointComponents::getI2(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mI2[mMapEntityToComponentIndex[jointEntity]];
}
// Set the inertia tensor of body 2 (in world-space coordinates)
inline void HingeJointComponents::setI2(Entity jointEntity, const Matrix3x3& i2) {
RP3D_FORCE_INLINE void HingeJointComponents::setI2(Entity jointEntity, const Matrix3x3& i2) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mI2[mMapEntityToComponentIndex[jointEntity]] = i2;
}
// Return the translation impulse
inline Vector3& HingeJointComponents::getImpulseTranslation(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& HingeJointComponents::getImpulseTranslation(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mImpulseTranslation[mMapEntityToComponentIndex[jointEntity]];
}
// Set the translation impulse
inline void HingeJointComponents::setImpulseTranslation(Entity jointEntity, const Vector3& impulseTranslation) {
RP3D_FORCE_INLINE void HingeJointComponents::setImpulseTranslation(Entity jointEntity, const Vector3& impulseTranslation) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mImpulseTranslation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
}
// Return the translation impulse
inline Vector2& HingeJointComponents::getImpulseRotation(Entity jointEntity) {
RP3D_FORCE_INLINE Vector2& HingeJointComponents::getImpulseRotation(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mImpulseRotation[mMapEntityToComponentIndex[jointEntity]];
}
// Set the translation impulse
inline void HingeJointComponents::setImpulseRotation(Entity jointEntity, const Vector2& impulseTranslation) {
RP3D_FORCE_INLINE void HingeJointComponents::setImpulseRotation(Entity jointEntity, const Vector2& impulseTranslation) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mImpulseRotation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
}
// Return the translation inverse mass matrix of the constraint
inline Matrix3x3& HingeJointComponents::getInverseMassMatrixTranslation(Entity jointEntity) {
RP3D_FORCE_INLINE Matrix3x3& HingeJointComponents::getInverseMassMatrixTranslation(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mInverseMassMatrixTranslation[mMapEntityToComponentIndex[jointEntity]];
@ -549,91 +549,91 @@ inline Matrix3x3& HingeJointComponents::getInverseMassMatrixTranslation(Entity j
// Set the translation inverse mass matrix of the constraint
inline void HingeJointComponents::setInverseMassMatrixTranslation(Entity jointEntity, const Matrix3x3& inverseMassMatrix) {
RP3D_FORCE_INLINE void HingeJointComponents::setInverseMassMatrixTranslation(Entity jointEntity, const Matrix3x3& inverseMassMatrix) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mInverseMassMatrixTranslation[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
}
// Return the rotation inverse mass matrix of the constraint
inline Matrix2x2& HingeJointComponents::getInverseMassMatrixRotation(Entity jointEntity) {
RP3D_FORCE_INLINE Matrix2x2& HingeJointComponents::getInverseMassMatrixRotation(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mInverseMassMatrixRotation[mMapEntityToComponentIndex[jointEntity]];
}
// Set the rotation inverse mass matrix of the constraint
inline void HingeJointComponents::setInverseMassMatrixRotation(Entity jointEntity, const Matrix2x2& inverseMassMatrix) {
RP3D_FORCE_INLINE void HingeJointComponents::setInverseMassMatrixRotation(Entity jointEntity, const Matrix2x2& inverseMassMatrix) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mInverseMassMatrixRotation[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
}
// Return the translation bias
inline Vector3& HingeJointComponents::getBiasTranslation(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& HingeJointComponents::getBiasTranslation(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mBiasTranslation[mMapEntityToComponentIndex[jointEntity]];
}
// Set the translation impulse
inline void HingeJointComponents::setBiasTranslation(Entity jointEntity, const Vector3 &impulseTranslation) {
RP3D_FORCE_INLINE void HingeJointComponents::setBiasTranslation(Entity jointEntity, const Vector3 &impulseTranslation) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mBiasTranslation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
}
// Return the rotation bias
inline Vector2 &HingeJointComponents::getBiasRotation(Entity jointEntity) {
RP3D_FORCE_INLINE Vector2 &HingeJointComponents::getBiasRotation(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mBiasRotation[mMapEntityToComponentIndex[jointEntity]];
}
// Set the rotation impulse
inline void HingeJointComponents::setBiasRotation(Entity jointEntity, const Vector2& impulseRotation) {
RP3D_FORCE_INLINE void HingeJointComponents::setBiasRotation(Entity jointEntity, const Vector2& impulseRotation) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mBiasRotation[mMapEntityToComponentIndex[jointEntity]] = impulseRotation;
}
// Return the initial orientation difference
inline Quaternion& HingeJointComponents::getInitOrientationDifferenceInv(Entity jointEntity) {
RP3D_FORCE_INLINE Quaternion& HingeJointComponents::getInitOrientationDifferenceInv(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mInitOrientationDifferenceInv[mMapEntityToComponentIndex[jointEntity]];
}
// Set the rotation impulse
inline void HingeJointComponents::setInitOrientationDifferenceInv(Entity jointEntity, const Quaternion& initOrientationDifferenceInv) {
RP3D_FORCE_INLINE void HingeJointComponents::setInitOrientationDifferenceInv(Entity jointEntity, const Quaternion& initOrientationDifferenceInv) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mInitOrientationDifferenceInv[mMapEntityToComponentIndex[jointEntity]] = initOrientationDifferenceInv;
}
// Return the hinge rotation axis (in local-space coordinates of body 1)
inline Vector3& HingeJointComponents::getHingeLocalAxisBody1(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& HingeJointComponents::getHingeLocalAxisBody1(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mHingeLocalAxisBody1[mMapEntityToComponentIndex[jointEntity]];
}
// Set the hinge rotation axis (in local-space coordinates of body 1)
inline void HingeJointComponents::setHingeLocalAxisBody1(Entity jointEntity, const Vector3& hingeLocalAxisBody1) {
RP3D_FORCE_INLINE void HingeJointComponents::setHingeLocalAxisBody1(Entity jointEntity, const Vector3& hingeLocalAxisBody1) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mHingeLocalAxisBody1[mMapEntityToComponentIndex[jointEntity]] = hingeLocalAxisBody1;
}
// Return the hinge rotation axis (in local-space coordiantes of body 2)
inline Vector3& HingeJointComponents::getHingeLocalAxisBody2(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& HingeJointComponents::getHingeLocalAxisBody2(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mHingeLocalAxisBody2[mMapEntityToComponentIndex[jointEntity]];
}
// Set the hinge rotation axis (in local-space coordiantes of body 2)
inline void HingeJointComponents::setHingeLocalAxisBody2(Entity jointEntity, const Vector3& hingeLocalAxisBody2) {
RP3D_FORCE_INLINE void HingeJointComponents::setHingeLocalAxisBody2(Entity jointEntity, const Vector3& hingeLocalAxisBody2) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mHingeLocalAxisBody2[mMapEntityToComponentIndex[jointEntity]] = hingeLocalAxisBody2;
@ -641,56 +641,56 @@ inline void HingeJointComponents::setHingeLocalAxisBody2(Entity jointEntity, con
// Return the hinge rotation axis (in world-space coordinates) computed from body 1
inline Vector3& HingeJointComponents::getA1(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& HingeJointComponents::getA1(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mA1[mMapEntityToComponentIndex[jointEntity]];
}
// Set the hinge rotation axis (in world-space coordinates) computed from body 1
inline void HingeJointComponents::setA1(Entity jointEntity, const Vector3& a1) {
RP3D_FORCE_INLINE void HingeJointComponents::setA1(Entity jointEntity, const Vector3& a1) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mA1[mMapEntityToComponentIndex[jointEntity]] = a1;
}
// Return the cross product of vector b2 and a1
inline Vector3& HingeJointComponents::getB2CrossA1(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& HingeJointComponents::getB2CrossA1(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mB2CrossA1[mMapEntityToComponentIndex[jointEntity]];
}
// Set the cross product of vector b2 and a1
inline void HingeJointComponents::setB2CrossA1(Entity jointEntity, const Vector3& b2CrossA1) {
RP3D_FORCE_INLINE void HingeJointComponents::setB2CrossA1(Entity jointEntity, const Vector3& b2CrossA1) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mB2CrossA1[mMapEntityToComponentIndex[jointEntity]] = b2CrossA1;
}
// Return the cross product of vector c2 and a1;
inline Vector3& HingeJointComponents::getC2CrossA1(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& HingeJointComponents::getC2CrossA1(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mC2CrossA1[mMapEntityToComponentIndex[jointEntity]];
}
// Set the cross product of vector c2 and a1;
inline void HingeJointComponents::setC2CrossA1(Entity jointEntity, const Vector3& c2CrossA1) {
RP3D_FORCE_INLINE void HingeJointComponents::setC2CrossA1(Entity jointEntity, const Vector3& c2CrossA1) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mC2CrossA1[mMapEntityToComponentIndex[jointEntity]] = c2CrossA1;
}
// Return the accumulated impulse for the lower limit constraint
inline decimal HingeJointComponents::getImpulseLowerLimit(Entity jointEntity) const {
RP3D_FORCE_INLINE decimal HingeJointComponents::getImpulseLowerLimit(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mImpulseLowerLimit[mMapEntityToComponentIndex[jointEntity]];
}
// Set the accumulated impulse for the lower limit constraint
inline void HingeJointComponents::setImpulseLowerLimit(Entity jointEntity, decimal impulseLowerLimit) {
RP3D_FORCE_INLINE void HingeJointComponents::setImpulseLowerLimit(Entity jointEntity, decimal impulseLowerLimit) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mImpulseLowerLimit[mMapEntityToComponentIndex[jointEntity]] = impulseLowerLimit;
@ -698,14 +698,14 @@ inline void HingeJointComponents::setImpulseLowerLimit(Entity jointEntity, decim
// Return the accumulated impulse for the upper limit constraint
inline decimal HingeJointComponents::getImpulseUpperLimit(Entity jointEntity) const {
RP3D_FORCE_INLINE decimal HingeJointComponents::getImpulseUpperLimit(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mImpulseUpperLimit[mMapEntityToComponentIndex[jointEntity]];
}
// Set the accumulated impulse for the upper limit constraint
inline void HingeJointComponents::setImpulseUpperLimit(Entity jointEntity, decimal impulseUpperLimit) const {
RP3D_FORCE_INLINE void HingeJointComponents::setImpulseUpperLimit(Entity jointEntity, decimal impulseUpperLimit) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mImpulseUpperLimit[mMapEntityToComponentIndex[jointEntity]] = impulseUpperLimit;
@ -713,182 +713,182 @@ inline void HingeJointComponents::setImpulseUpperLimit(Entity jointEntity, decim
// Return the accumulated impulse for the motor constraint;
inline decimal HingeJointComponents::getImpulseMotor(Entity jointEntity) const {
RP3D_FORCE_INLINE decimal HingeJointComponents::getImpulseMotor(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mImpulseMotor[mMapEntityToComponentIndex[jointEntity]];
}
// Set the accumulated impulse for the motor constraint;
inline void HingeJointComponents::setImpulseMotor(Entity jointEntity, decimal impulseMotor) {
RP3D_FORCE_INLINE void HingeJointComponents::setImpulseMotor(Entity jointEntity, decimal impulseMotor) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mImpulseMotor[mMapEntityToComponentIndex[jointEntity]] = impulseMotor;
}
// Return the inverse of mass matrix K=JM^-1J^t for the limits and motor constraints (1x1 matrix)
inline decimal HingeJointComponents::getInverseMassMatrixLimitMotor(Entity jointEntity) const {
RP3D_FORCE_INLINE decimal HingeJointComponents::getInverseMassMatrixLimitMotor(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mInverseMassMatrixLimitMotor[mMapEntityToComponentIndex[jointEntity]];
}
// Set the inverse of mass matrix K=JM^-1J^t for the limits and motor constraints (1x1 matrix)
inline void HingeJointComponents::setInverseMassMatrixLimitMotor(Entity jointEntity, decimal inverseMassMatrixLimitMotor) {
RP3D_FORCE_INLINE void HingeJointComponents::setInverseMassMatrixLimitMotor(Entity jointEntity, decimal inverseMassMatrixLimitMotor) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mInverseMassMatrixLimitMotor[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrixLimitMotor;
}
// Return the inverse of mass matrix K=JM^-1J^t for the motor
inline decimal HingeJointComponents::getInverseMassMatrixMotor(Entity jointEntity) {
RP3D_FORCE_INLINE decimal HingeJointComponents::getInverseMassMatrixMotor(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mInverseMassMatrixMotor[mMapEntityToComponentIndex[jointEntity]];
}
// Return the inverse of mass matrix K=JM^-1J^t for the motor
inline void HingeJointComponents::setInverseMassMatrixMotor(Entity jointEntity, decimal inverseMassMatrixMotor) {
RP3D_FORCE_INLINE void HingeJointComponents::setInverseMassMatrixMotor(Entity jointEntity, decimal inverseMassMatrixMotor) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mInverseMassMatrixMotor[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrixMotor;
}
// Return the bias of the lower limit constraint
inline decimal HingeJointComponents::getBLowerLimit(Entity jointEntity) const {
RP3D_FORCE_INLINE decimal HingeJointComponents::getBLowerLimit(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mBLowerLimit[mMapEntityToComponentIndex[jointEntity]];
}
// Set the bias of the lower limit constraint
inline void HingeJointComponents::setBLowerLimit(Entity jointEntity, decimal bLowerLimit) const {
RP3D_FORCE_INLINE void HingeJointComponents::setBLowerLimit(Entity jointEntity, decimal bLowerLimit) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mBLowerLimit[mMapEntityToComponentIndex[jointEntity]] = bLowerLimit;
}
// Return the bias of the upper limit constraint
inline decimal HingeJointComponents::getBUpperLimit(Entity jointEntity) const {
RP3D_FORCE_INLINE decimal HingeJointComponents::getBUpperLimit(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mBUpperLimit[mMapEntityToComponentIndex[jointEntity]];
}
// Set the bias of the upper limit constraint
inline void HingeJointComponents::setBUpperLimit(Entity jointEntity, decimal bUpperLimit) {
RP3D_FORCE_INLINE void HingeJointComponents::setBUpperLimit(Entity jointEntity, decimal bUpperLimit) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mBUpperLimit[mMapEntityToComponentIndex[jointEntity]] = bUpperLimit;
}
// Return true if the joint limits are enabled
inline bool HingeJointComponents::getIsLimitEnabled(Entity jointEntity) const {
RP3D_FORCE_INLINE bool HingeJointComponents::getIsLimitEnabled(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mIsLimitEnabled[mMapEntityToComponentIndex[jointEntity]];
}
// Set to true if the joint limits are enabled
inline void HingeJointComponents::setIsLimitEnabled(Entity jointEntity, bool isLimitEnabled) {
RP3D_FORCE_INLINE void HingeJointComponents::setIsLimitEnabled(Entity jointEntity, bool isLimitEnabled) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mIsLimitEnabled[mMapEntityToComponentIndex[jointEntity]] = isLimitEnabled;
}
// Return true if the motor of the joint in enabled
inline bool HingeJointComponents::getIsMotorEnabled(Entity jointEntity) const {
RP3D_FORCE_INLINE bool HingeJointComponents::getIsMotorEnabled(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mIsMotorEnabled[mMapEntityToComponentIndex[jointEntity]];
}
// Set to true if the motor of the joint in enabled
inline void HingeJointComponents::setIsMotorEnabled(Entity jointEntity, bool isMotorEnabled) const {
RP3D_FORCE_INLINE void HingeJointComponents::setIsMotorEnabled(Entity jointEntity, bool isMotorEnabled) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mIsMotorEnabled[mMapEntityToComponentIndex[jointEntity]] = isMotorEnabled;
}
// Return the Lower limit (minimum allowed rotation angle in radian)
inline decimal HingeJointComponents::getLowerLimit(Entity jointEntity) const {
RP3D_FORCE_INLINE decimal HingeJointComponents::getLowerLimit(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mLowerLimit[mMapEntityToComponentIndex[jointEntity]];
}
// Set the Lower limit (minimum allowed rotation angle in radian)
inline void HingeJointComponents::setLowerLimit(Entity jointEntity, decimal lowerLimit) const {
RP3D_FORCE_INLINE void HingeJointComponents::setLowerLimit(Entity jointEntity, decimal lowerLimit) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mLowerLimit[mMapEntityToComponentIndex[jointEntity]] = lowerLimit;
}
// Return the upper limit (maximum translation distance)
inline decimal HingeJointComponents::getUpperLimit(Entity jointEntity) const {
RP3D_FORCE_INLINE decimal HingeJointComponents::getUpperLimit(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mUpperLimit[mMapEntityToComponentIndex[jointEntity]];
}
// Set the upper limit (maximum translation distance)
inline void HingeJointComponents::setUpperLimit(Entity jointEntity, decimal upperLimit) {
RP3D_FORCE_INLINE void HingeJointComponents::setUpperLimit(Entity jointEntity, decimal upperLimit) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mUpperLimit[mMapEntityToComponentIndex[jointEntity]] = upperLimit;
}
// Return true if the lower limit is violated
inline bool HingeJointComponents::getIsLowerLimitViolated(Entity jointEntity) const {
RP3D_FORCE_INLINE bool HingeJointComponents::getIsLowerLimitViolated(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mIsLowerLimitViolated[mMapEntityToComponentIndex[jointEntity]];
}
// Set to true if the lower limit is violated
inline void HingeJointComponents::setIsLowerLimitViolated(Entity jointEntity, bool isLowerLimitViolated) {
RP3D_FORCE_INLINE void HingeJointComponents::setIsLowerLimitViolated(Entity jointEntity, bool isLowerLimitViolated) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mIsLowerLimitViolated[mMapEntityToComponentIndex[jointEntity]] = isLowerLimitViolated;
}
// Return true if the upper limit is violated
inline bool HingeJointComponents::getIsUpperLimitViolated(Entity jointEntity) const {
RP3D_FORCE_INLINE bool HingeJointComponents::getIsUpperLimitViolated(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mIsUpperLimitViolated[mMapEntityToComponentIndex[jointEntity]];
}
// Set to true if the upper limit is violated
inline void HingeJointComponents::setIsUpperLimitViolated(Entity jointEntity, bool isUpperLimitViolated) const {
RP3D_FORCE_INLINE void HingeJointComponents::setIsUpperLimitViolated(Entity jointEntity, bool isUpperLimitViolated) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mIsUpperLimitViolated[mMapEntityToComponentIndex[jointEntity]] = isUpperLimitViolated;
}
// Return the motor speed (in rad/s)
inline decimal HingeJointComponents::getMotorSpeed(Entity jointEntity) const {
RP3D_FORCE_INLINE decimal HingeJointComponents::getMotorSpeed(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mMotorSpeed[mMapEntityToComponentIndex[jointEntity]];
}
// Set the motor speed (in rad/s)
inline void HingeJointComponents::setMotorSpeed(Entity jointEntity, decimal motorSpeed) {
RP3D_FORCE_INLINE void HingeJointComponents::setMotorSpeed(Entity jointEntity, decimal motorSpeed) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mMotorSpeed[mMapEntityToComponentIndex[jointEntity]] = motorSpeed;
}
// Return the maximum motor torque (in Newtons) that can be applied to reach to desired motor speed
inline decimal HingeJointComponents::getMaxMotorTorque(Entity jointEntity) const {
RP3D_FORCE_INLINE decimal HingeJointComponents::getMaxMotorTorque(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mMaxMotorTorque[mMapEntityToComponentIndex[jointEntity]];
}
// Set the maximum motor torque (in Newtons) that can be applied to reach to desired motor speed
inline void HingeJointComponents::setMaxMotorTorque(Entity jointEntity, decimal maxMotorTorque) {
RP3D_FORCE_INLINE void HingeJointComponents::setMaxMotorTorque(Entity jointEntity, decimal maxMotorTorque) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mMaxMotorTorque[mMapEntityToComponentIndex[jointEntity]] = maxMotorTorque;

View File

@ -138,7 +138,7 @@ class JointComponents : public Components {
JointsPositionCorrectionTechnique getPositionCorrectionTechnique(Entity jointEntity) const;
/// Set the position correction technique of a joint
void getPositionCorrectionTechnique(Entity jointEntity, JointsPositionCorrectionTechnique positionCorrectionTechnique);
void setPositionCorrectionTechnique(Entity jointEntity, JointsPositionCorrectionTechnique positionCorrectionTechnique);
/// Return true if the collision is enabled between the two bodies of a joint
bool getIsCollisionEnabled(Entity jointEntity) const;
@ -157,64 +157,69 @@ class JointComponents : public Components {
friend class BroadPhaseSystem;
friend class ConstraintSolverSystem;
friend class PhysicsWorld;
friend class SolveBallAndSocketJointSystem;
friend class SolveFixedJointSystem;
friend class SolveHingeJointSystem;
friend class SolveSliderJointSystem;
};
// Return the entity of the first body of a joint
inline Entity JointComponents::getBody1Entity(Entity jointEntity) const {
RP3D_FORCE_INLINE Entity JointComponents::getBody1Entity(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mBody1Entities[mMapEntityToComponentIndex[jointEntity]];
}
// Return the entity of the second body of a joint
inline Entity JointComponents::getBody2Entity(Entity jointEntity) const {
RP3D_FORCE_INLINE Entity JointComponents::getBody2Entity(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mBody2Entities[mMapEntityToComponentIndex[jointEntity]];
}
// Return a pointer to the joint
inline Joint* JointComponents::getJoint(Entity jointEntity) const {
RP3D_FORCE_INLINE Joint* JointComponents::getJoint(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mJoints[mMapEntityToComponentIndex[jointEntity]];
}
// Return the type of a joint
inline JointType JointComponents::getType(Entity jointEntity) const {
RP3D_FORCE_INLINE JointType JointComponents::getType(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mTypes[mMapEntityToComponentIndex[jointEntity]];
}
// Return the position correction technique of a joint
inline JointsPositionCorrectionTechnique JointComponents::getPositionCorrectionTechnique(Entity jointEntity) const {
RP3D_FORCE_INLINE JointsPositionCorrectionTechnique JointComponents::getPositionCorrectionTechnique(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mPositionCorrectionTechniques[mMapEntityToComponentIndex[jointEntity]];
}
// Set the position correction technique of a joint
inline void JointComponents::getPositionCorrectionTechnique(Entity jointEntity, JointsPositionCorrectionTechnique positionCorrectionTechnique) {
RP3D_FORCE_INLINE void JointComponents::setPositionCorrectionTechnique(Entity jointEntity, JointsPositionCorrectionTechnique positionCorrectionTechnique) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mPositionCorrectionTechniques[mMapEntityToComponentIndex[jointEntity]] = positionCorrectionTechnique;
}
// Return true if the collision is enabled between the two bodies of a joint
inline bool JointComponents::getIsCollisionEnabled(Entity jointEntity) const {
RP3D_FORCE_INLINE bool JointComponents::getIsCollisionEnabled(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mIsCollisionEnabled[mMapEntityToComponentIndex[jointEntity]];
}
// Set whether the collision is enabled between the two bodies of a joint
inline void JointComponents::setIsCollisionEnabled(Entity jointEntity, bool isCollisionEnabled) {
RP3D_FORCE_INLINE void JointComponents::setIsCollisionEnabled(Entity jointEntity, bool isCollisionEnabled) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mIsCollisionEnabled[mMapEntityToComponentIndex[jointEntity]] = isCollisionEnabled;
}
// Return true if the joint has already been added into an island during island creation
inline bool JointComponents::getIsAlreadyInIsland(Entity jointEntity) const {
RP3D_FORCE_INLINE bool JointComponents::getIsAlreadyInIsland(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mIsAlreadyInIsland[mMapEntityToComponentIndex[jointEntity]];
}
// Set to true if the joint has already been added into an island during island creation
inline void JointComponents::setIsAlreadyInIsland(Entity jointEntity, bool isAlreadyInIsland) {
RP3D_FORCE_INLINE void JointComponents::setIsAlreadyInIsland(Entity jointEntity, bool isAlreadyInIsland) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mIsAlreadyInIsland[mMapEntityToComponentIndex[jointEntity]] = isAlreadyInIsland;
}

View File

@ -109,9 +109,12 @@ class RigidBodyComponents : public Components {
/// Array with the inertia tensor of each component
Vector3* mLocalInertiaTensors;
/// Array with the inverse of the inertia tensor of each component
/// Array with the inverse of the local inertia tensor of each component
Vector3* mInverseInertiaTensorsLocal;
/// Array with the inverse of the world inertia tensor of each component
Matrix3x3* mInverseInertiaTensorsWorld;
/// Array with the constrained linear velocity of each component
Vector3* mConstrainedLinearVelocities;
@ -142,8 +145,11 @@ class RigidBodyComponents : public Components {
/// Array with the boolean value to know if the body has already been added into an island
bool* mIsAlreadyInIsland;
/// For each body, the list of joints entities the body is part of
List<Entity>* mJoints;
/// For each body, the array of joints entities the body is part of
Array<Entity>* mJoints;
/// For each body, the array of the indices of contact pairs in which the body is involved
Array<uint>* mContactPairs;
// -------------------- Methods -------------------- //
@ -258,6 +264,9 @@ class RigidBodyComponents : public Components {
/// Return the inverse local inertia tensor of an entity
const Vector3& getInertiaTensorLocalInverse(Entity bodyEntity);
/// Return the inverse world inertia tensor of an entity
const Matrix3x3& getInertiaTensorWorldInverse(Entity bodyEntity);
/// Set the external force of an entity
void setExternalForce(Entity bodyEntity, const Vector3& externalForce);
@ -333,8 +342,8 @@ class RigidBodyComponents : public Components {
/// Set the value to know if the entity is already in an island
void setIsAlreadyInIsland(Entity bodyEntity, bool isAlreadyInIsland);
/// Return the list of joints of a body
const List<Entity>& getJoints(Entity bodyEntity) const;
/// Return the array of joints of a body
const Array<Entity>& getJoints(Entity bodyEntity) const;
/// Add a joint to a body component
void addJointToBody(Entity bodyEntity, Entity jointEntity);
@ -342,10 +351,14 @@ class RigidBodyComponents : public Components {
/// Remove a joint from a body component
void removeJointFromBody(Entity bodyEntity, Entity jointEntity);
/// A an associated contact pairs into the contact pairs array of the body
void addContacPair(Entity bodyEntity, uint contactPairIndex);
// -------------------- Friendship -------------------- //
friend class PhysicsWorld;
friend class ContactSolverSystem;
friend class CollisionDetectionSystem;
friend class SolveBallAndSocketJointSystem;
friend class SolveFixedJointSystem;
friend class SolveHingeJointSystem;
@ -358,7 +371,7 @@ class RigidBodyComponents : public Components {
};
// Return a pointer to a body rigid
inline RigidBody* RigidBodyComponents::getRigidBody(Entity bodyEntity) {
RP3D_FORCE_INLINE RigidBody* RigidBodyComponents::getRigidBody(Entity bodyEntity) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -366,7 +379,7 @@ inline RigidBody* RigidBodyComponents::getRigidBody(Entity bodyEntity) {
}
// Return true if the body is allowed to sleep
inline bool RigidBodyComponents::getIsAllowedToSleep(Entity bodyEntity) const {
RP3D_FORCE_INLINE bool RigidBodyComponents::getIsAllowedToSleep(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -374,7 +387,7 @@ inline bool RigidBodyComponents::getIsAllowedToSleep(Entity bodyEntity) const {
}
// Set the value to know if the body is allowed to sleep
inline void RigidBodyComponents::setIsAllowedToSleep(Entity bodyEntity, bool isAllowedToSleep) const {
RP3D_FORCE_INLINE void RigidBodyComponents::setIsAllowedToSleep(Entity bodyEntity, bool isAllowedToSleep) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -382,7 +395,7 @@ inline void RigidBodyComponents::setIsAllowedToSleep(Entity bodyEntity, bool isA
}
// Return true if the body is sleeping
inline bool RigidBodyComponents::getIsSleeping(Entity bodyEntity) const {
RP3D_FORCE_INLINE bool RigidBodyComponents::getIsSleeping(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -390,7 +403,7 @@ inline bool RigidBodyComponents::getIsSleeping(Entity bodyEntity) const {
}
// Set the value to know if the body is sleeping
inline void RigidBodyComponents::setIsSleeping(Entity bodyEntity, bool isSleeping) const {
RP3D_FORCE_INLINE void RigidBodyComponents::setIsSleeping(Entity bodyEntity, bool isSleeping) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -398,7 +411,7 @@ inline void RigidBodyComponents::setIsSleeping(Entity bodyEntity, bool isSleepin
}
// Return the sleep time
inline decimal RigidBodyComponents::getSleepTime(Entity bodyEntity) const {
RP3D_FORCE_INLINE decimal RigidBodyComponents::getSleepTime(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -406,7 +419,7 @@ inline decimal RigidBodyComponents::getSleepTime(Entity bodyEntity) const {
}
// Set the sleep time
inline void RigidBodyComponents::setSleepTime(Entity bodyEntity, decimal sleepTime) const {
RP3D_FORCE_INLINE void RigidBodyComponents::setSleepTime(Entity bodyEntity, decimal sleepTime) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -414,7 +427,7 @@ inline void RigidBodyComponents::setSleepTime(Entity bodyEntity, decimal sleepTi
}
// Return the body type of a body
inline BodyType RigidBodyComponents::getBodyType(Entity bodyEntity) {
RP3D_FORCE_INLINE BodyType RigidBodyComponents::getBodyType(Entity bodyEntity) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -422,7 +435,7 @@ inline BodyType RigidBodyComponents::getBodyType(Entity bodyEntity) {
}
// Set the body type of a body
inline void RigidBodyComponents::setBodyType(Entity bodyEntity, BodyType bodyType) {
RP3D_FORCE_INLINE void RigidBodyComponents::setBodyType(Entity bodyEntity, BodyType bodyType) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -430,7 +443,7 @@ inline void RigidBodyComponents::setBodyType(Entity bodyEntity, BodyType bodyTyp
}
// Return the linear velocity of an entity
inline const Vector3& RigidBodyComponents::getLinearVelocity(Entity bodyEntity) const {
RP3D_FORCE_INLINE const Vector3& RigidBodyComponents::getLinearVelocity(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -438,7 +451,7 @@ inline const Vector3& RigidBodyComponents::getLinearVelocity(Entity bodyEntity)
}
// Return the angular velocity of an entity
inline const Vector3& RigidBodyComponents::getAngularVelocity(Entity bodyEntity) const {
RP3D_FORCE_INLINE const Vector3& RigidBodyComponents::getAngularVelocity(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -446,7 +459,7 @@ inline const Vector3& RigidBodyComponents::getAngularVelocity(Entity bodyEntity)
}
// Set the linear velocity of an entity
inline void RigidBodyComponents::setLinearVelocity(Entity bodyEntity, const Vector3& linearVelocity) {
RP3D_FORCE_INLINE void RigidBodyComponents::setLinearVelocity(Entity bodyEntity, const Vector3& linearVelocity) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -454,7 +467,7 @@ inline void RigidBodyComponents::setLinearVelocity(Entity bodyEntity, const Vect
}
// Set the angular velocity of an entity
inline void RigidBodyComponents::setAngularVelocity(Entity bodyEntity, const Vector3& angularVelocity) {
RP3D_FORCE_INLINE void RigidBodyComponents::setAngularVelocity(Entity bodyEntity, const Vector3& angularVelocity) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -462,7 +475,7 @@ inline void RigidBodyComponents::setAngularVelocity(Entity bodyEntity, const Vec
}
// Return the external force of an entity
inline const Vector3& RigidBodyComponents::getExternalForce(Entity bodyEntity) const {
RP3D_FORCE_INLINE const Vector3& RigidBodyComponents::getExternalForce(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -470,7 +483,7 @@ inline const Vector3& RigidBodyComponents::getExternalForce(Entity bodyEntity) c
}
// Return the external torque of an entity
inline const Vector3& RigidBodyComponents::getExternalTorque(Entity bodyEntity) const {
RP3D_FORCE_INLINE const Vector3& RigidBodyComponents::getExternalTorque(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -478,7 +491,7 @@ inline const Vector3& RigidBodyComponents::getExternalTorque(Entity bodyEntity)
}
// Return the linear damping factor of an entity
inline decimal RigidBodyComponents::getLinearDamping(Entity bodyEntity) const {
RP3D_FORCE_INLINE decimal RigidBodyComponents::getLinearDamping(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -486,7 +499,7 @@ inline decimal RigidBodyComponents::getLinearDamping(Entity bodyEntity) const {
}
// Return the angular damping factor of an entity
inline decimal RigidBodyComponents::getAngularDamping(Entity bodyEntity) const {
RP3D_FORCE_INLINE decimal RigidBodyComponents::getAngularDamping(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -494,7 +507,7 @@ inline decimal RigidBodyComponents::getAngularDamping(Entity bodyEntity) const {
}
// Return the mass of an entity
inline decimal RigidBodyComponents::getMass(Entity bodyEntity) const {
RP3D_FORCE_INLINE decimal RigidBodyComponents::getMass(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -502,7 +515,7 @@ inline decimal RigidBodyComponents::getMass(Entity bodyEntity) const {
}
// Return the inverse mass of an entity
inline decimal RigidBodyComponents::getMassInverse(Entity bodyEntity) const {
RP3D_FORCE_INLINE decimal RigidBodyComponents::getMassInverse(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -510,15 +523,23 @@ inline decimal RigidBodyComponents::getMassInverse(Entity bodyEntity) const {
}
// Return the inverse local inertia tensor of an entity
inline const Vector3& RigidBodyComponents::getInertiaTensorLocalInverse(Entity bodyEntity) {
RP3D_FORCE_INLINE const Vector3& RigidBodyComponents::getInertiaTensorLocalInverse(Entity bodyEntity) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
return mInverseInertiaTensorsLocal[mMapEntityToComponentIndex[bodyEntity]];
}
// Return the inverse world inertia tensor of an entity
RP3D_FORCE_INLINE const Matrix3x3& RigidBodyComponents::getInertiaTensorWorldInverse(Entity bodyEntity) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
return mInverseInertiaTensorsWorld[mMapEntityToComponentIndex[bodyEntity]];
}
// Set the external force of an entity
inline void RigidBodyComponents::setExternalForce(Entity bodyEntity, const Vector3& externalForce) {
RP3D_FORCE_INLINE void RigidBodyComponents::setExternalForce(Entity bodyEntity, const Vector3& externalForce) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -526,7 +547,7 @@ inline void RigidBodyComponents::setExternalForce(Entity bodyEntity, const Vecto
}
// Set the external force of an entity
inline void RigidBodyComponents::setExternalTorque(Entity bodyEntity, const Vector3& externalTorque) {
RP3D_FORCE_INLINE void RigidBodyComponents::setExternalTorque(Entity bodyEntity, const Vector3& externalTorque) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -534,7 +555,7 @@ inline void RigidBodyComponents::setExternalTorque(Entity bodyEntity, const Vect
}
// Set the linear damping factor of an entity
inline void RigidBodyComponents::setLinearDamping(Entity bodyEntity, decimal linearDamping) {
RP3D_FORCE_INLINE void RigidBodyComponents::setLinearDamping(Entity bodyEntity, decimal linearDamping) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -542,7 +563,7 @@ inline void RigidBodyComponents::setLinearDamping(Entity bodyEntity, decimal lin
}
// Set the angular damping factor of an entity
inline void RigidBodyComponents::setAngularDamping(Entity bodyEntity, decimal angularDamping) {
RP3D_FORCE_INLINE void RigidBodyComponents::setAngularDamping(Entity bodyEntity, decimal angularDamping) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -550,7 +571,7 @@ inline void RigidBodyComponents::setAngularDamping(Entity bodyEntity, decimal an
}
// Set the mass of an entity
inline void RigidBodyComponents::setMass(Entity bodyEntity, decimal mass) {
RP3D_FORCE_INLINE void RigidBodyComponents::setMass(Entity bodyEntity, decimal mass) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -558,7 +579,7 @@ inline void RigidBodyComponents::setMass(Entity bodyEntity, decimal mass) {
}
// Set the mass inverse of an entity
inline void RigidBodyComponents::setMassInverse(Entity bodyEntity, decimal inverseMass) {
RP3D_FORCE_INLINE void RigidBodyComponents::setMassInverse(Entity bodyEntity, decimal inverseMass) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -566,7 +587,7 @@ inline void RigidBodyComponents::setMassInverse(Entity bodyEntity, decimal inver
}
// Return the local inertia tensor of an entity
inline const Vector3& RigidBodyComponents::getLocalInertiaTensor(Entity bodyEntity) {
RP3D_FORCE_INLINE const Vector3& RigidBodyComponents::getLocalInertiaTensor(Entity bodyEntity) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -574,7 +595,7 @@ inline const Vector3& RigidBodyComponents::getLocalInertiaTensor(Entity bodyEnti
}
// Set the local inertia tensor of an entity
inline void RigidBodyComponents::setLocalInertiaTensor(Entity bodyEntity, const Vector3& inertiaTensorLocal) {
RP3D_FORCE_INLINE void RigidBodyComponents::setLocalInertiaTensor(Entity bodyEntity, const Vector3& inertiaTensorLocal) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -582,7 +603,7 @@ inline void RigidBodyComponents::setLocalInertiaTensor(Entity bodyEntity, const
}
// Set the inverse local inertia tensor of an entity
inline void RigidBodyComponents::setInverseInertiaTensorLocal(Entity bodyEntity, const Vector3& inertiaTensorLocalInverse) {
RP3D_FORCE_INLINE void RigidBodyComponents::setInverseInertiaTensorLocal(Entity bodyEntity, const Vector3& inertiaTensorLocalInverse) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -590,7 +611,7 @@ inline void RigidBodyComponents::setInverseInertiaTensorLocal(Entity bodyEntity,
}
// Return the constrained linear velocity of an entity
inline const Vector3& RigidBodyComponents::getConstrainedLinearVelocity(Entity bodyEntity) const {
RP3D_FORCE_INLINE const Vector3& RigidBodyComponents::getConstrainedLinearVelocity(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -598,7 +619,7 @@ inline const Vector3& RigidBodyComponents::getConstrainedLinearVelocity(Entity b
}
// Return the constrained angular velocity of an entity
inline const Vector3& RigidBodyComponents::getConstrainedAngularVelocity(Entity bodyEntity) const {
RP3D_FORCE_INLINE const Vector3& RigidBodyComponents::getConstrainedAngularVelocity(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -606,7 +627,7 @@ inline const Vector3& RigidBodyComponents::getConstrainedAngularVelocity(Entity
}
// Return the split linear velocity of an entity
inline const Vector3& RigidBodyComponents::getSplitLinearVelocity(Entity bodyEntity) const {
RP3D_FORCE_INLINE const Vector3& RigidBodyComponents::getSplitLinearVelocity(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -614,7 +635,7 @@ inline const Vector3& RigidBodyComponents::getSplitLinearVelocity(Entity bodyEnt
}
// Return the split angular velocity of an entity
inline const Vector3& RigidBodyComponents::getSplitAngularVelocity(Entity bodyEntity) const {
RP3D_FORCE_INLINE const Vector3& RigidBodyComponents::getSplitAngularVelocity(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -622,7 +643,7 @@ inline const Vector3& RigidBodyComponents::getSplitAngularVelocity(Entity bodyEn
}
// Return the constrained position of an entity
inline Vector3& RigidBodyComponents::getConstrainedPosition(Entity bodyEntity) {
RP3D_FORCE_INLINE Vector3& RigidBodyComponents::getConstrainedPosition(Entity bodyEntity) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -630,7 +651,7 @@ inline Vector3& RigidBodyComponents::getConstrainedPosition(Entity bodyEntity) {
}
// Return the constrained orientation of an entity
inline Quaternion& RigidBodyComponents::getConstrainedOrientation(Entity bodyEntity) {
RP3D_FORCE_INLINE Quaternion& RigidBodyComponents::getConstrainedOrientation(Entity bodyEntity) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -638,7 +659,7 @@ inline Quaternion& RigidBodyComponents::getConstrainedOrientation(Entity bodyEnt
}
// Return the local center of mass of an entity
inline const Vector3& RigidBodyComponents::getCenterOfMassLocal(Entity bodyEntity) {
RP3D_FORCE_INLINE const Vector3& RigidBodyComponents::getCenterOfMassLocal(Entity bodyEntity) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -646,7 +667,7 @@ inline const Vector3& RigidBodyComponents::getCenterOfMassLocal(Entity bodyEntit
}
// Return the world center of mass of an entity
inline const Vector3& RigidBodyComponents::getCenterOfMassWorld(Entity bodyEntity) {
RP3D_FORCE_INLINE const Vector3& RigidBodyComponents::getCenterOfMassWorld(Entity bodyEntity) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -654,7 +675,7 @@ inline const Vector3& RigidBodyComponents::getCenterOfMassWorld(Entity bodyEntit
}
// Set the constrained linear velocity of an entity
inline void RigidBodyComponents::setConstrainedLinearVelocity(Entity bodyEntity, const Vector3& constrainedLinearVelocity) {
RP3D_FORCE_INLINE void RigidBodyComponents::setConstrainedLinearVelocity(Entity bodyEntity, const Vector3& constrainedLinearVelocity) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -662,7 +683,7 @@ inline void RigidBodyComponents::setConstrainedLinearVelocity(Entity bodyEntity,
}
// Set the constrained angular velocity of an entity
inline void RigidBodyComponents::setConstrainedAngularVelocity(Entity bodyEntity, const Vector3& constrainedAngularVelocity) {
RP3D_FORCE_INLINE void RigidBodyComponents::setConstrainedAngularVelocity(Entity bodyEntity, const Vector3& constrainedAngularVelocity) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -670,7 +691,7 @@ inline void RigidBodyComponents::setConstrainedAngularVelocity(Entity bodyEntity
}
// Set the split linear velocity of an entity
inline void RigidBodyComponents::setSplitLinearVelocity(Entity bodyEntity, const Vector3& splitLinearVelocity) {
RP3D_FORCE_INLINE void RigidBodyComponents::setSplitLinearVelocity(Entity bodyEntity, const Vector3& splitLinearVelocity) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -678,7 +699,7 @@ inline void RigidBodyComponents::setSplitLinearVelocity(Entity bodyEntity, const
}
// Set the split angular velocity of an entity
inline void RigidBodyComponents::setSplitAngularVelocity(Entity bodyEntity, const Vector3& splitAngularVelocity) {
RP3D_FORCE_INLINE void RigidBodyComponents::setSplitAngularVelocity(Entity bodyEntity, const Vector3& splitAngularVelocity) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -686,7 +707,7 @@ inline void RigidBodyComponents::setSplitAngularVelocity(Entity bodyEntity, cons
}
// Set the constrained position of an entity
inline void RigidBodyComponents::setConstrainedPosition(Entity bodyEntity, const Vector3& constrainedPosition) {
RP3D_FORCE_INLINE void RigidBodyComponents::setConstrainedPosition(Entity bodyEntity, const Vector3& constrainedPosition) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -694,7 +715,7 @@ inline void RigidBodyComponents::setConstrainedPosition(Entity bodyEntity, const
}
// Set the constrained orientation of an entity
inline void RigidBodyComponents::setConstrainedOrientation(Entity bodyEntity, const Quaternion& constrainedOrientation) {
RP3D_FORCE_INLINE void RigidBodyComponents::setConstrainedOrientation(Entity bodyEntity, const Quaternion& constrainedOrientation) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -702,7 +723,7 @@ inline void RigidBodyComponents::setConstrainedOrientation(Entity bodyEntity, co
}
// Set the local center of mass of an entity
inline void RigidBodyComponents::setCenterOfMassLocal(Entity bodyEntity, const Vector3& centerOfMassLocal) {
RP3D_FORCE_INLINE void RigidBodyComponents::setCenterOfMassLocal(Entity bodyEntity, const Vector3& centerOfMassLocal) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -710,7 +731,7 @@ inline void RigidBodyComponents::setCenterOfMassLocal(Entity bodyEntity, const V
}
// Set the world center of mass of an entity
inline void RigidBodyComponents::setCenterOfMassWorld(Entity bodyEntity, const Vector3& centerOfMassWorld) {
RP3D_FORCE_INLINE void RigidBodyComponents::setCenterOfMassWorld(Entity bodyEntity, const Vector3& centerOfMassWorld) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -718,7 +739,7 @@ inline void RigidBodyComponents::setCenterOfMassWorld(Entity bodyEntity, const V
}
// Return true if gravity is enabled for this entity
inline bool RigidBodyComponents::getIsGravityEnabled(Entity bodyEntity) const {
RP3D_FORCE_INLINE bool RigidBodyComponents::getIsGravityEnabled(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -726,7 +747,7 @@ inline bool RigidBodyComponents::getIsGravityEnabled(Entity bodyEntity) const {
}
// Return true if the entity is already in an island
inline bool RigidBodyComponents::getIsAlreadyInIsland(Entity bodyEntity) const {
RP3D_FORCE_INLINE bool RigidBodyComponents::getIsAlreadyInIsland(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -734,7 +755,7 @@ inline bool RigidBodyComponents::getIsAlreadyInIsland(Entity bodyEntity) const {
}
// Set the value to know if the gravity is enabled for this entity
inline void RigidBodyComponents::setIsGravityEnabled(Entity bodyEntity, bool isGravityEnabled) {
RP3D_FORCE_INLINE void RigidBodyComponents::setIsGravityEnabled(Entity bodyEntity, bool isGravityEnabled) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
@ -742,33 +763,40 @@ inline void RigidBodyComponents::setIsGravityEnabled(Entity bodyEntity, bool isG
}
// Set the value to know if the entity is already in an island
inline void RigidBodyComponents::setIsAlreadyInIsland(Entity bodyEntity, bool isAlreadyInIsland) {
RP3D_FORCE_INLINE void RigidBodyComponents::setIsAlreadyInIsland(Entity bodyEntity, bool isAlreadyInIsland) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
mIsAlreadyInIsland[mMapEntityToComponentIndex[bodyEntity]] = isAlreadyInIsland;
}
// Return the list of joints of a body
inline const List<Entity>& RigidBodyComponents::getJoints(Entity bodyEntity) const {
// Return the array of joints of a body
RP3D_FORCE_INLINE const Array<Entity>& RigidBodyComponents::getJoints(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
return mJoints[mMapEntityToComponentIndex[bodyEntity]];
}
// Add a joint to a body component
inline void RigidBodyComponents::addJointToBody(Entity bodyEntity, Entity jointEntity) {
RP3D_FORCE_INLINE void RigidBodyComponents::addJointToBody(Entity bodyEntity, Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
mJoints[mMapEntityToComponentIndex[bodyEntity]].add(jointEntity);
}
// Remove a joint from a body component
inline void RigidBodyComponents::removeJointFromBody(Entity bodyEntity, Entity jointEntity) {
RP3D_FORCE_INLINE void RigidBodyComponents::removeJointFromBody(Entity bodyEntity, Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
mJoints[mMapEntityToComponentIndex[bodyEntity]].remove(jointEntity);
}
// A an associated contact pairs into the contact pairs array of the body
RP3D_FORCE_INLINE void RigidBodyComponents::addContacPair(Entity bodyEntity, uint contactPairIndex) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
mContactPairs[mMapEntityToComponentIndex[bodyEntity]].add(contactPairIndex);
}
}
#endif

View File

@ -460,266 +460,266 @@ class SliderJointComponents : public Components {
};
// Return a pointer to a given joint
inline SliderJoint* SliderJointComponents::getJoint(Entity jointEntity) const {
RP3D_FORCE_INLINE SliderJoint* SliderJointComponents::getJoint(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mJoints[mMapEntityToComponentIndex[jointEntity]];
}
// Set the joint pointer to a given joint
inline void SliderJointComponents::setJoint(Entity jointEntity, SliderJoint* joint) const {
RP3D_FORCE_INLINE void SliderJointComponents::setJoint(Entity jointEntity, SliderJoint* joint) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mJoints[mMapEntityToComponentIndex[jointEntity]] = joint;
}
// Return the local anchor point of body 1 for a given joint
inline const Vector3& SliderJointComponents::getLocalAnchorPointBody1(Entity jointEntity) const {
RP3D_FORCE_INLINE const Vector3& SliderJointComponents::getLocalAnchorPointBody1(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]];
}
// Set the local anchor point of body 1 for a given joint
inline void SliderJointComponents::setLocalAnchorPointBody1(Entity jointEntity, const Vector3& localAnchoirPointBody1) {
RP3D_FORCE_INLINE void SliderJointComponents::setLocalAnchorPointBody1(Entity jointEntity, const Vector3& localAnchoirPointBody1) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]] = localAnchoirPointBody1;
}
// Return the local anchor point of body 2 for a given joint
inline const Vector3& SliderJointComponents::getLocalAnchorPointBody2(Entity jointEntity) const {
RP3D_FORCE_INLINE const Vector3& SliderJointComponents::getLocalAnchorPointBody2(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]];
}
// Set the local anchor point of body 2 for a given joint
inline void SliderJointComponents::setLocalAnchorPointBody2(Entity jointEntity, const Vector3& localAnchoirPointBody2) {
RP3D_FORCE_INLINE void SliderJointComponents::setLocalAnchorPointBody2(Entity jointEntity, const Vector3& localAnchoirPointBody2) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]] = localAnchoirPointBody2;
}
// Return the inertia tensor of body 1 (in world-space coordinates)
inline const Matrix3x3& SliderJointComponents::getI1(Entity jointEntity) const {
RP3D_FORCE_INLINE const Matrix3x3& SliderJointComponents::getI1(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mI1[mMapEntityToComponentIndex[jointEntity]];
}
// Set the inertia tensor of body 1 (in world-space coordinates)
inline void SliderJointComponents::setI1(Entity jointEntity, const Matrix3x3& i1) {
RP3D_FORCE_INLINE void SliderJointComponents::setI1(Entity jointEntity, const Matrix3x3& i1) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mI1[mMapEntityToComponentIndex[jointEntity]] = i1;
}
// Return the inertia tensor of body 2 (in world-space coordinates)
inline const Matrix3x3& SliderJointComponents::getI2(Entity jointEntity) const {
RP3D_FORCE_INLINE const Matrix3x3& SliderJointComponents::getI2(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mI2[mMapEntityToComponentIndex[jointEntity]];
}
// Set the inertia tensor of body 2 (in world-space coordinates)
inline void SliderJointComponents::setI2(Entity jointEntity, const Matrix3x3& i2) {
RP3D_FORCE_INLINE void SliderJointComponents::setI2(Entity jointEntity, const Matrix3x3& i2) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mI2[mMapEntityToComponentIndex[jointEntity]] = i2;
}
// Return the translation impulse
inline Vector2& SliderJointComponents::getImpulseTranslation(Entity jointEntity) {
RP3D_FORCE_INLINE Vector2& SliderJointComponents::getImpulseTranslation(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mImpulseTranslation[mMapEntityToComponentIndex[jointEntity]];
}
// Set the translation impulse
inline void SliderJointComponents::setImpulseTranslation(Entity jointEntity, const Vector2& impulseTranslation) {
RP3D_FORCE_INLINE void SliderJointComponents::setImpulseTranslation(Entity jointEntity, const Vector2& impulseTranslation) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mImpulseTranslation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
}
// Return the translation impulse
inline Vector3& SliderJointComponents::getImpulseRotation(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& SliderJointComponents::getImpulseRotation(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mImpulseRotation[mMapEntityToComponentIndex[jointEntity]];
}
// Set the translation impulse
inline void SliderJointComponents::setImpulseRotation(Entity jointEntity, const Vector3& impulseTranslation) {
RP3D_FORCE_INLINE void SliderJointComponents::setImpulseRotation(Entity jointEntity, const Vector3& impulseTranslation) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mImpulseRotation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
}
// Return the translation inverse mass matrix of the constraint
inline Matrix2x2& SliderJointComponents::getInverseMassMatrixTranslation(Entity jointEntity) {
RP3D_FORCE_INLINE Matrix2x2& SliderJointComponents::getInverseMassMatrixTranslation(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mInverseMassMatrixTranslation[mMapEntityToComponentIndex[jointEntity]];
}
// Set the translation inverse mass matrix of the constraint
inline void SliderJointComponents::setInverseMassMatrixTranslation(Entity jointEntity, const Matrix2x2& inverseMassMatrix) {
RP3D_FORCE_INLINE void SliderJointComponents::setInverseMassMatrixTranslation(Entity jointEntity, const Matrix2x2& inverseMassMatrix) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mInverseMassMatrixTranslation[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
}
// Return the rotation inverse mass matrix of the constraint
inline Matrix3x3& SliderJointComponents::getInverseMassMatrixRotation(Entity jointEntity) {
RP3D_FORCE_INLINE Matrix3x3& SliderJointComponents::getInverseMassMatrixRotation(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mInverseMassMatrixRotation[mMapEntityToComponentIndex[jointEntity]];
}
// Set the rotation inverse mass matrix of the constraint
inline void SliderJointComponents::setInverseMassMatrixRotation(Entity jointEntity, const Matrix3x3& inverseMassMatrix) {
RP3D_FORCE_INLINE void SliderJointComponents::setInverseMassMatrixRotation(Entity jointEntity, const Matrix3x3& inverseMassMatrix) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mInverseMassMatrixRotation[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
}
// Return the translation bias
inline Vector2& SliderJointComponents::getBiasTranslation(Entity jointEntity) {
RP3D_FORCE_INLINE Vector2& SliderJointComponents::getBiasTranslation(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mBiasTranslation[mMapEntityToComponentIndex[jointEntity]];
}
// Set the translation impulse
inline void SliderJointComponents::setBiasTranslation(Entity jointEntity, const Vector2& impulseTranslation) {
RP3D_FORCE_INLINE void SliderJointComponents::setBiasTranslation(Entity jointEntity, const Vector2& impulseTranslation) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mBiasTranslation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
}
// Return the rotation bias
inline Vector3& SliderJointComponents::getBiasRotation(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& SliderJointComponents::getBiasRotation(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mBiasRotation[mMapEntityToComponentIndex[jointEntity]];
}
// Set the rotation impulse
inline void SliderJointComponents::setBiasRotation(Entity jointEntity, const Vector3& impulseRotation) {
RP3D_FORCE_INLINE void SliderJointComponents::setBiasRotation(Entity jointEntity, const Vector3& impulseRotation) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mBiasRotation[mMapEntityToComponentIndex[jointEntity]] = impulseRotation;
}
// Return the initial orientation difference
inline Quaternion& SliderJointComponents::getInitOrientationDifferenceInv(Entity jointEntity) {
RP3D_FORCE_INLINE Quaternion& SliderJointComponents::getInitOrientationDifferenceInv(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mInitOrientationDifferenceInv[mMapEntityToComponentIndex[jointEntity]];
}
// Set the rotation impulse
inline void SliderJointComponents::setInitOrientationDifferenceInv(Entity jointEntity, const Quaternion& initOrientationDifferenceInv) {
RP3D_FORCE_INLINE void SliderJointComponents::setInitOrientationDifferenceInv(Entity jointEntity, const Quaternion& initOrientationDifferenceInv) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mInitOrientationDifferenceInv[mMapEntityToComponentIndex[jointEntity]] = initOrientationDifferenceInv;
}
// Return the slider axis (in local-space coordinates of body 1)
inline Vector3& SliderJointComponents::getSliderAxisBody1(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& SliderJointComponents::getSliderAxisBody1(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mSliderAxisBody1[mMapEntityToComponentIndex[jointEntity]];
}
// Set the slider axis (in local-space coordinates of body 1)
inline void SliderJointComponents::setSliderAxisBody1(Entity jointEntity, const Vector3& sliderAxisBody1) {
RP3D_FORCE_INLINE void SliderJointComponents::setSliderAxisBody1(Entity jointEntity, const Vector3& sliderAxisBody1) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mSliderAxisBody1[mMapEntityToComponentIndex[jointEntity]] = sliderAxisBody1;
}
// Retunr the slider axis in world-space coordinates
inline Vector3& SliderJointComponents::getSliderAxisWorld(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& SliderJointComponents::getSliderAxisWorld(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mSliderAxisWorld[mMapEntityToComponentIndex[jointEntity]];
}
// Set the slider axis in world-space coordinates
inline void SliderJointComponents::setSliderAxisWorld(Entity jointEntity, const Vector3& sliderAxisWorld) {
RP3D_FORCE_INLINE void SliderJointComponents::setSliderAxisWorld(Entity jointEntity, const Vector3& sliderAxisWorld) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mSliderAxisWorld[mMapEntityToComponentIndex[jointEntity]] = sliderAxisWorld;
}
// Return the vector r1 in world-space coordinates
inline Vector3& SliderJointComponents::getR1(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& SliderJointComponents::getR1(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mR1[mMapEntityToComponentIndex[jointEntity]];
}
// Set the vector r1 in world-space coordinates
inline void SliderJointComponents::setR1(Entity jointEntity, const Vector3& r1) {
RP3D_FORCE_INLINE void SliderJointComponents::setR1(Entity jointEntity, const Vector3& r1) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mR1[mMapEntityToComponentIndex[jointEntity]] = r1;
}
// Return the vector r2 in world-space coordinates
inline Vector3& SliderJointComponents::getR2(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& SliderJointComponents::getR2(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mR2[mMapEntityToComponentIndex[jointEntity]];
}
// Set the vector r2 in world-space coordinates
inline void SliderJointComponents::setR2(Entity jointEntity, const Vector3& r2) {
RP3D_FORCE_INLINE void SliderJointComponents::setR2(Entity jointEntity, const Vector3& r2) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mR2[mMapEntityToComponentIndex[jointEntity]] = r2;
}
// Return the first vector orthogonal to the slider axis local-space of body 1
inline Vector3& SliderJointComponents::getN1(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& SliderJointComponents::getN1(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mN1[mMapEntityToComponentIndex[jointEntity]];
}
// Set the first vector orthogonal to the slider axis local-space of body 1
inline void SliderJointComponents::setN1(Entity jointEntity, const Vector3& n1) {
RP3D_FORCE_INLINE void SliderJointComponents::setN1(Entity jointEntity, const Vector3& n1) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mN1[mMapEntityToComponentIndex[jointEntity]] = n1;
}
// Return the second vector orthogonal to the slider axis and mN1 in local-space of body 1
inline Vector3& SliderJointComponents::getN2(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& SliderJointComponents::getN2(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mN2[mMapEntityToComponentIndex[jointEntity]];
}
// Set the second vector orthogonal to the slider axis and mN1 in local-space of body 1
inline void SliderJointComponents::setN2(Entity jointEntity, const Vector3& n2) {
RP3D_FORCE_INLINE void SliderJointComponents::setN2(Entity jointEntity, const Vector3& n2) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mN2[mMapEntityToComponentIndex[jointEntity]] = n2;
}
// Return the accumulated impulse for the lower limit constraint
inline decimal SliderJointComponents::getImpulseLowerLimit(Entity jointEntity) const {
RP3D_FORCE_INLINE decimal SliderJointComponents::getImpulseLowerLimit(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mImpulseLowerLimit[mMapEntityToComponentIndex[jointEntity]];
}
// Set the accumulated impulse for the lower limit constraint
inline void SliderJointComponents::setImpulseLowerLimit(Entity jointEntity, decimal impulseLowerLimit) {
RP3D_FORCE_INLINE void SliderJointComponents::setImpulseLowerLimit(Entity jointEntity, decimal impulseLowerLimit) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mImpulseLowerLimit[mMapEntityToComponentIndex[jointEntity]] = impulseLowerLimit;
@ -727,14 +727,14 @@ inline void SliderJointComponents::setImpulseLowerLimit(Entity jointEntity, deci
// Return the accumulated impulse for the upper limit constraint
inline decimal SliderJointComponents::getImpulseUpperLimit(Entity jointEntity) const {
RP3D_FORCE_INLINE decimal SliderJointComponents::getImpulseUpperLimit(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mImpulseUpperLimit[mMapEntityToComponentIndex[jointEntity]];
}
// Set the accumulated impulse for the upper limit constraint
inline void SliderJointComponents::setImpulseUpperLimit(Entity jointEntity, decimal impulseUpperLimit) const {
RP3D_FORCE_INLINE void SliderJointComponents::setImpulseUpperLimit(Entity jointEntity, decimal impulseUpperLimit) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mImpulseUpperLimit[mMapEntityToComponentIndex[jointEntity]] = impulseUpperLimit;
@ -742,266 +742,266 @@ inline void SliderJointComponents::setImpulseUpperLimit(Entity jointEntity, deci
// Return the accumulated impulse for the motor constraint;
inline decimal SliderJointComponents::getImpulseMotor(Entity jointEntity) const {
RP3D_FORCE_INLINE decimal SliderJointComponents::getImpulseMotor(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mImpulseMotor[mMapEntityToComponentIndex[jointEntity]];
}
// Set the accumulated impulse for the motor constraint;
inline void SliderJointComponents::setImpulseMotor(Entity jointEntity, decimal impulseMotor) {
RP3D_FORCE_INLINE void SliderJointComponents::setImpulseMotor(Entity jointEntity, decimal impulseMotor) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mImpulseMotor[mMapEntityToComponentIndex[jointEntity]] = impulseMotor;
}
// Return the inverse of mass matrix K=JM^-1J^t for the limits (1x1 matrix)
inline decimal SliderJointComponents::getInverseMassMatrixLimit(Entity jointEntity) const {
RP3D_FORCE_INLINE decimal SliderJointComponents::getInverseMassMatrixLimit(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mInverseMassMatrixLimit[mMapEntityToComponentIndex[jointEntity]];
}
// Set the inverse of mass matrix K=JM^-1J^t for the limits (1x1 matrix)
inline void SliderJointComponents::setInverseMassMatrixLimit(Entity jointEntity, decimal inverseMassMatrixLimitMotor) {
RP3D_FORCE_INLINE void SliderJointComponents::setInverseMassMatrixLimit(Entity jointEntity, decimal inverseMassMatrixLimitMotor) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mInverseMassMatrixLimit[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrixLimitMotor;
}
// Return the inverse of mass matrix K=JM^-1J^t for the motor
inline decimal SliderJointComponents::getInverseMassMatrixMotor(Entity jointEntity) {
RP3D_FORCE_INLINE decimal SliderJointComponents::getInverseMassMatrixMotor(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mInverseMassMatrixMotor[mMapEntityToComponentIndex[jointEntity]];
}
// Return the inverse of mass matrix K=JM^-1J^t for the motor
inline void SliderJointComponents::setInverseMassMatrixMotor(Entity jointEntity, decimal inverseMassMatrixMotor) {
RP3D_FORCE_INLINE void SliderJointComponents::setInverseMassMatrixMotor(Entity jointEntity, decimal inverseMassMatrixMotor) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mInverseMassMatrixMotor[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrixMotor;
}
// Return the bias of the lower limit constraint
inline decimal SliderJointComponents::getBLowerLimit(Entity jointEntity) const {
RP3D_FORCE_INLINE decimal SliderJointComponents::getBLowerLimit(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mBLowerLimit[mMapEntityToComponentIndex[jointEntity]];
}
// Set the bias of the lower limit constraint
inline void SliderJointComponents::setBLowerLimit(Entity jointEntity, decimal bLowerLimit) const {
RP3D_FORCE_INLINE void SliderJointComponents::setBLowerLimit(Entity jointEntity, decimal bLowerLimit) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mBLowerLimit[mMapEntityToComponentIndex[jointEntity]] = bLowerLimit;
}
// Return the bias of the upper limit constraint
inline decimal SliderJointComponents::getBUpperLimit(Entity jointEntity) const {
RP3D_FORCE_INLINE decimal SliderJointComponents::getBUpperLimit(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mBUpperLimit[mMapEntityToComponentIndex[jointEntity]];
}
// Set the bias of the upper limit constraint
inline void SliderJointComponents::setBUpperLimit(Entity jointEntity, decimal bUpperLimit) {
RP3D_FORCE_INLINE void SliderJointComponents::setBUpperLimit(Entity jointEntity, decimal bUpperLimit) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mBUpperLimit[mMapEntityToComponentIndex[jointEntity]] = bUpperLimit;
}
// Return true if the joint limits are enabled
inline bool SliderJointComponents::getIsLimitEnabled(Entity jointEntity) const {
RP3D_FORCE_INLINE bool SliderJointComponents::getIsLimitEnabled(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mIsLimitEnabled[mMapEntityToComponentIndex[jointEntity]];
}
// Set to true if the joint limits are enabled
inline void SliderJointComponents::setIsLimitEnabled(Entity jointEntity, bool isLimitEnabled) {
RP3D_FORCE_INLINE void SliderJointComponents::setIsLimitEnabled(Entity jointEntity, bool isLimitEnabled) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mIsLimitEnabled[mMapEntityToComponentIndex[jointEntity]] = isLimitEnabled;
}
// Return true if the motor of the joint in enabled
inline bool SliderJointComponents::getIsMotorEnabled(Entity jointEntity) const {
RP3D_FORCE_INLINE bool SliderJointComponents::getIsMotorEnabled(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mIsMotorEnabled[mMapEntityToComponentIndex[jointEntity]];
}
// Set to true if the motor of the joint in enabled
inline void SliderJointComponents::setIsMotorEnabled(Entity jointEntity, bool isMotorEnabled) const {
RP3D_FORCE_INLINE void SliderJointComponents::setIsMotorEnabled(Entity jointEntity, bool isMotorEnabled) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mIsMotorEnabled[mMapEntityToComponentIndex[jointEntity]] = isMotorEnabled;
}
// Return the Lower limit (minimum allowed rotation angle in radian)
inline decimal SliderJointComponents::getLowerLimit(Entity jointEntity) const {
RP3D_FORCE_INLINE decimal SliderJointComponents::getLowerLimit(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mLowerLimit[mMapEntityToComponentIndex[jointEntity]];
}
// Set the Lower limit (minimum allowed rotation angle in radian)
inline void SliderJointComponents::setLowerLimit(Entity jointEntity, decimal lowerLimit) const {
RP3D_FORCE_INLINE void SliderJointComponents::setLowerLimit(Entity jointEntity, decimal lowerLimit) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mLowerLimit[mMapEntityToComponentIndex[jointEntity]] = lowerLimit;
}
// Return the upper limit (maximum translation distance)
inline decimal SliderJointComponents::getUpperLimit(Entity jointEntity) const {
RP3D_FORCE_INLINE decimal SliderJointComponents::getUpperLimit(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mUpperLimit[mMapEntityToComponentIndex[jointEntity]];
}
// Set the upper limit (maximum translation distance)
inline void SliderJointComponents::setUpperLimit(Entity jointEntity, decimal upperLimit) {
RP3D_FORCE_INLINE void SliderJointComponents::setUpperLimit(Entity jointEntity, decimal upperLimit) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mUpperLimit[mMapEntityToComponentIndex[jointEntity]] = upperLimit;
}
// Return true if the lower limit is violated
inline bool SliderJointComponents::getIsLowerLimitViolated(Entity jointEntity) const {
RP3D_FORCE_INLINE bool SliderJointComponents::getIsLowerLimitViolated(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mIsLowerLimitViolated[mMapEntityToComponentIndex[jointEntity]];
}
// Set to true if the lower limit is violated
inline void SliderJointComponents::setIsLowerLimitViolated(Entity jointEntity, bool isLowerLimitViolated) {
RP3D_FORCE_INLINE void SliderJointComponents::setIsLowerLimitViolated(Entity jointEntity, bool isLowerLimitViolated) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mIsLowerLimitViolated[mMapEntityToComponentIndex[jointEntity]] = isLowerLimitViolated;
}
// Return true if the upper limit is violated
inline bool SliderJointComponents::getIsUpperLimitViolated(Entity jointEntity) const {
RP3D_FORCE_INLINE bool SliderJointComponents::getIsUpperLimitViolated(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mIsUpperLimitViolated[mMapEntityToComponentIndex[jointEntity]];
}
// Set to true if the upper limit is violated
inline void SliderJointComponents::setIsUpperLimitViolated(Entity jointEntity, bool isUpperLimitViolated) const {
RP3D_FORCE_INLINE void SliderJointComponents::setIsUpperLimitViolated(Entity jointEntity, bool isUpperLimitViolated) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mIsUpperLimitViolated[mMapEntityToComponentIndex[jointEntity]] = isUpperLimitViolated;
}
// Return the motor speed (in rad/s)
inline decimal SliderJointComponents::getMotorSpeed(Entity jointEntity) const {
RP3D_FORCE_INLINE decimal SliderJointComponents::getMotorSpeed(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mMotorSpeed[mMapEntityToComponentIndex[jointEntity]];
}
// Set the motor speed (in rad/s)
inline void SliderJointComponents::setMotorSpeed(Entity jointEntity, decimal motorSpeed) {
RP3D_FORCE_INLINE void SliderJointComponents::setMotorSpeed(Entity jointEntity, decimal motorSpeed) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mMotorSpeed[mMapEntityToComponentIndex[jointEntity]] = motorSpeed;
}
// Return the maximum motor torque (in Newtons) that can be applied to reach to desired motor speed
inline decimal SliderJointComponents::getMaxMotorForce(Entity jointEntity) const {
RP3D_FORCE_INLINE decimal SliderJointComponents::getMaxMotorForce(Entity jointEntity) const {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mMaxMotorForce[mMapEntityToComponentIndex[jointEntity]];
}
// Set the maximum motor torque (in Newtons) that can be applied to reach to desired motor speed
inline void SliderJointComponents::setMaxMotorForce(Entity jointEntity, decimal maxMotorForce) {
RP3D_FORCE_INLINE void SliderJointComponents::setMaxMotorForce(Entity jointEntity, decimal maxMotorForce) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mMaxMotorForce[mMapEntityToComponentIndex[jointEntity]] = maxMotorForce;
}
// Return the cross product of r2 and n1
inline Vector3& SliderJointComponents::getR2CrossN1(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& SliderJointComponents::getR2CrossN1(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mR2CrossN1[mMapEntityToComponentIndex[jointEntity]];
}
// Set the cross product of r2 and n1
inline void SliderJointComponents::setR2CrossN1(Entity jointEntity, const Vector3& r2CrossN1) {
RP3D_FORCE_INLINE void SliderJointComponents::setR2CrossN1(Entity jointEntity, const Vector3& r2CrossN1) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mR2CrossN1[mMapEntityToComponentIndex[jointEntity]] = r2CrossN1;
}
// Return the cross product of r2 and n2
inline Vector3& SliderJointComponents::getR2CrossN2(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& SliderJointComponents::getR2CrossN2(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mR2CrossN2[mMapEntityToComponentIndex[jointEntity]];
}
// Set the cross product of r2 and n2
inline void SliderJointComponents::setR2CrossN2(Entity jointEntity, const Vector3& r2CrossN2) {
RP3D_FORCE_INLINE void SliderJointComponents::setR2CrossN2(Entity jointEntity, const Vector3& r2CrossN2) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mR2CrossN2[mMapEntityToComponentIndex[jointEntity]] = r2CrossN2;
}
// Return the cross product of r2 and the slider axis
inline Vector3& SliderJointComponents::getR2CrossSliderAxis(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& SliderJointComponents::getR2CrossSliderAxis(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mR2CrossSliderAxis[mMapEntityToComponentIndex[jointEntity]];
}
// Set the cross product of r2 and the slider axis
inline void SliderJointComponents::setR2CrossSliderAxis(Entity jointEntity, const Vector3& r2CrossSliderAxis) {
RP3D_FORCE_INLINE void SliderJointComponents::setR2CrossSliderAxis(Entity jointEntity, const Vector3& r2CrossSliderAxis) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mR2CrossSliderAxis[mMapEntityToComponentIndex[jointEntity]] = r2CrossSliderAxis;
}
// Return the cross product of vector (r1 + u) and n1
inline Vector3& SliderJointComponents::getR1PlusUCrossN1(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& SliderJointComponents::getR1PlusUCrossN1(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mR1PlusUCrossN1[mMapEntityToComponentIndex[jointEntity]];
}
// Set the cross product of vector (r1 + u) and n1
inline void SliderJointComponents::setR1PlusUCrossN1(Entity jointEntity, const Vector3& r1PlusUCrossN1) {
RP3D_FORCE_INLINE void SliderJointComponents::setR1PlusUCrossN1(Entity jointEntity, const Vector3& r1PlusUCrossN1) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mR1PlusUCrossN1[mMapEntityToComponentIndex[jointEntity]] = r1PlusUCrossN1;
}
// Return the cross product of vector (r1 + u) and n2
inline Vector3& SliderJointComponents::getR1PlusUCrossN2(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& SliderJointComponents::getR1PlusUCrossN2(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mR1PlusUCrossN2[mMapEntityToComponentIndex[jointEntity]];
}
// Set the cross product of vector (r1 + u) and n2
inline void SliderJointComponents::setR1PlusUCrossN2(Entity jointEntity, const Vector3& r1PlusUCrossN2) {
RP3D_FORCE_INLINE void SliderJointComponents::setR1PlusUCrossN2(Entity jointEntity, const Vector3& r1PlusUCrossN2) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mR1PlusUCrossN2[mMapEntityToComponentIndex[jointEntity]] = r1PlusUCrossN2;
}
// Return the cross product of vector (r1 + u) and the slider axis
inline Vector3& SliderJointComponents::getR1PlusUCrossSliderAxis(Entity jointEntity) {
RP3D_FORCE_INLINE Vector3& SliderJointComponents::getR1PlusUCrossSliderAxis(Entity jointEntity) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
return mR1PlusUCrossSliderAxis[mMapEntityToComponentIndex[jointEntity]];
}
// Set the cross product of vector (r1 + u) and the slider axis
inline void SliderJointComponents::setR1PlusUCrossSliderAxis(Entity jointEntity, const Vector3& r1PlusUCrossSliderAxis) {
RP3D_FORCE_INLINE void SliderJointComponents::setR1PlusUCrossSliderAxis(Entity jointEntity, const Vector3& r1PlusUCrossSliderAxis) {
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
mR1PlusUCrossSliderAxis[mMapEntityToComponentIndex[jointEntity]] = r1PlusUCrossSliderAxis;

View File

@ -107,13 +107,13 @@ class TransformComponents : public Components {
};
// Return the transform of an entity
inline Transform& TransformComponents::getTransform(Entity bodyEntity) const {
RP3D_FORCE_INLINE Transform& TransformComponents::getTransform(Entity bodyEntity) const {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
return mTransforms[mMapEntityToComponentIndex[bodyEntity]];
}
// Set the transform of an entity
inline void TransformComponents::setTransform(Entity bodyEntity, const Transform& transform) {
RP3D_FORCE_INLINE void TransformComponents::setTransform(Entity bodyEntity, const Transform& transform) {
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
mTransforms[mMapEntityToComponentIndex[bodyEntity]] = transform;
}

View File

@ -35,15 +35,35 @@
#include <reactphysics3d/decimal.h>
#include <reactphysics3d/containers/Pair.h>
// Windows platform
// Platforms
#if defined(WIN32) ||defined(_WIN32) || defined(_WIN64) ||defined(__WIN32__) || defined(__WINDOWS__)
#define WINDOWS_OS
#elif defined(__APPLE__) // Apple platform
#elif defined(__APPLE__)
#define APPLE_OS
#elif defined(__linux__) || defined(linux) || defined(__linux) // Linux platform
#define LINUX_OS
#endif
// Compilers
#if defined(_MSC_VER)
#define RP3D_COMPILER_VISUAL_STUDIO
#elif defined(__clang__)
#define RP3D_COMPILER_CLANG
#elif defined(__GNUC__)
#define RP3D_COMPILER_GCC
#else
#define RP3D_COMPILER_UNKNOWN
#endif
// Force RP3D_FORCE_INLINE macro
#if defined(RP3D_COMPILER_VISUAL_STUDIO)
#define RP3D_FORCE_INLINE __forceinline
#elif defined(RP3D_COMPILER_GCC) || defined(RP3D_COMPILER_CLANG)
#define RP3D_FORCE_INLINE inline __attribute__((always_inline))
#else
#define RP3D_FORCE_INLINE inline
#endif
/// Namespace reactphysics3d
namespace reactphysics3d {
@ -103,6 +123,18 @@ constexpr decimal PI_TIMES_2 = decimal(6.28318530);
/// without triggering a large modification of the tree each frame which can be costly
constexpr decimal DYNAMIC_TREE_FAT_AABB_INFLATE_PERCENTAGE = decimal(0.08);
/// Maximum number of contact points in a narrow phase info object
constexpr uint8 NB_MAX_CONTACT_POINTS_IN_NARROWPHASE_INFO = 16;
/// Maximum number of contact manifolds in an overlapping pair
constexpr uint8 NB_MAX_CONTACT_MANIFOLDS = 3;
/// Maximum number of potential contact manifolds in an overlapping pair
constexpr uint8 NB_MAX_POTENTIAL_CONTACT_MANIFOLDS = 4 * NB_MAX_CONTACT_MANIFOLDS;
/// Maximum number of contact points in potential contact manifold
constexpr uint8 NB_MAX_CONTACT_POINTS_IN_POTENTIAL_MANIFOLD = 16;
/// Current version of ReactPhysics3D
const std::string RP3D_VERSION = std::string("0.8.0");

View File

@ -129,7 +129,7 @@ class BallAndSocketJoint : public Joint {
};
// Return the number of bytes used by the joint
inline size_t BallAndSocketJoint::getSizeInBytes() const {
RP3D_FORCE_INLINE size_t BallAndSocketJoint::getSizeInBytes() const {
return sizeof(BallAndSocketJoint);
}

View File

@ -144,7 +144,7 @@ class ContactPoint {
/**
* @return The contact normal
*/
inline const Vector3& ContactPoint::getNormal() const {
RP3D_FORCE_INLINE const Vector3& ContactPoint::getNormal() const {
return mNormal;
}
@ -152,7 +152,7 @@ inline const Vector3& ContactPoint::getNormal() const {
/**
* @return The contact point on the first collider in the local-space of the collider
*/
inline const Vector3& ContactPoint::getLocalPointOnShape1() const {
RP3D_FORCE_INLINE const Vector3& ContactPoint::getLocalPointOnShape1() const {
return mLocalPointOnShape1;
}
@ -160,7 +160,7 @@ inline const Vector3& ContactPoint::getLocalPointOnShape1() const {
/**
* @return The contact point on the second collider in the local-space of the collider
*/
inline const Vector3& ContactPoint::getLocalPointOnShape2() const {
RP3D_FORCE_INLINE const Vector3& ContactPoint::getLocalPointOnShape2() const {
return mLocalPointOnShape2;
}
@ -168,12 +168,12 @@ inline const Vector3& ContactPoint::getLocalPointOnShape2() const {
/**
* @return The penetration impulse
*/
inline decimal ContactPoint::getPenetrationImpulse() const {
RP3D_FORCE_INLINE decimal ContactPoint::getPenetrationImpulse() const {
return mPenetrationImpulse;
}
// Return true if the contact point is similar (close enougth) to another given contact point
inline bool ContactPoint::isSimilarWithContactPoint(const ContactPointInfo* localContactPointBody1) const {
RP3D_FORCE_INLINE bool ContactPoint::isSimilarWithContactPoint(const ContactPointInfo* localContactPointBody1) const {
return (localContactPointBody1->localPoint1 - mLocalPointOnShape1).lengthSquare() <= (mPersistentContactDistanceThreshold *
mPersistentContactDistanceThreshold);
}
@ -182,7 +182,7 @@ inline bool ContactPoint::isSimilarWithContactPoint(const ContactPointInfo* loca
/**
* @param impulse Penetration impulse
*/
inline void ContactPoint::setPenetrationImpulse(decimal impulse) {
RP3D_FORCE_INLINE void ContactPoint::setPenetrationImpulse(decimal impulse) {
mPenetrationImpulse = impulse;
}
@ -190,7 +190,7 @@ inline void ContactPoint::setPenetrationImpulse(decimal impulse) {
/**
* @return True if it is a resting contact
*/
inline bool ContactPoint::getIsRestingContact() const {
RP3D_FORCE_INLINE bool ContactPoint::getIsRestingContact() const {
return mIsRestingContact;
}
@ -198,7 +198,7 @@ inline bool ContactPoint::getIsRestingContact() const {
/**
* @param isRestingContact True if it is a resting contact
*/
inline void ContactPoint::setIsRestingContact(bool isRestingContact) {
RP3D_FORCE_INLINE void ContactPoint::setIsRestingContact(bool isRestingContact) {
mIsRestingContact = isRestingContact;
}
@ -206,7 +206,7 @@ inline void ContactPoint::setIsRestingContact(bool isRestingContact) {
/**
* @return the penetration depth (in meters)
*/
inline decimal ContactPoint::getPenetrationDepth() const {
RP3D_FORCE_INLINE decimal ContactPoint::getPenetrationDepth() const {
return mPenetrationDepth;
}
@ -214,7 +214,7 @@ inline decimal ContactPoint::getPenetrationDepth() const {
/**
* @return The size of the contact point in memory (in bytes)
*/
inline size_t ContactPoint::getSizeInBytes() const {
RP3D_FORCE_INLINE size_t ContactPoint::getSizeInBytes() const {
return sizeof(ContactPoint);
}

View File

@ -119,7 +119,7 @@ class FixedJoint : public Joint {
};
// Return the number of bytes used by the joint
inline size_t FixedJoint::getSizeInBytes() const {
RP3D_FORCE_INLINE size_t FixedJoint::getSizeInBytes() const {
return sizeof(FixedJoint);
}

View File

@ -311,6 +311,9 @@ class HingeJoint : public Joint {
/// Return the intensity of the current torque applied for the joint motor
decimal getMotorTorque(decimal timeStep) const;
/// Return the current hinge angle
decimal getAngle() const;
/// Return a string representation
virtual std::string to_string() const override;
};

View File

@ -157,7 +157,7 @@ class Joint {
/**
* @return The entity of the joint
*/
inline Entity Joint::getEntity() const {
RP3D_FORCE_INLINE Entity Joint::getEntity() const {
return mEntity;
}

View File

@ -309,7 +309,7 @@ class SliderJoint : public Joint {
};
// Return the number of bytes used by the joint
inline size_t SliderJoint::getSizeInBytes() const {
RP3D_FORCE_INLINE size_t SliderJoint::getSizeInBytes() const {
return sizeof(SliderJoint);
}

View File

@ -23,8 +23,8 @@
* *
********************************************************************************/
#ifndef REACTPHYSICS3D_LIST_H
#define REACTPHYSICS3D_LIST_H
#ifndef REACTPHYSICS3D_ARRAY_H
#define REACTPHYSICS3D_ARRAY_H
// Libraries
#include <reactphysics3d/configuration.h>
@ -36,25 +36,25 @@
namespace reactphysics3d {
// Class List
// Class Array
/**
* This class represents a simple generic list with custom memory allocator.
* This class represents a simple dynamic array with custom memory allocator.
*/
template<typename T>
class List {
class Array {
private:
// -------------------- Attributes -------------------- //
/// Buffer for the list elements
void* mBuffer;
/// Buffer for the array elements
T* mBuffer;
/// Number of elements in the list
size_t mSize;
/// Number of elements in the array
uint32 mSize;
/// Number of allocated elements in the list
size_t mCapacity;
/// Number of allocated elements in the array
uint32 mCapacity;
/// Memory allocator
MemoryAllocator& mAllocator;
@ -63,15 +63,15 @@ class List {
/// Class Iterator
/**
* This class represents an iterator for the List
* This class represents an iterator for the array
*/
class Iterator {
private:
size_t mCurrentIndex;
uint32 mCurrentIndex;
T* mBuffer;
size_t mSize;
uint32 mSize;
public:
@ -88,7 +88,7 @@ class List {
Iterator() = default;
/// Constructor
Iterator(void* buffer, size_t index, size_t size)
Iterator(void* buffer, uint32 index, uint32 size)
:mCurrentIndex(index), mBuffer(static_cast<T*>(buffer)), mSize(size) {
}
@ -198,7 +198,7 @@ class List {
bool operator==(const Iterator& iterator) const {
assert(mCurrentIndex >= 0 && mCurrentIndex <= mSize);
// If both iterators points to the end of the list
// If both iterators points to the end of the array
if (mCurrentIndex == mSize && iterator.mCurrentIndex == iterator.mSize) {
return true;
}
@ -212,14 +212,14 @@ class List {
}
/// Frienship
friend class List;
friend class Array;
};
// -------------------- Methods -------------------- //
/// Constructor
List(MemoryAllocator& allocator, size_t capacity = 0)
Array(MemoryAllocator& allocator, uint32 capacity = 0)
: mBuffer(nullptr), mSize(0), mCapacity(0), mAllocator(allocator) {
if (capacity > 0) {
@ -230,43 +230,47 @@ class List {
}
/// Copy constructor
List(const List<T>& list) : mBuffer(nullptr), mSize(0), mCapacity(0), mAllocator(list.mAllocator) {
Array(const Array<T>& array) : mBuffer(nullptr), mSize(0), mCapacity(0), mAllocator(array.mAllocator) {
// All all the elements of the list to the current one
addRange(list);
// If we need to allocate more memory
if (array.mCapacity > 0) {
reserve(array.mCapacity);
}
// All all the elements of the array to the current one
addRange(array);
}
/// Destructor
~List() {
~Array() {
// If elements have been allocated
if (mCapacity > 0) {
// Clear the list
// Clear the array
clear(true);
}
}
/// Allocate memory for a given number of elements
void reserve(size_t capacity) {
void reserve(uint32 capacity) {
if (capacity <= mCapacity) return;
// Allocate memory for the new array
void* newMemory = mAllocator.allocate(capacity * sizeof(T));
T* destination = static_cast<T*>(newMemory);
if (mBuffer != nullptr) {
if (mSize > 0) {
// Copy the elements to the new allocated memory location
T* destination = static_cast<T*>(newMemory);
T* items = static_cast<T*>(mBuffer);
std::uninitialized_copy(items, items + mSize, destination);
std::uninitialized_copy(mBuffer, mBuffer + mSize, destination);
// Destruct the previous items
for (size_t i=0; i<mSize; i++) {
items[i].~T();
for (uint32 i=0; i<mSize; i++) {
mBuffer[i].~T();
}
}
@ -274,13 +278,13 @@ class List {
mAllocator.release(mBuffer, mCapacity * sizeof(T));
}
mBuffer = newMemory;
mBuffer = destination;
assert(mBuffer != nullptr);
mCapacity = capacity;
}
/// Add an element into the list
/// Add an element into the array
void add(const T& element) {
// If we need to allocate more memory
@ -288,30 +292,45 @@ class List {
reserve(mCapacity == 0 ? 1 : mCapacity * 2);
}
// Use the copy-constructor to construct the element
new (static_cast<char*>(mBuffer) + mSize * sizeof(T)) T(element);
// Use the constructor to construct the element
new (reinterpret_cast<void*>(mBuffer + mSize)) T(element);
mSize++;
}
/// Add a given numbers of elements at the end of the list but do not init them
void addWithoutInit(uint nbElements) {
/// Add an element into the array by constructing it directly into the array (in order to avoid a copy)
template<typename...Ts>
void emplace(Ts&&... args) {
// If we need to allocate more memory
if (mSize == mCapacity) {
reserve(mCapacity == 0 ? 1 : mCapacity * 2);
}
// Construct the element directly at its location in the array
new (reinterpret_cast<void*>(mBuffer + mSize)) T(std::forward<Ts>(args)...);
mSize++;
}
/// Add a given numbers of elements at the end of the array but do not init them
void addWithoutInit(uint32 nbElements) {
// If we need to allocate more memory
if ((mSize + nbElements) > mCapacity) {
reserve(mCapacity == 0 ? nbElements : (mCapacity + nbElements) * 2);
}
mSize += nbElements;
}
/// Try to find a given item of the list and return an iterator
/// pointing to that element if it exists in the list. Otherwise,
/// Try to find a given item of the array and return an iterator
/// pointing to that element if it exists in the array. Otherwise,
/// this method returns the end() iterator
Iterator find(const T& element) {
for (uint i=0; i<mSize; i++) {
if (element == static_cast<T*>(mBuffer)[i]) {
for (uint32 i=0; i<mSize; i++) {
if (element == mBuffer[i]) {
return Iterator(mBuffer, i, mSize);
}
}
@ -319,64 +338,80 @@ class List {
return end();
}
/// Look for an element in the list and remove it
/// Look for an element in the array and remove it
Iterator remove(const T& element) {
return remove(find(element));
}
/// Remove an element from the list and return a iterator
/// Remove an element from the array and return a iterator
/// pointing to the element after the removed one (or end() if none)
Iterator remove(const Iterator& it) {
assert(it.mBuffer == mBuffer);
return removeAt(it.mCurrentIndex);
}
/// Remove an element from the list at a given index (all the following items will be moved)
Iterator removeAt(uint index) {
/// Remove an element from the array at a given index (all the following items will be moved)
Iterator removeAt(uint32 index) {
assert(index >= 0 && index < mSize);
assert(index < mSize);
// Call the destructor
(static_cast<T*>(mBuffer)[index]).~T();
mBuffer[index].~T();
mSize--;
if (index != mSize) {
// Move the elements to fill in the empty slot
char* dest = static_cast<char*>(mBuffer) + index * sizeof(T);
char* src = dest + sizeof(T);
std::memmove(static_cast<void*>(dest), static_cast<void*>(src), (mSize - index) * sizeof(T));
void* dest = reinterpret_cast<void*>(mBuffer + index);
std::uintptr_t src = reinterpret_cast<std::uintptr_t>(dest) + sizeof(T);
std::memmove(dest, reinterpret_cast<const void*>(src), (mSize - index) * sizeof(T));
}
// Return an iterator pointing to the element after the removed one
return Iterator(mBuffer, index, mSize);
}
/// Append another list at the end of the current one
void addRange(const List<T>& list) {
/// Remove an element from the list at a given index and replace it by the last one of the list (if any)
void removeAtAndReplaceByLast(uint32 index) {
assert(index < mSize);
mBuffer[index] = mBuffer[mSize - 1];
// Call the destructor of the last element
mBuffer[mSize - 1].~T();
mSize--;
}
/// Remove an element from the array at a given index and replace it by the last one of the array (if any)
/// Append another array at the end of the current one
void addRange(const Array<T>& array, uint32 startIndex = 0) {
assert(startIndex <= array.size());
// If we need to allocate more memory
if (mSize + list.size() > mCapacity) {
if (mSize + (array.size() - startIndex) > mCapacity) {
// Allocate memory
reserve(mSize + list.size());
reserve(mSize + array.size() - startIndex);
}
// Add the elements of the list to the current one
for(uint i=0; i<list.size(); i++) {
// Add the elements of the array to the current one
for(uint32 i=startIndex; i<array.size(); i++) {
new (static_cast<char*>(mBuffer) + mSize * sizeof(T)) T(list[i]);
new (reinterpret_cast<void*>(mBuffer + mSize)) T(array[i]);
mSize++;
}
}
/// Clear the list
/// Clear the array
void clear(bool releaseMemory = false) {
// Call the destructor of each element
for (uint i=0; i < mSize; i++) {
(static_cast<T*>(mBuffer)[i]).~T();
for (uint32 i=0; i < mSize; i++) {
mBuffer[i].~T();
}
mSize = 0;
@ -392,36 +427,35 @@ class List {
}
}
/// Return the number of elements in the list
size_t size() const {
/// Return the number of elements in the array
uint32 size() const {
return mSize;
}
/// Return the capacity of the list
size_t capacity() const {
/// Return the capacity of the array
uint32 capacity() const {
return mCapacity;
}
/// Overloaded index operator
T& operator[](const uint index) {
T& operator[](const uint32 index) {
assert(index >= 0 && index < mSize);
return (static_cast<T*>(mBuffer)[index]);
return mBuffer[index];
}
/// Overloaded const index operator
const T& operator[](const uint index) const {
const T& operator[](const uint32 index) const {
assert(index >= 0 && index < mSize);
return (static_cast<T*>(mBuffer)[index]);
return mBuffer[index];
}
/// Overloaded equality operator
bool operator==(const List<T>& list) const {
bool operator==(const Array<T>& array) const {
if (mSize != list.mSize) return false;
if (mSize != array.mSize) return false;
T* items = static_cast<T*>(mBuffer);
for (size_t i=0; i < mSize; i++) {
if (items[i] != list[i]) {
for (uint32 i=0; i < mSize; i++) {
if (mBuffer[i] != array[i]) {
return false;
}
}
@ -430,21 +464,21 @@ class List {
}
/// Overloaded not equal operator
bool operator!=(const List<T>& list) const {
bool operator!=(const Array<T>& array) const {
return !((*this) == list);
return !((*this) == array);
}
/// Overloaded assignment operator
List<T>& operator=(const List<T>& list) {
Array<T>& operator=(const Array<T>& array) {
if (this != &list) {
if (this != &array) {
// Clear all the elements
clear();
// Add all the elements of the list to the current one
addRange(list);
// Add all the elements of the array to the current one
addRange(array);
}
return *this;

View File

@ -93,20 +93,20 @@ class LinkedList {
// Return the first element of the list
template<typename T>
inline typename LinkedList<T>::ListElement* LinkedList<T>::getListHead() const {
RP3D_FORCE_INLINE typename LinkedList<T>::ListElement* LinkedList<T>::getListHead() const {
return mListHead;
}
// Insert an element at the beginning of the linked list
template<typename T>
inline void LinkedList<T>::insert(const T& data) {
RP3D_FORCE_INLINE void LinkedList<T>::insert(const T& data) {
ListElement* element = new (mAllocator.allocate(sizeof(ListElement))) ListElement(data, mListHead);
mListHead = element;
}
// Remove all the elements of the list
template<typename T>
inline void LinkedList<T>::reset() {
RP3D_FORCE_INLINE void LinkedList<T>::reset() {
// Release all the list elements
ListElement* element = mListHead;

File diff suppressed because it is too large Load Diff

View File

@ -47,197 +47,59 @@ class Set {
private:
/// An entry of the set
struct Entry {
size_t hashCode; // Hash code of the entry
int next; // Index of the next entry
V* value; // Pointer to the value stored in the entry
/// Constructor
Entry() {
next = -1;
value = nullptr;
}
/// Constructor
Entry(size_t hashcode, int nextEntry) {
hashCode = hashcode;
next = nextEntry;
value = nullptr;
}
/// Copy-constructor
Entry(const Entry& entry) {
hashCode = entry.hashCode;
next = entry.next;
value = entry.value;
}
/// Destructor
~Entry() {
}
};
// -------------------- Constants -------------------- //
/// Number of prime numbers in array
static constexpr int NB_PRIMES = 70;
/// Default load factor
static constexpr float DEFAULT_LOAD_FACTOR = 0.75;
/// Array of prime numbers for the size of the set
static const int PRIMES[NB_PRIMES];
/// Largest prime number
static int LARGEST_PRIME;
/// Invalid index in the array
static constexpr uint32 INVALID_INDEX = 0xffffffff;
// -------------------- Attributes -------------------- //
/// Current number of used entries in the set
int mNbUsedEntries;
/// Total number of allocated entries
uint32 mNbAllocatedEntries;
/// Number of free entries among the used ones
int mNbFreeEntries;
/// Number of items in the set
uint32 mNbEntries;
/// Current capacity of the set
int mCapacity;
/// Number of buckets and size of the hash table (nbEntries = loadFactor * mHashSize)
uint32 mHashSize ;
/// Array with all the buckets
int* mBuckets;
uint32* mBuckets;
/// Array with all the entries
Entry* mEntries;
/// Array with all the entries (nbEntries = loadFactor * mHashSize)
V* mEntries;
/// For each entry, index of the next entry at the same bucket
uint32* mNextEntries;
/// Memory allocator
MemoryAllocator& mAllocator;
/// Index to the fist free entry
int mFreeIndex;
uint32 mFreeIndex;
// -------------------- Methods -------------------- //
/// Initialize the set
void initialize(int capacity) {
// Compute the next larger prime size
mCapacity = getPrimeSize(capacity);
// Allocate memory for the buckets
mBuckets = static_cast<int*>(mAllocator.allocate(mCapacity * sizeof(int)));
// Allocate memory for the entries
mEntries = static_cast<Entry*>(mAllocator.allocate(mCapacity * sizeof(Entry)));
// Initialize the buckets and entries
for (int i=0; i<mCapacity; i++) {
mBuckets[i] = -1;
// Construct the entry
new (&mEntries[i]) Entry();
}
mNbUsedEntries = 0;
mNbFreeEntries = 0;
mFreeIndex = -1;
}
/// Expand the capacity of the set
void expand(int newCapacity) {
assert(newCapacity > mCapacity);
assert(isPrimeNumber(newCapacity));
// Allocate memory for the buckets
int* newBuckets = static_cast<int*>(mAllocator.allocate(newCapacity * sizeof(int)));
// Allocate memory for the entries
Entry* newEntries = static_cast<Entry*>(mAllocator.allocate(newCapacity * sizeof(Entry)));
// Initialize the new buckets
for (int i=0; i<newCapacity; i++) {
newBuckets[i] = -1;
}
if (mNbUsedEntries > 0) {
// Copy the old entries to the new allocated memory location
std::uninitialized_copy(mEntries, mEntries + mNbUsedEntries, newEntries);
// Destruct the old entries at previous location
for (int i=0; i<mNbUsedEntries; i++) {
mEntries[i].~Entry();
}
}
// Construct the new entries
for (int i=mNbUsedEntries; i<newCapacity; i++) {
// Construct the entry
new (static_cast<void*>(&newEntries[i])) Entry();
}
// For each used entry
for (int i=0; i<mNbUsedEntries; i++) {
// If the entry is not free
if (newEntries[i].value != nullptr) {
// Get the corresponding bucket
int bucket = newEntries[i].hashCode % newCapacity;
newEntries[i].next = newBuckets[bucket];
newBuckets[bucket] = i;
}
}
// Release previously allocated memory
mAllocator.release(mBuckets, mCapacity * sizeof(int));
mAllocator.release(mEntries, mCapacity * sizeof(Entry));
mCapacity = newCapacity;
mBuckets = newBuckets;
mEntries = newEntries;
}
/// Return the index of the entry with a given value or -1 if there is no entry with this value
int findEntry(const V& value) const {
uint32 findEntry(const V& value) const {
if (mCapacity > 0) {
if (mHashSize > 0) {
size_t hashCode = Hash()(value);
int bucket = hashCode % mCapacity;
auto keyEqual = KeyEqual();
const size_t hashCode = Hash()(value);
const uint32 bucket = hashCode & (mHashSize - 1);
auto keyEqual = KeyEqual();
for (int i = mBuckets[bucket]; i >= 0; i = mEntries[i].next) {
if (mEntries[i].hashCode == hashCode && keyEqual(*mEntries[i].value, value)) {
for (uint32 i = mBuckets[bucket]; i != INVALID_INDEX; i = mNextEntries[i]) {
if (Hash()(mEntries[i]) == hashCode && keyEqual(mEntries[i], value)) {
return i;
}
}
}
return -1;
}
/// Return the prime number that is larger or equal to the number in parameter
/// for the size of the set
static int getPrimeSize(int number) {
// Check if the next larger prime number is in the precomputed array of primes
for (int i = 0; i < NB_PRIMES; i++) {
if (PRIMES[i] >= number) return PRIMES[i];
}
// Manually compute the next larger prime number
for (int i = (number | 1); i < std::numeric_limits<int>::max(); i+=2) {
if (isPrimeNumber(i)) {
return i;
}
}
return number;
return INVALID_INDEX;
}
public:
@ -250,36 +112,36 @@ class Set {
private:
/// Array of entries
const Entry* mEntries;
/// Pointer to the set
const Set* mSet;
/// Capacity of the map
int mCapacity;
/// Number of used entries in the map
int mNbUsedEntries;
/// Index of the current bucket
uint32 mCurrentBucketIndex;
/// Index of the current entry
int mCurrentEntry;
uint32 mCurrentEntryIndex;
/// Advance the iterator
void advance() {
// If we are trying to move past the end
assert(mCurrentEntry < mNbUsedEntries);
assert(mCurrentBucketIndex < mSet->mHashSize);
assert(mCurrentEntryIndex < mSet->mNbAllocatedEntries);
for (mCurrentEntry += 1; mCurrentEntry < mNbUsedEntries; mCurrentEntry++) {
// If the entry is not empty
if (mEntries[mCurrentEntry].value != nullptr) {
// We have found the next non empty entry
return;
}
// Try the next entry
if (mSet->mNextEntries[mCurrentEntryIndex] != INVALID_INDEX) {
mCurrentEntryIndex = mSet->mNextEntries[mCurrentEntryIndex];
return;
}
// We have not find a non empty entry, we return an iterator to the end
mCurrentEntry = mCapacity;
// Try to move to the next bucket
mCurrentEntryIndex = 0;
mCurrentBucketIndex++;
while(mCurrentBucketIndex < mSet->mHashSize && mSet->mBuckets[mCurrentBucketIndex] == INVALID_INDEX) {
mCurrentBucketIndex++;
}
if (mCurrentBucketIndex < mSet->mHashSize) {
mCurrentEntryIndex = mSet->mBuckets[mCurrentBucketIndex];
}
}
public:
@ -295,29 +157,29 @@ class Set {
Iterator() = default;
/// Constructor
Iterator(const Entry* entries, int capacity, int nbUsedEntries, int currentEntry)
:mEntries(entries), mCapacity(capacity), mNbUsedEntries(nbUsedEntries), mCurrentEntry(currentEntry) {
Iterator(const Set* set, uint32 bucketIndex, uint32 entryIndex)
:mSet(set), mCurrentBucketIndex(bucketIndex), mCurrentEntryIndex(entryIndex) {
}
/// Copy constructor
Iterator(const Iterator& it)
:mEntries(it.mEntries), mCapacity(it.mCapacity), mNbUsedEntries(it.mNbUsedEntries), mCurrentEntry(it.mCurrentEntry) {
:mSet(it.mSet), mCurrentBucketIndex(it.mCurrentBucketIndex), mCurrentEntryIndex(it.mCurrentEntryIndex) {
}
/// Deferencable
reference operator*() const {
assert(mCurrentEntry >= 0 && mCurrentEntry < mNbUsedEntries);
assert(mEntries[mCurrentEntry].value != nullptr);
return *(mEntries[mCurrentEntry].value);
assert(mCurrentEntryIndex < mSet->mNbAllocatedEntries);
assert(mCurrentEntryIndex != INVALID_INDEX);
return mSet->mEntries[mCurrentEntryIndex];
}
/// Deferencable
pointer operator->() const {
assert(mCurrentEntry >= 0 && mCurrentEntry < mNbUsedEntries);
assert(mEntries[mCurrentEntry].value != nullptr);
return mEntries[mCurrentEntry].value;
assert(mCurrentEntryIndex < mSet->mNbAllocatedEntries);
assert(mCurrentEntryIndex != INVALID_INDEX);
return &(mSet->mEntries[mCurrentEntryIndex]);
}
/// Post increment (it++)
@ -335,61 +197,71 @@ class Set {
/// Equality operator (it == end())
bool operator==(const Iterator& iterator) const {
return mCurrentEntry == iterator.mCurrentEntry && mEntries == iterator.mEntries;
return mCurrentBucketIndex == iterator.mCurrentBucketIndex && mCurrentEntryIndex == iterator.mCurrentEntryIndex && mSet == iterator.mSet;
}
/// Inequality operator (it != end())
bool operator!=(const Iterator& iterator) const {
return !(*this == iterator);
}
/// Overloaded assignment operator
Iterator& operator=(const Iterator& it) {
// Check for self assignment
if (this != &it) {
mSet = it.mSet;
mCurrentBucketIndex = it.mCurrentBucketIndex;
mCurrentEntryIndex = it.mCurrentEntryIndex;
}
return *this;
}
};
// -------------------- Methods -------------------- //
/// Constructor
Set(MemoryAllocator& allocator, size_t capacity = 0)
: mNbUsedEntries(0), mNbFreeEntries(0), mCapacity(0), mBuckets(nullptr),
mEntries(nullptr), mAllocator(allocator), mFreeIndex(-1) {
// If the largest prime has not been computed yet
if (LARGEST_PRIME == -1) {
// Compute the largest prime number (largest map capacity)
LARGEST_PRIME = getPrimeSize(PRIMES[NB_PRIMES - 1] + 2);
}
Set(MemoryAllocator& allocator, uint32 capacity = 0)
: mNbAllocatedEntries(0), mNbEntries(0), mHashSize(0), mBuckets(nullptr),
mEntries(nullptr), mNextEntries(nullptr), mAllocator(allocator), mFreeIndex(INVALID_INDEX) {
if (capacity > 0) {
initialize(capacity);
reserve(capacity);
}
}
/// Copy constructor
Set(const Set<V, Hash, KeyEqual>& set)
:mNbUsedEntries(set.mNbUsedEntries), mNbFreeEntries(set.mNbFreeEntries), mCapacity(set.mCapacity),
mBuckets(nullptr), mEntries(nullptr), mAllocator(set.mAllocator), mFreeIndex(set.mFreeIndex) {
:mNbAllocatedEntries(set.mNbAllocatedEntries), mNbEntries(set.mNbEntries), mHashSize(set.mHashSize),
mBuckets(nullptr), mEntries(nullptr), mNextEntries(nullptr), mAllocator(set.mAllocator), mFreeIndex(set.mFreeIndex) {
if (mCapacity > 0) {
// Allocate memory for the buckets
mBuckets = static_cast<uint32*>(mAllocator.allocate(mHashSize * sizeof(uint32)));
// Allocate memory for the buckets
mBuckets = static_cast<int*>(mAllocator.allocate(mCapacity * sizeof(int)));
// Allocate memory for the entries
mEntries = static_cast<V*>(mAllocator.allocate(mNbAllocatedEntries * sizeof(V)));
mNextEntries = static_cast<uint32*>(mAllocator.allocate(mNbAllocatedEntries * sizeof(uint32)));
// Allocate memory for the entries
mEntries = static_cast<Entry*>(mAllocator.allocate(mCapacity * sizeof(Entry)));
// Copy the buckets array
std::memcpy(mBuckets, set.mBuckets, mHashSize * sizeof(uint32));
// Copy the buckets
std::uninitialized_copy(set.mBuckets, set.mBuckets + mCapacity, mBuckets);
// Copy the next entries indices
std::memcpy(mNextEntries, set.mNextEntries, mNbAllocatedEntries * sizeof(uint32));
// Copy the entries
for (int i=0; i < mCapacity; i++) {
// Copy the entries
for (uint32 i=0; i<mHashSize; i++) {
new (&mEntries[i]) Entry(set.mEntries[i].hashCode, set.mEntries[i].next);
uint32 entryIndex = mBuckets[i];
while(entryIndex != INVALID_INDEX) {
if (set.mEntries[i].value != nullptr) {
mEntries[i].value = static_cast<V*>(mAllocator.allocate(sizeof(V)));
new (mEntries[i].value) V(*(set.mEntries[i].value));
}
// Copy the entry to the new location and destroy the previous one
new (mEntries + entryIndex) V(set.mEntries[entryIndex]);
entryIndex = mNextEntries[entryIndex];
}
}
}
@ -401,82 +273,146 @@ class Set {
}
/// Allocate memory for a given number of elements
void reserve(int capacity) {
void reserve(uint32 capacity) {
if (capacity <= mCapacity) return;
if (capacity <= mHashSize) return;
if (capacity > LARGEST_PRIME && LARGEST_PRIME > mCapacity) {
capacity = LARGEST_PRIME;
}
else {
capacity = getPrimeSize(capacity);
}
if (capacity < 16) capacity = 16;
expand(capacity);
// Make sure we have a power of two size
if (!isPowerOfTwo(capacity)) {
capacity = nextPowerOfTwo32Bits(capacity);
}
assert(capacity < INVALID_INDEX);
assert(capacity > mHashSize);
// Allocate memory for the buckets
uint32* newBuckets = static_cast<uint32*>(mAllocator.allocate(capacity * sizeof(uint32)));
// Allocate memory for the entries
const uint32 nbAllocatedEntries = capacity * DEFAULT_LOAD_FACTOR;
assert(nbAllocatedEntries > 0);
V* newEntries = static_cast<V*>(mAllocator.allocate(nbAllocatedEntries * sizeof(V)));
uint32* newNextEntries = static_cast<uint32*>(mAllocator.allocate(nbAllocatedEntries * sizeof(uint32)));
assert(newEntries != nullptr);
assert(newNextEntries != nullptr);
// Initialize the new buckets
for (uint32 i=0; i<capacity; i++) {
newBuckets[i] = INVALID_INDEX;
}
if (mNbAllocatedEntries > 0) {
assert(mNextEntries != nullptr);
// Copy the free nodes indices in the nextEntries array
std::memcpy(newNextEntries, mNextEntries, mNbAllocatedEntries * sizeof(uint32));
}
// Recompute the buckets (hash) with the new hash size
for (uint32 i=0; i<mHashSize; i++) {
uint32 entryIndex = mBuckets[i];
while(entryIndex != INVALID_INDEX) {
// Get the corresponding bucket
const size_t hashCode = Hash()(mEntries[entryIndex]);
const uint32 bucketIndex = hashCode & (capacity - 1);
newNextEntries[entryIndex] = newBuckets[bucketIndex];
newBuckets[bucketIndex] = entryIndex;
// Copy the entry to the new location and destroy the previous one
new (newEntries + entryIndex) V(mEntries[entryIndex]);
mEntries[entryIndex].~V();
entryIndex = mNextEntries[entryIndex];
}
}
if (mNbAllocatedEntries > 0) {
// Release previously allocated memory
mAllocator.release(mBuckets, mHashSize * sizeof(uint32));
mAllocator.release(mEntries, mNbAllocatedEntries * sizeof(V));
mAllocator.release(mNextEntries, mNbAllocatedEntries * sizeof(uint32));
}
// Add the new entries to the free list
for (uint32 i=mNbAllocatedEntries; i < nbAllocatedEntries-1; i++) {
newNextEntries[i] = i + 1;
}
newNextEntries[nbAllocatedEntries - 1] = mFreeIndex;
mFreeIndex = mNbAllocatedEntries;
mHashSize = capacity;
mNbAllocatedEntries = nbAllocatedEntries;
mBuckets = newBuckets;
mEntries = newEntries;
mNextEntries = newNextEntries;
assert(mFreeIndex != INVALID_INDEX);
}
/// Return true if the set contains a given value
bool contains(const V& value) const {
return findEntry(value) != -1;
return findEntry(value) != INVALID_INDEX;
}
/// Add a value into the set.
/// Returns true if the item has been inserted and false otherwise.
bool add(const V& value) {
if (mCapacity == 0) {
initialize(0);
}
uint32 bucket;
// Compute the hash code of the value
size_t hashCode = Hash()(value);
const size_t hashCode = Hash()(value);
// Compute the corresponding bucket index
int bucket = hashCode % mCapacity;
if (mHashSize > 0) {
auto keyEqual = KeyEqual();
// Compute the corresponding bucket index
bucket = hashCode & (mHashSize - 1);
// Check if the item is already in the set
for (int i = mBuckets[bucket]; i >= 0; i = mEntries[i].next) {
auto keyEqual = KeyEqual();
// If there is already an item with the same value in the set
if (mEntries[i].hashCode == hashCode && keyEqual(*mEntries[i].value, value)) {
// Check if the item is already in the set
for (uint32 i = mBuckets[bucket]; i != INVALID_INDEX; i = mNextEntries[i]) {
return false;
// If there is already an item with the same value in the set
if (Hash()(mEntries[i]) == hashCode && keyEqual(mEntries[i], value)) {
return false;
}
}
}
size_t entryIndex;
// If there are free entries to use
if (mNbFreeEntries > 0) {
assert(mFreeIndex >= 0);
entryIndex = mFreeIndex;
mFreeIndex = mEntries[entryIndex].next;
mNbFreeEntries--;
}
else {
// If there are no more free entries to use
if (mFreeIndex == INVALID_INDEX) {
// If we need to allocator more entries
if (mNbUsedEntries == mCapacity) {
// Allocate more memory
reserve(mHashSize == 0 ? 16 : mHashSize * 2);
// Allocate more memory
reserve(mCapacity * 2);
// Recompute the bucket index
bucket = hashCode % mCapacity;
}
entryIndex = mNbUsedEntries;
mNbUsedEntries++;
// Recompute the bucket index
bucket = hashCode & (mHashSize - 1);
}
assert(mEntries[entryIndex].value == nullptr);
mEntries[entryIndex].hashCode = hashCode;
mEntries[entryIndex].next = mBuckets[bucket];
mEntries[entryIndex].value = static_cast<V*>(mAllocator.allocate(sizeof(V)));
assert(mEntries[entryIndex].value != nullptr);
new (mEntries[entryIndex].value) V(value);
assert(mNbEntries < mNbAllocatedEntries);
assert(mFreeIndex != INVALID_INDEX);
// Get the next free entry
entryIndex = mFreeIndex;
mFreeIndex = mNextEntries[entryIndex];
mNbEntries++;
mNextEntries[entryIndex] = mBuckets[bucket];
new (mEntries + entryIndex) V(value);
mBuckets[bucket] = entryIndex;
return true;
@ -495,46 +431,46 @@ class Set {
/// element after the one that has been removed
Iterator remove(const V& value) {
if (mCapacity > 0) {
if (mHashSize > 0) {
size_t hashcode = Hash()(value);
auto keyEqual = KeyEqual();
int bucket = hashcode % mCapacity;
int last = -1;
for (int i = mBuckets[bucket]; i >= 0; last = i, i = mEntries[i].next) {
const size_t hashcode = Hash()(value);
auto keyEqual = KeyEqual();
const uint32 bucket = hashcode & (mHashSize - 1);
uint32 last = INVALID_INDEX;
for (uint32 i = mBuckets[bucket]; i != INVALID_INDEX; last = i, i = mNextEntries[i]) {
if (mEntries[i].hashCode == hashcode && keyEqual(*mEntries[i].value, value)) {
// If we have found the item
if (Hash()(mEntries[i]) == hashcode && keyEqual(mEntries[i], value)) {
if (last < 0 ) {
mBuckets[bucket] = mEntries[i].next;
if (last == INVALID_INDEX) {
mBuckets[bucket] = mNextEntries[i];
}
else {
mEntries[last].next = mEntries[i].next;
mNextEntries[last] = mNextEntries[i];
}
// Release memory for the value if any
if (mEntries[i].value != nullptr) {
mEntries[i].value->~V();
mAllocator.release(mEntries[i].value, sizeof(V));
mEntries[i].value = nullptr;
}
assert(mEntries[i].value == nullptr);
mEntries[i].next = mFreeIndex;
uint32 nextEntryIndex = mNextEntries[i];
uint32 nextBucketIndex = bucket;
mEntries[i].~V();
mNextEntries[i] = mFreeIndex;
mFreeIndex = i;
mNbFreeEntries++;
mNbEntries--;
// Find the next valid entry to return an iterator
for (i += 1; i < mNbUsedEntries; i++) {
// If the entry is not empty
if (mEntries[i].value != nullptr) {
// We have found the next non empty entry
return Iterator(mEntries, mCapacity, mNbUsedEntries, i);
// Find the next entry to return an iterator
if (nextEntryIndex == INVALID_INDEX) {
nextEntryIndex = 0;
nextBucketIndex++;
while(nextBucketIndex < mHashSize && mBuckets[nextBucketIndex] == INVALID_INDEX) {
nextBucketIndex++;
}
if (nextBucketIndex < mHashSize) {
nextEntryIndex = mBuckets[nextBucketIndex];
}
}
return end();
// We have found the next non empty entry
return Iterator(this, nextBucketIndex, nextEntryIndex);
}
}
}
@ -542,67 +478,67 @@ class Set {
return end();
}
/// Return a list with all the values of the set
List<V> toList(MemoryAllocator& listAllocator) const {
/// Return an array with all the values of the set
Array<V> toArray(MemoryAllocator& arrayAllocator) const {
List<V> list(listAllocator);
Array<V> array(arrayAllocator);
for (int i=0; i < mCapacity; i++) {
if (mEntries[i].value != nullptr) {
list.add(*(mEntries[i].value));
}
for (auto it = begin(); it != end(); ++it) {
array.add(*it);
}
return list;
return array;
}
/// Clear the set
void clear(bool releaseMemory = false) {
if (mNbUsedEntries > 0) {
for (uint32 i=0; i<mHashSize; i++) {
for (int i=0; i < mCapacity; i++) {
mBuckets[i] = -1;
mEntries[i].next = -1;
if (mEntries[i].value != nullptr) {
mEntries[i].value->~V();
mAllocator.release(mEntries[i].value, sizeof(V));
mEntries[i].value = nullptr;
}
uint32 entryIndex = mBuckets[i];
while(entryIndex != INVALID_INDEX) {
// Destroy the entry
mEntries[entryIndex].~V();
uint32 nextEntryIndex = mNextEntries[entryIndex];
// Add entry to the free list
mNextEntries[entryIndex] = mFreeIndex;
mFreeIndex = entryIndex;
entryIndex = nextEntryIndex;
}
mFreeIndex = -1;
mNbUsedEntries = 0;
mNbFreeEntries = 0;
mBuckets[i] = INVALID_INDEX;
}
// If elements have been allocated
if (releaseMemory && mCapacity > 0) {
if (releaseMemory && mNbAllocatedEntries > 0) {
// Destroy the entries
for (int i=0; i < mCapacity; i++) {
mEntries[i].~Entry();
}
// Release previously allocated memory
mAllocator.release(mBuckets, mHashSize * sizeof(uint32));
mAllocator.release(mEntries, mNbAllocatedEntries * sizeof(V));
mAllocator.release(mNextEntries, mNbAllocatedEntries * sizeof(uint32));
mAllocator.release(mBuckets, mCapacity * sizeof(int));
mAllocator.release(mEntries, mCapacity * sizeof(Entry));
mCapacity = 0;
mBuckets = nullptr;
mEntries = nullptr;
mNextEntries = nullptr;
mNbAllocatedEntries = 0;
mHashSize = 0;
}
assert(size() == 0);
mNbEntries = 0;
}
/// Return the number of elements in the set
int size() const {
return mNbUsedEntries - mNbFreeEntries;
uint32 size() const {
return mNbEntries;
}
/// Return the capacity of the set
int capacity() const {
return mCapacity;
uint32 capacity() const {
return mHashSize;
}
/// Try to find an item of the set given a key.
@ -610,30 +546,28 @@ class Set {
/// an iterator pointing to the end if not found
Iterator find(const V& value) const {
int bucket;
int entry = -1;
uint32 bucket;
uint32 entry = INVALID_INDEX;
if (mCapacity > 0) {
if (mHashSize > 0) {
size_t hashCode = Hash()(value);
bucket = hashCode % mCapacity;
auto keyEqual = KeyEqual();
const size_t hashCode = Hash()(value);
bucket = hashCode & (mHashSize - 1);
auto keyEqual = KeyEqual();
for (int i = mBuckets[bucket]; i >= 0; i = mEntries[i].next) {
if (mEntries[i].hashCode == hashCode && keyEqual(*(mEntries[i].value), value)) {
for (uint32 i = mBuckets[bucket]; i != INVALID_INDEX; i = mNextEntries[i]) {
if (Hash()(mEntries[i]) == hashCode && keyEqual(mEntries[i], value)) {
entry = i;
break;
}
}
}
if (entry == -1) {
if (entry == INVALID_INDEX) {
return end();
}
assert(mEntries[entry].value != nullptr);
return Iterator(mEntries, mCapacity, mNbUsedEntries, entry);
return Iterator(this, bucket, entry);
}
/// Overloaded equality operator
@ -665,34 +599,35 @@ class Set {
// Clear the set
clear(true);
if (set.mCapacity > 0) {
mNbAllocatedEntries = set.mNbAllocatedEntries;
mNbEntries = set.mNbEntries;
mHashSize = set.mHashSize;
mFreeIndex = set.mFreeIndex;
// Compute the next larger prime size
mCapacity = getPrimeSize(set.mCapacity);
// Allocate memory for the buckets
mBuckets = static_cast<uint32*>(mAllocator.allocate(mHashSize * sizeof(uint32)));
// Allocate memory for the buckets
mBuckets = static_cast<int*>(mAllocator.allocate(mCapacity * sizeof(int)));
// Allocate memory for the entries
mEntries = static_cast<V*>(mAllocator.allocate(mNbAllocatedEntries * sizeof(V)));
mNextEntries = static_cast<uint32*>(mAllocator.allocate(mNbAllocatedEntries * sizeof(uint32)));
// Allocate memory for the entries
mEntries = static_cast<Entry*>(mAllocator.allocate(mCapacity * sizeof(Entry)));
// Copy the buckets array
std::memcpy(mBuckets, set.mBuckets, mHashSize * sizeof(uint32));
// Copy the buckets
std::uninitialized_copy(set.mBuckets, set.mBuckets + mCapacity, mBuckets);
// Copy the next entries indices
std::memcpy(mNextEntries, set.mNextEntries, mNbAllocatedEntries * sizeof(uint32));
// Copy the entries
for (int i=0; i < mCapacity; i++) {
// Copy the entries
for (uint32 i=0; i<mHashSize; i++) {
new (&mEntries[i]) Entry(set.mEntries[i].hashCode, set.mEntries[i].next);
uint32 entryIndex = mBuckets[i];
while(entryIndex != INVALID_INDEX) {
if (set.mEntries[i].value != nullptr) {
mEntries[i].value = static_cast<V*>(mAllocator.allocate(sizeof(V)));
new (mEntries[i].value) V(*(set.mEntries[i].value));
}
// Copy the entry to the new location and destroy the previous one
new (mEntries + entryIndex) V(set.mEntries[entryIndex]);
entryIndex = mNextEntries[entryIndex];
}
mNbUsedEntries = set.mNbUsedEntries;
mNbFreeEntries = set.mNbFreeEntries;
mFreeIndex = set.mFreeIndex;
}
}
@ -702,7 +637,7 @@ class Set {
/// Return a begin iterator
Iterator begin() const {
// If the map is empty
// If the set is empty
if (size() == 0) {
// Return an iterator to the end
@ -710,33 +645,29 @@ class Set {
}
// Find the first used entry
int entry;
for (entry=0; entry < mNbUsedEntries; entry++) {
if (mEntries[entry].value != nullptr) {
return Iterator(mEntries, mCapacity, mNbUsedEntries, entry);
}
uint32 bucketIndex = 0;
while (mBuckets[bucketIndex] == INVALID_INDEX) {
bucketIndex++;
}
assert(false);
return end();
assert(bucketIndex < mHashSize);
assert(mBuckets[bucketIndex] != INVALID_INDEX);
return Iterator(this, bucketIndex, mBuckets[bucketIndex]);
}
/// Return a end iterator
Iterator end() const {
return Iterator(mEntries, mCapacity, mNbUsedEntries, mCapacity);
return Iterator(this, mHashSize, 0);
}
// ---------- Friendship ---------- //
friend class Iterator;
};
template<typename V, class Hash, class KeyEqual>
const int Set<V, Hash, KeyEqual>::PRIMES[NB_PRIMES] = {3, 7, 11, 17, 23, 29, 37, 47, 59, 71, 89, 107, 131, 163, 197, 239, 293, 353, 431, 521, 631, 761, 919,
1103, 1327, 1597, 1931, 2333, 2801, 3371, 4049, 4861, 5839, 7013, 8419, 10103, 12143, 14591,
17519, 21023, 25229, 30293, 36353, 43627, 52361, 62851, 75431, 90523, 108631, 130363, 156437,
187751, 225307, 270371, 324449, 389357, 467237, 560689, 672827, 807403, 968897, 1162687, 1395263,
1674319, 2009191, 2411033, 2893249, 3471899, 4166287, 4999559};
template<typename V, class Hash, class KeyEqual>
int Set<V, Hash, KeyEqual>::LARGEST_PRIME = -1;
}
#endif

View File

@ -29,6 +29,7 @@
// Libraries
#include <cstddef>
#include <functional>
#include <reactphysics3d/configuration.h>
namespace reactphysics3d {

View File

@ -107,23 +107,23 @@ struct Entity {
};
// Return the lookup index of the entity in a array
inline uint32 Entity::getIndex() const {
RP3D_FORCE_INLINE uint32 Entity::getIndex() const {
return id & ENTITY_INDEX_MASK;
}
// Return the generation number of the entity
inline uint32 Entity::getGeneration() const {
RP3D_FORCE_INLINE uint32 Entity::getGeneration() const {
return (id >> ENTITY_INDEX_BITS) & ENTITY_GENERATION_MASK;
}
// Equality operator
inline bool Entity::operator==(const Entity& entity) const {
RP3D_FORCE_INLINE bool Entity::operator==(const Entity& entity) const {
return entity.id == id;
}
// Inequality operator
inline bool Entity::operator!=(const Entity& entity) const {
RP3D_FORCE_INLINE bool Entity::operator!=(const Entity& entity) const {
return entity.id != id;
}

View File

@ -28,7 +28,7 @@
// Libraries
#include <reactphysics3d/configuration.h>
#include <reactphysics3d/containers/List.h>
#include <reactphysics3d/containers/Array.h>
#include <reactphysics3d/containers/Deque.h>
#include <reactphysics3d/engine/Entity.h>
@ -45,8 +45,8 @@ class EntityManager {
// -------------------- Attributes -------------------- //
/// List storing the generations of the created entities
List<uint8> mGenerations;
/// Array storing the generations of the created entities
Array<uint8> mGenerations;
/// Deque with the indices of destroyed entities that can be reused
Deque<uint32> mFreeIndices;
@ -71,7 +71,7 @@ class EntityManager {
};
// Return true if the entity is still valid (not destroyed)
inline bool EntityManager::isValid(Entity entity) const {
RP3D_FORCE_INLINE bool EntityManager::isValid(Entity entity) const {
return mGenerations[entity.getIndex()] == entity.getGeneration();
}

View File

@ -105,35 +105,35 @@ class Island {
};
// Add a body into the island
inline void Island::addBody(RigidBody* body) {
RP3D_FORCE_INLINE void Island::addBody(RigidBody* body) {
assert(!body->isSleeping());
mBodies[mNbBodies] = body;
mNbBodies++;
}
// Add a contact manifold into the island
inline void Island::addContactManifold(ContactManifold* contactManifold) {
RP3D_FORCE_INLINE void Island::addContactManifold(ContactManifold* contactManifold) {
mContactManifolds[mNbContactManifolds] = contactManifold;
mNbContactManifolds++;
}
// Return the number of bodies in the island
inline uint Island::getNbBodies() const {
RP3D_FORCE_INLINE uint Island::getNbBodies() const {
return mNbBodies;
}
// Return the number of contact manifolds in the island
inline uint Island::getNbContactManifolds() const {
RP3D_FORCE_INLINE uint Island::getNbContactManifolds() const {
return mNbContactManifolds;
}
// Return a pointer to the array of bodies
inline RigidBody** Island::getBodies() {
RP3D_FORCE_INLINE RigidBody** Island::getBodies() {
return mBodies;
}
// Return a pointer to the array of contact manifolds
inline ContactManifold** Island::getContactManifolds() {
RP3D_FORCE_INLINE ContactManifold** Island::getContactManifolds() {
return mContactManifolds;
}

View File

@ -28,7 +28,7 @@
// Libraries
#include <reactphysics3d/configuration.h>
#include <reactphysics3d/containers/List.h>
#include <reactphysics3d/containers/Array.h>
#include <reactphysics3d/engine/Entity.h>
#include <reactphysics3d/constraint/Joint.h>
@ -46,10 +46,17 @@ struct Islands {
private:
// -------------------- Attributes -------------------- //
/// Number of islands in the previous frame
uint32 mNbIslandsPreviousFrame;
/// Reference to the memory allocator
MemoryAllocator& memoryAllocator;
/// Number of items in the bodyEntities array in the previous frame
uint32 mNbBodyEntitiesPreviousFrame;
/// Maximum number of bodies in a single island in the previous frame
uint32 mNbMaxBodiesInIslandPreviousFrame;
/// Maximum number of bodies in a single island in the current frame
uint32 mNbMaxBodiesInIslandCurrentFrame;
public:
@ -57,20 +64,27 @@ struct Islands {
/// For each island, index of the first contact manifold of the island in the array of contact manifolds
List<uint> contactManifoldsIndices;
Array<uint> contactManifoldsIndices;
/// For each island, number of contact manifolds in the island
List<uint> nbContactManifolds;
Array<uint> nbContactManifolds;
/// For each island, list of all the entities of the bodies in the island
List<List<Entity>> bodyEntities;
/// Array of all the entities of the bodies in the islands (stored sequentially)
Array<Entity> bodyEntities;
/// For each island we store the starting index of the bodies of that island in the "bodyEntities" array
Array<uint32> startBodyEntitiesIndex;
/// For each island, total number of bodies in the island
Array<uint32> nbBodiesInIsland;
// -------------------- Methods -------------------- //
/// Constructor
Islands(MemoryAllocator& allocator)
:memoryAllocator(allocator), contactManifoldsIndices(allocator), nbContactManifolds(allocator),
bodyEntities(allocator) {
:mNbIslandsPreviousFrame(16), mNbBodyEntitiesPreviousFrame(32), mNbMaxBodiesInIslandPreviousFrame(0), mNbMaxBodiesInIslandCurrentFrame(0),
contactManifoldsIndices(allocator), nbContactManifolds(allocator),
bodyEntities(allocator), startBodyEntitiesIndex(allocator), nbBodiesInIsland(allocator) {
}
@ -78,34 +92,76 @@ struct Islands {
~Islands() = default;
/// Assignment operator
Islands& operator=(const Islands& island) = default;
Islands& operator=(const Islands& island) = delete;
/// Copy-constructor
Islands(const Islands& island) = default;
/// Return the number of islands
uint32 getNbIslands() const {
return static_cast<uint32>(contactManifoldsIndices.size());
return contactManifoldsIndices.size();
}
/// Add an island and return its index
uint32 addIsland(uint32 contactManifoldStartIndex) {
uint32 islandIndex = contactManifoldsIndices.size();
const uint32 islandIndex = contactManifoldsIndices.size();
contactManifoldsIndices.add(contactManifoldStartIndex);
nbContactManifolds.add(0);
bodyEntities.add(List<Entity>(memoryAllocator));
startBodyEntitiesIndex.add(bodyEntities.size());
nbBodiesInIsland.add(0);
if (islandIndex > 0 && nbBodiesInIsland[islandIndex-1] > mNbMaxBodiesInIslandCurrentFrame) {
mNbMaxBodiesInIslandCurrentFrame = nbBodiesInIsland[islandIndex-1];
}
return islandIndex;
}
void addBodyToIsland(Entity bodyEntity) {
const uint32 islandIndex = contactManifoldsIndices.size();
assert(islandIndex > 0);
bodyEntities.add(bodyEntity);
nbBodiesInIsland[islandIndex - 1]++;
}
/// Reserve memory for the current frame
void reserveMemory() {
contactManifoldsIndices.reserve(mNbIslandsPreviousFrame);
nbContactManifolds.reserve(mNbIslandsPreviousFrame);
startBodyEntitiesIndex.reserve(mNbIslandsPreviousFrame);
nbBodiesInIsland.reserve(mNbIslandsPreviousFrame);
bodyEntities.reserve(mNbBodyEntitiesPreviousFrame);
}
/// Clear all the islands
void clear() {
const uint32 nbIslands = nbContactManifolds.size();
if (nbIslands > 0 && nbBodiesInIsland[nbIslands-1] > mNbMaxBodiesInIslandCurrentFrame) {
mNbMaxBodiesInIslandCurrentFrame = nbBodiesInIsland[nbIslands-1];
}
mNbMaxBodiesInIslandPreviousFrame = mNbMaxBodiesInIslandCurrentFrame;
mNbIslandsPreviousFrame = nbIslands;
mNbMaxBodiesInIslandCurrentFrame = 0;
mNbBodyEntitiesPreviousFrame = bodyEntities.size();
contactManifoldsIndices.clear(true);
nbContactManifolds.clear(true);
bodyEntities.clear(true);
startBodyEntitiesIndex.clear(true);
nbBodiesInIsland.clear(true);
}
uint32 getNbMaxBodiesInIslandPreviousFrame() const {
return mNbMaxBodiesInIslandPreviousFrame;
}
};

View File

@ -28,6 +28,7 @@
// Libraries
#include <cassert>
#include <cmath>
#include <reactphysics3d/configuration.h>
namespace reactphysics3d {
@ -44,11 +45,8 @@ class Material {
// -------------------- Attributes -------------------- //
/// Friction coefficient (positive value)
decimal mFrictionCoefficient;
/// Rolling resistance factor (positive value)
decimal mRollingResistance;
/// Square root of the friction coefficient
decimal mFrictionCoefficientSqrt;
/// Bounciness during collisions (between 0 and 1) where 1 is for a very bouncy body
decimal mBounciness;
@ -59,14 +57,7 @@ class Material {
// -------------------- Methods -------------------- //
/// Constructor
Material(decimal frictionCoefficient, decimal rollingResistance, decimal bounciness,
decimal massDensity = decimal(1.0));
/// Copy-constructor
Material(const Material& material);
/// Destructor
~Material() = default;
Material(decimal frictionCoefficient, decimal bounciness, decimal massDensity = decimal(1.0));
public :
@ -84,11 +75,8 @@ class Material {
/// Set the friction coefficient.
void setFrictionCoefficient(decimal frictionCoefficient);
/// Return the rolling resistance factor
decimal getRollingResistance() const;
/// Set the rolling resistance factor
void setRollingResistance(decimal rollingResistance);
/// Return the square root friction coefficient
decimal getFrictionCoefficientSqrt() const;
/// Return the mass density of the collider
decimal getMassDensity() const;
@ -99,19 +87,18 @@ class Material {
/// Return a string representation for the material
std::string to_string() const;
/// Overloaded assignment operator
Material& operator=(const Material& material);
// ---------- Friendship ---------- //
friend class Collider;
friend class CollisionBody;
friend class RigidBody;
};
// Return the bounciness
/**
* @return Bounciness factor (between 0 and 1) where 1 is very bouncy
*/
inline decimal Material::getBounciness() const {
RP3D_FORCE_INLINE decimal Material::getBounciness() const {
return mBounciness;
}
@ -121,7 +108,7 @@ inline decimal Material::getBounciness() const {
/**
* @param bounciness Bounciness factor (between 0 and 1) where 1 is very bouncy
*/
inline void Material::setBounciness(decimal bounciness) {
RP3D_FORCE_INLINE void Material::setBounciness(decimal bounciness) {
assert(bounciness >= decimal(0.0) && bounciness <= decimal(1.0));
mBounciness = bounciness;
}
@ -130,8 +117,8 @@ inline void Material::setBounciness(decimal bounciness) {
/**
* @return Friction coefficient (positive value)
*/
inline decimal Material::getFrictionCoefficient() const {
return mFrictionCoefficient;
RP3D_FORCE_INLINE decimal Material::getFrictionCoefficient() const {
return mFrictionCoefficientSqrt * mFrictionCoefficientSqrt;
}
// Set the friction coefficient.
@ -140,34 +127,18 @@ inline decimal Material::getFrictionCoefficient() const {
/**
* @param frictionCoefficient Friction coefficient (positive value)
*/
inline void Material::setFrictionCoefficient(decimal frictionCoefficient) {
RP3D_FORCE_INLINE void Material::setFrictionCoefficient(decimal frictionCoefficient) {
assert(frictionCoefficient >= decimal(0.0));
mFrictionCoefficient = frictionCoefficient;
mFrictionCoefficientSqrt = std::sqrt(frictionCoefficient);
}
// Return the rolling resistance factor. If this value is larger than zero,
// it will be used to slow down the body when it is rolling
// against another body.
/**
* @return The rolling resistance factor (positive value)
*/
inline decimal Material::getRollingResistance() const {
return mRollingResistance;
}
// Set the rolling resistance factor. If this value is larger than zero,
// it will be used to slow down the body when it is rolling
// against another body.
/**
* @param rollingResistance The rolling resistance factor
*/
inline void Material::setRollingResistance(decimal rollingResistance) {
assert(rollingResistance >= 0);
mRollingResistance = rollingResistance;
// Return the square root friction coefficient
RP3D_FORCE_INLINE decimal Material::getFrictionCoefficientSqrt() const {
return mFrictionCoefficientSqrt;
}
// Return the mass density of the collider
inline decimal Material::getMassDensity() const {
RP3D_FORCE_INLINE decimal Material::getMassDensity() const {
return mMassDensity;
}
@ -175,36 +146,21 @@ inline decimal Material::getMassDensity() const {
/**
* @param massDensity The mass density of the collider
*/
inline void Material::setMassDensity(decimal massDensity) {
RP3D_FORCE_INLINE void Material::setMassDensity(decimal massDensity) {
mMassDensity = massDensity;
}
// Return a string representation for the material
inline std::string Material::to_string() const {
RP3D_FORCE_INLINE std::string Material::to_string() const {
std::stringstream ss;
ss << "frictionCoefficient=" << mFrictionCoefficient << std::endl;
ss << "rollingResistance=" << mRollingResistance << std::endl;
ss << "frictionCoefficient=" << (mFrictionCoefficientSqrt * mFrictionCoefficientSqrt) << std::endl;
ss << "bounciness=" << mBounciness << std::endl;
return ss.str();
}
// Overloaded assignment operator
inline Material& Material::operator=(const Material& material) {
// Check for self-assignment
if (this != &material) {
mFrictionCoefficient = material.mFrictionCoefficient;
mBounciness = material.mBounciness;
mRollingResistance = material.mRollingResistance;
}
// Return this material
return *this;
}
}
#endif

View File

@ -54,6 +54,8 @@ class CollisionDispatch;
*/
struct LastFrameCollisionInfo {
// TODO OPTI : Use bit flags instead of bools here
/// True if we have information about the previous frame
bool isValid;
@ -77,9 +79,9 @@ struct LastFrameCollisionInfo {
// SAT Algorithm
bool satIsAxisFacePolyhedron1;
bool satIsAxisFacePolyhedron2;
uint satMinAxisFaceIndex;
uint satMinEdge1Index;
uint satMinEdge2Index;
uint8 satMinAxisFaceIndex;
uint8 satMinEdge1Index;
uint8 satMinEdge2Index;
/// Constructor
LastFrameCollisionInfo() {
@ -104,80 +106,194 @@ struct LastFrameCollisionInfo {
*/
class OverlappingPairs {
public:
struct OverlappingPair {
/// Ids of the convex vs convex pairs
uint64 pairID;
/// Broad-phase Id of the first shape
// TODO OPTI : Is this used ?
int32 broadPhaseId1;
/// Broad-phase Id of the second shape
// TODO OPTI : Is this used ?
int32 broadPhaseId2;
/// Entity of the first collider of the convex vs convex pairs
Entity collider1;
/// Entity of the second collider of the convex vs convex pairs
Entity collider2;
/// True if we need to test if the convex vs convex overlapping pairs of shapes still overlap
bool needToTestOverlap;
/// Pointer to the narrow-phase algorithm
NarrowPhaseAlgorithmType narrowPhaseAlgorithmType;
/// True if the colliders of the overlapping pair were colliding in the previous frame
bool collidingInPreviousFrame;
/// True if the colliders of the overlapping pair are colliding in the current frame
bool collidingInCurrentFrame;
/// Constructor
OverlappingPair(uint64 pairId, int32 broadPhaseId1, int32 broadPhaseId2, Entity collider1, Entity collider2,
NarrowPhaseAlgorithmType narrowPhaseAlgorithmType)
: pairID(pairId), broadPhaseId1(broadPhaseId1), broadPhaseId2(broadPhaseId2), collider1(collider1) , collider2(collider2),
needToTestOverlap(false), narrowPhaseAlgorithmType(narrowPhaseAlgorithmType), collidingInPreviousFrame(false),
collidingInCurrentFrame(false) {
}
/// Destructor
virtual ~OverlappingPair() = default;
};
// Overlapping pair between two convex colliders
struct ConvexOverlappingPair : public OverlappingPair {
/// Temporal coherence collision data for each overlapping collision shapes of this pair.
/// Temporal coherence data store collision information about the last frame.
/// If two convex shapes overlap, we have a single collision data but if one shape is concave,
/// we might have collision data for several overlapping triangles.
LastFrameCollisionInfo lastFrameCollisionInfo;
/// Constructor
ConvexOverlappingPair(uint64 pairId, int32 broadPhaseId1, int32 broadPhaseId2, Entity collider1, Entity collider2,
NarrowPhaseAlgorithmType narrowPhaseAlgorithmType)
: OverlappingPair(pairId, broadPhaseId1, broadPhaseId2, collider1, collider2, narrowPhaseAlgorithmType) {
}
};
// Overlapping pair between two a convex collider and a concave collider
struct ConcaveOverlappingPair : public OverlappingPair {
private:
MemoryAllocator* mPoolAllocator;
public:
/// True if the first shape of the pair is convex
bool isShape1Convex;
/// Temporal coherence collision data for each overlapping collision shapes of this pair.
/// Temporal coherence data store collision information about the last frame.
/// If two convex shapes overlap, we have a single collision data but if one shape is concave,
/// we might have collision data for several overlapping triangles. The key in the map is the
/// shape Ids of the two collision shapes.
Map<uint64, LastFrameCollisionInfo*> lastFrameCollisionInfos;
/// Constructor
ConcaveOverlappingPair(uint64 pairId, int32 broadPhaseId1, int32 broadPhaseId2, Entity collider1, Entity collider2,
NarrowPhaseAlgorithmType narrowPhaseAlgorithmType,
bool isShape1Convex, MemoryAllocator& poolAllocator, MemoryAllocator& heapAllocator)
: OverlappingPair(pairId, broadPhaseId1, broadPhaseId2, collider1, collider2, narrowPhaseAlgorithmType), mPoolAllocator(&poolAllocator),
isShape1Convex(isShape1Convex), lastFrameCollisionInfos(heapAllocator, 16) {
}
// Destroy all the LastFrameCollisionInfo objects
void destroyLastFrameCollisionInfos() {
for (auto it = lastFrameCollisionInfos.begin(); it != lastFrameCollisionInfos.end(); ++it) {
// Call the destructor
it->second->LastFrameCollisionInfo::~LastFrameCollisionInfo();
// Release memory
mPoolAllocator->release(it->second, sizeof(LastFrameCollisionInfo));
}
lastFrameCollisionInfos.clear();
}
// Add a new last frame collision info if it does not exist for the given shapes already
LastFrameCollisionInfo* addLastFrameInfoIfNecessary(uint32 shapeId1, uint32 shapeId2) {
uint32 maxShapeId = shapeId1;
uint32 minShapeId = shapeId2;
if (shapeId1 < shapeId2) {
maxShapeId = shapeId2;
minShapeId = shapeId1;
}
// Try to get the corresponding last frame collision info
const uint64 shapesId = pairNumbers(maxShapeId, minShapeId);
// If there is no collision info for those two shapes already
auto it = lastFrameCollisionInfos.find(shapesId);
if (it == lastFrameCollisionInfos.end()) {
LastFrameCollisionInfo* lastFrameInfo = new (mPoolAllocator->allocate(sizeof(LastFrameCollisionInfo))) LastFrameCollisionInfo();
// Add it into the map of collision infos
lastFrameCollisionInfos.add(Pair<uint64, LastFrameCollisionInfo*>(shapesId, lastFrameInfo));
return lastFrameInfo;
}
else {
// The existing collision info is not obsolete
it->second->isObsolete = false;
return it->second;
}
}
/// Clear the obsolete LastFrameCollisionInfo objects
void clearObsoleteLastFrameInfos() {
// For each last frame collision info
for (auto it = lastFrameCollisionInfos.begin(); it != lastFrameCollisionInfos.end(); ) {
// If the collision info is obsolete
if (it->second->isObsolete) {
// Call the destructor
it->second->LastFrameCollisionInfo::~LastFrameCollisionInfo();
// Release memory
mPoolAllocator->release(it->second, sizeof(LastFrameCollisionInfo));
it = lastFrameCollisionInfos.remove(it);
}
else { // If the collision info is not obsolete
// Do not delete it but mark it as obsolete
it->second->isObsolete = true;
++it;
}
}
}
};
private:
// -------------------- Constants -------------------- //
/// Number of pairs to allocated at the beginning
const uint32 INIT_NB_ALLOCATED_PAIRS = 10;
// -------------------- Attributes -------------------- //
/// Persistent memory allocator
MemoryAllocator& mPersistentAllocator;
/// Pool memory allocator
MemoryAllocator& mPoolAllocator;
/// Memory allocator used to allocated memory for the ContactManifoldInfo and ContactPointInfo
// TODO : Do we need to keep this ?
MemoryAllocator& mTempMemoryAllocator;
/// Heap memory allocator
MemoryAllocator& mHeapAllocator;
/// Current number of components
uint64 mNbPairs;
/// Array of convex vs convex overlapping pairs
Array<ConvexOverlappingPair> mConvexPairs;
/// Index in the array of the first convex vs concave pair
uint64 mConcavePairsStartIndex;
/// Size (in bytes) of a single pair
size_t mPairDataSize;
/// Number of allocated pairs
uint64 mNbAllocatedPairs;
/// Allocated memory for all the data of the pairs
void* mBuffer;
/// Array of convex vs concave overlapping pairs
Array<ConcaveOverlappingPair> mConcavePairs;
/// Map a pair id to the internal array index
Map<uint64, uint64> mMapPairIdToPairIndex;
Map<uint64, uint64> mMapConvexPairIdToPairIndex;
/// Ids of the convex vs convex pairs
uint64* mPairIds;
/// Array with the broad-phase Ids of the first shape
int32* mPairBroadPhaseId1;
/// Array with the broad-phase Ids of the second shape
int32* mPairBroadPhaseId2;
/// Array of Entity of the first collider of the convex vs convex pairs
Entity* mColliders1;
/// Array of Entity of the second collider of the convex vs convex pairs
Entity* mColliders2;
/// Temporal coherence collision data for each overlapping collision shapes of this pair.
/// Temporal coherence data store collision information about the last frame.
/// If two convex shapes overlap, we have a single collision data but if one shape is concave,
/// we might have collision data for several overlapping triangles. The key in the map is the
/// shape Ids of the two collision shapes.
Map<uint64, LastFrameCollisionInfo*>* mLastFrameCollisionInfos;
/// True if we need to test if the convex vs convex overlapping pairs of shapes still overlap
bool* mNeedToTestOverlap;
/// True if the overlapping pair is active (at least one body of the pair is active and not static)
bool* mIsActive;
/// Array with the pointer to the narrow-phase algorithm for each overlapping pair
NarrowPhaseAlgorithmType* mNarrowPhaseAlgorithmType;
/// True if the first shape of the pair is convex
bool* mIsShape1Convex;
/// True if the colliders of the overlapping pair were colliding in the previous frame
bool* mCollidingInPreviousFrame;
/// True if the colliders of the overlapping pair are colliding in the current frame
bool* mCollidingInCurrentFrame;
/// Map a pair id to the internal array index
Map<uint64, uint64> mMapConcavePairIdToPairIndex;
/// Reference to the colliders components
ColliderComponents& mColliderComponents;
@ -203,15 +319,6 @@ class OverlappingPairs {
// -------------------- Methods -------------------- //
/// Allocate memory for a given number of pairs
void allocate(uint64 nbPairsToAllocate);
/// Compute the index where we need to insert the new pair
uint64 prepareAddPair(bool isConvexVsConvex);
/// Destroy a pair at a given index
void destroyPair(uint64 index);
// Move a pair from a source to a destination index in the pairs array
void movePairToIndex(uint64 srcIndex, uint64 destIndex);
@ -223,8 +330,8 @@ class OverlappingPairs {
// -------------------- Methods -------------------- //
/// Constructor
OverlappingPairs(MemoryAllocator& persistentMemoryAllocator, MemoryAllocator& temporaryMemoryAllocator,
ColliderComponents& colliderComponents, CollisionBodyComponents& collisionBodyComponents,
OverlappingPairs(MemoryManager& memoryManager, ColliderComponents& colliderComponents,
CollisionBodyComponents& collisionBodyComponents,
RigidBodyComponents& rigidBodyComponents, Set<bodypair>& noCollisionPairs,
CollisionDispatch& collisionDispatch);
@ -238,46 +345,13 @@ class OverlappingPairs {
OverlappingPairs& operator=(const OverlappingPairs& pair) = delete;
/// Add an overlapping pair
uint64 addPair(Collider* shape1, Collider* shape2);
uint64 addPair(uint32 collider1Index, uint32 collider2Index, bool isConvexVsConvex);
/// Remove a component at a given index
void removePair(uint64 pairId);
/// Return the number of pairs
uint64 getNbPairs() const;
/// Return the number of convex vs convex pairs
uint64 getNbConvexVsConvexPairs() const;
/// Return the number of convex vs concave pairs
uint64 getNbConvexVsConcavePairs() const;
/// Return the starting index of the convex vs concave pairs
uint64 getConvexVsConcavePairsStartIndex() const;
/// Return the entity of the first collider
Entity getCollider1(uint64 pairId) const;
/// Return the entity of the second collider
Entity getCollider2(uint64 pairId) const;
/// Notify if a given pair is active or not
void setIsPairActive(uint64 pairId, bool isActive);
/// Return the index of a given overlapping pair in the internal array
uint64 getPairIndex(uint64 pairId) const;
/// Return the last frame collision info
LastFrameCollisionInfo* getLastFrameCollisionInfo(uint64, uint64 shapesId);
/// Return a reference to the temporary memory allocator
MemoryAllocator& getTemporaryAllocator();
/// Add a new last frame collision info if it does not exist for the given shapes already
LastFrameCollisionInfo* addLastFrameInfoIfNecessary(uint64 pairIndex, uint32 shapeId1, uint32 shapeId2);
/// Update whether a given overlapping pair is active or not
void updateOverlappingPairIsActive(uint64 pairId);
/// Remove a pair
void removePair(uint64 pairIndex, bool isConvexVsConvex);
/// Delete all the obsolete last frame collision info
void clearObsoleteLastFrameCollisionInfos();
@ -291,11 +365,8 @@ class OverlappingPairs {
/// Set if we need to test a given pair for overlap
void setNeedToTestOverlap(uint64 pairId, bool needToTestOverlap);
/// Return true if the two colliders of the pair were already colliding the previous frame
bool getCollidingInPreviousFrame(uint64 pairId) const;
/// Set to true if the two colliders of the pair were already colliding the previous frame
void setCollidingInPreviousFrame(uint64 pairId, bool wereCollidingInPreviousFrame);
/// Return a reference to an overlapping pair
OverlappingPair* getOverlappingPair(uint64 pairId);
#ifdef IS_RP3D_PROFILING_ENABLED
@ -310,51 +381,8 @@ class OverlappingPairs {
friend class CollisionDetectionSystem;
};
// Return the entity of the first collider
inline Entity OverlappingPairs::getCollider1(uint64 pairId) const {
assert(mMapPairIdToPairIndex.containsKey(pairId));
assert(mMapPairIdToPairIndex[pairId] < mNbPairs);
return mColliders1[mMapPairIdToPairIndex[pairId]];
}
// Return the entity of the second collider
inline Entity OverlappingPairs::getCollider2(uint64 pairId) const {
assert(mMapPairIdToPairIndex.containsKey(pairId));
assert(mMapPairIdToPairIndex[pairId] < mNbPairs);
return mColliders2[mMapPairIdToPairIndex[pairId]];
}
// Notify if a given pair is active or not
inline void OverlappingPairs::setIsPairActive(uint64 pairId, bool isActive) {
assert(mMapPairIdToPairIndex.containsKey(pairId));
assert(mMapPairIdToPairIndex[pairId] < mNbPairs);
mIsActive[mMapPairIdToPairIndex[pairId]] = isActive;
}
// Return the index of a given overlapping pair in the internal array
inline uint64 OverlappingPairs::getPairIndex(uint64 pairId) const {
assert(mMapPairIdToPairIndex.containsKey(pairId));
return mMapPairIdToPairIndex[pairId];
}
// Return the last frame collision info for a given shape id or nullptr if none is found
inline LastFrameCollisionInfo* OverlappingPairs::getLastFrameCollisionInfo(uint64 pairId, uint64 shapesId) {
assert(mMapPairIdToPairIndex.containsKey(pairId));
const uint64 index = mMapPairIdToPairIndex[pairId];
assert(index < mNbPairs);
Map<uint64, LastFrameCollisionInfo*>::Iterator it = mLastFrameCollisionInfos[index].find(shapesId);
if (it != mLastFrameCollisionInfos[index].end()) {
return it->second;
}
return nullptr;
}
// Return the pair of bodies index
inline bodypair OverlappingPairs::computeBodiesIndexPair(Entity body1Entity, Entity body2Entity) {
RP3D_FORCE_INLINE bodypair OverlappingPairs::computeBodiesIndexPair(Entity body1Entity, Entity body2Entity) {
// Construct the pair of body index
bodypair indexPair = body1Entity.id < body2Entity.id ?
@ -364,53 +392,39 @@ inline bodypair OverlappingPairs::computeBodiesIndexPair(Entity body1Entity, Ent
return indexPair;
}
// Return the number of pairs
inline uint64 OverlappingPairs::getNbPairs() const {
return mNbPairs;
}
// Return the number of convex vs convex pairs
inline uint64 OverlappingPairs::getNbConvexVsConvexPairs() const {
return mConcavePairsStartIndex;
}
// Return the number of convex vs concave pairs
inline uint64 OverlappingPairs::getNbConvexVsConcavePairs() const {
return mNbPairs - mConcavePairsStartIndex;
}
// Return the starting index of the convex vs concave pairs
inline uint64 OverlappingPairs::getConvexVsConcavePairsStartIndex() const {
return mConcavePairsStartIndex;
}
// Return a reference to the temporary memory allocator
inline MemoryAllocator& OverlappingPairs::getTemporaryAllocator() {
return mTempMemoryAllocator;
}
// Set if we need to test a given pair for overlap
inline void OverlappingPairs::setNeedToTestOverlap(uint64 pairId, bool needToTestOverlap) {
assert(mMapPairIdToPairIndex.containsKey(pairId));
mNeedToTestOverlap[mMapPairIdToPairIndex[pairId]] = needToTestOverlap;
RP3D_FORCE_INLINE void OverlappingPairs::setNeedToTestOverlap(uint64 pairId, bool needToTestOverlap) {
assert(mMapConvexPairIdToPairIndex.containsKey(pairId) || mMapConcavePairIdToPairIndex.containsKey(pairId));
auto it = mMapConvexPairIdToPairIndex.find(pairId);
if (it != mMapConvexPairIdToPairIndex.end()) {
mConvexPairs[it->second].needToTestOverlap = needToTestOverlap;
}
else {
mConcavePairs[mMapConcavePairIdToPairIndex[pairId]].needToTestOverlap = needToTestOverlap;
}
}
// Return true if the two colliders of the pair were already colliding the previous frame
inline bool OverlappingPairs::getCollidingInPreviousFrame(uint64 pairId) const {
assert(mMapPairIdToPairIndex.containsKey(pairId));
return mCollidingInPreviousFrame[mMapPairIdToPairIndex[pairId]];
}
// Return a reference to an overlapping pair
RP3D_FORCE_INLINE OverlappingPairs::OverlappingPair* OverlappingPairs::getOverlappingPair(uint64 pairId) {
// Set to true if the two colliders of the pair were already colliding the previous frame
inline void OverlappingPairs::setCollidingInPreviousFrame(uint64 pairId, bool wereCollidingInPreviousFrame) {
assert(mMapPairIdToPairIndex.containsKey(pairId));
mCollidingInPreviousFrame[mMapPairIdToPairIndex[pairId]] = wereCollidingInPreviousFrame;
auto it = mMapConvexPairIdToPairIndex.find(pairId);
if (it != mMapConvexPairIdToPairIndex.end()) {
return &(mConvexPairs[it->second]);
}
it = mMapConcavePairIdToPairIndex.find(pairId);
if (it != mMapConcavePairIdToPairIndex.end()) {
return &(mConcavePairs[it->second]);
}
return nullptr;
}
#ifdef IS_RP3D_PROFILING_ENABLED
// Set the profiler
inline void OverlappingPairs::setProfiler(Profiler* profiler) {
RP3D_FORCE_INLINE void OverlappingPairs::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}

View File

@ -92,11 +92,56 @@ class PhysicsCommon {
/// Set of default loggers
Set<DefaultLogger*> mDefaultLoggers;
/// Half-edge structure of a box polyhedron
HalfEdgeStructure mBoxShapeHalfEdgeStructure;
/// Half-edge structure of a triangle shape
HalfEdgeStructure mTriangleShapeHalfEdgeStructure;
// -------------------- Methods -------------------- //
/// Initialization
void init();
/// Destroy and release everything that has been allocated
void release();
/// Delete an instance of PhysicsWorld
void deletePhysicsWorld(PhysicsWorld* world);
/// Delete a sphere collision shape
void deleteSphereShape(SphereShape* sphereShape);
/// Delete a box collision shape
void deleteBoxShape(BoxShape* boxShape);
/// Delete a capsule collision shape
void deleteCapsuleShape(CapsuleShape* capsuleShape);
/// Delete a convex mesh shape
void deleteConvexMeshShape(ConvexMeshShape* convexMeshShape);
/// Delete a height-field shape
void deleteHeightFieldShape(HeightFieldShape* heightFieldShape);
/// Delete a concave mesh shape
void deleteConcaveMeshShape(ConcaveMeshShape* concaveMeshShape);
/// Delete a polyhedron mesh
void deletePolyhedronMesh(PolyhedronMesh* polyhedronMesh);
/// Delete a triangle mesh
void deleteTriangleMesh(TriangleMesh* triangleMesh);
/// Delete a default logger
void deleteDefaultLogger(DefaultLogger* logger);
/// Initialize the half-edge structure of a BoxShape
void initBoxShapeHalfEdgeStructure();
/// Initialize the static half-edge structure of a TriangleShape
void initTriangleShapeHalfEdgeStructure();
// If profiling is enabled
#ifdef IS_RP3D_PROFILING_ENABLED
@ -106,6 +151,9 @@ class PhysicsCommon {
/// Destroy a profiler
void destroyProfiler(Profiler* profiler);
/// Delete a profiler
void deleteProfiler(Profiler* profiler);
#endif
public :
@ -187,13 +235,19 @@ class PhysicsCommon {
/// Set the logger
static void setLogger(Logger* logger);
// ---------- Friendship ---------- //
friend class BoxShape;
friend class TriangleShape;
friend class PhysicsWorld;
};
// Return the current logger
/**
* @return A pointer to the current logger
*/
inline Logger* PhysicsCommon::getLogger() {
RP3D_FORCE_INLINE Logger* PhysicsCommon::getLogger() {
return mLogger;
}
@ -201,7 +255,7 @@ inline Logger* PhysicsCommon::getLogger() {
/**
* @param logger A pointer to the logger to use
*/
inline void PhysicsCommon::setLogger(Logger* logger) {
RP3D_FORCE_INLINE void PhysicsCommon::setLogger(Logger* logger) {
mLogger = logger;
}

View File

@ -28,7 +28,7 @@
// Libraries
#include <reactphysics3d/mathematics/mathematics.h>
#include <reactphysics3d/containers/List.h>
#include <reactphysics3d/containers/Array.h>
#include <reactphysics3d/constraint/Joint.h>
#include <reactphysics3d/memory/MemoryManager.h>
#include <reactphysics3d/engine/EntityManager.h>
@ -59,6 +59,7 @@ namespace reactphysics3d {
// Declarations
class Island;
class RigidBody;
class PhysicsCommon;
struct JointInfo;
// Class PhysicsWorld
@ -93,9 +94,6 @@ class PhysicsWorld {
/// Velocity threshold for contact velocity restitution
decimal restitutionVelocityThreshold;
/// Default rolling resistance
decimal defaultRollingRestistance;
/// True if the sleeping technique is enabled
bool isSleepingEnabled;
@ -116,9 +114,6 @@ class PhysicsWorld {
/// might enter sleeping mode
decimal defaultSleepAngularVelocity;
/// Maximum number of contact manifolds in an overlapping pair
uint nbMaxContactManifolds;
/// This is used to test if two contact manifold are similar (same contact normal) in order to
/// merge them. If the cosine of the angle between the normals of the two manifold are larger
/// than the value bellow, the manifold are considered to be similar.
@ -132,14 +127,12 @@ class PhysicsWorld {
defaultFrictionCoefficient = decimal(0.3);
defaultBounciness = decimal(0.5);
restitutionVelocityThreshold = decimal(0.5);
defaultRollingRestistance = decimal(0.0);
isSleepingEnabled = true;
defaultVelocitySolverNbIterations = 10;
defaultPositionSolverNbIterations = 5;
defaultVelocitySolverNbIterations = 6;
defaultPositionSolverNbIterations = 3;
defaultTimeBeforeSleep = 1.0f;
defaultSleepLinearVelocity = decimal(0.02);
defaultSleepAngularVelocity = decimal(3.0) * (PI_RP3D / decimal(180.0));
nbMaxContactManifolds = 3;
cosAngleSimilarContactManifold = decimal(0.95);
}
@ -156,14 +149,12 @@ class PhysicsWorld {
ss << "defaultFrictionCoefficient=" << defaultFrictionCoefficient << std::endl;
ss << "defaultBounciness=" << defaultBounciness << std::endl;
ss << "restitutionVelocityThreshold=" << restitutionVelocityThreshold << std::endl;
ss << "defaultRollingRestistance=" << defaultRollingRestistance << std::endl;
ss << "isSleepingEnabled=" << isSleepingEnabled << std::endl;
ss << "defaultVelocitySolverNbIterations=" << defaultVelocitySolverNbIterations << std::endl;
ss << "defaultPositionSolverNbIterations=" << defaultPositionSolverNbIterations << std::endl;
ss << "defaultTimeBeforeSleep=" << defaultTimeBeforeSleep << std::endl;
ss << "defaultSleepLinearVelocity=" << defaultSleepLinearVelocity << std::endl;
ss << "defaultSleepAngularVelocity=" << defaultSleepAngularVelocity << std::endl;
ss << "nbMaxContactManifolds=" << nbMaxContactManifolds << std::endl;
ss << "cosAngleSimilarContactManifold=" << cosAngleSimilarContactManifold << std::endl;
return ss.str();
@ -220,7 +211,7 @@ class PhysicsWorld {
CollisionDetectionSystem mCollisionDetection;
/// All the collision bodies of the world
List<CollisionBody*> mCollisionBodies;
Array<CollisionBody*> mCollisionBodies;
/// Pointer to an event listener object
EventListener* mEventListener;
@ -240,6 +231,11 @@ class PhysicsWorld {
/// All the islands of bodies of the current frame
Islands mIslands;
/// Order in which to process the ContactPairs for contact creation such that
/// all the contact manifolds and contact points of a given island are packed together
/// This array contains the indices of the ContactPairs.
Array<uint32> mProcessContactPairsOrderIslands;
/// Contact solver system
ContactSolverSystem mContactSolverSystem;
@ -259,7 +255,7 @@ class PhysicsWorld {
bool mIsSleepingEnabled;
/// All the rigid bodies of the physics world
List<RigidBody*> mRigidBodies;
Array<RigidBody*> mRigidBodies;
/// True if the gravity force is on
bool mIsGravityEnabled;
@ -280,7 +276,7 @@ class PhysicsWorld {
// -------------------- Methods -------------------- //
/// Constructor
PhysicsWorld(MemoryManager& memoryManager, const WorldSettings& worldSettings = WorldSettings(), Profiler* profiler = nullptr);
PhysicsWorld(MemoryManager& memoryManager, PhysicsCommon& physicsCommon, const WorldSettings& worldSettings = WorldSettings(), Profiler* profiler = nullptr);
/// Notify the world if a body is disabled (slepping or inactive) or not
void setBodyDisabled(Entity entity, bool isDisabled);
@ -303,9 +299,12 @@ class PhysicsWorld {
/// Put bodies to sleep if needed.
void updateSleepingBodies(decimal timeStep);
/// Add the joint to the list of joints of the two bodies involved in the joint
/// Add the joint to the array of joints of the two bodies involved in the joint
void addJointToBodies(Entity body1, Entity body2, Entity joint);
/// Update the world inverse inertia tensors of rigid bodies
void updateBodiesInverseWorldInertiaTensors();
/// Destructor
~PhysicsWorld();
@ -491,7 +490,7 @@ class PhysicsWorld {
* @param CollisionDispatch Pointer to a collision dispatch object describing
* which collision detection algorithm to use for two given collision shapes
*/
inline CollisionDispatch& PhysicsWorld::getCollisionDispatch() {
RP3D_FORCE_INLINE CollisionDispatch& PhysicsWorld::getCollisionDispatch() {
return mCollisionDetection.getCollisionDispatch();
}
@ -502,7 +501,7 @@ inline CollisionDispatch& PhysicsWorld::getCollisionDispatch() {
* @param raycastWithCategoryMaskBits Bits mask corresponding to the category of
* bodies to be raycasted
*/
inline void PhysicsWorld::raycast(const Ray& ray,
RP3D_FORCE_INLINE void PhysicsWorld::raycast(const Ray& ray,
RaycastCallback* raycastCallback,
unsigned short raycastWithCategoryMaskBits) const {
mCollisionDetection.raycast(raycastCallback, ray, raycastWithCategoryMaskBits);
@ -518,7 +517,7 @@ inline void PhysicsWorld::raycast(const Ray& ray,
* @param body2 Pointer to the second body to test
* @param callback Pointer to the object with the callback method
*/
inline void PhysicsWorld::testCollision(CollisionBody* body1, CollisionBody* body2, CollisionCallback& callback) {
RP3D_FORCE_INLINE void PhysicsWorld::testCollision(CollisionBody* body1, CollisionBody* body2, CollisionCallback& callback) {
mCollisionDetection.testCollision(body1, body2, callback);
}
@ -531,7 +530,7 @@ inline void PhysicsWorld::testCollision(CollisionBody* body1, CollisionBody* bod
* @param body Pointer to the body against which we need to test collision
* @param callback Pointer to the object with the callback method to report contacts
*/
inline void PhysicsWorld::testCollision(CollisionBody* body, CollisionCallback& callback) {
RP3D_FORCE_INLINE void PhysicsWorld::testCollision(CollisionBody* body, CollisionCallback& callback) {
mCollisionDetection.testCollision(body, callback);
}
@ -543,7 +542,7 @@ inline void PhysicsWorld::testCollision(CollisionBody* body, CollisionCallback&
/**
* @param callback Pointer to the object with the callback method to report contacts
*/
inline void PhysicsWorld::testCollision(CollisionCallback& callback) {
RP3D_FORCE_INLINE void PhysicsWorld::testCollision(CollisionCallback& callback) {
mCollisionDetection.testCollision(callback);
}
@ -555,7 +554,7 @@ inline void PhysicsWorld::testCollision(CollisionCallback& callback) {
* @param body Pointer to the collision body to test overlap with
* @param overlapCallback Pointer to the callback class to report overlap
*/
inline void PhysicsWorld::testOverlap(CollisionBody* body, OverlapCallback& overlapCallback) {
RP3D_FORCE_INLINE void PhysicsWorld::testOverlap(CollisionBody* body, OverlapCallback& overlapCallback) {
mCollisionDetection.testOverlap(body, overlapCallback);
}
@ -566,12 +565,12 @@ inline void PhysicsWorld::testOverlap(CollisionBody* body, OverlapCallback& over
/**
* @param overlapCallback Pointer to the callback class to report overlap
*/
inline void PhysicsWorld::testOverlap(OverlapCallback& overlapCallback) {
RP3D_FORCE_INLINE void PhysicsWorld::testOverlap(OverlapCallback& overlapCallback) {
mCollisionDetection.testOverlap(overlapCallback);
}
// Return a reference to the memory manager of the world
inline MemoryManager& PhysicsWorld::getMemoryManager() {
RP3D_FORCE_INLINE MemoryManager& PhysicsWorld::getMemoryManager() {
return mMemoryManager;
}
@ -579,7 +578,7 @@ inline MemoryManager& PhysicsWorld::getMemoryManager() {
/**
* @return Name of the world
*/
inline const std::string& PhysicsWorld::getName() const {
RP3D_FORCE_INLINE const std::string& PhysicsWorld::getName() const {
return mName;
}
@ -589,7 +588,7 @@ inline const std::string& PhysicsWorld::getName() const {
/**
* @return A pointer to the profiler
*/
inline Profiler* PhysicsWorld::getProfiler() {
RP3D_FORCE_INLINE Profiler* PhysicsWorld::getProfiler() {
return mProfiler;
}
@ -599,7 +598,7 @@ inline Profiler* PhysicsWorld::getProfiler() {
/**
* @return The number of iterations of the velocity constraint solver
*/
inline uint PhysicsWorld::getNbIterationsVelocitySolver() const {
RP3D_FORCE_INLINE uint PhysicsWorld::getNbIterationsVelocitySolver() const {
return mNbVelocitySolverIterations;
}
@ -607,7 +606,7 @@ inline uint PhysicsWorld::getNbIterationsVelocitySolver() const {
/**
* @return The number of iterations of the position constraint solver
*/
inline uint PhysicsWorld::getNbIterationsPositionSolver() const {
RP3D_FORCE_INLINE uint PhysicsWorld::getNbIterationsPositionSolver() const {
return mNbPositionSolverIterations;
}
@ -615,7 +614,7 @@ inline uint PhysicsWorld::getNbIterationsPositionSolver() const {
/**
* @param technique Technique used for the position correction (Baumgarte or Split Impulses)
*/
inline void PhysicsWorld::setContactsPositionCorrectionTechnique(
RP3D_FORCE_INLINE void PhysicsWorld::setContactsPositionCorrectionTechnique(
ContactsPositionCorrectionTechnique technique) {
if (technique == ContactsPositionCorrectionTechnique::BAUMGARTE_CONTACTS) {
mContactSolverSystem.setIsSplitImpulseActive(false);
@ -629,7 +628,7 @@ inline void PhysicsWorld::setContactsPositionCorrectionTechnique(
/**
* @return The current gravity vector (in meter per seconds squared)
*/
inline Vector3 PhysicsWorld::getGravity() const {
RP3D_FORCE_INLINE Vector3 PhysicsWorld::getGravity() const {
return mConfig.gravity;
}
@ -637,7 +636,7 @@ inline Vector3 PhysicsWorld::getGravity() const {
/**
* @return True if the gravity is enabled in the world
*/
inline bool PhysicsWorld::isGravityEnabled() const {
RP3D_FORCE_INLINE bool PhysicsWorld::isGravityEnabled() const {
return mIsGravityEnabled;
}
@ -645,7 +644,7 @@ inline bool PhysicsWorld::isGravityEnabled() const {
/**
* @return True if the sleeping technique is enabled and false otherwise
*/
inline bool PhysicsWorld::isSleepingEnabled() const {
RP3D_FORCE_INLINE bool PhysicsWorld::isSleepingEnabled() const {
return mIsSleepingEnabled;
}
@ -653,7 +652,7 @@ inline bool PhysicsWorld::isSleepingEnabled() const {
/**
* @return The sleep linear velocity (in meters per second)
*/
inline decimal PhysicsWorld::getSleepLinearVelocity() const {
RP3D_FORCE_INLINE decimal PhysicsWorld::getSleepLinearVelocity() const {
return mSleepLinearVelocity;
}
@ -661,7 +660,7 @@ inline decimal PhysicsWorld::getSleepLinearVelocity() const {
/**
* @return The sleep angular velocity (in radian per second)
*/
inline decimal PhysicsWorld::getSleepAngularVelocity() const {
RP3D_FORCE_INLINE decimal PhysicsWorld::getSleepAngularVelocity() const {
return mSleepAngularVelocity;
}
@ -669,7 +668,7 @@ inline decimal PhysicsWorld::getSleepAngularVelocity() const {
/**
* @return Time a body is required to stay still before sleeping (in seconds)
*/
inline decimal PhysicsWorld::getTimeBeforeSleep() const {
RP3D_FORCE_INLINE decimal PhysicsWorld::getTimeBeforeSleep() const {
return mTimeBeforeSleep;
}
@ -679,7 +678,7 @@ inline decimal PhysicsWorld::getTimeBeforeSleep() const {
* @param eventListener Pointer to the event listener object that will receive
* event callbacks during the simulation
*/
inline void PhysicsWorld::setEventListener(EventListener* eventListener) {
RP3D_FORCE_INLINE void PhysicsWorld::setEventListener(EventListener* eventListener) {
mEventListener = eventListener;
}
@ -688,7 +687,7 @@ inline void PhysicsWorld::setEventListener(EventListener* eventListener) {
/**
* @return The number of collision bodies in the physics world
*/
inline uint PhysicsWorld::getNbCollisionBodies() const {
RP3D_FORCE_INLINE uint32 PhysicsWorld::getNbCollisionBodies() const {
return mCollisionBodies.size();
}
@ -696,7 +695,7 @@ inline uint PhysicsWorld::getNbCollisionBodies() const {
/**
* @return The number of rigid bodies in the physics world
*/
inline uint PhysicsWorld::getNbRigidBodies() const {
RP3D_FORCE_INLINE uint32 PhysicsWorld::getNbRigidBodies() const {
return mRigidBodies.size();
}
@ -704,7 +703,7 @@ inline uint PhysicsWorld::getNbRigidBodies() const {
/**
* @return True if the debug rendering is enabled and false otherwise
*/
inline bool PhysicsWorld::getIsDebugRenderingEnabled() const {
RP3D_FORCE_INLINE bool PhysicsWorld::getIsDebugRenderingEnabled() const {
return mIsDebugRenderingEnabled;
}
@ -712,7 +711,7 @@ inline bool PhysicsWorld::getIsDebugRenderingEnabled() const {
/**
* @param isEnabled True if you want to enable the debug rendering and false otherwise
*/
inline void PhysicsWorld::setIsDebugRenderingEnabled(bool isEnabled) {
RP3D_FORCE_INLINE void PhysicsWorld::setIsDebugRenderingEnabled(bool isEnabled) {
mIsDebugRenderingEnabled = isEnabled;
}
@ -720,7 +719,7 @@ inline void PhysicsWorld::setIsDebugRenderingEnabled(bool isEnabled) {
/**
* @return A reference to the DebugRenderer object of the world
*/
inline DebugRenderer& PhysicsWorld::getDebugRenderer() {
RP3D_FORCE_INLINE DebugRenderer& PhysicsWorld::getDebugRenderer() {
return mDebugRenderer;
}

View File

@ -120,28 +120,28 @@ class Timer {
};
// Return the timestep of the physics engine
inline double Timer::getTimeStep() const {
RP3D_FORCE_INLINE double Timer::getTimeStep() const {
return mTimeStep;
}
// Set the timestep of the physics engine
inline void Timer::setTimeStep(double timeStep) {
RP3D_FORCE_INLINE void Timer::setTimeStep(double timeStep) {
assert(timeStep > 0.0f);
mTimeStep = timeStep;
}
// Return the current time
inline long double Timer::getPhysicsTime() const {
RP3D_FORCE_INLINE long double Timer::getPhysicsTime() const {
return mLastUpdateTime;
}
// Return if the timer is running
inline bool Timer::getIsRunning() const {
RP3D_FORCE_INLINE bool Timer::getIsRunning() const {
return mIsRunning;
}
// Start the timer
inline void Timer::start() {
RP3D_FORCE_INLINE void Timer::start() {
if (!mIsRunning) {
// Get the current system time
@ -153,17 +153,17 @@ inline void Timer::start() {
}
// Stop the timer
inline void Timer::stop() {
RP3D_FORCE_INLINE void Timer::stop() {
mIsRunning = false;
}
// True if it's possible to take a new step
inline bool Timer::isPossibleToTakeStep() const {
RP3D_FORCE_INLINE bool Timer::isPossibleToTakeStep() const {
return (mAccumulator >= mTimeStep);
}
// Take a new step => update the timer by adding the timeStep value to the current time
inline void Timer::nextStep() {
RP3D_FORCE_INLINE void Timer::nextStep() {
assert(mIsRunning);
// Update the accumulator value
@ -171,12 +171,12 @@ inline void Timer::nextStep() {
}
// Compute the interpolation factor
inline decimal Timer::computeInterpolationFactor() {
RP3D_FORCE_INLINE decimal Timer::computeInterpolationFactor() {
return (decimal(mAccumulator / mTimeStep));
}
// Compute the time since the last update() call and add it to the accumulator
inline void Timer::update() {
RP3D_FORCE_INLINE void Timer::update() {
// Get the current system time
long double currentTime = getCurrentSystemTime();

View File

@ -151,57 +151,57 @@ class Matrix2x2 {
};
// Constructor of the class Matrix2x2
inline Matrix2x2::Matrix2x2() {
RP3D_FORCE_INLINE Matrix2x2::Matrix2x2() {
// Initialize all values in the matrix to zero
setAllValues(0.0, 0.0, 0.0, 0.0);
}
// Constructor
inline Matrix2x2::Matrix2x2(decimal value) {
RP3D_FORCE_INLINE Matrix2x2::Matrix2x2(decimal value) {
setAllValues(value, value, value, value);
}
// Constructor with arguments
inline Matrix2x2::Matrix2x2(decimal a1, decimal a2, decimal b1, decimal b2) {
RP3D_FORCE_INLINE Matrix2x2::Matrix2x2(decimal a1, decimal a2, decimal b1, decimal b2) {
// Initialize the matrix with the values
setAllValues(a1, a2, b1, b2);
}
// Copy-constructor
inline Matrix2x2::Matrix2x2(const Matrix2x2& matrix) {
RP3D_FORCE_INLINE Matrix2x2::Matrix2x2(const Matrix2x2& matrix) {
setAllValues(matrix.mRows[0][0], matrix.mRows[0][1],
matrix.mRows[1][0], matrix.mRows[1][1]);
}
// Method to set all the values in the matrix
inline void Matrix2x2::setAllValues(decimal a1, decimal a2,
RP3D_FORCE_INLINE void Matrix2x2::setAllValues(decimal a1, decimal a2,
decimal b1, decimal b2) {
mRows[0][0] = a1; mRows[0][1] = a2;
mRows[1][0] = b1; mRows[1][1] = b2;
}
// Set the matrix to zero
inline void Matrix2x2::setToZero() {
RP3D_FORCE_INLINE void Matrix2x2::setToZero() {
mRows[0].setToZero();
mRows[1].setToZero();
}
// Return a column
inline Vector2 Matrix2x2::getColumn(int i) const {
RP3D_FORCE_INLINE Vector2 Matrix2x2::getColumn(int i) const {
assert(i>= 0 && i<2);
return Vector2(mRows[0][i], mRows[1][i]);
}
// Return a row
inline Vector2 Matrix2x2::getRow(int i) const {
RP3D_FORCE_INLINE Vector2 Matrix2x2::getRow(int i) const {
assert(i>= 0 && i<2);
return mRows[i];
}
// Return the transpose matrix
inline Matrix2x2 Matrix2x2::getTranspose() const {
RP3D_FORCE_INLINE Matrix2x2 Matrix2x2::getTranspose() const {
// Return the transpose matrix
return Matrix2x2(mRows[0][0], mRows[1][0],
@ -209,45 +209,45 @@ inline Matrix2x2 Matrix2x2::getTranspose() const {
}
// Return the determinant of the matrix
inline decimal Matrix2x2::getDeterminant() const {
RP3D_FORCE_INLINE decimal Matrix2x2::getDeterminant() const {
// Compute and return the determinant of the matrix
return mRows[0][0] * mRows[1][1] - mRows[1][0] * mRows[0][1];
}
// Return the trace of the matrix
inline decimal Matrix2x2::getTrace() const {
RP3D_FORCE_INLINE decimal Matrix2x2::getTrace() const {
// Compute and return the trace
return (mRows[0][0] + mRows[1][1]);
}
// Set the matrix to the identity matrix
inline void Matrix2x2::setToIdentity() {
RP3D_FORCE_INLINE void Matrix2x2::setToIdentity() {
mRows[0][0] = 1.0; mRows[0][1] = 0.0;
mRows[1][0] = 0.0; mRows[1][1] = 1.0;
}
// Return the 2x2 identity matrix
inline Matrix2x2 Matrix2x2::identity() {
RP3D_FORCE_INLINE Matrix2x2 Matrix2x2::identity() {
// Return the isdentity matrix
return Matrix2x2(1.0, 0.0, 0.0, 1.0);
}
// Return the 2x2 zero matrix
inline Matrix2x2 Matrix2x2::zero() {
RP3D_FORCE_INLINE Matrix2x2 Matrix2x2::zero() {
return Matrix2x2(0.0, 0.0, 0.0, 0.0);
}
// Return the matrix with absolute values
inline Matrix2x2 Matrix2x2::getAbsoluteMatrix() const {
return Matrix2x2(fabs(mRows[0][0]), fabs(mRows[0][1]),
fabs(mRows[1][0]), fabs(mRows[1][1]));
RP3D_FORCE_INLINE Matrix2x2 Matrix2x2::getAbsoluteMatrix() const {
return Matrix2x2(std::abs(mRows[0][0]), std::abs(mRows[0][1]),
std::abs(mRows[1][0]), std::abs(mRows[1][1]));
}
// Overloaded operator for addition
inline Matrix2x2 operator+(const Matrix2x2& matrix1, const Matrix2x2& matrix2) {
RP3D_FORCE_INLINE Matrix2x2 operator+(const Matrix2x2& matrix1, const Matrix2x2& matrix2) {
return Matrix2x2(matrix1.mRows[0][0] + matrix2.mRows[0][0],
matrix1.mRows[0][1] + matrix2.mRows[0][1],
matrix1.mRows[1][0] + matrix2.mRows[1][0],
@ -255,7 +255,7 @@ inline Matrix2x2 operator+(const Matrix2x2& matrix1, const Matrix2x2& matrix2) {
}
// Overloaded operator for substraction
inline Matrix2x2 operator-(const Matrix2x2& matrix1, const Matrix2x2& matrix2) {
RP3D_FORCE_INLINE Matrix2x2 operator-(const Matrix2x2& matrix1, const Matrix2x2& matrix2) {
return Matrix2x2(matrix1.mRows[0][0] - matrix2.mRows[0][0],
matrix1.mRows[0][1] - matrix2.mRows[0][1],
matrix1.mRows[1][0] - matrix2.mRows[1][0],
@ -263,24 +263,24 @@ inline Matrix2x2 operator-(const Matrix2x2& matrix1, const Matrix2x2& matrix2) {
}
// Overloaded operator for the negative of the matrix
inline Matrix2x2 operator-(const Matrix2x2& matrix) {
RP3D_FORCE_INLINE Matrix2x2 operator-(const Matrix2x2& matrix) {
return Matrix2x2(-matrix.mRows[0][0], -matrix.mRows[0][1],
-matrix.mRows[1][0], -matrix.mRows[1][1]);
}
// Overloaded operator for multiplication with a number
inline Matrix2x2 operator*(decimal nb, const Matrix2x2& matrix) {
RP3D_FORCE_INLINE Matrix2x2 operator*(decimal nb, const Matrix2x2& matrix) {
return Matrix2x2(matrix.mRows[0][0] * nb, matrix.mRows[0][1] * nb,
matrix.mRows[1][0] * nb, matrix.mRows[1][1] * nb);
}
// Overloaded operator for multiplication with a matrix
inline Matrix2x2 operator*(const Matrix2x2& matrix, decimal nb) {
RP3D_FORCE_INLINE Matrix2x2 operator*(const Matrix2x2& matrix, decimal nb) {
return nb * matrix;
}
// Overloaded operator for matrix multiplication
inline Matrix2x2 operator*(const Matrix2x2& matrix1, const Matrix2x2& matrix2) {
RP3D_FORCE_INLINE Matrix2x2 operator*(const Matrix2x2& matrix1, const Matrix2x2& matrix2) {
return Matrix2x2(matrix1.mRows[0][0] * matrix2.mRows[0][0] + matrix1.mRows[0][1] *
matrix2.mRows[1][0],
matrix1.mRows[0][0] * matrix2.mRows[0][1] + matrix1.mRows[0][1] *
@ -292,38 +292,38 @@ inline Matrix2x2 operator*(const Matrix2x2& matrix1, const Matrix2x2& matrix2) {
}
// Overloaded operator for multiplication with a vector
inline Vector2 operator*(const Matrix2x2& matrix, const Vector2& vector) {
RP3D_FORCE_INLINE Vector2 operator*(const Matrix2x2& matrix, const Vector2& vector) {
return Vector2(matrix.mRows[0][0]*vector.x + matrix.mRows[0][1]*vector.y,
matrix.mRows[1][0]*vector.x + matrix.mRows[1][1]*vector.y);
}
// Overloaded operator for equality condition
inline bool Matrix2x2::operator==(const Matrix2x2& matrix) const {
RP3D_FORCE_INLINE bool Matrix2x2::operator==(const Matrix2x2& matrix) const {
return (mRows[0][0] == matrix.mRows[0][0] && mRows[0][1] == matrix.mRows[0][1] &&
mRows[1][0] == matrix.mRows[1][0] && mRows[1][1] == matrix.mRows[1][1]);
}
// Overloaded operator for the is different condition
inline bool Matrix2x2::operator!= (const Matrix2x2& matrix) const {
RP3D_FORCE_INLINE bool Matrix2x2::operator!= (const Matrix2x2& matrix) const {
return !(*this == matrix);
}
// Overloaded operator for addition with assignment
inline Matrix2x2& Matrix2x2::operator+=(const Matrix2x2& matrix) {
RP3D_FORCE_INLINE Matrix2x2& Matrix2x2::operator+=(const Matrix2x2& matrix) {
mRows[0][0] += matrix.mRows[0][0]; mRows[0][1] += matrix.mRows[0][1];
mRows[1][0] += matrix.mRows[1][0]; mRows[1][1] += matrix.mRows[1][1];
return *this;
}
// Overloaded operator for substraction with assignment
inline Matrix2x2& Matrix2x2::operator-=(const Matrix2x2& matrix) {
RP3D_FORCE_INLINE Matrix2x2& Matrix2x2::operator-=(const Matrix2x2& matrix) {
mRows[0][0] -= matrix.mRows[0][0]; mRows[0][1] -= matrix.mRows[0][1];
mRows[1][0] -= matrix.mRows[1][0]; mRows[1][1] -= matrix.mRows[1][1];
return *this;
}
// Overloaded operator for multiplication with a number with assignment
inline Matrix2x2& Matrix2x2::operator*=(decimal nb) {
RP3D_FORCE_INLINE Matrix2x2& Matrix2x2::operator*=(decimal nb) {
mRows[0][0] *= nb; mRows[0][1] *= nb;
mRows[1][0] *= nb; mRows[1][1] *= nb;
return *this;
@ -332,19 +332,19 @@ inline Matrix2x2& Matrix2x2::operator*=(decimal nb) {
// Overloaded operator to return a row of the matrix.
/// This operator is also used to access a matrix value using the syntax
/// matrix[row][col].
inline const Vector2& Matrix2x2::operator[](int row) const {
RP3D_FORCE_INLINE const Vector2& Matrix2x2::operator[](int row) const {
return mRows[row];
}
// Overloaded operator to return a row of the matrix.
/// This operator is also used to access a matrix value using the syntax
/// matrix[row][col].
inline Vector2& Matrix2x2::operator[](int row) {
RP3D_FORCE_INLINE Vector2& Matrix2x2::operator[](int row) {
return mRows[row];
}
// Get the string representation
inline std::string Matrix2x2::to_string() const {
RP3D_FORCE_INLINE std::string Matrix2x2::to_string() const {
return "Matrix2x2(" + std::to_string(mRows[0][0]) + "," + std::to_string(mRows[0][1]) + "," +
std::to_string(mRows[1][0]) + "," + std::to_string(mRows[1][1]) + ")";
}

View File

@ -158,18 +158,18 @@ class Matrix3x3 {
};
// Constructor of the class Matrix3x3
inline Matrix3x3::Matrix3x3() {
RP3D_FORCE_INLINE Matrix3x3::Matrix3x3() {
// Initialize all values in the matrix to zero
setAllValues(0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0);
}
// Constructor
inline Matrix3x3::Matrix3x3(decimal value) {
RP3D_FORCE_INLINE Matrix3x3::Matrix3x3(decimal value) {
setAllValues(value, value, value, value, value, value, value, value, value);
}
// Constructor with arguments
inline Matrix3x3::Matrix3x3(decimal a1, decimal a2, decimal a3,
RP3D_FORCE_INLINE Matrix3x3::Matrix3x3(decimal a1, decimal a2, decimal a3,
decimal b1, decimal b2, decimal b3,
decimal c1, decimal c2, decimal c3) {
// Initialize the matrix with the values
@ -177,14 +177,14 @@ inline Matrix3x3::Matrix3x3(decimal a1, decimal a2, decimal a3,
}
// Copy-constructor
inline Matrix3x3::Matrix3x3(const Matrix3x3& matrix) {
RP3D_FORCE_INLINE Matrix3x3::Matrix3x3(const Matrix3x3& matrix) {
setAllValues(matrix.mRows[0][0], matrix.mRows[0][1], matrix.mRows[0][2],
matrix.mRows[1][0], matrix.mRows[1][1], matrix.mRows[1][2],
matrix.mRows[2][0], matrix.mRows[2][1], matrix.mRows[2][2]);
}
// Method to set all the values in the matrix
inline void Matrix3x3::setAllValues(decimal a1, decimal a2, decimal a3,
RP3D_FORCE_INLINE void Matrix3x3::setAllValues(decimal a1, decimal a2, decimal a3,
decimal b1, decimal b2, decimal b3,
decimal c1, decimal c2, decimal c3) {
mRows[0][0] = a1; mRows[0][1] = a2; mRows[0][2] = a3;
@ -193,26 +193,26 @@ inline void Matrix3x3::setAllValues(decimal a1, decimal a2, decimal a3,
}
// Set the matrix to zero
inline void Matrix3x3::setToZero() {
RP3D_FORCE_INLINE void Matrix3x3::setToZero() {
mRows[0].setToZero();
mRows[1].setToZero();
mRows[2].setToZero();
}
// Return a column
inline Vector3 Matrix3x3::getColumn(int i) const {
RP3D_FORCE_INLINE Vector3 Matrix3x3::getColumn(int i) const {
assert(i>= 0 && i<3);
return Vector3(mRows[0][i], mRows[1][i], mRows[2][i]);
}
// Return a row
inline Vector3 Matrix3x3::getRow(int i) const {
RP3D_FORCE_INLINE Vector3 Matrix3x3::getRow(int i) const {
assert(i>= 0 && i<3);
return mRows[i];
}
// Return the transpose matrix
inline Matrix3x3 Matrix3x3::getTranspose() const {
RP3D_FORCE_INLINE Matrix3x3 Matrix3x3::getTranspose() const {
// Return the transpose matrix
return Matrix3x3(mRows[0][0], mRows[1][0], mRows[2][0],
@ -221,7 +221,7 @@ inline Matrix3x3 Matrix3x3::getTranspose() const {
}
// Return the determinant of the matrix
inline decimal Matrix3x3::getDeterminant() const {
RP3D_FORCE_INLINE decimal Matrix3x3::getDeterminant() const {
// Compute and return the determinant of the matrix
return (mRows[0][0]*(mRows[1][1]*mRows[2][2]-mRows[2][1]*mRows[1][2]) -
@ -230,44 +230,44 @@ inline decimal Matrix3x3::getDeterminant() const {
}
// Return the trace of the matrix
inline decimal Matrix3x3::getTrace() const {
RP3D_FORCE_INLINE decimal Matrix3x3::getTrace() const {
// Compute and return the trace
return (mRows[0][0] + mRows[1][1] + mRows[2][2]);
}
// Set the matrix to the identity matrix
inline void Matrix3x3::setToIdentity() {
RP3D_FORCE_INLINE void Matrix3x3::setToIdentity() {
mRows[0][0] = 1.0; mRows[0][1] = 0.0; mRows[0][2] = 0.0;
mRows[1][0] = 0.0; mRows[1][1] = 1.0; mRows[1][2] = 0.0;
mRows[2][0] = 0.0; mRows[2][1] = 0.0; mRows[2][2] = 1.0;
}
// Return the 3x3 identity matrix
inline Matrix3x3 Matrix3x3::identity() {
RP3D_FORCE_INLINE Matrix3x3 Matrix3x3::identity() {
return Matrix3x3(1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0);
}
// Return the 3x3 zero matrix
inline Matrix3x3 Matrix3x3::zero() {
RP3D_FORCE_INLINE Matrix3x3 Matrix3x3::zero() {
return Matrix3x3(0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0);
}
// Return a skew-symmetric matrix using a given vector that can be used
// to compute cross product with another vector using matrix multiplication
inline Matrix3x3 Matrix3x3::computeSkewSymmetricMatrixForCrossProduct(const Vector3& vector) {
RP3D_FORCE_INLINE Matrix3x3 Matrix3x3::computeSkewSymmetricMatrixForCrossProduct(const Vector3& vector) {
return Matrix3x3(0, -vector.z, vector.y, vector.z, 0, -vector.x, -vector.y, vector.x, 0);
}
// Return the matrix with absolute values
inline Matrix3x3 Matrix3x3::getAbsoluteMatrix() const {
return Matrix3x3(std::fabs(mRows[0][0]), std::fabs(mRows[0][1]), std::fabs(mRows[0][2]),
std::fabs(mRows[1][0]), std::fabs(mRows[1][1]), std::fabs(mRows[1][2]),
std::fabs(mRows[2][0]), std::fabs(mRows[2][1]), std::fabs(mRows[2][2]));
RP3D_FORCE_INLINE Matrix3x3 Matrix3x3::getAbsoluteMatrix() const {
return Matrix3x3(std::abs(mRows[0][0]), std::abs(mRows[0][1]), std::abs(mRows[0][2]),
std::abs(mRows[1][0]), std::abs(mRows[1][1]), std::abs(mRows[1][2]),
std::abs(mRows[2][0]), std::abs(mRows[2][1]), std::abs(mRows[2][2]));
}
// Overloaded operator for addition
inline Matrix3x3 operator+(const Matrix3x3& matrix1, const Matrix3x3& matrix2) {
RP3D_FORCE_INLINE Matrix3x3 operator+(const Matrix3x3& matrix1, const Matrix3x3& matrix2) {
return Matrix3x3(matrix1.mRows[0][0] + matrix2.mRows[0][0], matrix1.mRows[0][1] +
matrix2.mRows[0][1], matrix1.mRows[0][2] + matrix2.mRows[0][2],
matrix1.mRows[1][0] + matrix2.mRows[1][0], matrix1.mRows[1][1] +
@ -277,7 +277,7 @@ inline Matrix3x3 operator+(const Matrix3x3& matrix1, const Matrix3x3& matrix2) {
}
// Overloaded operator for substraction
inline Matrix3x3 operator-(const Matrix3x3& matrix1, const Matrix3x3& matrix2) {
RP3D_FORCE_INLINE Matrix3x3 operator-(const Matrix3x3& matrix1, const Matrix3x3& matrix2) {
return Matrix3x3(matrix1.mRows[0][0] - matrix2.mRows[0][0], matrix1.mRows[0][1] -
matrix2.mRows[0][1], matrix1.mRows[0][2] - matrix2.mRows[0][2],
matrix1.mRows[1][0] - matrix2.mRows[1][0], matrix1.mRows[1][1] -
@ -287,26 +287,26 @@ inline Matrix3x3 operator-(const Matrix3x3& matrix1, const Matrix3x3& matrix2) {
}
// Overloaded operator for the negative of the matrix
inline Matrix3x3 operator-(const Matrix3x3& matrix) {
RP3D_FORCE_INLINE Matrix3x3 operator-(const Matrix3x3& matrix) {
return Matrix3x3(-matrix.mRows[0][0], -matrix.mRows[0][1], -matrix.mRows[0][2],
-matrix.mRows[1][0], -matrix.mRows[1][1], -matrix.mRows[1][2],
-matrix.mRows[2][0], -matrix.mRows[2][1], -matrix.mRows[2][2]);
}
// Overloaded operator for multiplication with a number
inline Matrix3x3 operator*(decimal nb, const Matrix3x3& matrix) {
RP3D_FORCE_INLINE Matrix3x3 operator*(decimal nb, const Matrix3x3& matrix) {
return Matrix3x3(matrix.mRows[0][0] * nb, matrix.mRows[0][1] * nb, matrix.mRows[0][2] * nb,
matrix.mRows[1][0] * nb, matrix.mRows[1][1] * nb, matrix.mRows[1][2] * nb,
matrix.mRows[2][0] * nb, matrix.mRows[2][1] * nb, matrix.mRows[2][2] * nb);
}
// Overloaded operator for multiplication with a matrix
inline Matrix3x3 operator*(const Matrix3x3& matrix, decimal nb) {
RP3D_FORCE_INLINE Matrix3x3 operator*(const Matrix3x3& matrix, decimal nb) {
return nb * matrix;
}
// Overloaded operator for matrix multiplication
inline Matrix3x3 operator*(const Matrix3x3& matrix1, const Matrix3x3& matrix2) {
RP3D_FORCE_INLINE Matrix3x3 operator*(const Matrix3x3& matrix1, const Matrix3x3& matrix2) {
return Matrix3x3(matrix1.mRows[0][0]*matrix2.mRows[0][0] + matrix1.mRows[0][1] *
matrix2.mRows[1][0] + matrix1.mRows[0][2]*matrix2.mRows[2][0],
matrix1.mRows[0][0]*matrix2.mRows[0][1] + matrix1.mRows[0][1] *
@ -328,7 +328,7 @@ inline Matrix3x3 operator*(const Matrix3x3& matrix1, const Matrix3x3& matrix2) {
}
// Overloaded operator for multiplication with a vector
inline Vector3 operator*(const Matrix3x3& matrix, const Vector3& vector) {
RP3D_FORCE_INLINE Vector3 operator*(const Matrix3x3& matrix, const Vector3& vector) {
return Vector3(matrix.mRows[0][0]*vector.x + matrix.mRows[0][1]*vector.y +
matrix.mRows[0][2]*vector.z,
matrix.mRows[1][0]*vector.x + matrix.mRows[1][1]*vector.y +
@ -338,7 +338,7 @@ inline Vector3 operator*(const Matrix3x3& matrix, const Vector3& vector) {
}
// Overloaded operator for equality condition
inline bool Matrix3x3::operator==(const Matrix3x3& matrix) const {
RP3D_FORCE_INLINE bool Matrix3x3::operator==(const Matrix3x3& matrix) const {
return (mRows[0][0] == matrix.mRows[0][0] && mRows[0][1] == matrix.mRows[0][1] &&
mRows[0][2] == matrix.mRows[0][2] &&
mRows[1][0] == matrix.mRows[1][0] && mRows[1][1] == matrix.mRows[1][1] &&
@ -348,12 +348,12 @@ inline bool Matrix3x3::operator==(const Matrix3x3& matrix) const {
}
// Overloaded operator for the is different condition
inline bool Matrix3x3::operator!= (const Matrix3x3& matrix) const {
RP3D_FORCE_INLINE bool Matrix3x3::operator!= (const Matrix3x3& matrix) const {
return !(*this == matrix);
}
// Overloaded operator for addition with assignment
inline Matrix3x3& Matrix3x3::operator+=(const Matrix3x3& matrix) {
RP3D_FORCE_INLINE Matrix3x3& Matrix3x3::operator+=(const Matrix3x3& matrix) {
mRows[0][0] += matrix.mRows[0][0]; mRows[0][1] += matrix.mRows[0][1];
mRows[0][2] += matrix.mRows[0][2]; mRows[1][0] += matrix.mRows[1][0];
mRows[1][1] += matrix.mRows[1][1]; mRows[1][2] += matrix.mRows[1][2];
@ -363,7 +363,7 @@ inline Matrix3x3& Matrix3x3::operator+=(const Matrix3x3& matrix) {
}
// Overloaded operator for substraction with assignment
inline Matrix3x3& Matrix3x3::operator-=(const Matrix3x3& matrix) {
RP3D_FORCE_INLINE Matrix3x3& Matrix3x3::operator-=(const Matrix3x3& matrix) {
mRows[0][0] -= matrix.mRows[0][0]; mRows[0][1] -= matrix.mRows[0][1];
mRows[0][2] -= matrix.mRows[0][2]; mRows[1][0] -= matrix.mRows[1][0];
mRows[1][1] -= matrix.mRows[1][1]; mRows[1][2] -= matrix.mRows[1][2];
@ -373,7 +373,7 @@ inline Matrix3x3& Matrix3x3::operator-=(const Matrix3x3& matrix) {
}
// Overloaded operator for multiplication with a number with assignment
inline Matrix3x3& Matrix3x3::operator*=(decimal nb) {
RP3D_FORCE_INLINE Matrix3x3& Matrix3x3::operator*=(decimal nb) {
mRows[0][0] *= nb; mRows[0][1] *= nb; mRows[0][2] *= nb;
mRows[1][0] *= nb; mRows[1][1] *= nb; mRows[1][2] *= nb;
mRows[2][0] *= nb; mRows[2][1] *= nb; mRows[2][2] *= nb;
@ -383,19 +383,19 @@ inline Matrix3x3& Matrix3x3::operator*=(decimal nb) {
// Overloaded operator to return a row of the matrix.
/// This operator is also used to access a matrix value using the syntax
/// matrix[row][col].
inline const Vector3& Matrix3x3::operator[](int row) const {
RP3D_FORCE_INLINE const Vector3& Matrix3x3::operator[](int row) const {
return mRows[row];
}
// Overloaded operator to return a row of the matrix.
/// This operator is also used to access a matrix value using the syntax
/// matrix[row][col].
inline Vector3& Matrix3x3::operator[](int row) {
RP3D_FORCE_INLINE Vector3& Matrix3x3::operator[](int row) {
return mRows[row];
}
// Get the string representation
inline std::string Matrix3x3::to_string() const {
RP3D_FORCE_INLINE std::string Matrix3x3::to_string() const {
return "Matrix3x3(" + std::to_string(mRows[0][0]) + "," + std::to_string(mRows[0][1]) + "," + std::to_string(mRows[0][2]) + "," +
std::to_string(mRows[1][0]) + "," + std::to_string(mRows[1][1]) + "," + std::to_string(mRows[1][2]) + "," +
std::to_string(mRows[2][0]) + "," + std::to_string(mRows[2][1]) + "," + std::to_string(mRows[2][2]) + ")";

View File

@ -182,28 +182,28 @@ struct Quaternion {
};
// Constructor of the class
inline Quaternion::Quaternion() : x(0.0), y(0.0), z(0.0), w(0.0) {
RP3D_FORCE_INLINE Quaternion::Quaternion() : x(0.0), y(0.0), z(0.0), w(0.0) {
}
// Constructor with arguments
inline Quaternion::Quaternion(decimal newX, decimal newY, decimal newZ, decimal newW)
RP3D_FORCE_INLINE Quaternion::Quaternion(decimal newX, decimal newY, decimal newZ, decimal newW)
:x(newX), y(newY), z(newZ), w(newW) {
}
// Constructor with the component w and the vector v=(x y z)
inline Quaternion::Quaternion(decimal newW, const Vector3& v) : x(v.x), y(v.y), z(v.z), w(newW) {
RP3D_FORCE_INLINE Quaternion::Quaternion(decimal newW, const Vector3& v) : x(v.x), y(v.y), z(v.z), w(newW) {
}
// Constructor with the component w and the vector v=(x y z)
inline Quaternion::Quaternion(const Vector3& v, decimal newW) : x(v.x), y(v.y), z(v.z), w(newW) {
RP3D_FORCE_INLINE Quaternion::Quaternion(const Vector3& v, decimal newW) : x(v.x), y(v.y), z(v.z), w(newW) {
}
// Set all the values
inline void Quaternion::setAllValues(decimal newX, decimal newY, decimal newZ, decimal newW) {
RP3D_FORCE_INLINE void Quaternion::setAllValues(decimal newX, decimal newY, decimal newZ, decimal newW) {
x = newX;
y = newY;
z = newZ;
@ -211,7 +211,7 @@ inline void Quaternion::setAllValues(decimal newX, decimal newY, decimal newZ, d
}
// Set the quaternion to zero
inline void Quaternion::setToZero() {
RP3D_FORCE_INLINE void Quaternion::setToZero() {
x = 0;
y = 0;
z = 0;
@ -219,7 +219,7 @@ inline void Quaternion::setToZero() {
}
// Set to the identity quaternion
inline void Quaternion::setToIdentity() {
RP3D_FORCE_INLINE void Quaternion::setToIdentity() {
x = 0;
y = 0;
z = 0;
@ -227,24 +227,24 @@ inline void Quaternion::setToIdentity() {
}
// Return the vector v=(x y z) of the quaternion
inline Vector3 Quaternion::getVectorV() const {
RP3D_FORCE_INLINE Vector3 Quaternion::getVectorV() const {
// Return the vector v
return Vector3(x, y, z);
}
// Return the length of the quaternion (inline)
inline decimal Quaternion::length() const {
// Return the length of the quaternion (RP3D_FORCE_INLINE)
RP3D_FORCE_INLINE decimal Quaternion::length() const {
return std::sqrt(x*x + y*y + z*z + w*w);
}
// Return the square of the length of the quaternion
inline decimal Quaternion::lengthSquare() const {
RP3D_FORCE_INLINE decimal Quaternion::lengthSquare() const {
return x*x + y*y + z*z + w*w;
}
// Normalize the quaternion
inline void Quaternion::normalize() {
RP3D_FORCE_INLINE void Quaternion::normalize() {
decimal l = length();
@ -258,7 +258,7 @@ inline void Quaternion::normalize() {
}
// Inverse the quaternion
inline void Quaternion::inverse() {
RP3D_FORCE_INLINE void Quaternion::inverse() {
// Use the conjugate of the current quaternion
x = -x;
@ -267,7 +267,7 @@ inline void Quaternion::inverse() {
}
// Return the unit quaternion
inline Quaternion Quaternion::getUnit() const {
RP3D_FORCE_INLINE Quaternion Quaternion::getUnit() const {
decimal lengthQuaternion = length();
// Check if the length is not equal to zero
@ -279,60 +279,60 @@ inline Quaternion Quaternion::getUnit() const {
}
// Return the identity quaternion
inline Quaternion Quaternion::identity() {
RP3D_FORCE_INLINE Quaternion Quaternion::identity() {
return Quaternion(0.0, 0.0, 0.0, 1.0);
}
// Return the conjugate of the quaternion (inline)
inline Quaternion Quaternion::getConjugate() const {
// Return the conjugate of the quaternion (RP3D_FORCE_INLINE)
RP3D_FORCE_INLINE Quaternion Quaternion::getConjugate() const {
return Quaternion(-x, -y, -z, w);
}
// Return the inverse of the quaternion (inline)
inline Quaternion Quaternion::getInverse() const {
// Return the inverse of the quaternion (RP3D_FORCE_INLINE)
RP3D_FORCE_INLINE Quaternion Quaternion::getInverse() const {
// Return the conjugate quaternion
return Quaternion(-x, -y, -z, w);
}
// Scalar product between two quaternions
inline decimal Quaternion::dot(const Quaternion& quaternion) const {
RP3D_FORCE_INLINE decimal Quaternion::dot(const Quaternion& quaternion) const {
return (x*quaternion.x + y*quaternion.y + z*quaternion.z + w*quaternion.w);
}
// Return true if the values are not NAN OR INF
inline bool Quaternion::isFinite() const {
RP3D_FORCE_INLINE bool Quaternion::isFinite() const {
return std::isfinite(x) && std::isfinite(y) && std::isfinite(z) && std::isfinite(w);
}
// Return true if it is a unit quaternion
inline bool Quaternion::isUnit() const {
RP3D_FORCE_INLINE bool Quaternion::isUnit() const {
const decimal length = std::sqrt(x*x + y*y + z*z + w*w);
const decimal tolerance = 1e-5f;
return std::abs(length - decimal(1.0)) < tolerance;
}
// Return true if it is a valid quaternion
inline bool Quaternion::isValid() const {
RP3D_FORCE_INLINE bool Quaternion::isValid() const {
return isFinite() && isUnit();
}
// Overloaded operator for the addition of two quaternions
inline Quaternion Quaternion::operator+(const Quaternion& quaternion) const {
RP3D_FORCE_INLINE Quaternion Quaternion::operator+(const Quaternion& quaternion) const {
// Return the result quaternion
return Quaternion(x + quaternion.x, y + quaternion.y, z + quaternion.z, w + quaternion.w);
}
// Overloaded operator for the substraction of two quaternions
inline Quaternion Quaternion::operator-(const Quaternion& quaternion) const {
RP3D_FORCE_INLINE Quaternion Quaternion::operator-(const Quaternion& quaternion) const {
// Return the result of the substraction
return Quaternion(x - quaternion.x, y - quaternion.y, z - quaternion.z, w - quaternion.w);
}
// Overloaded operator for addition with assignment
inline Quaternion& Quaternion::operator+=(const Quaternion& quaternion) {
RP3D_FORCE_INLINE Quaternion& Quaternion::operator+=(const Quaternion& quaternion) {
x += quaternion.x;
y += quaternion.y;
z += quaternion.z;
@ -341,7 +341,7 @@ inline Quaternion& Quaternion::operator+=(const Quaternion& quaternion) {
}
// Overloaded operator for substraction with assignment
inline Quaternion& Quaternion::operator-=(const Quaternion& quaternion) {
RP3D_FORCE_INLINE Quaternion& Quaternion::operator-=(const Quaternion& quaternion) {
x -= quaternion.x;
y -= quaternion.y;
z -= quaternion.z;
@ -350,12 +350,12 @@ inline Quaternion& Quaternion::operator-=(const Quaternion& quaternion) {
}
// Overloaded operator for the multiplication with a constant
inline Quaternion Quaternion::operator*(decimal nb) const {
RP3D_FORCE_INLINE Quaternion Quaternion::operator*(decimal nb) const {
return Quaternion(nb * x, nb * y, nb * z, nb * w);
}
// Overloaded operator for the multiplication of two quaternions
inline Quaternion Quaternion::operator*(const Quaternion& quaternion) const {
RP3D_FORCE_INLINE Quaternion Quaternion::operator*(const Quaternion& quaternion) const {
/* The followin code is equivalent to this
return Quaternion(w * quaternion.w - getVectorV().dot(quaternion.getVectorV()),
@ -371,7 +371,7 @@ inline Quaternion Quaternion::operator*(const Quaternion& quaternion) const {
// Overloaded operator for the multiplication with a vector.
/// This methods rotates a point given the rotation of a quaternion.
inline Vector3 Quaternion::operator*(const Vector3& point) const {
RP3D_FORCE_INLINE Vector3 Quaternion::operator*(const Vector3& point) const {
/* The following code is equivalent to this
* Quaternion p(point.x, point.y, point.z, 0.0);
@ -388,7 +388,7 @@ inline Vector3 Quaternion::operator*(const Vector3& point) const {
}
// Overloaded operator for the assignment
inline Quaternion& Quaternion::operator=(const Quaternion& quaternion) {
RP3D_FORCE_INLINE Quaternion& Quaternion::operator=(const Quaternion& quaternion) {
// Check for self-assignment
if (this != &quaternion) {
@ -403,13 +403,13 @@ inline Quaternion& Quaternion::operator=(const Quaternion& quaternion) {
}
// Overloaded operator for equality condition
inline bool Quaternion::operator==(const Quaternion& quaternion) const {
RP3D_FORCE_INLINE bool Quaternion::operator==(const Quaternion& quaternion) const {
return (x == quaternion.x && y == quaternion.y &&
z == quaternion.z && w == quaternion.w);
}
// Get the string representation
inline std::string Quaternion::to_string() const {
RP3D_FORCE_INLINE std::string Quaternion::to_string() const {
return "Quaternion(" + std::to_string(x) + "," + std::to_string(y) + "," + std::to_string(z) + "," +
std::to_string(w) + ")";
}

View File

@ -125,62 +125,62 @@ class Transform {
};
// Constructor
inline Transform::Transform() : mPosition(Vector3(0.0, 0.0, 0.0)), mOrientation(Quaternion::identity()) {
RP3D_FORCE_INLINE Transform::Transform() : mPosition(Vector3(0.0, 0.0, 0.0)), mOrientation(Quaternion::identity()) {
}
// Constructor
inline Transform::Transform(const Vector3& position, const Matrix3x3& orientation)
RP3D_FORCE_INLINE Transform::Transform(const Vector3& position, const Matrix3x3& orientation)
: mPosition(position), mOrientation(Quaternion(orientation)) {
}
// Constructor
inline Transform::Transform(const Vector3& position, const Quaternion& orientation)
RP3D_FORCE_INLINE Transform::Transform(const Vector3& position, const Quaternion& orientation)
: mPosition(position), mOrientation(orientation) {
}
// Copy-constructor
inline Transform::Transform(const Transform& transform)
RP3D_FORCE_INLINE Transform::Transform(const Transform& transform)
: mPosition(transform.mPosition), mOrientation(transform.mOrientation) {
}
// Return the position of the transform
inline const Vector3& Transform::getPosition() const {
RP3D_FORCE_INLINE const Vector3& Transform::getPosition() const {
return mPosition;
}
// Set the origin of the transform
inline void Transform::setPosition(const Vector3& position) {
RP3D_FORCE_INLINE void Transform::setPosition(const Vector3& position) {
mPosition = position;
}
// Return the rotation matrix
inline const Quaternion& Transform::getOrientation() const {
RP3D_FORCE_INLINE const Quaternion& Transform::getOrientation() const {
return mOrientation;
}
// Set the rotation matrix of the transform
inline void Transform::setOrientation(const Quaternion& orientation) {
RP3D_FORCE_INLINE void Transform::setOrientation(const Quaternion& orientation) {
mOrientation = orientation;
}
// Set the transform to the identity transform
inline void Transform::setToIdentity() {
RP3D_FORCE_INLINE void Transform::setToIdentity() {
mPosition = Vector3(0.0, 0.0, 0.0);
mOrientation = Quaternion::identity();
}
// Return the inverse of the transform
inline Transform Transform::getInverse() const {
RP3D_FORCE_INLINE Transform Transform::getInverse() const {
const Quaternion& invQuaternion = mOrientation.getInverse();
return Transform(invQuaternion * (-mPosition), invQuaternion);
}
// Return an interpolated transform
inline Transform Transform::interpolateTransforms(const Transform& oldTransform,
RP3D_FORCE_INLINE Transform Transform::interpolateTransforms(const Transform& oldTransform,
const Transform& newTransform,
decimal interpolationFactor) {
@ -195,22 +195,22 @@ inline Transform Transform::interpolateTransforms(const Transform& oldTransform,
}
// Return the identity transform
inline Transform Transform::identity() {
RP3D_FORCE_INLINE Transform Transform::identity() {
return Transform(Vector3(0, 0, 0), Quaternion::identity());
}
// Return true if it is a valid transform
inline bool Transform::isValid() const {
RP3D_FORCE_INLINE bool Transform::isValid() const {
return mPosition.isFinite() && mOrientation.isValid();
}
// Return the transformed vector
inline Vector3 Transform::operator*(const Vector3& vector) const {
RP3D_FORCE_INLINE Vector3 Transform::operator*(const Vector3& vector) const {
return (mOrientation * vector) + mPosition;
}
// Operator of multiplication of a transform with another one
inline Transform Transform::operator*(const Transform& transform2) const {
RP3D_FORCE_INLINE Transform Transform::operator*(const Transform& transform2) const {
// The following code is equivalent to this
//return Transform(mPosition + mOrientation * transform2.mPosition,
@ -239,17 +239,17 @@ inline Transform Transform::operator*(const Transform& transform2) const {
}
// Return true if the two transforms are equal
inline bool Transform::operator==(const Transform& transform2) const {
RP3D_FORCE_INLINE bool Transform::operator==(const Transform& transform2) const {
return (mPosition == transform2.mPosition) && (mOrientation == transform2.mOrientation);
}
// Return true if the two transforms are different
inline bool Transform::operator!=(const Transform& transform2) const {
RP3D_FORCE_INLINE bool Transform::operator!=(const Transform& transform2) const {
return !(*this == transform2);
}
// Assignment operator
inline Transform& Transform::operator=(const Transform& transform) {
RP3D_FORCE_INLINE Transform& Transform::operator=(const Transform& transform) {
if (&transform != this) {
mPosition = transform.mPosition;
mOrientation = transform.mOrientation;
@ -258,7 +258,7 @@ inline Transform& Transform::operator=(const Transform& transform) {
}
// Get the string representation
inline std::string Transform::to_string() const {
RP3D_FORCE_INLINE std::string Transform::to_string() const {
return "Transform(" + mPosition.to_string() + "," + mOrientation.to_string() + ")";
}

View File

@ -148,6 +148,9 @@ struct Vector2 {
/// Return the zero vector
static Vector2 zero();
/// Function to test if two vectors are (almost) equal
static bool approxEqual(const Vector2& vec1, const Vector2& vec2, decimal epsilon = MACHINE_EPSILON);
// -------------------- Friends -------------------- //
friend Vector2 operator+(const Vector2& vector1, const Vector2& vector2);
@ -161,50 +164,50 @@ struct Vector2 {
};
// Constructor
inline Vector2::Vector2() : x(0.0), y(0.0) {
RP3D_FORCE_INLINE Vector2::Vector2() : x(0.0), y(0.0) {
}
// Constructor with arguments
inline Vector2::Vector2(decimal newX, decimal newY) : x(newX), y(newY) {
RP3D_FORCE_INLINE Vector2::Vector2(decimal newX, decimal newY) : x(newX), y(newY) {
}
// Copy-constructor
inline Vector2::Vector2(const Vector2& vector) : x(vector.x), y(vector.y) {
RP3D_FORCE_INLINE Vector2::Vector2(const Vector2& vector) : x(vector.x), y(vector.y) {
}
// Set the vector to zero
inline void Vector2::setToZero() {
RP3D_FORCE_INLINE void Vector2::setToZero() {
x = 0;
y = 0;
}
// Set all the values of the vector
inline void Vector2::setAllValues(decimal newX, decimal newY) {
RP3D_FORCE_INLINE void Vector2::setAllValues(decimal newX, decimal newY) {
x = newX;
y = newY;
}
// Return the length of the vector
inline decimal Vector2::length() const {
RP3D_FORCE_INLINE decimal Vector2::length() const {
return std::sqrt(x*x + y*y);
}
// Return the square of the length of the vector
inline decimal Vector2::lengthSquare() const {
RP3D_FORCE_INLINE decimal Vector2::lengthSquare() const {
return x*x + y*y;
}
// Scalar product of two vectors (inline)
inline decimal Vector2::dot(const Vector2& vector) const {
// Scalar product of two vectors (RP3D_FORCE_INLINE)
RP3D_FORCE_INLINE decimal Vector2::dot(const Vector2& vector) const {
return (x*vector.x + y*vector.y);
}
// Normalize the vector
inline void Vector2::normalize() {
RP3D_FORCE_INLINE void Vector2::normalize() {
decimal l = length();
if (l < MACHINE_EPSILON) {
return;
@ -214,68 +217,68 @@ inline void Vector2::normalize() {
}
// Return the corresponding absolute value vector
inline Vector2 Vector2::getAbsoluteVector() const {
RP3D_FORCE_INLINE Vector2 Vector2::getAbsoluteVector() const {
return Vector2(std::abs(x), std::abs(y));
}
// Return the axis with the minimal value
inline int Vector2::getMinAxis() const {
RP3D_FORCE_INLINE int Vector2::getMinAxis() const {
return (x < y ? 0 : 1);
}
// Return the axis with the maximal value
inline int Vector2::getMaxAxis() const {
RP3D_FORCE_INLINE int Vector2::getMaxAxis() const {
return (x < y ? 1 : 0);
}
// Return true if the vector is unit and false otherwise
inline bool Vector2::isUnit() const {
return approxEqual(lengthSquare(), 1.0);
RP3D_FORCE_INLINE bool Vector2::isUnit() const {
return reactphysics3d::approxEqual(lengthSquare(), decimal(1.0));
}
// Return true if the values are not NAN OR INF
inline bool Vector2::isFinite() const {
RP3D_FORCE_INLINE bool Vector2::isFinite() const {
return std::isfinite(x) && std::isfinite(y);
}
// Return true if the vector is the zero vector
inline bool Vector2::isZero() const {
return approxEqual(lengthSquare(), 0.0);
RP3D_FORCE_INLINE bool Vector2::isZero() const {
return reactphysics3d::approxEqual(lengthSquare(), decimal(0.0));
}
// Overloaded operator for the equality condition
inline bool Vector2::operator== (const Vector2& vector) const {
RP3D_FORCE_INLINE bool Vector2::operator== (const Vector2& vector) const {
return (x == vector.x && y == vector.y);
}
// Overloaded operator for the is different condition
inline bool Vector2::operator!= (const Vector2& vector) const {
RP3D_FORCE_INLINE bool Vector2::operator!= (const Vector2& vector) const {
return !(*this == vector);
}
// Overloaded operator for addition with assignment
inline Vector2& Vector2::operator+=(const Vector2& vector) {
RP3D_FORCE_INLINE Vector2& Vector2::operator+=(const Vector2& vector) {
x += vector.x;
y += vector.y;
return *this;
}
// Overloaded operator for substraction with assignment
inline Vector2& Vector2::operator-=(const Vector2& vector) {
RP3D_FORCE_INLINE Vector2& Vector2::operator-=(const Vector2& vector) {
x -= vector.x;
y -= vector.y;
return *this;
}
// Overloaded operator for multiplication with a number with assignment
inline Vector2& Vector2::operator*=(decimal number) {
RP3D_FORCE_INLINE Vector2& Vector2::operator*=(decimal number) {
x *= number;
y *= number;
return *this;
}
// Overloaded operator for division by a number with assignment
inline Vector2& Vector2::operator/=(decimal number) {
RP3D_FORCE_INLINE Vector2& Vector2::operator/=(decimal number) {
assert(number > std::numeric_limits<decimal>::epsilon());
x /= number;
y /= number;
@ -283,60 +286,60 @@ inline Vector2& Vector2::operator/=(decimal number) {
}
// Overloaded operator for value access
inline decimal& Vector2::operator[] (int index) {
RP3D_FORCE_INLINE decimal& Vector2::operator[] (int index) {
return (&x)[index];
}
// Overloaded operator for value access
inline const decimal& Vector2::operator[] (int index) const {
RP3D_FORCE_INLINE const decimal& Vector2::operator[] (int index) const {
return (&x)[index];
}
// Overloaded operator for addition
inline Vector2 operator+(const Vector2& vector1, const Vector2& vector2) {
RP3D_FORCE_INLINE Vector2 operator+(const Vector2& vector1, const Vector2& vector2) {
return Vector2(vector1.x + vector2.x, vector1.y + vector2.y);
}
// Overloaded operator for substraction
inline Vector2 operator-(const Vector2& vector1, const Vector2& vector2) {
RP3D_FORCE_INLINE Vector2 operator-(const Vector2& vector1, const Vector2& vector2) {
return Vector2(vector1.x - vector2.x, vector1.y - vector2.y);
}
// Overloaded operator for the negative of a vector
inline Vector2 operator-(const Vector2& vector) {
RP3D_FORCE_INLINE Vector2 operator-(const Vector2& vector) {
return Vector2(-vector.x, -vector.y);
}
// Overloaded operator for multiplication with a number
inline Vector2 operator*(const Vector2& vector, decimal number) {
RP3D_FORCE_INLINE Vector2 operator*(const Vector2& vector, decimal number) {
return Vector2(number * vector.x, number * vector.y);
}
// Overloaded operator for multiplication of two vectors
inline Vector2 operator*(const Vector2& vector1, const Vector2& vector2) {
RP3D_FORCE_INLINE Vector2 operator*(const Vector2& vector1, const Vector2& vector2) {
return Vector2(vector1.x * vector2.x, vector1.y * vector2.y);
}
// Overloaded operator for division by a number
inline Vector2 operator/(const Vector2& vector, decimal number) {
RP3D_FORCE_INLINE Vector2 operator/(const Vector2& vector, decimal number) {
assert(number > MACHINE_EPSILON);
return Vector2(vector.x / number, vector.y / number);
}
// Overload operator for division between two vectors
inline Vector2 operator/(const Vector2& vector1, const Vector2& vector2) {
RP3D_FORCE_INLINE Vector2 operator/(const Vector2& vector1, const Vector2& vector2) {
assert(vector2.x > MACHINE_EPSILON);
assert(vector2.y > MACHINE_EPSILON);
return Vector2(vector1.x / vector2.x, vector1.y / vector2.y);
}
// Overloaded operator for multiplication with a number
inline Vector2 operator*(decimal number, const Vector2& vector) {
RP3D_FORCE_INLINE Vector2 operator*(decimal number, const Vector2& vector) {
return vector * number;
}
// Assignment operator
inline Vector2& Vector2::operator=(const Vector2& vector) {
RP3D_FORCE_INLINE Vector2& Vector2::operator=(const Vector2& vector) {
if (&vector != this) {
x = vector.x;
y = vector.y;
@ -345,32 +348,37 @@ inline Vector2& Vector2::operator=(const Vector2& vector) {
}
// Overloaded less than operator for ordering to be used inside std::set for instance
inline bool Vector2::operator<(const Vector2& vector) const {
RP3D_FORCE_INLINE bool Vector2::operator<(const Vector2& vector) const {
return (x == vector.x ? y < vector.y : x < vector.x);
}
// Return a vector taking the minimum components of two vectors
inline Vector2 Vector2::min(const Vector2& vector1, const Vector2& vector2) {
RP3D_FORCE_INLINE Vector2 Vector2::min(const Vector2& vector1, const Vector2& vector2) {
return Vector2(std::min(vector1.x, vector2.x),
std::min(vector1.y, vector2.y));
}
// Return a vector taking the maximum components of two vectors
inline Vector2 Vector2::max(const Vector2& vector1, const Vector2& vector2) {
RP3D_FORCE_INLINE Vector2 Vector2::max(const Vector2& vector1, const Vector2& vector2) {
return Vector2(std::max(vector1.x, vector2.x),
std::max(vector1.y, vector2.y));
}
// Get the string representation
inline std::string Vector2::to_string() const {
RP3D_FORCE_INLINE std::string Vector2::to_string() const {
return "Vector2(" + std::to_string(x) + "," + std::to_string(y) + ")";
}
// Return the zero vector
inline Vector2 Vector2::zero() {
RP3D_FORCE_INLINE Vector2 Vector2::zero() {
return Vector2(0, 0);
}
// Function to test if two vectors are (almost) equal
RP3D_FORCE_INLINE bool approxEqual(const Vector2& vec1, const Vector2& vec2, decimal epsilon) {
return approxEqual(vec1.x, vec2.x, epsilon) && approxEqual(vec1.y, vec2.y, epsilon);
}
}
#endif

View File

@ -28,8 +28,11 @@
// Libraries
#include <cassert>
#include <reactphysics3d/mathematics/mathematics_functions.h>
#include <cmath>
#include <algorithm>
#include <reactphysics3d/decimal.h>
#include <reactphysics3d/mathematics/mathematics_common.h>
#include <reactphysics3d/configuration.h>
/// ReactPhysics3D namespace
namespace reactphysics3d {
@ -160,6 +163,9 @@ struct Vector3 {
/// Return the zero vector
static Vector3 zero();
/// Function to test if two vectors are (almost) equal
static bool approxEqual(const Vector3& vec1, const Vector3& vec2, decimal epsilon = MACHINE_EPSILON);
// -------------------- Friends -------------------- //
friend Vector3 operator+(const Vector3& vector1, const Vector3& vector2);
@ -173,58 +179,58 @@ struct Vector3 {
};
// Constructor of the struct Vector3
inline Vector3::Vector3() : x(0.0), y(0.0), z(0.0) {
RP3D_FORCE_INLINE Vector3::Vector3() : x(0.0), y(0.0), z(0.0) {
}
// Constructor with arguments
inline Vector3::Vector3(decimal newX, decimal newY, decimal newZ) : x(newX), y(newY), z(newZ) {
RP3D_FORCE_INLINE Vector3::Vector3(decimal newX, decimal newY, decimal newZ) : x(newX), y(newY), z(newZ) {
}
// Copy-constructor
inline Vector3::Vector3(const Vector3& vector) : x(vector.x), y(vector.y), z(vector.z) {
RP3D_FORCE_INLINE Vector3::Vector3(const Vector3& vector) : x(vector.x), y(vector.y), z(vector.z) {
}
// Set the vector to zero
inline void Vector3::setToZero() {
RP3D_FORCE_INLINE void Vector3::setToZero() {
x = 0;
y = 0;
z = 0;
}
// Set all the values of the vector
inline void Vector3::setAllValues(decimal newX, decimal newY, decimal newZ) {
RP3D_FORCE_INLINE void Vector3::setAllValues(decimal newX, decimal newY, decimal newZ) {
x = newX;
y = newY;
z = newZ;
}
// Return the length of the vector
inline decimal Vector3::length() const {
RP3D_FORCE_INLINE decimal Vector3::length() const {
return std::sqrt(x*x + y*y + z*z);
}
// Return the square of the length of the vector
inline decimal Vector3::lengthSquare() const {
RP3D_FORCE_INLINE decimal Vector3::lengthSquare() const {
return x*x + y*y + z*z;
}
// Scalar product of two vectors (inline)
inline decimal Vector3::dot(const Vector3& vector) const {
// Scalar product of two vectors (RP3D_FORCE_INLINE)
RP3D_FORCE_INLINE decimal Vector3::dot(const Vector3& vector) const {
return (x*vector.x + y*vector.y + z*vector.z);
}
// Cross product of two vectors (inline)
inline Vector3 Vector3::cross(const Vector3& vector) const {
// Cross product of two vectors (RP3D_FORCE_INLINE)
RP3D_FORCE_INLINE Vector3 Vector3::cross(const Vector3& vector) const {
return Vector3(y * vector.z - z * vector.y,
z * vector.x - x * vector.z,
x * vector.y - y * vector.x);
}
// Normalize the vector
inline void Vector3::normalize() {
RP3D_FORCE_INLINE void Vector3::normalize() {
decimal l = length();
if (l < MACHINE_EPSILON) {
return;
@ -235,47 +241,47 @@ inline void Vector3::normalize() {
}
// Return the corresponding absolute value vector
inline Vector3 Vector3::getAbsoluteVector() const {
RP3D_FORCE_INLINE Vector3 Vector3::getAbsoluteVector() const {
return Vector3(std::abs(x), std::abs(y), std::abs(z));
}
// Return the axis with the minimal value
inline int Vector3::getMinAxis() const {
RP3D_FORCE_INLINE int Vector3::getMinAxis() const {
return (x < y ? (x < z ? 0 : 2) : (y < z ? 1 : 2));
}
// Return the axis with the maximal value
inline int Vector3::getMaxAxis() const {
RP3D_FORCE_INLINE int Vector3::getMaxAxis() const {
return (x < y ? (y < z ? 2 : 1) : (x < z ? 2 : 0));
}
// Return true if the vector is unit and false otherwise
inline bool Vector3::isUnit() const {
return approxEqual(lengthSquare(), 1.0);
RP3D_FORCE_INLINE bool Vector3::isUnit() const {
return reactphysics3d::approxEqual(lengthSquare(), decimal(1.0));
}
// Return true if the values are not NAN OR INF
inline bool Vector3::isFinite() const {
RP3D_FORCE_INLINE bool Vector3::isFinite() const {
return std::isfinite(x) && std::isfinite(y) && std::isfinite(z);
}
// Return true if the vector is the zero vector
inline bool Vector3::isZero() const {
return approxEqual(lengthSquare(), 0.0);
RP3D_FORCE_INLINE bool Vector3::isZero() const {
return reactphysics3d::approxEqual(lengthSquare(), decimal(0.0));
}
// Overloaded operator for the equality condition
inline bool Vector3::operator== (const Vector3& vector) const {
RP3D_FORCE_INLINE bool Vector3::operator== (const Vector3& vector) const {
return (x == vector.x && y == vector.y && z == vector.z);
}
// Overloaded operator for the is different condition
inline bool Vector3::operator!= (const Vector3& vector) const {
RP3D_FORCE_INLINE bool Vector3::operator!= (const Vector3& vector) const {
return !(*this == vector);
}
// Overloaded operator for addition with assignment
inline Vector3& Vector3::operator+=(const Vector3& vector) {
RP3D_FORCE_INLINE Vector3& Vector3::operator+=(const Vector3& vector) {
x += vector.x;
y += vector.y;
z += vector.z;
@ -283,7 +289,7 @@ inline Vector3& Vector3::operator+=(const Vector3& vector) {
}
// Overloaded operator for substraction with assignment
inline Vector3& Vector3::operator-=(const Vector3& vector) {
RP3D_FORCE_INLINE Vector3& Vector3::operator-=(const Vector3& vector) {
x -= vector.x;
y -= vector.y;
z -= vector.z;
@ -291,7 +297,7 @@ inline Vector3& Vector3::operator-=(const Vector3& vector) {
}
// Overloaded operator for multiplication with a number with assignment
inline Vector3& Vector3::operator*=(decimal number) {
RP3D_FORCE_INLINE Vector3& Vector3::operator*=(decimal number) {
x *= number;
y *= number;
z *= number;
@ -299,7 +305,7 @@ inline Vector3& Vector3::operator*=(decimal number) {
}
// Overloaded operator for division by a number with assignment
inline Vector3& Vector3::operator/=(decimal number) {
RP3D_FORCE_INLINE Vector3& Vector3::operator/=(decimal number) {
assert(number > std::numeric_limits<decimal>::epsilon());
x /= number;
y /= number;
@ -308,43 +314,43 @@ inline Vector3& Vector3::operator/=(decimal number) {
}
// Overloaded operator for value access
inline decimal& Vector3::operator[] (int index) {
RP3D_FORCE_INLINE decimal& Vector3::operator[] (int index) {
return (&x)[index];
}
// Overloaded operator for value access
inline const decimal& Vector3::operator[] (int index) const {
RP3D_FORCE_INLINE const decimal& Vector3::operator[] (int index) const {
return (&x)[index];
}
// Overloaded operator for addition
inline Vector3 operator+(const Vector3& vector1, const Vector3& vector2) {
RP3D_FORCE_INLINE Vector3 operator+(const Vector3& vector1, const Vector3& vector2) {
return Vector3(vector1.x + vector2.x, vector1.y + vector2.y, vector1.z + vector2.z);
}
// Overloaded operator for substraction
inline Vector3 operator-(const Vector3& vector1, const Vector3& vector2) {
RP3D_FORCE_INLINE Vector3 operator-(const Vector3& vector1, const Vector3& vector2) {
return Vector3(vector1.x - vector2.x, vector1.y - vector2.y, vector1.z - vector2.z);
}
// Overloaded operator for the negative of a vector
inline Vector3 operator-(const Vector3& vector) {
RP3D_FORCE_INLINE Vector3 operator-(const Vector3& vector) {
return Vector3(-vector.x, -vector.y, -vector.z);
}
// Overloaded operator for multiplication with a number
inline Vector3 operator*(const Vector3& vector, decimal number) {
RP3D_FORCE_INLINE Vector3 operator*(const Vector3& vector, decimal number) {
return Vector3(number * vector.x, number * vector.y, number * vector.z);
}
// Overloaded operator for division by a number
inline Vector3 operator/(const Vector3& vector, decimal number) {
RP3D_FORCE_INLINE Vector3 operator/(const Vector3& vector, decimal number) {
assert(number > MACHINE_EPSILON);
return Vector3(vector.x / number, vector.y / number, vector.z / number);
}
// Overload operator for division between two vectors
inline Vector3 operator/(const Vector3& vector1, const Vector3& vector2) {
RP3D_FORCE_INLINE Vector3 operator/(const Vector3& vector1, const Vector3& vector2) {
assert(vector2.x > MACHINE_EPSILON);
assert(vector2.y > MACHINE_EPSILON);
assert(vector2.z > MACHINE_EPSILON);
@ -352,17 +358,17 @@ inline Vector3 operator/(const Vector3& vector1, const Vector3& vector2) {
}
// Overloaded operator for multiplication with a number
inline Vector3 operator*(decimal number, const Vector3& vector) {
RP3D_FORCE_INLINE Vector3 operator*(decimal number, const Vector3& vector) {
return vector * number;
}
// Overload operator for multiplication between two vectors
inline Vector3 operator*(const Vector3& vector1, const Vector3& vector2) {
RP3D_FORCE_INLINE Vector3 operator*(const Vector3& vector1, const Vector3& vector2) {
return Vector3(vector1.x * vector2.x, vector1.y * vector2.y, vector1.z * vector2.z);
}
// Assignment operator
inline Vector3& Vector3::operator=(const Vector3& vector) {
RP3D_FORCE_INLINE Vector3& Vector3::operator=(const Vector3& vector) {
if (&vector != this) {
x = vector.x;
y = vector.y;
@ -372,44 +378,50 @@ inline Vector3& Vector3::operator=(const Vector3& vector) {
}
// Overloaded less than operator for ordering to be used inside std::set for instance
inline bool Vector3::operator<(const Vector3& vector) const {
RP3D_FORCE_INLINE bool Vector3::operator<(const Vector3& vector) const {
return (x == vector.x ? (y == vector.y ? z < vector.z : y < vector.y) : x < vector.x);
}
// Return a vector taking the minimum components of two vectors
inline Vector3 Vector3::min(const Vector3& vector1, const Vector3& vector2) {
RP3D_FORCE_INLINE Vector3 Vector3::min(const Vector3& vector1, const Vector3& vector2) {
return Vector3(std::min(vector1.x, vector2.x),
std::min(vector1.y, vector2.y),
std::min(vector1.z, vector2.z));
}
// Return a vector taking the maximum components of two vectors
inline Vector3 Vector3::max(const Vector3& vector1, const Vector3& vector2) {
RP3D_FORCE_INLINE Vector3 Vector3::max(const Vector3& vector1, const Vector3& vector2) {
return Vector3(std::max(vector1.x, vector2.x),
std::max(vector1.y, vector2.y),
std::max(vector1.z, vector2.z));
}
// Return the minimum value among the three components of a vector
inline decimal Vector3::getMinValue() const {
RP3D_FORCE_INLINE decimal Vector3::getMinValue() const {
return std::min(std::min(x, y), z);
}
// Return the maximum value among the three components of a vector
inline decimal Vector3::getMaxValue() const {
RP3D_FORCE_INLINE decimal Vector3::getMaxValue() const {
return std::max(std::max(x, y), z);
}
// Get the string representation
inline std::string Vector3::to_string() const {
RP3D_FORCE_INLINE std::string Vector3::to_string() const {
return "Vector3(" + std::to_string(x) + "," + std::to_string(y) + "," + std::to_string(z) + ")";
}
// Return the zero vector
inline Vector3 Vector3::zero() {
RP3D_FORCE_INLINE Vector3 Vector3::zero() {
return Vector3(0, 0, 0);
}
// Function to test if two vectors are (almost) equal
RP3D_FORCE_INLINE bool approxEqual(const Vector3& vec1, const Vector3& vec2, decimal epsilon) {
return approxEqual(vec1.x, vec2.x, epsilon) && approxEqual(vec1.y, vec2.y, epsilon) &&
approxEqual(vec1.z, vec2.z, epsilon);
}
}
#endif

View File

@ -23,50 +23,28 @@
* *
********************************************************************************/
#ifndef REACTPHYSICS3D_SPHERE_VS_SPHERE_NARROW_PHASE_INFO_BATCH_H
#define REACTPHYSICS3D_SPHERE_VS_SPHERE_NARROW_PHASE_INFO_BATCH_H
#ifndef REACTPHYSICS3D_MATHEMATICS_COMMON_H
#define REACTPHYSICS3D_MATHEMATICS_COMMON_H
// Libraries
#include <reactphysics3d/collision/narrowphase/NarrowPhaseInfoBatch.h>
#include <reactphysics3d/configuration.h>
#include <reactphysics3d/decimal.h>
#include <cassert>
#include <cmath>
/// Namespace ReactPhysics3D
/// ReactPhysics3D namespace
namespace reactphysics3d {
// Struct SphereVsSphereNarrowPhaseInfoBatch
/**
* This structure collects all the potential collisions from the middle-phase algorithm
* that have to be tested during narrow-phase collision detection. This class collects all the
* sphere vs sphere collision detection tests.
*/
struct SphereVsSphereNarrowPhaseInfoBatch : public NarrowPhaseInfoBatch {
// ---------- Mathematics functions ---------- //
public:
/// Function to test if two real numbers are (almost) equal
/// We test if two numbers a and b are such that (a-b) are in [-EPSILON; EPSILON]
RP3D_FORCE_INLINE bool approxEqual(decimal a, decimal b, decimal epsilon = MACHINE_EPSILON) {
return (std::abs(a - b) < epsilon);
}
/// List of radiuses for the first spheres
List<decimal> sphere1Radiuses;
/// List of radiuses for the second spheres
List<decimal> sphere2Radiuses;
/// Constructor
SphereVsSphereNarrowPhaseInfoBatch(MemoryAllocator& allocator, OverlappingPairs& overlappingPairs);
/// Destructor
virtual ~SphereVsSphereNarrowPhaseInfoBatch() override = default;
/// Add shapes to be tested during narrow-phase collision detection into the batch
virtual void addNarrowPhaseInfo(uint64 airId, uint64 pairIndex, Entity collider1, Entity collider2, CollisionShape* shape1,
CollisionShape* shape2, const Transform& shape1Transform,
const Transform& shape2Transform, bool needToReportContacts, MemoryAllocator& shapeAllocator) override;
// Initialize the containers using cached capacity
virtual void reserveMemory() override;
/// Clear all the objects in the batch
virtual void clear() override;
};
}
#endif
#endif

View File

@ -29,10 +29,11 @@
// Libraries
#include <reactphysics3d/configuration.h>
#include <reactphysics3d/decimal.h>
#include <reactphysics3d/mathematics/Vector3.h>
#include <algorithm>
#include <cassert>
#include <cmath>
#include <reactphysics3d/containers/List.h>
#include <reactphysics3d/containers/Array.h>
/// ReactPhysics3D namespace
namespace reactphysics3d {
@ -42,98 +43,392 @@ struct Vector2;
// ---------- Mathematics functions ---------- //
/// Function to test if two real numbers are (almost) equal
/// We test if two numbers a and b are such that (a-b) are in [-EPSILON; EPSILON]
inline bool approxEqual(decimal a, decimal b, decimal epsilon = MACHINE_EPSILON) {
return (std::fabs(a - b) < epsilon);
}
/// Function to test if two vectors are (almost) equal
bool approxEqual(const Vector3& vec1, const Vector3& vec2, decimal epsilon = MACHINE_EPSILON);
/// Function to test if two vectors are (almost) equal
bool approxEqual(const Vector2& vec1, const Vector2& vec2, decimal epsilon = MACHINE_EPSILON);
/// Function that returns the result of the "value" clamped by
/// two others values "lowerLimit" and "upperLimit"
inline int clamp(int value, int lowerLimit, int upperLimit) {
RP3D_FORCE_INLINE int clamp(int value, int lowerLimit, int upperLimit) {
assert(lowerLimit <= upperLimit);
return std::min(std::max(value, lowerLimit), upperLimit);
}
/// Function that returns the result of the "value" clamped by
/// two others values "lowerLimit" and "upperLimit"
inline decimal clamp(decimal value, decimal lowerLimit, decimal upperLimit) {
RP3D_FORCE_INLINE decimal clamp(decimal value, decimal lowerLimit, decimal upperLimit) {
assert(lowerLimit <= upperLimit);
return std::min(std::max(value, lowerLimit), upperLimit);
}
/// Return the minimum value among three values
inline decimal min3(decimal a, decimal b, decimal c) {
RP3D_FORCE_INLINE decimal min3(decimal a, decimal b, decimal c) {
return std::min(std::min(a, b), c);
}
/// Return the maximum value among three values
inline decimal max3(decimal a, decimal b, decimal c) {
RP3D_FORCE_INLINE decimal max3(decimal a, decimal b, decimal c) {
return std::max(std::max(a, b), c);
}
/// Return true if two values have the same sign
inline bool sameSign(decimal a, decimal b) {
RP3D_FORCE_INLINE bool sameSign(decimal a, decimal b) {
return a * b >= decimal(0.0);
}
/// Return true if two vectors are parallel
bool areParallelVectors(const Vector3& vector1, const Vector3& vector2);
// Return true if two vectors are parallel
RP3D_FORCE_INLINE bool areParallelVectors(const Vector3& vector1, const Vector3& vector2) {
return vector1.cross(vector2).lengthSquare() < decimal(0.00001);
}
/// Return true if two vectors are orthogonal
bool areOrthogonalVectors(const Vector3& vector1, const Vector3& vector2);
/// Clamp a vector such that it is no longer than a given maximum length
Vector3 clamp(const Vector3& vector, decimal maxLength);
// Return true if two vectors are orthogonal
RP3D_FORCE_INLINE bool areOrthogonalVectors(const Vector3& vector1, const Vector3& vector2) {
return std::abs(vector1.dot(vector2)) < decimal(0.001);
}
// Clamp a vector such that it is no longer than a given maximum length
RP3D_FORCE_INLINE Vector3 clamp(const Vector3& vector, decimal maxLength) {
if (vector.lengthSquare() > maxLength * maxLength) {
return vector.getUnit() * maxLength;
}
return vector;
}
// Compute and return a point on segment from "segPointA" and "segPointB" that is closest to point "pointC"
Vector3 computeClosestPointOnSegment(const Vector3& segPointA, const Vector3& segPointB, const Vector3& pointC);
RP3D_FORCE_INLINE Vector3 computeClosestPointOnSegment(const Vector3& segPointA, const Vector3& segPointB, const Vector3& pointC) {
const Vector3 ab = segPointB - segPointA;
decimal abLengthSquare = ab.lengthSquare();
// If the segment has almost zero length
if (abLengthSquare < MACHINE_EPSILON) {
// Return one end-point of the segment as the closest point
return segPointA;
}
// Project point C onto "AB" line
decimal t = (pointC - segPointA).dot(ab) / abLengthSquare;
// If projected point onto the line is outside the segment, clamp it to the segment
if (t < decimal(0.0)) t = decimal(0.0);
if (t > decimal(1.0)) t = decimal(1.0);
// Return the closest point on the segment
return segPointA + t * ab;
}
// Compute the closest points between two segments
void computeClosestPointBetweenTwoSegments(const Vector3& seg1PointA, const Vector3& seg1PointB,
const Vector3& seg2PointA, const Vector3& seg2PointB,
Vector3& closestPointSeg1, Vector3& closestPointSeg2);
// This method uses the technique described in the book Real-Time
// collision detection by Christer Ericson.
RP3D_FORCE_INLINE void computeClosestPointBetweenTwoSegments(const Vector3& seg1PointA, const Vector3& seg1PointB,
const Vector3& seg2PointA, const Vector3& seg2PointB,
Vector3& closestPointSeg1, Vector3& closestPointSeg2) {
/// Compute the barycentric coordinates u, v, w of a point p inside the triangle (a, b, c)
void computeBarycentricCoordinatesInTriangle(const Vector3& a, const Vector3& b, const Vector3& c,
const Vector3& p, decimal& u, decimal& v, decimal& w);
const Vector3 d1 = seg1PointB - seg1PointA;
const Vector3 d2 = seg2PointB - seg2PointA;
const Vector3 r = seg1PointA - seg2PointA;
decimal a = d1.lengthSquare();
decimal e = d2.lengthSquare();
decimal f = d2.dot(r);
decimal s, t;
/// Compute the intersection between a plane and a segment
decimal computePlaneSegmentIntersection(const Vector3& segA, const Vector3& segB, const decimal planeD, const Vector3& planeNormal);
// If both segments degenerate into points
if (a <= MACHINE_EPSILON && e <= MACHINE_EPSILON) {
/// Compute the distance between a point and a line
decimal computePointToLineDistance(const Vector3& linePointA, const Vector3& linePointB, const Vector3& point);
closestPointSeg1 = seg1PointA;
closestPointSeg2 = seg2PointA;
return;
}
if (a <= MACHINE_EPSILON) { // If first segment degenerates into a point
/// Clip a segment against multiple planes and return the clipped segment vertices
List<Vector3> clipSegmentWithPlanes(const Vector3& segA, const Vector3& segB,
const List<Vector3>& planesPoints,
const List<Vector3>& planesNormals,
MemoryAllocator& allocator);
s = decimal(0.0);
/// Clip a polygon against multiple planes and return the clipped polygon vertices
List<Vector3> clipPolygonWithPlanes(const List<Vector3>& polygonVertices, const List<Vector3>& planesPoints,
const List<Vector3>& planesNormals, MemoryAllocator& allocator);
// Compute the closest point on second segment
t = clamp(f / e, decimal(0.0), decimal(1.0));
}
else {
/// Project a point onto a plane that is given by a point and its unit length normal
Vector3 projectPointOntoPlane(const Vector3& point, const Vector3& planeNormal, const Vector3& planePoint);
decimal c = d1.dot(r);
/// Return the distance between a point and a plane (the plane normal must be normalized)
decimal computePointToPlaneDistance(const Vector3& point, const Vector3& planeNormal, const Vector3& planePoint);
// If the second segment degenerates into a point
if (e <= MACHINE_EPSILON) {
/// Return true if the given number is prime
bool isPrimeNumber(int number);
t = decimal(0.0);
s = clamp(-c / a, decimal(0.0), decimal(1.0));
}
else {
decimal b = d1.dot(d2);
decimal denom = a * e - b * b;
// If the segments are not parallel
if (denom != decimal(0.0)) {
// Compute the closest point on line 1 to line 2 and
// clamp to first segment.
s = clamp((b * f - c * e) / denom, decimal(0.0), decimal(1.0));
}
else {
// Pick an arbitrary point on first segment
s = decimal(0.0);
}
// Compute the point on line 2 closest to the closest point
// we have just found
t = (b * s + f) / e;
// If this closest point is inside second segment (t in [0, 1]), we are done.
// Otherwise, we clamp the point to the second segment and compute again the
// closest point on segment 1
if (t < decimal(0.0)) {
t = decimal(0.0);
s = clamp(-c / a, decimal(0.0), decimal(1.0));
}
else if (t > decimal(1.0)) {
t = decimal(1.0);
s = clamp((b - c) / a, decimal(0.0), decimal(1.0));
}
}
}
// Compute the closest points on both segments
closestPointSeg1 = seg1PointA + d1 * s;
closestPointSeg2 = seg2PointA + d2 * t;
}
// Compute the barycentric coordinates u, v, w of a point p inside the triangle (a, b, c)
// This method uses the technique described in the book Real-Time collision detection by
// Christer Ericson.
RP3D_FORCE_INLINE void computeBarycentricCoordinatesInTriangle(const Vector3& a, const Vector3& b, const Vector3& c,
const Vector3& p, decimal& u, decimal& v, decimal& w) {
const Vector3 v0 = b - a;
const Vector3 v1 = c - a;
const Vector3 v2 = p - a;
const decimal d00 = v0.dot(v0);
const decimal d01 = v0.dot(v1);
const decimal d11 = v1.dot(v1);
const decimal d20 = v2.dot(v0);
const decimal d21 = v2.dot(v1);
const decimal denom = d00 * d11 - d01 * d01;
v = (d11 * d20 - d01 * d21) / denom;
w = (d00 * d21 - d01 * d20) / denom;
u = decimal(1.0) - v - w;
}
// Compute the intersection between a plane and a segment
// Let the plane define by the equation planeNormal.dot(X) = planeD with X a point on the plane and "planeNormal" the plane normal. This method
// computes the intersection P between the plane and the segment (segA, segB). The method returns the value "t" such
// that P = segA + t * (segB - segA). Note that it only returns a value in [0, 1] if there is an intersection. Otherwise,
// there is no intersection between the plane and the segment.
RP3D_FORCE_INLINE decimal computePlaneSegmentIntersection(const Vector3& segA, const Vector3& segB, const decimal planeD, const Vector3& planeNormal) {
const decimal parallelEpsilon = decimal(0.0001);
decimal t = decimal(-1);
const decimal nDotAB = planeNormal.dot(segB - segA);
// If the segment is not parallel to the plane
if (std::abs(nDotAB) > parallelEpsilon) {
t = (planeD - planeNormal.dot(segA)) / nDotAB;
}
return t;
}
// Compute the distance between a point "point" and a line given by the points "linePointA" and "linePointB"
RP3D_FORCE_INLINE decimal computePointToLineDistance(const Vector3& linePointA, const Vector3& linePointB, const Vector3& point) {
decimal distAB = (linePointB - linePointA).length();
if (distAB < MACHINE_EPSILON) {
return (point - linePointA).length();
}
return ((point - linePointA).cross(point - linePointB)).length() / distAB;
}
// Clip a segment against multiple planes and return the clipped segment vertices
// This method implements the SutherlandHodgman clipping algorithm
RP3D_FORCE_INLINE Array<Vector3> clipSegmentWithPlanes(const Vector3& segA, const Vector3& segB,
const Array<Vector3>& planesPoints,
const Array<Vector3>& planesNormals,
MemoryAllocator& allocator) {
assert(planesPoints.size() == planesNormals.size());
Array<Vector3> inputVertices(allocator, 2);
Array<Vector3> outputVertices(allocator, 2);
inputVertices.add(segA);
inputVertices.add(segB);
// For each clipping plane
const uint32 nbPlanesPoints = planesPoints.size();
for (uint32 p=0; p < nbPlanesPoints; p++) {
// If there is no more vertices, stop
if (inputVertices.size() == 0) return inputVertices;
assert(inputVertices.size() == 2);
outputVertices.clear();
Vector3& v1 = inputVertices[0];
Vector3& v2 = inputVertices[1];
decimal v1DotN = (v1 - planesPoints[p]).dot(planesNormals[p]);
decimal v2DotN = (v2 - planesPoints[p]).dot(planesNormals[p]);
// If the second vertex is in front of the clippling plane
if (v2DotN >= decimal(0.0)) {
// If the first vertex is not in front of the clippling plane
if (v1DotN < decimal(0.0)) {
// The second point we keep is the intersection between the segment v1, v2 and the clipping plane
decimal t = computePlaneSegmentIntersection(v1, v2, planesNormals[p].dot(planesPoints[p]), planesNormals[p]);
if (t >= decimal(0) && t <= decimal(1.0)) {
outputVertices.add(v1 + t * (v2 - v1));
}
else {
outputVertices.add(v2);
}
}
else {
outputVertices.add(v1);
}
// Add the second vertex
outputVertices.add(v2);
}
else { // If the second vertex is behind the clipping plane
// If the first vertex is in front of the clippling plane
if (v1DotN >= decimal(0.0)) {
outputVertices.add(v1);
// The first point we keep is the intersection between the segment v1, v2 and the clipping plane
decimal t = computePlaneSegmentIntersection(v1, v2, -planesNormals[p].dot(planesPoints[p]), -planesNormals[p]);
if (t >= decimal(0.0) && t <= decimal(1.0)) {
outputVertices.add(v1 + t * (v2 - v1));
}
}
}
inputVertices = outputVertices;
}
return outputVertices;
}
// Clip a polygon against a single plane and return the clipped polygon vertices
// This method implements the SutherlandHodgman polygon clipping algorithm
RP3D_FORCE_INLINE void clipPolygonWithPlane(const Array<Vector3>& polygonVertices, const Vector3& planePoint,
const Vector3& planeNormal, Array<Vector3>& outClippedPolygonVertices) {
uint32 nbInputVertices = polygonVertices.size();
assert(outClippedPolygonVertices.size() == 0);
uint32 vStartIndex = nbInputVertices - 1;
const decimal planeNormalDotPlanePoint = planeNormal.dot(planePoint);
decimal vStartDotN = (polygonVertices[vStartIndex] - planePoint).dot(planeNormal);
// For each edge of the polygon
for (uint vEndIndex = 0; vEndIndex < nbInputVertices; vEndIndex++) {
const Vector3& vStart = polygonVertices[vStartIndex];
const Vector3& vEnd = polygonVertices[vEndIndex];
const decimal vEndDotN = (vEnd - planePoint).dot(planeNormal);
// If the second vertex is in front of the clippling plane
if (vEndDotN >= decimal(0.0)) {
// If the first vertex is not in front of the clippling plane
if (vStartDotN < decimal(0.0)) {
// The second point we keep is the intersection between the segment v1, v2 and the clipping plane
const decimal t = computePlaneSegmentIntersection(vStart, vEnd, planeNormalDotPlanePoint, planeNormal);
if (t >= decimal(0) && t <= decimal(1.0)) {
outClippedPolygonVertices.add(vStart + t * (vEnd - vStart));
}
else {
outClippedPolygonVertices.add(vEnd);
}
}
// Add the second vertex
outClippedPolygonVertices.add(vEnd);
}
else { // If the second vertex is behind the clipping plane
// If the first vertex is in front of the clippling plane
if (vStartDotN >= decimal(0.0)) {
// The first point we keep is the intersection between the segment v1, v2 and the clipping plane
const decimal t = computePlaneSegmentIntersection(vStart, vEnd, -planeNormalDotPlanePoint, -planeNormal);
if (t >= decimal(0.0) && t <= decimal(1.0)) {
outClippedPolygonVertices.add(vStart + t * (vEnd - vStart));
}
else {
outClippedPolygonVertices.add(vStart);
}
}
}
vStartIndex = vEndIndex;
vStartDotN = vEndDotN;
}
}
// Project a point onto a plane that is given by a point and its unit length normal
RP3D_FORCE_INLINE Vector3 projectPointOntoPlane(const Vector3& point, const Vector3& unitPlaneNormal, const Vector3& planePoint) {
return point - unitPlaneNormal.dot(point - planePoint) * unitPlaneNormal;
}
// Return the distance between a point and a plane (the plane normal must be normalized)
RP3D_FORCE_INLINE decimal computePointToPlaneDistance(const Vector3& point, const Vector3& planeNormal, const Vector3& planePoint) {
return planeNormal.dot(point - planePoint);
}
/// Return true if a number is a power of two
RP3D_FORCE_INLINE bool isPowerOfTwo(uint32 number) {
return number != 0 && !(number & (number -1));
}
/// Return the next power of two larger than the number in parameter
RP3D_FORCE_INLINE uint32 nextPowerOfTwo32Bits(uint32 number) {
number--;
number |= number >> 1;
number |= number >> 2;
number |= number >> 4;
number |= number >> 8;
number |= number >> 16;
number++;
number += (number == 0);
return number;
}
/// Return an unique integer from two integer numbers (pairing function)
/// Here we assume that the two parameter numbers are sorted such that
/// number1 = max(number1, number2)
/// http://szudzik.com/ElegantPairing.pdf
uint64 pairNumbers(uint32 number1, uint32 number2);
RP3D_FORCE_INLINE uint64 pairNumbers(uint32 number1, uint32 number2) {
assert(number1 == std::max(number1, number2));
return number1 * number1 + number1 + number2;
}
}

View File

@ -102,7 +102,7 @@ class MemoryManager {
};
// Allocate memory of a given type
inline void* MemoryManager::allocate(AllocationType allocationType, size_t size) {
RP3D_FORCE_INLINE void* MemoryManager::allocate(AllocationType allocationType, size_t size) {
switch (allocationType) {
case AllocationType::Base: return mBaseAllocator->allocate(size);
@ -115,7 +115,7 @@ inline void* MemoryManager::allocate(AllocationType allocationType, size_t size)
}
// Release previously allocated memory.
inline void MemoryManager::release(AllocationType allocationType, void* pointer, size_t size) {
RP3D_FORCE_INLINE void MemoryManager::release(AllocationType allocationType, void* pointer, size_t size) {
switch (allocationType) {
case AllocationType::Base: mBaseAllocator->release(pointer, size); break;
@ -126,22 +126,22 @@ inline void MemoryManager::release(AllocationType allocationType, void* pointer,
}
// Return the pool allocator
inline PoolAllocator& MemoryManager::getPoolAllocator() {
RP3D_FORCE_INLINE PoolAllocator& MemoryManager::getPoolAllocator() {
return mPoolAllocator;
}
// Return the single frame stack allocator
inline SingleFrameAllocator& MemoryManager::getSingleFrameAllocator() {
RP3D_FORCE_INLINE SingleFrameAllocator& MemoryManager::getSingleFrameAllocator() {
return mSingleFrameAllocator;
}
// Return the heap allocator
inline HeapAllocator& MemoryManager::getHeapAllocator() {
RP3D_FORCE_INLINE HeapAllocator& MemoryManager::getHeapAllocator() {
return mHeapAllocator;
}
// Reset the single frame allocator
inline void MemoryManager::resetFrameAllocator() {
RP3D_FORCE_INLINE void MemoryManager::resetFrameAllocator() {
mSingleFrameAllocator.reset();
}

View File

@ -64,7 +64,7 @@
#include <reactphysics3d/constraint/SliderJoint.h>
#include <reactphysics3d/constraint/HingeJoint.h>
#include <reactphysics3d/constraint/FixedJoint.h>
#include <reactphysics3d/containers/List.h>
#include <reactphysics3d/containers/Array.h>
/// Alias to the ReactPhysics3D namespace
namespace rp3d = reactphysics3d;

View File

@ -51,10 +51,10 @@ class AABBOverlapCallback : public DynamicAABBTreeOverlapCallback {
public:
List<int>& mOverlappingNodes;
Array<int>& mOverlappingNodes;
// Constructor
AABBOverlapCallback(List<int>& overlappingNodes) : mOverlappingNodes(overlappingNodes) {
AABBOverlapCallback(Array<int>& overlappingNodes) : mOverlappingNodes(overlappingNodes) {
}
@ -184,7 +184,7 @@ class BroadPhaseSystem {
void removeMovedCollider(int broadPhaseID);
/// Compute all the overlapping pairs of collision shapes
void computeOverlappingPairs(MemoryManager& memoryManager, List<Pair<int32, int32>>& overlappingNodes);
void computeOverlappingPairs(MemoryManager& memoryManager, Array<Pair<int32, int32>>& overlappingNodes);
/// Return the collider corresponding to the broad-phase node id in parameter
Collider* getColliderForBroadPhaseId(int broadPhaseId) const;
@ -208,27 +208,27 @@ class BroadPhaseSystem {
};
// Return the fat AABB of a given broad-phase shape
inline const AABB& BroadPhaseSystem::getFatAABB(int broadPhaseId) const {
RP3D_FORCE_INLINE const AABB& BroadPhaseSystem::getFatAABB(int broadPhaseId) const {
return mDynamicAABBTree.getFatAABB(broadPhaseId);
}
// Remove a collider from the array of colliders that have moved in the last simulation step
// and that need to be tested again for broad-phase overlapping.
inline void BroadPhaseSystem::removeMovedCollider(int broadPhaseID) {
RP3D_FORCE_INLINE void BroadPhaseSystem::removeMovedCollider(int broadPhaseID) {
// Remove the broad-phase ID from the set
mMovedShapes.remove(broadPhaseID);
}
// Return the collider corresponding to the broad-phase node id in parameter
inline Collider* BroadPhaseSystem::getColliderForBroadPhaseId(int broadPhaseId) const {
RP3D_FORCE_INLINE Collider* BroadPhaseSystem::getColliderForBroadPhaseId(int broadPhaseId) const {
return static_cast<Collider*>(mDynamicAABBTree.getNodeDataPointer(broadPhaseId));
}
#ifdef IS_RP3D_PROFILING_ENABLED
// Set the profiler
inline void BroadPhaseSystem::setProfiler(Profiler* profiler) {
RP3D_FORCE_INLINE void BroadPhaseSystem::setProfiler(Profiler* profiler) {
mProfiler = profiler;
mDynamicAABBTree.setProfiler(profiler);
}

View File

@ -43,6 +43,7 @@
#include <reactphysics3d/containers/Set.h>
#include <reactphysics3d/components/ColliderComponents.h>
#include <reactphysics3d/components/TransformComponents.h>
#include <reactphysics3d/collision/HalfEdgeStructure.h>
/// ReactPhysics3D namespace
namespace reactphysics3d {
@ -83,6 +84,9 @@ class CollisionDetectionSystem {
/// Reference the collider components
ColliderComponents& mCollidersComponents;
/// Reference to the rigid bodies components
RigidBodyComponents& mRigidBodyComponents;
/// Collision Detection Dispatch configuration
CollisionDispatch mCollisionDispatch;
@ -95,6 +99,9 @@ class CollisionDetectionSystem {
/// Broad-phase overlapping pairs
OverlappingPairs mOverlappingPairs;
/// Overlapping nodes during broad-phase computation
Array<Pair<int32, int32>> mBroadPhaseOverlappingNodes;
/// Broad-phase system
BroadPhaseSystem mBroadPhaseSystem;
@ -104,67 +111,66 @@ class CollisionDetectionSystem {
/// Narrow-phase collision detection input
NarrowPhaseInput mNarrowPhaseInput;
/// List of the potential contact points
List<ContactPointInfo> mPotentialContactPoints;
/// Array of the potential contact points
Array<ContactPointInfo> mPotentialContactPoints;
/// List of the potential contact manifolds
List<ContactManifoldInfo> mPotentialContactManifolds;
/// Array of the potential contact manifolds
Array<ContactManifoldInfo> mPotentialContactManifolds;
/// First list of narrow-phase pair contacts
List<ContactPair> mContactPairs1;
/// First array of narrow-phase pair contacts
Array<ContactPair> mContactPairs1;
/// Second list of narrow-phase pair contacts
List<ContactPair> mContactPairs2;
/// Second array of narrow-phase pair contacts
Array<ContactPair> mContactPairs2;
/// Pointer to the list of contact pairs of the previous frame (either mContactPairs1 or mContactPairs2)
List<ContactPair>* mPreviousContactPairs;
/// Pointer to the array of contact pairs of the previous frame (either mContactPairs1 or mContactPairs2)
Array<ContactPair>* mPreviousContactPairs;
/// Pointer to the list of contact pairs of the current frame (either mContactPairs1 or mContactPairs2)
List<ContactPair>* mCurrentContactPairs;
/// Pointer to the array of contact pairs of the current frame (either mContactPairs1 or mContactPairs2)
Array<ContactPair>* mCurrentContactPairs;
/// List of lost contact pairs (contact pairs in contact in previous frame but not in the current one)
List<ContactPair> mLostContactPairs;
/// First map of overlapping pair id to the index of the corresponding pair contact
Map<uint64, uint> mMapPairIdToContactPairIndex1;
/// Second map of overlapping pair id to the index of the corresponding pair contact
Map<uint64, uint> mMapPairIdToContactPairIndex2;
/// Array of lost contact pairs (contact pairs in contact in previous frame but not in the current one)
Array<ContactPair> mLostContactPairs;
/// Pointer to the map of overlappingPairId to the index of contact pair of the previous frame
/// (either mMapPairIdToContactPairIndex1 or mMapPairIdToContactPairIndex2)
Map<uint64, uint>* mPreviousMapPairIdToContactPairIndex;
Map<uint64, uint> mPreviousMapPairIdToContactPairIndex;
/// Pointer to the map of overlappingPairId to the index of contact pair of the current frame
/// (either mMapPairIdToContactPairIndex1 or mMapPairIdToContactPairIndex2)
Map<uint64, uint>* mCurrentMapPairIdToContactPairIndex;
/// First array with the contact manifolds
Array<ContactManifold> mContactManifolds1;
/// First list with the contact manifolds
List<ContactManifold> mContactManifolds1;
/// Second array with the contact manifolds
Array<ContactManifold> mContactManifolds2;
/// Second list with the contact manifolds
List<ContactManifold> mContactManifolds2;
/// Pointer to the array of contact manifolds from the previous frame (either mContactManifolds1 or mContactManifolds2)
Array<ContactManifold>* mPreviousContactManifolds;
/// Pointer to the list of contact manifolds from the previous frame (either mContactManifolds1 or mContactManifolds2)
List<ContactManifold>* mPreviousContactManifolds;
/// Pointer to the array of contact manifolds from the current frame (either mContactManifolds1 or mContactManifolds2)
Array<ContactManifold>* mCurrentContactManifolds;
/// Pointer to the list of contact manifolds from the current frame (either mContactManifolds1 or mContactManifolds2)
List<ContactManifold>* mCurrentContactManifolds;
/// Second array of contact points (contact points from either the current frame of the previous frame)
Array<ContactPoint> mContactPoints1;
/// Second list of contact points (contact points from either the current frame of the previous frame)
List<ContactPoint> mContactPoints1;
/// Second list of contact points (contact points from either the current frame of the previous frame)
List<ContactPoint> mContactPoints2;
/// Second array of contact points (contact points from either the current frame of the previous frame)
Array<ContactPoint> mContactPoints2;
/// Pointer to the contact points of the previous frame (either mContactPoints1 or mContactPoints2)
List<ContactPoint>* mPreviousContactPoints;
Array<ContactPoint>* mPreviousContactPoints;
/// Pointer to the contact points of the current frame (either mContactPoints1 or mContactPoints2)
List<ContactPoint>* mCurrentContactPoints;
Array<ContactPoint>* mCurrentContactPoints;
/// Map a body entity to the list of contact pairs in which it is involved
Map<Entity, List<uint>> mMapBodyToContactPairs;
/// Array with the indices of all the contact pairs that have at least one CollisionBody
Array<uint32> mCollisionBodyContactPairsIndices;
/// Number of potential contact manifolds in the previous frame
uint32 mNbPreviousPotentialContactManifolds;
/// Number of potential contact points in the previous frame
uint32 mNbPreviousPotentialContactPoints;
/// Reference to the half-edge structure of the triangle polyhedron
HalfEdgeStructure& mTriangleHalfEdgeStructure;
#ifdef IS_RP3D_PROFILING_ENABLED
@ -182,7 +188,7 @@ class CollisionDetectionSystem {
void computeMiddlePhase(NarrowPhaseInput& narrowPhaseInput, bool needToReportContacts);
// Compute the middle-phase collision detection
void computeMiddlePhaseCollisionSnapshot(List<uint64>& convexPairs, List<uint64>& concavePairs, NarrowPhaseInput& narrowPhaseInput,
void computeMiddlePhaseCollisionSnapshot(Array<uint64>& convexPairs, Array<uint64>& concavePairs, NarrowPhaseInput& narrowPhaseInput,
bool reportContacts);
/// Compute the narrow-phase collision detection
@ -195,89 +201,95 @@ class CollisionDetectionSystem {
bool computeNarrowPhaseCollisionSnapshot(NarrowPhaseInput& narrowPhaseInput, CollisionCallback& callback);
/// Process the potential contacts after narrow-phase collision detection
void computeOverlapSnapshotContactPairs(NarrowPhaseInput& narrowPhaseInput, List<ContactPair>& contactPairs) const;
void computeOverlapSnapshotContactPairs(NarrowPhaseInput& narrowPhaseInput, Array<ContactPair>& contactPairs) const;
/// Convert the potential contact into actual contacts
void computeOverlapSnapshotContactPairs(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, List<ContactPair>& contactPairs,
void computeOverlapSnapshotContactPairs(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, Array<ContactPair>& contactPairs,
Set<uint64>& setOverlapContactPairId) const;
/// Take a list of overlapping nodes in the broad-phase and create new overlapping pairs if necessary
void updateOverlappingPairs(const List<Pair<int32, int32> >& overlappingNodes);
/// Take an array of overlapping nodes in the broad-phase and create new overlapping pairs if necessary
void updateOverlappingPairs(const Array<Pair<int32, int32> >& overlappingNodes);
/// Remove pairs that are not overlapping anymore
void removeNonOverlappingPairs();
/// Add a lost contact pair (pair of colliders that are not in contact anymore)
void addLostContactPair(uint64 overlappingPairIndex);
void addLostContactPair(OverlappingPairs::OverlappingPair& overlappingPair);
/// Execute the narrow-phase collision detection algorithm on batches
bool testNarrowPhaseCollision(NarrowPhaseInput& narrowPhaseInput, bool clipWithPreviousAxisIfStillColliding, MemoryAllocator& allocator);
/// Compute the concave vs convex middle-phase algorithm for a given pair of bodies
void computeConvexVsConcaveMiddlePhase(uint64 pairIndex, MemoryAllocator& allocator,
void computeConvexVsConcaveMiddlePhase(OverlappingPairs::ConcaveOverlappingPair& overlappingPair, MemoryAllocator& allocator,
NarrowPhaseInput& narrowPhaseInput);
/// Swap the previous and current contacts lists
/// Swap the previous and current contacts arrays
void swapPreviousAndCurrentContacts();
/// Convert the potential contact into actual contacts
void processPotentialContacts(NarrowPhaseInfoBatch& narrowPhaseInfoBatch,
bool updateLastFrameInfo, List<ContactPointInfo>& potentialContactPoints,
Map<uint64, uint>* mapPairIdToContactPairIndex,
List<ContactManifoldInfo>& potentialContactManifolds, List<ContactPair>* contactPairs,
Map<Entity, List<uint>>& mapBodyToContactPairs);
bool updateLastFrameInfo, Array<ContactPointInfo>& potentialContactPoints,
Array<ContactManifoldInfo>& potentialContactManifolds,
Map<uint64, uint>& mapPairIdToContactPairIndex, Array<ContactPair>* contactPairs);
/// Process the potential contacts after narrow-phase collision detection
void processAllPotentialContacts(NarrowPhaseInput& narrowPhaseInput, bool updateLastFrameInfo, List<ContactPointInfo>& potentialContactPoints,
Map<uint64, uint>* mapPairIdToContactPairIndex,
List<ContactManifoldInfo>& potentialContactManifolds, List<ContactPair>* contactPairs,
Map<Entity, List<uint>>& mapBodyToContactPairs);
void processAllPotentialContacts(NarrowPhaseInput& narrowPhaseInput, bool updateLastFrameInfo, Array<ContactPointInfo>& potentialContactPoints,
Array<ContactManifoldInfo>& potentialContactManifolds, Array<ContactPair>* contactPairs);
/// Reduce the potential contact manifolds and contact points of the overlapping pair contacts
void reducePotentialContactManifolds(List<ContactPair>* contactPairs, List<ContactManifoldInfo>& potentialContactManifolds,
const List<ContactPointInfo>& potentialContactPoints) const;
void reducePotentialContactManifolds(Array<ContactPair>* contactPairs, Array<ContactManifoldInfo>& potentialContactManifolds,
const Array<ContactPointInfo>& potentialContactPoints) const;
/// Create the actual contact manifolds and contacts points (from potential contacts) for a given contact pair
void createContacts();
/// Add the contact pairs to the corresponding bodies
void addContactPairsToBodies();
/// Compute the map from contact pairs ids to contact pair for the next frame
void computeMapPreviousContactPairs();
/// Compute the lost contact pairs (contact pairs in contact in the previous frame but not in the current one)
void computeLostContactPairs();
/// Create the actual contact manifolds and contacts points for testCollision() methods
void createSnapshotContacts(List<ContactPair>& contactPairs, List<ContactManifold> &contactManifolds,
List<ContactPoint>& contactPoints,
List<ContactManifoldInfo>& potentialContactManifolds,
List<ContactPointInfo>& potentialContactPoints);
void createSnapshotContacts(Array<ContactPair>& contactPairs, Array<ContactManifold> &contactManifolds,
Array<ContactPoint>& contactPoints,
Array<ContactManifoldInfo>& potentialContactManifolds,
Array<ContactPointInfo>& potentialContactPoints);
/// Initialize the current contacts with the contacts from the previous frame (for warmstarting)
void initContactsWithPreviousOnes();
/// Reduce the number of contact points of a potential contact manifold
void reduceContactPoints(ContactManifoldInfo& manifold, const Transform& shape1ToWorldTransform,
const List<ContactPointInfo>& potentialContactPoints) const;
const Array<ContactPointInfo>& potentialContactPoints) const;
/// Report contacts
void reportContacts(CollisionCallback& callback, List<ContactPair>* contactPairs,
List<ContactManifold>* manifolds, List<ContactPoint>* contactPoints, List<ContactPair>& lostContactPairs);
void reportContacts(CollisionCallback& callback, Array<ContactPair>* contactPairs,
Array<ContactManifold>* manifolds, Array<ContactPoint>* contactPoints, Array<ContactPair>& lostContactPairs);
/// Report all triggers
void reportTriggers(EventListener& eventListener, List<ContactPair>* contactPairs, List<ContactPair>& lostContactPairs);
void reportTriggers(EventListener& eventListener, Array<ContactPair>* contactPairs, Array<ContactPair>& lostContactPairs);
/// Report all contacts for debug rendering
void reportDebugRenderingContacts(List<ContactPair>* contactPairs, List<ContactManifold>* manifolds, List<ContactPoint>* contactPoints, List<ContactPair>& lostContactPairs);
void reportDebugRenderingContacts(Array<ContactPair>* contactPairs, Array<ContactManifold>* manifolds, Array<ContactPoint>* contactPoints, Array<ContactPair>& lostContactPairs);
/// Return the largest depth of all the contact points of a potential manifold
decimal computePotentialManifoldLargestContactDepth(const ContactManifoldInfo& manifold,
const List<ContactPointInfo>& potentialContactPoints) const;
const Array<ContactPointInfo>& potentialContactPoints) const;
/// Process the potential contacts where one collion is a concave shape
void processSmoothMeshContacts(OverlappingPair* pair);
/// Filter the overlapping pairs to keep only the pairs where a given body is involved
void filterOverlappingPairs(Entity bodyEntity, List<uint64>& convexPairs, List<uint64>& concavePairs) const;
void filterOverlappingPairs(Entity bodyEntity, Array<uint64>& convexPairs, Array<uint64>& concavePairs) const;
/// Filter the overlapping pairs to keep only the pairs where two given bodies are involved
void filterOverlappingPairs(Entity body1Entity, Entity body2Entity, List<uint64>& convexPairs, List<uint64>& concavePairs) const;
void filterOverlappingPairs(Entity body1Entity, Entity body2Entity, Array<uint64>& convexPairs, Array<uint64>& concavePairs) const;
/// Remove an element in an array (and replace it by the last one in the array)
void removeItemAtInArray(uint array[], uint8 index, uint8& arraySize) const;
public :
@ -286,7 +298,7 @@ class CollisionDetectionSystem {
/// Constructor
CollisionDetectionSystem(PhysicsWorld* world, ColliderComponents& collidersComponents,
TransformComponents& transformComponents, CollisionBodyComponents& collisionBodyComponents, RigidBodyComponents& rigidBodyComponents,
MemoryManager& memoryManager);
MemoryManager& memoryManager, HalfEdgeStructure& triangleHalfEdgeStructure);
/// Destructor
~CollisionDetectionSystem() = default;
@ -380,12 +392,12 @@ class CollisionDetectionSystem {
};
// Return a reference to the collision dispatch configuration
inline CollisionDispatch& CollisionDetectionSystem::getCollisionDispatch() {
RP3D_FORCE_INLINE CollisionDispatch& CollisionDetectionSystem::getCollisionDispatch() {
return mCollisionDispatch;
}
// Add a body to the collision detection
inline void CollisionDetectionSystem::addCollider(Collider* collider, const AABB& aabb) {
RP3D_FORCE_INLINE void CollisionDetectionSystem::addCollider(Collider* collider, const AABB& aabb) {
// Add the body to the broad-phase
mBroadPhaseSystem.addCollider(collider, aabb);
@ -399,19 +411,19 @@ inline void CollisionDetectionSystem::addCollider(Collider* collider, const AABB
}
// Add a pair of bodies that cannot collide with each other
inline void CollisionDetectionSystem::addNoCollisionPair(Entity body1Entity, Entity body2Entity) {
RP3D_FORCE_INLINE void CollisionDetectionSystem::addNoCollisionPair(Entity body1Entity, Entity body2Entity) {
mNoCollisionPairs.add(OverlappingPairs::computeBodiesIndexPair(body1Entity, body2Entity));
}
// Remove a pair of bodies that cannot collide with each other
inline void CollisionDetectionSystem::removeNoCollisionPair(Entity body1Entity, Entity body2Entity) {
RP3D_FORCE_INLINE void CollisionDetectionSystem::removeNoCollisionPair(Entity body1Entity, Entity body2Entity) {
mNoCollisionPairs.remove(OverlappingPairs::computeBodiesIndexPair(body1Entity, body2Entity));
}
// Ask for a collision shape to be tested again during broad-phase.
/// We simply put the shape in the list of collision shape that have moved in the
/// We simply put the shape in the array of collision shape that have moved in the
/// previous frame so that it is tested for collision again in the broad-phase.
inline void CollisionDetectionSystem::askForBroadPhaseCollisionCheck(Collider* collider) {
RP3D_FORCE_INLINE void CollisionDetectionSystem::askForBroadPhaseCollisionCheck(Collider* collider) {
if (collider->getBroadPhaseId() != -1) {
mBroadPhaseSystem.addMovedCollider(collider->getBroadPhaseId(), collider);
@ -419,31 +431,31 @@ inline void CollisionDetectionSystem::askForBroadPhaseCollisionCheck(Collider* c
}
// Return a pointer to the world
inline PhysicsWorld* CollisionDetectionSystem::getWorld() {
RP3D_FORCE_INLINE PhysicsWorld* CollisionDetectionSystem::getWorld() {
return mWorld;
}
// Return a reference to the memory manager
inline MemoryManager& CollisionDetectionSystem::getMemoryManager() const {
RP3D_FORCE_INLINE MemoryManager& CollisionDetectionSystem::getMemoryManager() const {
return mMemoryManager;
}
// Update a collider (that has moved for instance)
inline void CollisionDetectionSystem::updateCollider(Entity colliderEntity, decimal timeStep) {
RP3D_FORCE_INLINE void CollisionDetectionSystem::updateCollider(Entity colliderEntity, decimal timeStep) {
// Update the collider component
mBroadPhaseSystem.updateCollider(colliderEntity, timeStep);
}
// Update all the enabled colliders
inline void CollisionDetectionSystem::updateColliders(decimal timeStep) {
RP3D_FORCE_INLINE void CollisionDetectionSystem::updateColliders(decimal timeStep) {
mBroadPhaseSystem.updateColliders(timeStep);
}
#ifdef IS_RP3D_PROFILING_ENABLED
// Set the profiler
inline void CollisionDetectionSystem::setProfiler(Profiler* profiler) {
RP3D_FORCE_INLINE void CollisionDetectionSystem::setProfiler(Profiler* profiler) {
mProfiler = profiler;
mBroadPhaseSystem.setProfiler(profiler);
mCollisionDispatch.setProfiler(profiler);

View File

@ -210,12 +210,15 @@ class ConstraintSolverSystem {
#endif
// ---------- Friendship ----------
friend class HingeJoint;
};
#ifdef IS_RP3D_PROFILING_ENABLED
// Set the profiler
inline void ConstraintSolverSystem::setProfiler(Profiler* profiler) {
RP3D_FORCE_INLINE void ConstraintSolverSystem::setProfiler(Profiler* profiler) {
mProfiler = profiler;
mSolveBallAndSocketJointSystem.setProfiler(profiler);
mSolveFixedJointSystem.setProfiler(profiler);

View File

@ -30,6 +30,8 @@
#include <reactphysics3d/configuration.h>
#include <reactphysics3d/mathematics/Vector3.h>
#include <reactphysics3d/mathematics/Matrix3x3.h>
#include <reactphysics3d/containers/Array.h>
#include <reactphysics3d/engine/Material.h>
/// ReactPhysics3D namespace
namespace reactphysics3d {
@ -198,9 +200,6 @@ class ContactSolverSystem {
/// Mix friction coefficient for the two bodies
decimal frictionCoefficient;
/// Rolling resistance factor between the two bodies
decimal rollingResistanceFactor;
// - Variables used when friction constraints are apply at the center of the manifold-//
/// Average normal vector of the contact manifold
@ -239,9 +238,6 @@ class ContactSolverSystem {
/// Matrix K for the twist friction constraint
decimal inverseTwistFrictionMass;
/// Matrix K for the rolling resistance constraint
Matrix3x3 inverseRollingResistance;
/// First friction direction at contact manifold center
Vector3 frictionVector1;
@ -263,9 +259,6 @@ class ContactSolverSystem {
/// Twist friction impulse at contact manifold center
decimal frictionTwistImpulse;
/// Rolling resistance impulse
Vector3 rollingResistanceImpulse;
/// Number of contact points
int8 nbContacts;
};
@ -310,11 +303,11 @@ class ContactSolverSystem {
/// Reference to the islands
Islands& mIslands;
/// Pointer to the list of contact manifolds from narrow-phase
List<ContactManifold>* mAllContactManifolds;
/// Pointer to the array of contact manifolds from narrow-phase
Array<ContactManifold>* mAllContactManifolds;
/// Pointer to the list of contact points from narrow-phase
List<ContactPoint>* mAllContactPoints;
/// Pointer to the array of contact points from narrow-phase
Array<ContactPoint>* mAllContactPoints;
/// Reference to the body components
CollisionBodyComponents& mBodyComponents;
@ -338,14 +331,10 @@ class ContactSolverSystem {
// -------------------- Methods -------------------- //
/// Compute the collision restitution factor from the restitution factor of each collider
decimal computeMixedRestitutionFactor(Collider* collider1,
Collider* collider2) const;
decimal computeMixedRestitutionFactor(const Material& material1, const Material& material2) const;
/// Compute the mixed friction coefficient from the friction coefficient of each collider
decimal computeMixedFrictionCoefficient(Collider* collider1, Collider* collider2) const;
/// Compute th mixed rolling resistance factor between two colliders
decimal computeMixedRollingResistance(Collider* collider1, Collider* collider2) const;
decimal computeMixedFrictionCoefficient(const Material &material1, const Material &material2) const;
/// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction
/// plane for a contact manifold. The two vectors have to be
@ -368,7 +357,7 @@ class ContactSolverSystem {
~ContactSolverSystem() = default;
/// Initialize the contact constraints
void init(List<ContactManifold>* contactManifolds, List<ContactPoint>* contactPoints, decimal timeStep);
void init(Array<ContactManifold>* contactManifolds, Array<ContactPoint>* contactPoints, decimal timeStep);
/// Initialize the constraint solver for a given island
void initializeForIsland(uint islandIndex);
@ -398,19 +387,36 @@ class ContactSolverSystem {
};
// Return true if the split impulses position correction technique is used for contacts
inline bool ContactSolverSystem::isSplitImpulseActive() const {
RP3D_FORCE_INLINE bool ContactSolverSystem::isSplitImpulseActive() const {
return mIsSplitImpulseActive;
}
// Activate or Deactivate the split impulses for contacts
inline void ContactSolverSystem::setIsSplitImpulseActive(bool isActive) {
RP3D_FORCE_INLINE void ContactSolverSystem::setIsSplitImpulseActive(bool isActive) {
mIsSplitImpulseActive = isActive;
}
// Compute the collision restitution factor from the restitution factor of each collider
RP3D_FORCE_INLINE decimal ContactSolverSystem::computeMixedRestitutionFactor(const Material& material1, const Material& material2) const {
const decimal restitution1 = material1.getBounciness();
const decimal restitution2 = material2.getBounciness();
// Return the largest restitution factor
return (restitution1 > restitution2) ? restitution1 : restitution2;
}
// Compute the mixed friction coefficient from the friction coefficient of each collider
RP3D_FORCE_INLINE decimal ContactSolverSystem::computeMixedFrictionCoefficient(const Material& material1, const Material& material2) const {
// Use the geometric mean to compute the mixed friction coefficient
return material1.getFrictionCoefficientSqrt() * material2.getFrictionCoefficientSqrt();
}
#ifdef IS_RP3D_PROFILING_ENABLED
// Set the profiler
inline void ContactSolverSystem::setProfiler(Profiler* profiler) {
RP3D_FORCE_INLINE void ContactSolverSystem::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}

View File

@ -114,7 +114,7 @@ class DynamicsSystem {
#ifdef IS_RP3D_PROFILING_ENABLED
// Set the profiler
inline void DynamicsSystem::setProfiler(Profiler* profiler) {
RP3D_FORCE_INLINE void DynamicsSystem::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}

View File

@ -123,20 +123,20 @@ class SolveBallAndSocketJointSystem {
#ifdef IS_RP3D_PROFILING_ENABLED
// Set the profiler
inline void SolveBallAndSocketJointSystem::setProfiler(Profiler* profiler) {
RP3D_FORCE_INLINE void SolveBallAndSocketJointSystem::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}
#endif
// Set the time step
inline void SolveBallAndSocketJointSystem::setTimeStep(decimal timeStep) {
RP3D_FORCE_INLINE void SolveBallAndSocketJointSystem::setTimeStep(decimal timeStep) {
assert(timeStep > decimal(0.0));
mTimeStep = timeStep;
}
// Set to true to enable warm starting
inline void SolveBallAndSocketJointSystem::setIsWarmStartingActive(bool isWarmStartingActive) {
RP3D_FORCE_INLINE void SolveBallAndSocketJointSystem::setIsWarmStartingActive(bool isWarmStartingActive) {
mIsWarmStartingActive = isWarmStartingActive;
}

View File

@ -120,20 +120,20 @@ class SolveFixedJointSystem {
#ifdef IS_RP3D_PROFILING_ENABLED
// Set the profiler
inline void SolveFixedJointSystem::setProfiler(Profiler* profiler) {
RP3D_FORCE_INLINE void SolveFixedJointSystem::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}
#endif
// Set the time step
inline void SolveFixedJointSystem::setTimeStep(decimal timeStep) {
RP3D_FORCE_INLINE void SolveFixedJointSystem::setTimeStep(decimal timeStep) {
assert(timeStep > decimal(0.0));
mTimeStep = timeStep;
}
// Set to true to enable warm starting
inline void SolveFixedJointSystem::setIsWarmStartingActive(bool isWarmStartingActive) {
RP3D_FORCE_INLINE void SolveFixedJointSystem::setIsWarmStartingActive(bool isWarmStartingActive) {
mIsWarmStartingActive = isWarmStartingActive;
}

View File

@ -92,8 +92,7 @@ class SolveHingeJointSystem {
decimal upperLimitAngle) const;
/// Compute the current angle around the hinge axis
decimal computeCurrentHingeAngle(Entity jointEntity, const Quaternion& orientationBody1,
const Quaternion& orientationBody2);
decimal computeCurrentHingeAngle(Entity jointEntity, const Quaternion& orientationBody1, const Quaternion& orientationBody2);
public :
@ -133,25 +132,29 @@ class SolveHingeJointSystem {
#endif
// ---------- Friendship ----------
friend class HingeJoint;
};
#ifdef IS_RP3D_PROFILING_ENABLED
// Set the profiler
inline void SolveHingeJointSystem::setProfiler(Profiler* profiler) {
RP3D_FORCE_INLINE void SolveHingeJointSystem::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}
#endif
// Set the time step
inline void SolveHingeJointSystem::setTimeStep(decimal timeStep) {
RP3D_FORCE_INLINE void SolveHingeJointSystem::setTimeStep(decimal timeStep) {
assert(timeStep > decimal(0.0));
mTimeStep = timeStep;
}
// Set to true to enable warm starting
inline void SolveHingeJointSystem::setIsWarmStartingActive(bool isWarmStartingActive) {
RP3D_FORCE_INLINE void SolveHingeJointSystem::setIsWarmStartingActive(bool isWarmStartingActive) {
mIsWarmStartingActive = isWarmStartingActive;
}

View File

@ -124,20 +124,20 @@ class SolveSliderJointSystem {
#ifdef IS_RP3D_PROFILING_ENABLED
// Set the profiler
inline void SolveSliderJointSystem::setProfiler(Profiler* profiler) {
RP3D_FORCE_INLINE void SolveSliderJointSystem::setProfiler(Profiler* profiler) {
mProfiler = profiler;
}
#endif
// Set the time step
inline void SolveSliderJointSystem::setTimeStep(decimal timeStep) {
RP3D_FORCE_INLINE void SolveSliderJointSystem::setTimeStep(decimal timeStep) {
assert(timeStep > decimal(0.0));
mTimeStep = timeStep;
}
// Set to true to enable warm starting
inline void SolveSliderJointSystem::setIsWarmStartingActive(bool isWarmStartingActive) {
RP3D_FORCE_INLINE void SolveSliderJointSystem::setIsWarmStartingActive(bool isWarmStartingActive) {
mIsWarmStartingActive = isWarmStartingActive;
}

View File

@ -27,7 +27,7 @@
#define REACTPHYSICS3D_DEBUG_RENDERER_H
// Libraries
#include <reactphysics3d/containers/List.h>
#include <reactphysics3d/containers/Array.h>
#include <reactphysics3d/containers/Map.h>
#include <reactphysics3d/mathematics/mathematics.h>
#include <reactphysics3d/engine/EventListener.h>
@ -47,7 +47,7 @@ class PhysicsWorld;
/**
* This class is used to display physics debug information directly into the user application view.
* For instance, it is possible to display AABBs of colliders, colliders or contact points. This class
* can be used to get the debug information as lists of basic primitives (points, linges, triangles, ...).
* can be used to get the debug information as arrays of basic primitives (points, linges, triangles, ...).
* You can use this to render physics debug information in your simulation on top of your object. Note that
* you should use this only for debugging purpose and you should disable it when you compile the final release
* version of your application because computing/rendering phyiscs debug information can be expensive.
@ -159,11 +159,11 @@ class DebugRenderer : public EventListener {
/// Memory allocator
MemoryAllocator& mAllocator;
/// List with all the debug lines
List<DebugLine> mLines;
/// Array with all the debug lines
Array<DebugLine> mLines;
/// List with all the debug triangles
List<DebugTriangle> mTriangles;
/// Array with all the debug triangles
Array<DebugTriangle> mTriangles;
/// 32-bits integer that contains all the flags of debug items to display
uint32 mDisplayedDebugItems;
@ -216,8 +216,8 @@ class DebugRenderer : public EventListener {
/// Return the number of lines
uint32 getNbLines() const;
/// Return a reference to the list of lines
const List<DebugLine>& getLines() const;
/// Return a reference to the array of lines
const Array<DebugLine>& getLines() const;
/// Return a pointer to the array of lines
const DebugLine* getLinesArray() const;
@ -225,8 +225,8 @@ class DebugRenderer : public EventListener {
/// Return the number of triangles
uint32 getNbTriangles() const;
/// Return a reference to the list of triangles
const List<DebugTriangle>& getTriangles() const;
/// Return a reference to the array of triangles
const Array<DebugTriangle>& getTriangles() const;
/// Return a pointer to the array of triangles
const DebugTriangle* getTrianglesArray() const;
@ -263,15 +263,15 @@ class DebugRenderer : public EventListener {
/**
* @return The number of lines in the array of lines to draw
*/
inline uint32 DebugRenderer::getNbLines() const {
RP3D_FORCE_INLINE uint32 DebugRenderer::getNbLines() const {
return mLines.size();
}
// Return a reference to the list of lines
// Return a reference to the array of lines
/**
* @return The list of lines to draw
* @return The array of lines to draw
*/
inline const List<DebugRenderer::DebugLine>& DebugRenderer::getLines() const {
RP3D_FORCE_INLINE const Array<DebugRenderer::DebugLine>& DebugRenderer::getLines() const {
return mLines;
}
@ -279,7 +279,7 @@ inline const List<DebugRenderer::DebugLine>& DebugRenderer::getLines() const {
/**
* @return A pointer to the first element of the lines array to draw
*/
inline const DebugRenderer::DebugLine* DebugRenderer::getLinesArray() const {
RP3D_FORCE_INLINE const DebugRenderer::DebugLine* DebugRenderer::getLinesArray() const {
return &(mLines[0]);
}
@ -287,15 +287,15 @@ inline const DebugRenderer::DebugLine* DebugRenderer::getLinesArray() const {
/**
* @return The number of triangles in the array of triangles to draw
*/
inline uint32 DebugRenderer::getNbTriangles() const {
RP3D_FORCE_INLINE uint32 DebugRenderer::getNbTriangles() const {
return mTriangles.size();
}
// Return a reference to the list of triangles
// Return a reference to the array of triangles
/**
* @return The list of triangles to draw
* @return The array of triangles to draw
*/
inline const List<DebugRenderer::DebugTriangle>& DebugRenderer::getTriangles() const {
RP3D_FORCE_INLINE const Array<DebugRenderer::DebugTriangle>& DebugRenderer::getTriangles() const {
return mTriangles;
}
@ -303,7 +303,7 @@ inline const List<DebugRenderer::DebugTriangle>& DebugRenderer::getTriangles() c
/**
* @return A pointer to the first element of the triangles array to draw
*/
inline const DebugRenderer::DebugTriangle* DebugRenderer::getTrianglesArray() const {
RP3D_FORCE_INLINE const DebugRenderer::DebugTriangle* DebugRenderer::getTrianglesArray() const {
return &(mTriangles[0]);
}
@ -312,7 +312,7 @@ inline const DebugRenderer::DebugTriangle* DebugRenderer::getTrianglesArray() co
* @param item A debug item
* @return True if the given debug item is being displayed and false otherwise
*/
inline bool DebugRenderer::getIsDebugItemDisplayed(DebugItem item) const {
RP3D_FORCE_INLINE bool DebugRenderer::getIsDebugItemDisplayed(DebugItem item) const {
return mDisplayedDebugItems & static_cast<uint32>(item);
}
@ -321,7 +321,7 @@ inline bool DebugRenderer::getIsDebugItemDisplayed(DebugItem item) const {
* @param item A debug item to draw
* @param isDisplayed True if the given debug item has to be displayed and false otherwise
*/
inline void DebugRenderer::setIsDebugItemDisplayed(DebugItem item, bool isDisplayed) {
RP3D_FORCE_INLINE void DebugRenderer::setIsDebugItemDisplayed(DebugItem item, bool isDisplayed) {
const uint32 itemFlag = static_cast<uint32>(item);
uint32 resetBit = ~(itemFlag);
mDisplayedDebugItems &= resetBit;
@ -334,7 +334,7 @@ inline void DebugRenderer::setIsDebugItemDisplayed(DebugItem item, bool isDispla
/**
* @return The radius of the sphere used to display a contact point
*/
inline decimal DebugRenderer::getContactPointSphereRadius() const {
RP3D_FORCE_INLINE decimal DebugRenderer::getContactPointSphereRadius() const {
return mContactPointSphereRadius;
}
@ -342,7 +342,7 @@ inline decimal DebugRenderer::getContactPointSphereRadius() const {
/**
* @param radius The radius of the sphere used to display a contact point
*/
inline void DebugRenderer::setContactPointSphereRadius(decimal radius) {
RP3D_FORCE_INLINE void DebugRenderer::setContactPointSphereRadius(decimal radius) {
assert(radius > decimal(0.0));
mContactPointSphereRadius = radius;
}
@ -352,7 +352,7 @@ inline void DebugRenderer::setContactPointSphereRadius(decimal radius) {
/**
* @return The length of the contact normal to display
*/
inline decimal DebugRenderer::getContactNormalLength() const {
RP3D_FORCE_INLINE decimal DebugRenderer::getContactNormalLength() const {
return mContactNormalLength;
}
@ -360,7 +360,7 @@ inline decimal DebugRenderer::getContactNormalLength() const {
/**
* @param contactNormalLength The length of the contact normal to display
*/
inline void DebugRenderer::setContactNormalLength(decimal contactNormalLength) {
RP3D_FORCE_INLINE void DebugRenderer::setContactNormalLength(decimal contactNormalLength) {
mContactNormalLength = contactNormalLength;
}

View File

@ -28,7 +28,7 @@
// Libraries
#include <reactphysics3d/utils/Logger.h>
#include <reactphysics3d/containers/List.h>
#include <reactphysics3d/containers/Array.h>
#include <reactphysics3d/containers/Map.h>
#include <string>
#include <iostream>
@ -445,7 +445,7 @@ class DefaultLogger : public Logger {
MemoryAllocator& mAllocator;
/// All the log destinations
List<Destination*> mDestinations;
Array<Destination*> mDestinations;
/// Map a log format to the given formatter object
Map<Format, Formatter*> mFormatters;

View File

@ -27,7 +27,7 @@
#define REACTPHYSICS3D_LOGGER_H
// Libraries
#include <reactphysics3d/containers/List.h>
#include <reactphysics3d/containers/Array.h>
#include <reactphysics3d/containers/Map.h>
#include <string>
#include <iostream>

View File

@ -34,7 +34,7 @@
#include <reactphysics3d/configuration.h>
#include <reactphysics3d/engine/Timer.h>
#include <fstream>
#include <reactphysics3d/containers/List.h>
#include <reactphysics3d/containers/Array.h>
/// ReactPhysics3D namespace
namespace reactphysics3d {
@ -401,113 +401,113 @@ class ProfileSample {
#define RP3D_PROFILE(name, profiler) ProfileSample profileSample(name, profiler)
// Return true if we are at the root of the profiler tree
inline bool ProfileNodeIterator::isRoot() {
RP3D_FORCE_INLINE bool ProfileNodeIterator::isRoot() {
return (mCurrentParentNode->getParentNode() == nullptr);
}
// Return true if we are at the end of a branch of the profiler tree
inline bool ProfileNodeIterator::isEnd() {
RP3D_FORCE_INLINE bool ProfileNodeIterator::isEnd() {
return (mCurrentChildNode == nullptr);
}
// Return the name of the current node
inline const char* ProfileNodeIterator::getCurrentName() {
RP3D_FORCE_INLINE const char* ProfileNodeIterator::getCurrentName() {
return mCurrentChildNode->getName();
}
// Return the total time of the current node
inline long double ProfileNodeIterator::getCurrentTotalTime() {
RP3D_FORCE_INLINE long double ProfileNodeIterator::getCurrentTotalTime() {
return mCurrentChildNode->getTotalTime();
}
// Return the total number of calls of the current node
inline uint ProfileNodeIterator::getCurrentNbTotalCalls() {
RP3D_FORCE_INLINE uint ProfileNodeIterator::getCurrentNbTotalCalls() {
return mCurrentChildNode->getNbTotalCalls();
}
// Return the name of the current parent node
inline const char* ProfileNodeIterator::getCurrentParentName() {
RP3D_FORCE_INLINE const char* ProfileNodeIterator::getCurrentParentName() {
return mCurrentParentNode->getName();
}
// Return the total time of the current parent node
inline long double ProfileNodeIterator::getCurrentParentTotalTime() {
RP3D_FORCE_INLINE long double ProfileNodeIterator::getCurrentParentTotalTime() {
return mCurrentParentNode->getTotalTime();
}
// Return the total number of calls of the current parent node
inline uint ProfileNodeIterator::getCurrentParentNbTotalCalls() {
RP3D_FORCE_INLINE uint ProfileNodeIterator::getCurrentParentNbTotalCalls() {
return mCurrentParentNode->getNbTotalCalls();
}
// Go to the first node
inline void ProfileNodeIterator::first() {
RP3D_FORCE_INLINE void ProfileNodeIterator::first() {
mCurrentChildNode = mCurrentParentNode->getChildNode();
}
// Go to the next node
inline void ProfileNodeIterator::next() {
RP3D_FORCE_INLINE void ProfileNodeIterator::next() {
mCurrentChildNode = mCurrentChildNode->getSiblingNode();
}
// Return a pointer to the parent node
inline ProfileNode* ProfileNode::getParentNode() {
RP3D_FORCE_INLINE ProfileNode* ProfileNode::getParentNode() {
return mParentNode;
}
// Return a pointer to a sibling node
inline ProfileNode* ProfileNode::getSiblingNode() {
RP3D_FORCE_INLINE ProfileNode* ProfileNode::getSiblingNode() {
return mSiblingNode;
}
// Return a pointer to a child node
inline ProfileNode* ProfileNode::getChildNode() {
RP3D_FORCE_INLINE ProfileNode* ProfileNode::getChildNode() {
return mChildNode;
}
// Return the name of the node
inline const char* ProfileNode::getName() {
RP3D_FORCE_INLINE const char* ProfileNode::getName() {
return mName;
}
// Return the total number of call of the corresponding block of code
inline uint ProfileNode::getNbTotalCalls() const {
RP3D_FORCE_INLINE uint ProfileNode::getNbTotalCalls() const {
return mNbTotalCalls;
}
// Return the total time spent in the block of code
inline long double ProfileNode::getTotalTime() const {
RP3D_FORCE_INLINE long double ProfileNode::getTotalTime() const {
return mTotalTime;
}
// Return the number of frames
inline uint Profiler::getNbFrames() {
RP3D_FORCE_INLINE uint Profiler::getNbFrames() {
return mFrameCounter;
}
// Return the elasped time since the start/reset of the profiling
inline long double Profiler::getElapsedTimeSinceStart() {
RP3D_FORCE_INLINE long double Profiler::getElapsedTimeSinceStart() {
long double currentTime = Timer::getCurrentSystemTime() * 1000.0L;
return currentTime - mProfilingStartTime;
}
// Increment the frame counter
inline void Profiler::incrementFrameCounter() {
RP3D_FORCE_INLINE void Profiler::incrementFrameCounter() {
mFrameCounter++;
}
// Return an iterator over the profiler tree starting at the root
inline ProfileNodeIterator* Profiler::getIterator() {
RP3D_FORCE_INLINE ProfileNodeIterator* Profiler::getIterator() {
return new ProfileNodeIterator(&mRootNode);
}
// Destroy a previously allocated iterator
inline void Profiler::destroyIterator(ProfileNodeIterator* iterator) {
RP3D_FORCE_INLINE void Profiler::destroyIterator(ProfileNodeIterator* iterator) {
delete iterator;
}
// Destroy the profiler (release the memory)
inline void Profiler::destroy() {
RP3D_FORCE_INLINE void Profiler::destroy() {
mRootNode.destroy();
}

View File

@ -89,12 +89,13 @@ Collider* CollisionBody::addCollider(CollisionShape* collisionShape, const Trans
// TODO : Maybe this method can directly returns an AABB
collisionShape->getLocalBounds(localBoundsMin, localBoundsMax);
const Transform localToWorldTransform = mWorld.mTransformComponents.getTransform(mEntity) * transform;
ColliderComponents::ColliderComponent colliderComponent(mEntity, collider,
AABB(localBoundsMin, localBoundsMax),
transform, collisionShape, 0x0001, 0xFFFF, localToWorldTransform);
Material material(mWorld.mConfig.defaultFrictionCoefficient, mWorld.mConfig.defaultBounciness);
ColliderComponents::ColliderComponent colliderComponent(mEntity, collider, AABB(localBoundsMin, localBoundsMax),
transform, collisionShape, 0x0001, 0xFFFF, localToWorldTransform, material);
bool isActive = mWorld.mCollisionBodyComponents.getIsActive(mEntity);
mWorld.mCollidersComponents.addComponent(colliderEntity, !isActive, colliderComponent);
mWorld.mCollisionBodyComponents.addColliderToBody(mEntity, colliderEntity);
// Assign the collider with the collision shape
@ -130,8 +131,8 @@ Collider* CollisionBody::addCollider(CollisionShape* collisionShape, const Trans
/**
* @return The number of colliders associated with this body
*/
uint CollisionBody::getNbColliders() const {
return static_cast<uint>(mWorld.mCollisionBodyComponents.getColliders(mEntity).size());
uint32 CollisionBody::getNbColliders() const {
return mWorld.mCollisionBodyComponents.getColliders(mEntity).size();
}
// Return a const pointer to a given collider of the body
@ -199,9 +200,9 @@ void CollisionBody::removeCollider(Collider* collider) {
void CollisionBody::removeAllColliders() {
// Look for the collider that contains the collision shape in parameter.
// Note that we need to copy the list of collider entities because we are deleting them in a loop.
const List<Entity> collidersEntities = mWorld.mCollisionBodyComponents.getColliders(mEntity);
for (uint i=0; i < collidersEntities.size(); i++) {
// Note that we need to copy the array of collider entities because we are deleting them in a loop.
const Array<Entity> collidersEntities = mWorld.mCollisionBodyComponents.getColliders(mEntity);
for (uint32 i=0; i < collidersEntities.size(); i++) {
removeCollider(mWorld.mCollidersComponents.getCollider(collidersEntities[i]));
}
@ -221,8 +222,9 @@ const Transform& CollisionBody::getTransform() const {
void CollisionBody::updateBroadPhaseState(decimal timeStep) const {
// For all the colliders of the body
const List<Entity>& colliderEntities = mWorld.mCollisionBodyComponents.getColliders(mEntity);
for (uint i=0; i < colliderEntities.size(); i++) {
const Array<Entity>& colliderEntities = mWorld.mCollisionBodyComponents.getColliders(mEntity);
const uint32 nbColliderEntities = colliderEntities.size();
for (uint32 i=0; i < nbColliderEntities; i++) {
// Update the local-to-world transform of the collider
mWorld.mCollidersComponents.setLocalToWorldTransform(colliderEntities[i],
@ -251,8 +253,8 @@ void CollisionBody::setIsActive(bool isActive) {
const Transform& transform = mWorld.mTransformComponents.getTransform(mEntity);
// For each collider of the body
const List<Entity>& colliderEntities = mWorld.mCollisionBodyComponents.getColliders(mEntity);
for (uint i=0; i < colliderEntities.size(); i++) {
const Array<Entity>& colliderEntities = mWorld.mCollisionBodyComponents.getColliders(mEntity);
for (uint32 i=0; i < colliderEntities.size(); i++) {
Collider* collider = mWorld.mCollidersComponents.getCollider(colliderEntities[i]);
@ -267,8 +269,8 @@ void CollisionBody::setIsActive(bool isActive) {
else { // If we have to deactivate the body
// For each collider of the body
const List<Entity>& colliderEntities = mWorld.mCollisionBodyComponents.getColliders(mEntity);
for (uint i=0; i < colliderEntities.size(); i++) {
const Array<Entity>& colliderEntities = mWorld.mCollisionBodyComponents.getColliders(mEntity);
for (uint32 i=0; i < colliderEntities.size(); i++) {
Collider* collider = mWorld.mCollidersComponents.getCollider(colliderEntities[i]);
@ -290,8 +292,9 @@ void CollisionBody::setIsActive(bool isActive) {
void CollisionBody::askForBroadPhaseCollisionCheck() const {
// For all the colliders of the body
const List<Entity>& colliderEntities = mWorld.mCollisionBodyComponents.getColliders(mEntity);
for (uint i=0; i < colliderEntities.size(); i++) {
const Array<Entity>& colliderEntities = mWorld.mCollisionBodyComponents.getColliders(mEntity);
const uint32 nbColliderEntities = colliderEntities.size();
for (uint32 i=0; i < nbColliderEntities; i++) {
Collider* collider = mWorld.mCollidersComponents.getCollider(colliderEntities[i]);
@ -308,8 +311,8 @@ void CollisionBody::askForBroadPhaseCollisionCheck() const {
bool CollisionBody::testPointInside(const Vector3& worldPoint) const {
// For each collider of the body
const List<Entity>& colliderEntities = mWorld.mCollisionBodyComponents.getColliders(mEntity);
for (uint i=0; i < colliderEntities.size(); i++) {
const Array<Entity>& colliderEntities = mWorld.mCollisionBodyComponents.getColliders(mEntity);
for (uint32 i=0; i < colliderEntities.size(); i++) {
Collider* collider = mWorld.mCollidersComponents.getCollider(colliderEntities[i]);
@ -337,8 +340,9 @@ bool CollisionBody::raycast(const Ray& ray, RaycastInfo& raycastInfo) {
Ray rayTemp(ray);
// For each collider of the body
const List<Entity>& colliderEntities = mWorld.mCollisionBodyComponents.getColliders(mEntity);
for (uint i=0; i < colliderEntities.size(); i++) {
const Array<Entity>& colliderEntities = mWorld.mCollisionBodyComponents.getColliders(mEntity);
const uint32 nbColliderEntities = colliderEntities.size();
for (uint32 i=0; i < nbColliderEntities; i++) {
Collider* collider = mWorld.mCollidersComponents.getCollider(colliderEntities[i]);
@ -360,7 +364,7 @@ AABB CollisionBody::getAABB() const {
AABB bodyAABB;
const List<Entity>& colliderEntities = mWorld.mCollisionBodyComponents.getColliders(mEntity);
const Array<Entity>& colliderEntities = mWorld.mCollisionBodyComponents.getColliders(mEntity);
if (colliderEntities.size() == 0) return bodyAABB;
const Transform& transform = mWorld.mTransformComponents.getTransform(mEntity);
@ -369,7 +373,8 @@ AABB CollisionBody::getAABB() const {
collider->getCollisionShape()->computeAABB(bodyAABB, transform * collider->getLocalToBodyTransform());
// For each collider of the body
for (uint i=1; i < colliderEntities.size(); i++) {
const uint32 nbColliderEntities = colliderEntities.size();
for (uint32 i=1; i < nbColliderEntities; i++) {
Collider* collider = mWorld.mCollidersComponents.getCollider(colliderEntities[i]);

Some files were not shown because too many files have changed in this diff Show More