Add force inline macro
This commit is contained in:
parent
92884e2486
commit
fd09fcf660
include/reactphysics3d
body
collision
Collider.hCollisionCallback.hHalfEdgeStructure.hOverlapCallback.hPolygonVertexArray.hPolyhedronMesh.hTriangleMesh.hTriangleVertexArray.h
broadphase
narrowphase
shapes
components
BallAndSocketJointComponents.hColliderComponents.hCollisionBodyComponents.hComponents.hFixedJointComponents.hHingeJointComponents.hJointComponents.hRigidBodyComponents.hSliderJointComponents.hTransformComponents.h
configuration.hconstraint
containers
engine
mathematics
memory
systems
BroadPhaseSystem.hCollisionDetectionSystem.hConstraintSolverSystem.hContactSolverSystem.hDynamicsSystem.hSolveBallAndSocketJointSystem.hSolveFixedJointSystem.hSolveHingeJointSystem.hSolveSliderJointSystem.h
utils
src
|
@ -178,7 +178,7 @@ class CollisionBody {
|
||||||
* @param worldAABB The AABB (in world-space coordinates) that will be used to test overlap
|
* @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
|
* @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());
|
return worldAABB.testCollision(getAABB());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -186,14 +186,14 @@ inline bool CollisionBody::testAABBOverlap(const AABB& worldAABB) const {
|
||||||
/**
|
/**
|
||||||
* @return The entity of the body
|
* @return The entity of the body
|
||||||
*/
|
*/
|
||||||
inline Entity CollisionBody::getEntity() const {
|
RP3D_FORCE_INLINE Entity CollisionBody::getEntity() const {
|
||||||
return mEntity;
|
return mEntity;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef IS_RP3D_PROFILING_ENABLED
|
#ifdef IS_RP3D_PROFILING_ENABLED
|
||||||
|
|
||||||
// Set the profiler
|
// Set the profiler
|
||||||
inline void CollisionBody::setProfiler(Profiler* profiler) {
|
RP3D_FORCE_INLINE void CollisionBody::setProfiler(Profiler* profiler) {
|
||||||
mProfiler = profiler;
|
mProfiler = profiler;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -188,7 +188,7 @@ class Collider {
|
||||||
/**
|
/**
|
||||||
* @return The entity of the collider
|
* @return The entity of the collider
|
||||||
*/
|
*/
|
||||||
inline Entity Collider::getEntity() const {
|
RP3D_FORCE_INLINE Entity Collider::getEntity() const {
|
||||||
return mEntity;
|
return mEntity;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -196,7 +196,7 @@ inline Entity Collider::getEntity() const {
|
||||||
/**
|
/**
|
||||||
* @return Pointer to the parent body
|
* @return Pointer to the parent body
|
||||||
*/
|
*/
|
||||||
inline CollisionBody* Collider::getBody() const {
|
RP3D_FORCE_INLINE CollisionBody* Collider::getBody() const {
|
||||||
return mBody;
|
return mBody;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -204,7 +204,7 @@ inline CollisionBody* Collider::getBody() const {
|
||||||
/**
|
/**
|
||||||
* @return A pointer to the user data stored into the collider
|
* @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;
|
return mUserData;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -212,7 +212,7 @@ inline void* Collider::getUserData() const {
|
||||||
/**
|
/**
|
||||||
* @param userData Pointer to the user data you want to store within the collider
|
* @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;
|
mUserData = userData;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -221,7 +221,7 @@ inline void Collider::setUserData(void* userData) {
|
||||||
* @param worldAABB The AABB (in world-space coordinates) that will be used to test overlap
|
* @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
|
* @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 worldAABB.testCollision(getWorldAABB());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -229,7 +229,7 @@ inline bool Collider::testAABBOverlap(const AABB& worldAABB) const {
|
||||||
/**
|
/**
|
||||||
* @return A reference to the material of the body
|
* @return A reference to the material of the body
|
||||||
*/
|
*/
|
||||||
inline Material& Collider::getMaterial() {
|
RP3D_FORCE_INLINE Material& Collider::getMaterial() {
|
||||||
return mMaterial;
|
return mMaterial;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -296,7 +296,7 @@ class CollisionCallback {
|
||||||
/**
|
/**
|
||||||
* @return The number of contact pairs
|
* @return The number of contact pairs
|
||||||
*/
|
*/
|
||||||
inline uint CollisionCallback::CallbackData::getNbContactPairs() const {
|
RP3D_FORCE_INLINE uint CollisionCallback::CallbackData::getNbContactPairs() const {
|
||||||
return mContactPairsIndices.size() + mLostContactPairsIndices.size();
|
return mContactPairsIndices.size() + mLostContactPairsIndices.size();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -304,7 +304,7 @@ inline uint CollisionCallback::CallbackData::getNbContactPairs() const {
|
||||||
/**
|
/**
|
||||||
* @return The number of contact points
|
* @return The number of contact points
|
||||||
*/
|
*/
|
||||||
inline uint CollisionCallback::ContactPair::getNbContactPoints() const {
|
RP3D_FORCE_INLINE uint CollisionCallback::ContactPair::getNbContactPoints() const {
|
||||||
return mContactPair.nbToTalContactPoints;
|
return mContactPair.nbToTalContactPoints;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -312,7 +312,7 @@ inline uint CollisionCallback::ContactPair::getNbContactPoints() const {
|
||||||
/**
|
/**
|
||||||
* @return The penetration depth (larger than zero)
|
* @return The penetration depth (larger than zero)
|
||||||
*/
|
*/
|
||||||
inline decimal CollisionCallback::ContactPoint::getPenetrationDepth() const {
|
RP3D_FORCE_INLINE decimal CollisionCallback::ContactPoint::getPenetrationDepth() const {
|
||||||
return mContactPoint.getPenetrationDepth();
|
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)
|
* @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();
|
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
|
* @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();
|
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
|
* @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();
|
return mContactPoint.getLocalPointOnShape2();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -129,7 +129,7 @@ class HalfEdgeStructure {
|
||||||
/**
|
/**
|
||||||
* @param vertexPointIndex Index of the vertex in the vertex data array
|
* @param vertexPointIndex Index of the vertex in the vertex data array
|
||||||
*/
|
*/
|
||||||
inline uint HalfEdgeStructure::addVertex(uint vertexPointIndex) {
|
RP3D_FORCE_INLINE uint HalfEdgeStructure::addVertex(uint vertexPointIndex) {
|
||||||
Vertex vertex(vertexPointIndex);
|
Vertex vertex(vertexPointIndex);
|
||||||
mVertices.add(vertex);
|
mVertices.add(vertex);
|
||||||
return mVertices.size() - 1;
|
return mVertices.size() - 1;
|
||||||
|
@ -140,7 +140,7 @@ inline uint HalfEdgeStructure::addVertex(uint vertexPointIndex) {
|
||||||
* @param faceVertices List of the vertices in a face (ordered in CCW order as seen from outside
|
* @param faceVertices List of the vertices in a face (ordered in CCW order as seen from outside
|
||||||
* the polyhedron
|
* the polyhedron
|
||||||
*/
|
*/
|
||||||
inline void HalfEdgeStructure::addFace(List<uint> faceVertices) {
|
RP3D_FORCE_INLINE void HalfEdgeStructure::addFace(List<uint> faceVertices) {
|
||||||
|
|
||||||
// Create a new face
|
// Create a new face
|
||||||
Face face(faceVertices);
|
Face face(faceVertices);
|
||||||
|
@ -151,7 +151,7 @@ inline void HalfEdgeStructure::addFace(List<uint> faceVertices) {
|
||||||
/**
|
/**
|
||||||
* @return The number of faces in the polyhedron
|
* @return The number of faces in the polyhedron
|
||||||
*/
|
*/
|
||||||
inline uint HalfEdgeStructure::getNbFaces() const {
|
RP3D_FORCE_INLINE uint HalfEdgeStructure::getNbFaces() const {
|
||||||
return static_cast<uint>(mFaces.size());
|
return static_cast<uint>(mFaces.size());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -159,7 +159,7 @@ inline uint HalfEdgeStructure::getNbFaces() const {
|
||||||
/**
|
/**
|
||||||
* @return The number of edges in the polyhedron
|
* @return The number of edges in the polyhedron
|
||||||
*/
|
*/
|
||||||
inline uint HalfEdgeStructure::getNbHalfEdges() const {
|
RP3D_FORCE_INLINE uint HalfEdgeStructure::getNbHalfEdges() const {
|
||||||
return static_cast<uint>(mEdges.size());
|
return static_cast<uint>(mEdges.size());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -167,7 +167,7 @@ inline uint HalfEdgeStructure::getNbHalfEdges() const {
|
||||||
/**
|
/**
|
||||||
* @return The number of vertices in the polyhedron
|
* @return The number of vertices in the polyhedron
|
||||||
*/
|
*/
|
||||||
inline uint HalfEdgeStructure::getNbVertices() const {
|
RP3D_FORCE_INLINE uint HalfEdgeStructure::getNbVertices() const {
|
||||||
return static_cast<uint>(mVertices.size());
|
return static_cast<uint>(mVertices.size());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -175,7 +175,7 @@ inline uint HalfEdgeStructure::getNbVertices() const {
|
||||||
/**
|
/**
|
||||||
* @return A given face of the polyhedron
|
* @return A given face of the polyhedron
|
||||||
*/
|
*/
|
||||||
inline const HalfEdgeStructure::Face& HalfEdgeStructure::getFace(uint index) const {
|
RP3D_FORCE_INLINE const HalfEdgeStructure::Face& HalfEdgeStructure::getFace(uint index) const {
|
||||||
assert(index < mFaces.size());
|
assert(index < mFaces.size());
|
||||||
return mFaces[index];
|
return mFaces[index];
|
||||||
}
|
}
|
||||||
|
@ -184,7 +184,7 @@ inline const HalfEdgeStructure::Face& HalfEdgeStructure::getFace(uint index) con
|
||||||
/**
|
/**
|
||||||
* @return A given edge of the polyhedron
|
* @return A given edge of the polyhedron
|
||||||
*/
|
*/
|
||||||
inline const HalfEdgeStructure::Edge& HalfEdgeStructure::getHalfEdge(uint index) const {
|
RP3D_FORCE_INLINE const HalfEdgeStructure::Edge& HalfEdgeStructure::getHalfEdge(uint index) const {
|
||||||
assert(index < mEdges.size());
|
assert(index < mEdges.size());
|
||||||
return mEdges[index];
|
return mEdges[index];
|
||||||
}
|
}
|
||||||
|
@ -193,7 +193,7 @@ inline const HalfEdgeStructure::Edge& HalfEdgeStructure::getHalfEdge(uint index)
|
||||||
/**
|
/**
|
||||||
* @return A given vertex of the polyhedron
|
* @return A given vertex of the polyhedron
|
||||||
*/
|
*/
|
||||||
inline const HalfEdgeStructure::Vertex& HalfEdgeStructure::getVertex(uint index) const {
|
RP3D_FORCE_INLINE const HalfEdgeStructure::Vertex& HalfEdgeStructure::getVertex(uint index) const {
|
||||||
assert(index < mVertices.size());
|
assert(index < mVertices.size());
|
||||||
return mVertices[index];
|
return mVertices[index];
|
||||||
}
|
}
|
||||||
|
|
|
@ -185,7 +185,7 @@ class OverlapCallback {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return the number of overlapping pairs of bodies
|
// Return the number of overlapping pairs of bodies
|
||||||
inline uint OverlapCallback::CallbackData::getNbOverlappingPairs() const {
|
RP3D_FORCE_INLINE uint OverlapCallback::CallbackData::getNbOverlappingPairs() const {
|
||||||
return mContactPairsIndices.size() + mLostContactPairsIndices.size();
|
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()
|
/// 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
|
/// 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.
|
/// 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(uint index) const {
|
||||||
|
|
||||||
assert(index < getNbOverlappingPairs());
|
assert(index < getNbOverlappingPairs());
|
||||||
|
|
||||||
|
|
|
@ -140,7 +140,7 @@ class PolygonVertexArray {
|
||||||
/**
|
/**
|
||||||
* @return The data type of the vertices in the array
|
* @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;
|
return mVertexDataType;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -148,7 +148,7 @@ inline PolygonVertexArray::VertexDataType PolygonVertexArray::getVertexDataType(
|
||||||
/**
|
/**
|
||||||
* @return The data type of the indices in the array
|
* @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;
|
return mIndexDataType;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -156,7 +156,7 @@ inline PolygonVertexArray::IndexDataType PolygonVertexArray::getIndexDataType()
|
||||||
/**
|
/**
|
||||||
* @return The number of vertices in the array
|
* @return The number of vertices in the array
|
||||||
*/
|
*/
|
||||||
inline uint PolygonVertexArray::getNbVertices() const {
|
RP3D_FORCE_INLINE uint PolygonVertexArray::getNbVertices() const {
|
||||||
return mNbVertices;
|
return mNbVertices;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -164,7 +164,7 @@ inline uint PolygonVertexArray::getNbVertices() const {
|
||||||
/**
|
/**
|
||||||
* @return The number of faces in the array
|
* @return The number of faces in the array
|
||||||
*/
|
*/
|
||||||
inline uint PolygonVertexArray::getNbFaces() const {
|
RP3D_FORCE_INLINE uint PolygonVertexArray::getNbFaces() const {
|
||||||
return mNbFaces;
|
return mNbFaces;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -172,7 +172,7 @@ inline uint PolygonVertexArray::getNbFaces() const {
|
||||||
/**
|
/**
|
||||||
* @return The number of bytes between two vertices
|
* @return The number of bytes between two vertices
|
||||||
*/
|
*/
|
||||||
inline int PolygonVertexArray::getVerticesStride() const {
|
RP3D_FORCE_INLINE int PolygonVertexArray::getVerticesStride() const {
|
||||||
return mVerticesStride;
|
return mVerticesStride;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -180,7 +180,7 @@ inline int PolygonVertexArray::getVerticesStride() const {
|
||||||
/**
|
/**
|
||||||
* @return The number of bytes between two consecutive face indices
|
* @return The number of bytes between two consecutive face indices
|
||||||
*/
|
*/
|
||||||
inline int PolygonVertexArray::getIndicesStride() const {
|
RP3D_FORCE_INLINE int PolygonVertexArray::getIndicesStride() const {
|
||||||
return mIndicesStride;
|
return mIndicesStride;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -189,7 +189,7 @@ inline int PolygonVertexArray::getIndicesStride() const {
|
||||||
* @param faceIndex Index of a given face
|
* @param faceIndex Index of a given face
|
||||||
* @return A polygon 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);
|
assert(faceIndex < mNbFaces);
|
||||||
return &mPolygonFacesStart[faceIndex];
|
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
|
* @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;
|
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
|
* @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;
|
return mIndicesStart;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -117,7 +117,7 @@ class PolyhedronMesh {
|
||||||
/**
|
/**
|
||||||
* @return The number of vertices in the mesh
|
* @return The number of vertices in the mesh
|
||||||
*/
|
*/
|
||||||
inline uint PolyhedronMesh::getNbVertices() const {
|
RP3D_FORCE_INLINE uint PolyhedronMesh::getNbVertices() const {
|
||||||
return mHalfEdgeStructure.getNbVertices();
|
return mHalfEdgeStructure.getNbVertices();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -125,7 +125,7 @@ inline uint PolyhedronMesh::getNbVertices() const {
|
||||||
/**
|
/**
|
||||||
* @return The number of faces in the mesh
|
* @return The number of faces in the mesh
|
||||||
*/
|
*/
|
||||||
inline uint PolyhedronMesh::getNbFaces() const {
|
RP3D_FORCE_INLINE uint PolyhedronMesh::getNbFaces() const {
|
||||||
return mHalfEdgeStructure.getNbFaces();
|
return mHalfEdgeStructure.getNbFaces();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -134,7 +134,7 @@ inline uint PolyhedronMesh::getNbFaces() const {
|
||||||
* @param faceIndex The index of a given face of the mesh
|
* @param faceIndex The index of a given face of the mesh
|
||||||
* @return The normal vector 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());
|
assert(faceIndex < mHalfEdgeStructure.getNbFaces());
|
||||||
return mFacesNormals[faceIndex];
|
return mFacesNormals[faceIndex];
|
||||||
}
|
}
|
||||||
|
@ -143,7 +143,7 @@ inline Vector3 PolyhedronMesh::getFaceNormal(uint faceIndex) const {
|
||||||
/**
|
/**
|
||||||
* @return The Half-Edge structure of the mesh
|
* @return The Half-Edge structure of the mesh
|
||||||
*/
|
*/
|
||||||
inline const HalfEdgeStructure& PolyhedronMesh::getHalfEdgeStructure() const {
|
RP3D_FORCE_INLINE const HalfEdgeStructure& PolyhedronMesh::getHalfEdgeStructure() const {
|
||||||
return mHalfEdgeStructure;
|
return mHalfEdgeStructure;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -151,7 +151,7 @@ inline const HalfEdgeStructure& PolyhedronMesh::getHalfEdgeStructure() const {
|
||||||
/**
|
/**
|
||||||
* @return The centroid of the mesh
|
* @return The centroid of the mesh
|
||||||
*/
|
*/
|
||||||
inline Vector3 PolyhedronMesh::getCentroid() const {
|
RP3D_FORCE_INLINE Vector3 PolyhedronMesh::getCentroid() const {
|
||||||
return mCentroid;
|
return mCentroid;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -78,7 +78,7 @@ class TriangleMesh {
|
||||||
/**
|
/**
|
||||||
* @param triangleVertexArray Pointer to the TriangleVertexArray to add into the mesh
|
* @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 );
|
mTriangleArrays.add(triangleVertexArray );
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -87,7 +87,7 @@ inline void TriangleMesh::addSubpart(TriangleVertexArray* triangleVertexArray) {
|
||||||
* @param indexSubpart The index of the sub-part of the mesh
|
* @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
|
* @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(uint indexSubpart) const {
|
||||||
assert(indexSubpart < mTriangleArrays.size());
|
assert(indexSubpart < mTriangleArrays.size());
|
||||||
return mTriangleArrays[indexSubpart];
|
return mTriangleArrays[indexSubpart];
|
||||||
}
|
}
|
||||||
|
@ -96,7 +96,7 @@ inline TriangleVertexArray* TriangleMesh::getSubpart(uint indexSubpart) const {
|
||||||
/**
|
/**
|
||||||
* @return The number of sub-parts of the mesh
|
* @return The number of sub-parts of the mesh
|
||||||
*/
|
*/
|
||||||
inline uint TriangleMesh::getNbSubparts() const {
|
RP3D_FORCE_INLINE uint TriangleMesh::getNbSubparts() const {
|
||||||
return mTriangleArrays.size();
|
return mTriangleArrays.size();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -182,7 +182,7 @@ class TriangleVertexArray {
|
||||||
/**
|
/**
|
||||||
* @return The data type of the vertices in the array
|
* @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;
|
return mVertexDataType;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -190,7 +190,7 @@ inline TriangleVertexArray::VertexDataType TriangleVertexArray::getVertexDataTyp
|
||||||
/**
|
/**
|
||||||
* @return The data type of the normals in the array
|
* @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;
|
return mVertexNormaldDataType;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -198,7 +198,7 @@ inline TriangleVertexArray::NormalDataType TriangleVertexArray::getVertexNormalD
|
||||||
/**
|
/**
|
||||||
* @return The data type of the face indices in the array
|
* @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;
|
return mIndexDataType;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -206,7 +206,7 @@ inline TriangleVertexArray::IndexDataType TriangleVertexArray::getIndexDataType(
|
||||||
/**
|
/**
|
||||||
* @return The number of vertices in the array
|
* @return The number of vertices in the array
|
||||||
*/
|
*/
|
||||||
inline uint TriangleVertexArray::getNbVertices() const {
|
RP3D_FORCE_INLINE uint TriangleVertexArray::getNbVertices() const {
|
||||||
return mNbVertices;
|
return mNbVertices;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -214,7 +214,7 @@ inline uint TriangleVertexArray::getNbVertices() const {
|
||||||
/**
|
/**
|
||||||
* @return The number of triangles in the array
|
* @return The number of triangles in the array
|
||||||
*/
|
*/
|
||||||
inline uint TriangleVertexArray::getNbTriangles() const {
|
RP3D_FORCE_INLINE uint TriangleVertexArray::getNbTriangles() const {
|
||||||
return mNbTriangles;
|
return mNbTriangles;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -222,7 +222,7 @@ inline uint TriangleVertexArray::getNbTriangles() const {
|
||||||
/**
|
/**
|
||||||
* @return The number of bytes separating two consecutive vertices in the array
|
* @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;
|
return mVerticesStride;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -230,7 +230,7 @@ inline uint TriangleVertexArray::getVerticesStride() const {
|
||||||
/**
|
/**
|
||||||
* @return The number of bytes separating two consecutive normals in the array
|
* @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;
|
return mVerticesNormalsStride;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -238,7 +238,7 @@ inline uint TriangleVertexArray::getVerticesNormalsStride() const {
|
||||||
/**
|
/**
|
||||||
* @return The number of bytes separating two consecutive face indices in the array
|
* @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;
|
return mIndicesStride;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -246,7 +246,7 @@ inline uint TriangleVertexArray::getIndicesStride() const {
|
||||||
/**
|
/**
|
||||||
* @return A pointer to the start of the vertices data in the array
|
* @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;
|
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
|
* @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;
|
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
|
* @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;
|
return mIndicesStart;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -264,38 +264,38 @@ class DynamicAABBTree {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return true if the node is a leaf of the tree
|
// 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 (height == 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the fat AABB corresponding to a given node ID
|
// 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);
|
assert(nodeID >= 0 && nodeID < mNbAllocatedNodes);
|
||||||
return mNodes[nodeID].aabb;
|
return mNodes[nodeID].aabb;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the pointer to the data array of a given leaf node of the tree
|
// 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(nodeID >= 0 && nodeID < mNbAllocatedNodes);
|
||||||
assert(mNodes[nodeID].isLeaf());
|
assert(mNodes[nodeID].isLeaf());
|
||||||
return mNodes[nodeID].dataInt;
|
return mNodes[nodeID].dataInt;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the pointer to the data pointer of a given leaf node of the tree
|
// 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(nodeID >= 0 && nodeID < mNbAllocatedNodes);
|
||||||
assert(mNodes[nodeID].isLeaf());
|
assert(mNodes[nodeID].isLeaf());
|
||||||
return mNodes[nodeID].dataPointer;
|
return mNodes[nodeID].dataPointer;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the root AABB of the tree
|
// Return the root AABB of the tree
|
||||||
inline AABB DynamicAABBTree::getRootAABB() const {
|
RP3D_FORCE_INLINE AABB DynamicAABBTree::getRootAABB() const {
|
||||||
return getFatAABB(mRootNodeID);
|
return getFatAABB(mRootNodeID);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Add an object into the tree. This method creates a new leaf node in the tree and
|
// Add an object into the tree. This method creates a new leaf node in the tree and
|
||||||
// returns the ID of the corresponding node.
|
// 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);
|
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
|
// Add an object into the tree. This method creates a new leaf node in the tree and
|
||||||
// returns the ID of the corresponding node.
|
// 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);
|
int32 nodeId = addObjectInternal(aabb);
|
||||||
|
|
||||||
|
@ -319,7 +319,7 @@ inline int32 DynamicAABBTree::addObject(const AABB& aabb, void* data) {
|
||||||
#ifdef IS_RP3D_PROFILING_ENABLED
|
#ifdef IS_RP3D_PROFILING_ENABLED
|
||||||
|
|
||||||
// Set the profiler
|
// Set the profiler
|
||||||
inline void DynamicAABBTree::setProfiler(Profiler* profiler) {
|
RP3D_FORCE_INLINE void DynamicAABBTree::setProfiler(Profiler* profiler) {
|
||||||
mProfiler = profiler;
|
mProfiler = profiler;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -173,39 +173,39 @@ class CollisionDispatch {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Get the Sphere vs Sphere narrow-phase collision detection algorithm
|
// Get the Sphere vs Sphere narrow-phase collision detection algorithm
|
||||||
inline SphereVsSphereAlgorithm* CollisionDispatch::getSphereVsSphereAlgorithm() {
|
RP3D_FORCE_INLINE SphereVsSphereAlgorithm* CollisionDispatch::getSphereVsSphereAlgorithm() {
|
||||||
return mSphereVsSphereAlgorithm;
|
return mSphereVsSphereAlgorithm;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get the Sphere vs Capsule narrow-phase collision detection algorithm
|
// Get the Sphere vs Capsule narrow-phase collision detection algorithm
|
||||||
inline SphereVsCapsuleAlgorithm* CollisionDispatch::getSphereVsCapsuleAlgorithm() {
|
RP3D_FORCE_INLINE SphereVsCapsuleAlgorithm* CollisionDispatch::getSphereVsCapsuleAlgorithm() {
|
||||||
return mSphereVsCapsuleAlgorithm;
|
return mSphereVsCapsuleAlgorithm;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get the Capsule vs Capsule narrow-phase collision detection algorithm
|
// Get the Capsule vs Capsule narrow-phase collision detection algorithm
|
||||||
inline CapsuleVsCapsuleAlgorithm* CollisionDispatch::getCapsuleVsCapsuleAlgorithm() {
|
RP3D_FORCE_INLINE CapsuleVsCapsuleAlgorithm* CollisionDispatch::getCapsuleVsCapsuleAlgorithm() {
|
||||||
return mCapsuleVsCapsuleAlgorithm;
|
return mCapsuleVsCapsuleAlgorithm;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get the Sphere vs Convex Polyhedron narrow-phase collision detection algorithm
|
// Get the Sphere vs Convex Polyhedron narrow-phase collision detection algorithm
|
||||||
inline SphereVsConvexPolyhedronAlgorithm* CollisionDispatch::getSphereVsConvexPolyhedronAlgorithm() {
|
RP3D_FORCE_INLINE SphereVsConvexPolyhedronAlgorithm* CollisionDispatch::getSphereVsConvexPolyhedronAlgorithm() {
|
||||||
return mSphereVsConvexPolyhedronAlgorithm;
|
return mSphereVsConvexPolyhedronAlgorithm;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get the Capsule vs Convex Polyhedron narrow-phase collision detection algorithm
|
// Get the Capsule vs Convex Polyhedron narrow-phase collision detection algorithm
|
||||||
inline CapsuleVsConvexPolyhedronAlgorithm* CollisionDispatch::getCapsuleVsConvexPolyhedronAlgorithm() {
|
RP3D_FORCE_INLINE CapsuleVsConvexPolyhedronAlgorithm* CollisionDispatch::getCapsuleVsConvexPolyhedronAlgorithm() {
|
||||||
return mCapsuleVsConvexPolyhedronAlgorithm;
|
return mCapsuleVsConvexPolyhedronAlgorithm;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get the Convex Polyhedron vs Convex Polyhedron narrow-phase collision detection algorithm
|
// Get the Convex Polyhedron vs Convex Polyhedron narrow-phase collision detection algorithm
|
||||||
inline ConvexPolyhedronVsConvexPolyhedronAlgorithm* CollisionDispatch::getConvexPolyhedronVsConvexPolyhedronAlgorithm() {
|
RP3D_FORCE_INLINE ConvexPolyhedronVsConvexPolyhedronAlgorithm* CollisionDispatch::getConvexPolyhedronVsConvexPolyhedronAlgorithm() {
|
||||||
return mConvexPolyhedronVsConvexPolyhedronAlgorithm;
|
return mConvexPolyhedronVsConvexPolyhedronAlgorithm;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef IS_RP3D_PROFILING_ENABLED
|
#ifdef IS_RP3D_PROFILING_ENABLED
|
||||||
|
|
||||||
// Set the profiler
|
// Set the profiler
|
||||||
inline void CollisionDispatch::setProfiler(Profiler* profiler) {
|
RP3D_FORCE_INLINE void CollisionDispatch::setProfiler(Profiler* profiler) {
|
||||||
|
|
||||||
mProfiler = profiler;
|
mProfiler = profiler;
|
||||||
mSphereVsSphereAlgorithm->setProfiler(profiler);
|
mSphereVsSphereAlgorithm->setProfiler(profiler);
|
||||||
|
|
|
@ -112,7 +112,7 @@ class GJKAlgorithm {
|
||||||
#ifdef IS_RP3D_PROFILING_ENABLED
|
#ifdef IS_RP3D_PROFILING_ENABLED
|
||||||
|
|
||||||
// Set the profiler
|
// Set the profiler
|
||||||
inline void GJKAlgorithm::setProfiler(Profiler* profiler) {
|
RP3D_FORCE_INLINE void GJKAlgorithm::setProfiler(Profiler* profiler) {
|
||||||
mProfiler = profiler;
|
mProfiler = profiler;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -171,17 +171,17 @@ class VoronoiSimplex {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return true if the simplex contains 4 points
|
// Return true if the simplex contains 4 points
|
||||||
inline bool VoronoiSimplex::isFull() const {
|
RP3D_FORCE_INLINE bool VoronoiSimplex::isFull() const {
|
||||||
return mNbPoints == 4;
|
return mNbPoints == 4;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the simple is empty
|
// Return true if the simple is empty
|
||||||
inline bool VoronoiSimplex::isEmpty() const {
|
RP3D_FORCE_INLINE bool VoronoiSimplex::isEmpty() const {
|
||||||
return mNbPoints == 0;
|
return mNbPoints == 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the barycentric coordinates of the closest point
|
// 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[0] = a;
|
||||||
mBarycentricCoords[1] = b;
|
mBarycentricCoords[1] = b;
|
||||||
mBarycentricCoords[2] = c;
|
mBarycentricCoords[2] = c;
|
||||||
|
@ -189,7 +189,7 @@ inline void VoronoiSimplex::setBarycentricCoords(decimal a, decimal b, decimal c
|
||||||
}
|
}
|
||||||
|
|
||||||
// Compute the closest point "v" to the origin of the current simplex.
|
// 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();
|
bool isValid = recomputeClosestPoint();
|
||||||
v = mClosestPoint;
|
v = mClosestPoint;
|
||||||
|
@ -197,7 +197,7 @@ inline bool VoronoiSimplex::computeClosestPoint(Vector3& v) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the
|
// 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) &&
|
return mBarycentricCoords[0] >= decimal(0.0) && mBarycentricCoords[1] >= decimal(0.0) &&
|
||||||
mBarycentricCoords[2] >= decimal(0.0) && mBarycentricCoords[3] >= decimal(0.0);
|
mBarycentricCoords[2] >= decimal(0.0) && mBarycentricCoords[3] >= decimal(0.0);
|
||||||
}
|
}
|
||||||
|
|
|
@ -106,7 +106,7 @@ class NarrowPhaseAlgorithm {
|
||||||
#ifdef IS_RP3D_PROFILING_ENABLED
|
#ifdef IS_RP3D_PROFILING_ENABLED
|
||||||
|
|
||||||
// Set the profiler
|
// Set the profiler
|
||||||
inline void NarrowPhaseAlgorithm::setProfiler(Profiler* profiler) {
|
RP3D_FORCE_INLINE void NarrowPhaseAlgorithm::setProfiler(Profiler* profiler) {
|
||||||
mProfiler = profiler;
|
mProfiler = profiler;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -29,6 +29,7 @@
|
||||||
// Libraries
|
// Libraries
|
||||||
#include <reactphysics3d/engine/OverlappingPairs.h>
|
#include <reactphysics3d/engine/OverlappingPairs.h>
|
||||||
#include <reactphysics3d/collision/ContactPointInfo.h>
|
#include <reactphysics3d/collision/ContactPointInfo.h>
|
||||||
|
#include <reactphysics3d/configuration.h>
|
||||||
|
|
||||||
/// Namespace ReactPhysics3D
|
/// Namespace ReactPhysics3D
|
||||||
namespace reactphysics3d {
|
namespace reactphysics3d {
|
||||||
|
@ -145,10 +146,46 @@ struct NarrowPhaseInfoBatch {
|
||||||
};
|
};
|
||||||
|
|
||||||
/// Return the number of objects in the batch
|
/// Return the number of objects in the batch
|
||||||
inline uint NarrowPhaseInfoBatch::getNbObjects() const {
|
RP3D_FORCE_INLINE uint NarrowPhaseInfoBatch::getNbObjects() const {
|
||||||
return narrowPhaseInfos.size();
|
return narrowPhaseInfos.size();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Add shapes to be tested during narrow-phase collision detection into the batch
|
||||||
|
RP3D_FORCE_INLINE void NarrowPhaseInfoBatch::addNarrowPhaseInfo(uint64 pairId, uint64 pairIndex, Entity collider1, Entity collider2, CollisionShape* shape1,
|
||||||
|
CollisionShape* shape2, const Transform& shape1Transform, const Transform& shape2Transform,
|
||||||
|
bool needToReportContacts, MemoryAllocator& shapeAllocator) {
|
||||||
|
|
||||||
|
// Add a collision info for the two collision shapes into the overlapping pair (if not present yet)
|
||||||
|
// TODO OPTI : Can we better manage this
|
||||||
|
LastFrameCollisionInfo* lastFrameInfo = mOverlappingPairs.addLastFrameInfoIfNecessary(pairIndex, shape1->getId(), shape2->getId());
|
||||||
|
|
||||||
|
// 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;
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -29,6 +29,7 @@
|
||||||
// Libraries
|
// Libraries
|
||||||
#include <reactphysics3d/containers/List.h>
|
#include <reactphysics3d/containers/List.h>
|
||||||
#include <reactphysics3d/collision/narrowphase/NarrowPhaseInfoBatch.h>
|
#include <reactphysics3d/collision/narrowphase/NarrowPhaseInfoBatch.h>
|
||||||
|
#include <reactphysics3d/collision/narrowphase/CollisionDispatch.h>
|
||||||
|
|
||||||
/// Namespace ReactPhysics3D
|
/// Namespace ReactPhysics3D
|
||||||
namespace reactphysics3d {
|
namespace reactphysics3d {
|
||||||
|
@ -97,34 +98,64 @@ class NarrowPhaseInput {
|
||||||
|
|
||||||
|
|
||||||
// Get a reference to the sphere vs sphere batch contacts
|
// Get a reference to the sphere vs sphere batch contacts
|
||||||
inline NarrowPhaseInfoBatch& NarrowPhaseInput::getSphereVsSphereBatch() {
|
RP3D_FORCE_INLINE NarrowPhaseInfoBatch& NarrowPhaseInput::getSphereVsSphereBatch() {
|
||||||
return mSphereVsSphereBatch;
|
return mSphereVsSphereBatch;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get a reference to the sphere vs capsule batch contacts
|
// Get a reference to the sphere vs capsule batch contacts
|
||||||
inline NarrowPhaseInfoBatch& NarrowPhaseInput::getSphereVsCapsuleBatch() {
|
RP3D_FORCE_INLINE NarrowPhaseInfoBatch& NarrowPhaseInput::getSphereVsCapsuleBatch() {
|
||||||
return mSphereVsCapsuleBatch;
|
return mSphereVsCapsuleBatch;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get a reference to the capsule vs capsule batch contacts
|
// Get a reference to the capsule vs capsule batch contacts
|
||||||
inline NarrowPhaseInfoBatch& NarrowPhaseInput::getCapsuleVsCapsuleBatch() {
|
RP3D_FORCE_INLINE NarrowPhaseInfoBatch& NarrowPhaseInput::getCapsuleVsCapsuleBatch() {
|
||||||
return mCapsuleVsCapsuleBatch;
|
return mCapsuleVsCapsuleBatch;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get a reference to the sphere vs convex polyhedron batch contacts
|
// Get a reference to the sphere vs convex polyhedron batch contacts
|
||||||
inline NarrowPhaseInfoBatch& NarrowPhaseInput::getSphereVsConvexPolyhedronBatch() {
|
RP3D_FORCE_INLINE NarrowPhaseInfoBatch& NarrowPhaseInput::getSphereVsConvexPolyhedronBatch() {
|
||||||
return mSphereVsConvexPolyhedronBatch;
|
return mSphereVsConvexPolyhedronBatch;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get a reference to the capsule vs convex polyhedron batch contacts
|
// Get a reference to the capsule vs convex polyhedron batch contacts
|
||||||
inline NarrowPhaseInfoBatch& NarrowPhaseInput::getCapsuleVsConvexPolyhedronBatch() {
|
RP3D_FORCE_INLINE NarrowPhaseInfoBatch& NarrowPhaseInput::getCapsuleVsConvexPolyhedronBatch() {
|
||||||
return mCapsuleVsConvexPolyhedronBatch;
|
return mCapsuleVsConvexPolyhedronBatch;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get a reference to the convex polyhedron vs convex polyhedron batch contacts
|
// Get a reference to the convex polyhedron vs convex polyhedron batch contacts
|
||||||
inline NarrowPhaseInfoBatch &NarrowPhaseInput::getConvexPolyhedronVsConvexPolyhedronBatch() {
|
RP3D_FORCE_INLINE NarrowPhaseInfoBatch &NarrowPhaseInput::getConvexPolyhedronVsConvexPolyhedronBatch() {
|
||||||
return mConvexPolyhedronVsConvexPolyhedronBatch;
|
return mConvexPolyhedronVsConvexPolyhedronBatch;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Add shapes to be tested during narrow-phase collision detection into the batch
|
||||||
|
RP3D_FORCE_INLINE void NarrowPhaseInput::addNarrowPhaseTest(uint64 pairId, uint64 pairIndex, Entity collider1, Entity collider2, CollisionShape* shape1, CollisionShape* shape2,
|
||||||
|
const Transform& shape1Transform, const Transform& shape2Transform,
|
||||||
|
NarrowPhaseAlgorithmType narrowPhaseAlgorithmType, bool reportContacts, MemoryAllocator& shapeAllocator) {
|
||||||
|
|
||||||
|
switch (narrowPhaseAlgorithmType) {
|
||||||
|
case NarrowPhaseAlgorithmType::SphereVsSphere:
|
||||||
|
mSphereVsSphereBatch.addNarrowPhaseInfo(pairId, pairIndex, collider1, collider2, shape1, shape2, shape1Transform, shape2Transform, reportContacts, shapeAllocator);
|
||||||
|
break;
|
||||||
|
case NarrowPhaseAlgorithmType::SphereVsCapsule:
|
||||||
|
mSphereVsCapsuleBatch.addNarrowPhaseInfo(pairId, pairIndex, collider1, collider2, shape1, shape2, shape1Transform, shape2Transform, reportContacts, shapeAllocator);
|
||||||
|
break;
|
||||||
|
case NarrowPhaseAlgorithmType::CapsuleVsCapsule:
|
||||||
|
mCapsuleVsCapsuleBatch.addNarrowPhaseInfo(pairId, pairIndex, collider1, collider2, shape1, shape2, shape1Transform, shape2Transform, reportContacts, shapeAllocator);
|
||||||
|
break;
|
||||||
|
case NarrowPhaseAlgorithmType::SphereVsConvexPolyhedron:
|
||||||
|
mSphereVsConvexPolyhedronBatch.addNarrowPhaseInfo(pairId, pairIndex, collider1, collider2, shape1, shape2, shape1Transform, shape2Transform, reportContacts, shapeAllocator);
|
||||||
|
break;
|
||||||
|
case NarrowPhaseAlgorithmType::CapsuleVsConvexPolyhedron:
|
||||||
|
mCapsuleVsConvexPolyhedronBatch.addNarrowPhaseInfo(pairId, pairIndex, collider1, collider2, shape1, shape2, shape1Transform, shape2Transform, reportContacts, shapeAllocator);
|
||||||
|
break;
|
||||||
|
case NarrowPhaseAlgorithmType::ConvexPolyhedronVsConvexPolyhedron:
|
||||||
|
mConvexPolyhedronVsConvexPolyhedronBatch.addNarrowPhaseInfo(pairId, pairIndex, collider1, collider2, shape1, shape2, shape1Transform, shape2Transform, reportContacts, shapeAllocator);
|
||||||
|
break;
|
||||||
|
case NarrowPhaseAlgorithmType::None:
|
||||||
|
// Must never happen
|
||||||
|
assert(false);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -185,7 +185,7 @@ class SATAlgorithm {
|
||||||
#ifdef IS_RP3D_PROFILING_ENABLED
|
#ifdef IS_RP3D_PROFILING_ENABLED
|
||||||
|
|
||||||
// Set the profiler
|
// Set the profiler
|
||||||
inline void SATAlgorithm::setProfiler(Profiler* profiler) {
|
RP3D_FORCE_INLINE void SATAlgorithm::setProfiler(Profiler* profiler) {
|
||||||
|
|
||||||
mProfiler = profiler;
|
mProfiler = profiler;
|
||||||
}
|
}
|
||||||
|
|
|
@ -127,44 +127,44 @@ class AABB {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return the center point of the AABB in world coordinates
|
// 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 (mMinCoordinates + mMaxCoordinates) * decimal(0.5);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the minimum coordinates of the AABB
|
// Return the minimum coordinates of the AABB
|
||||||
inline const Vector3& AABB::getMin() const {
|
RP3D_FORCE_INLINE const Vector3& AABB::getMin() const {
|
||||||
return mMinCoordinates;
|
return mMinCoordinates;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the minimum coordinates of the AABB
|
// 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;
|
mMinCoordinates = min;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the maximum coordinates of the AABB
|
// Return the maximum coordinates of the AABB
|
||||||
inline const Vector3& AABB::getMax() const {
|
RP3D_FORCE_INLINE const Vector3& AABB::getMax() const {
|
||||||
return mMaxCoordinates;
|
return mMaxCoordinates;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the maximum coordinates of the AABB
|
// 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;
|
mMaxCoordinates = max;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the size of the AABB in the three dimension x, y and z
|
// 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;
|
return mMaxCoordinates - mMinCoordinates;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Inflate each side of the AABB by a given size
|
// 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);
|
mMaxCoordinates += Vector3(dx, dy, dz);
|
||||||
mMinCoordinates -= Vector3(dx, dy, dz);
|
mMinCoordinates -= Vector3(dx, dy, dz);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the current AABB is overlapping with the AABB in argument.
|
// 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
|
/// 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 ||
|
if (mMaxCoordinates.x < aabb.mMinCoordinates.x ||
|
||||||
aabb.mMaxCoordinates.x < mMinCoordinates.x) return false;
|
aabb.mMaxCoordinates.x < mMinCoordinates.x) return false;
|
||||||
if (mMaxCoordinates.y < aabb.mMinCoordinates.y ||
|
if (mMaxCoordinates.y < aabb.mMinCoordinates.y ||
|
||||||
|
@ -175,13 +175,13 @@ inline bool AABB::testCollision(const AABB& aabb) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the volume of the AABB
|
// Return the volume of the AABB
|
||||||
inline decimal AABB::getVolume() const {
|
RP3D_FORCE_INLINE decimal AABB::getVolume() const {
|
||||||
const Vector3 diff = mMaxCoordinates - mMinCoordinates;
|
const Vector3 diff = mMaxCoordinates - mMinCoordinates;
|
||||||
return (diff.x * diff.y * diff.z);
|
return (diff.x * diff.y * diff.z);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the AABB of a triangle intersects the AABB
|
// 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].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;
|
if (min3(trianglePoints[0].y, trianglePoints[1].y, trianglePoints[2].y) > mMaxCoordinates.y) return false;
|
||||||
|
@ -195,7 +195,7 @@ inline bool AABB::testCollisionTriangleAABB(const Vector3* trianglePoints) const
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if a point is inside the AABB
|
// 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 &&
|
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 &&
|
point.y >= mMinCoordinates.y - MACHINE_EPSILON && point.y <= mMaxCoordinates.y + MACHINE_EPSILON &&
|
||||||
|
@ -203,13 +203,13 @@ inline bool AABB::contains(const Vector3& point) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Apply a scale factor to the AABB
|
// 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;
|
mMinCoordinates = mMinCoordinates * scale;
|
||||||
mMaxCoordinates = mMaxCoordinates * scale;
|
mMaxCoordinates = mMaxCoordinates * scale;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Assignment operator
|
// Assignment operator
|
||||||
inline AABB& AABB::operator=(const AABB& aabb) {
|
RP3D_FORCE_INLINE AABB& AABB::operator=(const AABB& aabb) {
|
||||||
if (this != &aabb) {
|
if (this != &aabb) {
|
||||||
mMinCoordinates = aabb.mMinCoordinates;
|
mMinCoordinates = aabb.mMinCoordinates;
|
||||||
mMaxCoordinates = aabb.mMaxCoordinates;
|
mMaxCoordinates = aabb.mMaxCoordinates;
|
||||||
|
|
|
@ -140,7 +140,7 @@ class BoxShape : public ConvexPolyhedronShape {
|
||||||
/**
|
/**
|
||||||
* @return The vector with the three half-extents of the box shape
|
* @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;
|
return mHalfExtents;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -150,7 +150,7 @@ inline Vector3 BoxShape::getHalfExtents() const {
|
||||||
/**
|
/**
|
||||||
* @param halfExtents The vector with the three half-extents of the box
|
* @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;
|
mHalfExtents = halfExtents;
|
||||||
|
|
||||||
notifyColliderAboutChangedSize();
|
notifyColliderAboutChangedSize();
|
||||||
|
@ -162,7 +162,7 @@ inline void BoxShape::setHalfExtents(const Vector3& halfExtents) {
|
||||||
* @param min The minimum bounds of the shape in local-space coordinates
|
* @param min The minimum bounds of the shape in local-space coordinates
|
||||||
* @param max The maximum 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
|
// Maximum bounds
|
||||||
max = mHalfExtents;
|
max = mHalfExtents;
|
||||||
|
@ -172,12 +172,12 @@ inline void BoxShape::getLocalBounds(Vector3& min, Vector3& max) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the number of bytes used by the collision shape
|
// 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 sizeof(BoxShape);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a local support point in a given direction without the object margin
|
// 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,
|
return Vector3(direction.x < decimal(0.0) ? -mHalfExtents.x : mHalfExtents.x,
|
||||||
direction.y < decimal(0.0) ? -mHalfExtents.y : mHalfExtents.y,
|
direction.y < decimal(0.0) ? -mHalfExtents.y : mHalfExtents.y,
|
||||||
|
@ -185,36 +185,36 @@ inline Vector3 BoxShape::getLocalSupportPointWithoutMargin(const Vector3& direct
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if a point is inside the collision shape
|
// 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] &&
|
return (localPoint.x < mHalfExtents[0] && localPoint.x > -mHalfExtents[0] &&
|
||||||
localPoint.y < mHalfExtents[1] && localPoint.y > -mHalfExtents[1] &&
|
localPoint.y < mHalfExtents[1] && localPoint.y > -mHalfExtents[1] &&
|
||||||
localPoint.z < mHalfExtents[2] && localPoint.z > -mHalfExtents[2]);
|
localPoint.z < mHalfExtents[2] && localPoint.z > -mHalfExtents[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the number of faces of the polyhedron
|
// Return the number of faces of the polyhedron
|
||||||
inline uint BoxShape::getNbFaces() const {
|
RP3D_FORCE_INLINE uint BoxShape::getNbFaces() const {
|
||||||
return 6;
|
return 6;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a given face of the polyhedron
|
// Return a given face of the polyhedron
|
||||||
inline const HalfEdgeStructure::Face& BoxShape::getFace(uint faceIndex) const {
|
RP3D_FORCE_INLINE const HalfEdgeStructure::Face& BoxShape::getFace(uint faceIndex) const {
|
||||||
assert(faceIndex < mHalfEdgeStructure.getNbFaces());
|
assert(faceIndex < mHalfEdgeStructure.getNbFaces());
|
||||||
return mHalfEdgeStructure.getFace(faceIndex);
|
return mHalfEdgeStructure.getFace(faceIndex);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the number of vertices of the polyhedron
|
// Return the number of vertices of the polyhedron
|
||||||
inline uint BoxShape::getNbVertices() const {
|
RP3D_FORCE_INLINE uint BoxShape::getNbVertices() const {
|
||||||
return 8;
|
return 8;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a given vertex of the polyhedron
|
// Return a given vertex of the polyhedron
|
||||||
inline HalfEdgeStructure::Vertex BoxShape::getVertex(uint vertexIndex) const {
|
RP3D_FORCE_INLINE HalfEdgeStructure::Vertex BoxShape::getVertex(uint vertexIndex) const {
|
||||||
assert(vertexIndex < getNbVertices());
|
assert(vertexIndex < getNbVertices());
|
||||||
return mHalfEdgeStructure.getVertex(vertexIndex);
|
return mHalfEdgeStructure.getVertex(vertexIndex);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the position of a given vertex
|
// 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());
|
assert(vertexIndex < getNbVertices());
|
||||||
|
|
||||||
Vector3 extent = getHalfExtents();
|
Vector3 extent = getHalfExtents();
|
||||||
|
@ -235,7 +235,7 @@ inline Vector3 BoxShape::getVertexPosition(uint vertexIndex) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the normal vector of a given face of the polyhedron
|
// 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());
|
assert(faceIndex < getNbFaces());
|
||||||
|
|
||||||
switch(faceIndex) {
|
switch(faceIndex) {
|
||||||
|
@ -252,27 +252,27 @@ inline Vector3 BoxShape::getFaceNormal(uint faceIndex) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the centroid of the box
|
// Return the centroid of the box
|
||||||
inline Vector3 BoxShape::getCentroid() const {
|
RP3D_FORCE_INLINE Vector3 BoxShape::getCentroid() const {
|
||||||
return Vector3::zero();
|
return Vector3::zero();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Compute and return the volume of the collision shape
|
// 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 8 * mHalfExtents.x * mHalfExtents.y * mHalfExtents.z;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the string representation of the shape
|
// 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 "BoxShape{extents=" + mHalfExtents.to_string() + "}";
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the number of half-edges of the polyhedron
|
// Return the number of half-edges of the polyhedron
|
||||||
inline uint BoxShape::getNbHalfEdges() const {
|
RP3D_FORCE_INLINE uint BoxShape::getNbHalfEdges() const {
|
||||||
return 24;
|
return 24;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a given half-edge of the polyhedron
|
// Return a given half-edge of the polyhedron
|
||||||
inline const HalfEdgeStructure::Edge& BoxShape::getHalfEdge(uint edgeIndex) const {
|
RP3D_FORCE_INLINE const HalfEdgeStructure::Edge& BoxShape::getHalfEdge(uint edgeIndex) const {
|
||||||
assert(edgeIndex < getNbHalfEdges());
|
assert(edgeIndex < getNbHalfEdges());
|
||||||
return mHalfEdgeStructure.getHalfEdge(edgeIndex);
|
return mHalfEdgeStructure.getHalfEdge(edgeIndex);
|
||||||
}
|
}
|
||||||
|
|
|
@ -126,7 +126,7 @@ class CapsuleShape : public ConvexShape {
|
||||||
/**
|
/**
|
||||||
* @return The radius of the capsule shape (in meters)
|
* @return The radius of the capsule shape (in meters)
|
||||||
*/
|
*/
|
||||||
inline decimal CapsuleShape::getRadius() const {
|
RP3D_FORCE_INLINE decimal CapsuleShape::getRadius() const {
|
||||||
return mMargin;
|
return mMargin;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -136,7 +136,7 @@ inline decimal CapsuleShape::getRadius() const {
|
||||||
/**
|
/**
|
||||||
* @param radius The radius of the capsule (in meters)
|
* @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));
|
assert(radius > decimal(0.0));
|
||||||
mMargin = radius;
|
mMargin = radius;
|
||||||
|
@ -148,7 +148,7 @@ inline void CapsuleShape::setRadius(decimal radius) {
|
||||||
/**
|
/**
|
||||||
* @return The height of the capsule shape (in meters)
|
* @return The height of the capsule shape (in meters)
|
||||||
*/
|
*/
|
||||||
inline decimal CapsuleShape::getHeight() const {
|
RP3D_FORCE_INLINE decimal CapsuleShape::getHeight() const {
|
||||||
return mHalfHeight + mHalfHeight;
|
return mHalfHeight + mHalfHeight;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -158,7 +158,7 @@ inline decimal CapsuleShape::getHeight() const {
|
||||||
/**
|
/**
|
||||||
* @param height The height of the capsule (in meters)
|
* @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));
|
assert(height > decimal(0.0));
|
||||||
mHalfHeight = height * decimal(0.5);
|
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
|
// 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);
|
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 min The minimum bounds of the shape in local-space coordinates
|
||||||
* @param max The maximum 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
|
// Maximum bounds
|
||||||
max.x = mMargin;
|
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
|
// 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 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
|
// Return true if the collision shape is a polyhedron
|
||||||
inline bool CapsuleShape::isPolyhedron() const {
|
RP3D_FORCE_INLINE bool CapsuleShape::isPolyhedron() const {
|
||||||
return false;
|
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
|
/// 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
|
/// 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.
|
/// 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
|
// Support point top sphere
|
||||||
decimal dotProductTop = mHalfHeight * direction.y;
|
decimal dotProductTop = mHalfHeight * direction.y;
|
||||||
|
@ -225,7 +225,7 @@ inline Vector3 CapsuleShape::getLocalSupportPointWithoutMargin(const Vector3& di
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the string representation of the shape
|
// 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()) + "}";
|
return "CapsuleShape{halfHeight=" + std::to_string(mHalfHeight) + ", radius=" + std::to_string(getRadius()) + "}";
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -172,7 +172,7 @@ class CollisionShape {
|
||||||
/**
|
/**
|
||||||
* @return The name of the collision shape (box, sphere, triangle, ...)
|
* @return The name of the collision shape (box, sphere, triangle, ...)
|
||||||
*/
|
*/
|
||||||
inline CollisionShapeName CollisionShape::getName() const {
|
RP3D_FORCE_INLINE CollisionShapeName CollisionShape::getName() const {
|
||||||
return mName;
|
return mName;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -180,29 +180,29 @@ inline CollisionShapeName CollisionShape::getName() const {
|
||||||
/**
|
/**
|
||||||
* @return The type of the collision shape (sphere, capsule, convex polyhedron, concave mesh)
|
* @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 mType;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the id of the shape
|
// Return the id of the shape
|
||||||
inline uint32 CollisionShape::getId() const {
|
RP3D_FORCE_INLINE uint32 CollisionShape::getId() const {
|
||||||
return mId;
|
return mId;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Assign a new collider to the collision shape
|
// 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);
|
mColliders.add(collider);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Remove an assigned collider from the collision shape
|
// 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);
|
mColliders.remove(collider);
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef IS_RP3D_PROFILING_ENABLED
|
#ifdef IS_RP3D_PROFILING_ENABLED
|
||||||
|
|
||||||
// Set the profiler
|
// Set the profiler
|
||||||
inline void CollisionShape::setProfiler(Profiler* profiler) {
|
RP3D_FORCE_INLINE void CollisionShape::setProfiler(Profiler* profiler) {
|
||||||
|
|
||||||
mProfiler = profiler;
|
mProfiler = profiler;
|
||||||
}
|
}
|
||||||
|
|
|
@ -212,7 +212,7 @@ class ConcaveMeshShape : public ConcaveShape {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return the number of bytes used by the collision shape
|
// 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);
|
return sizeof(ConcaveMeshShape);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -222,7 +222,7 @@ inline size_t ConcaveMeshShape::getSizeInBytes() const {
|
||||||
* @param min The minimum bounds of the shape in local-space coordinates
|
* @param min The minimum bounds of the shape in local-space coordinates
|
||||||
* @param max The maximum 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
|
// Get the AABB of the whole tree
|
||||||
AABB treeAABB = mDynamicAABBTree.getRootAABB();
|
AABB treeAABB = mDynamicAABBTree.getRootAABB();
|
||||||
|
@ -233,7 +233,7 @@ inline void ConcaveMeshShape::getLocalBounds(Vector3& min, Vector3& max) const {
|
||||||
|
|
||||||
// Called when a overlapping node has been found during the call to
|
// Called when a overlapping node has been found during the call to
|
||||||
// DynamicAABBTree:reportAllShapesOverlappingWithAABB()
|
// 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)
|
// Get the node data (triangle index and mesh subpart index)
|
||||||
int32* data = mDynamicAABBTree.getNodeDataInt(nodeId);
|
int32* data = mDynamicAABBTree.getNodeDataInt(nodeId);
|
||||||
|
@ -253,7 +253,7 @@ inline void ConvexTriangleAABBOverlapCallback::notifyOverlappingNode(int nodeId)
|
||||||
#ifdef IS_RP3D_PROFILING_ENABLED
|
#ifdef IS_RP3D_PROFILING_ENABLED
|
||||||
|
|
||||||
// Set the profiler
|
// Set the profiler
|
||||||
inline void ConcaveMeshShape::setProfiler(Profiler* profiler) {
|
RP3D_FORCE_INLINE void ConcaveMeshShape::setProfiler(Profiler* profiler) {
|
||||||
|
|
||||||
CollisionShape::setProfiler(profiler);
|
CollisionShape::setProfiler(profiler);
|
||||||
|
|
||||||
|
|
|
@ -120,22 +120,22 @@ class ConcaveShape : public CollisionShape {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return true if the collision shape is convex, false if it is concave
|
// Return true if the collision shape is convex, false if it is concave
|
||||||
inline bool ConcaveShape::isConvex() const {
|
RP3D_FORCE_INLINE bool ConcaveShape::isConvex() const {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the collision shape is a polyhedron
|
// 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;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if a point is inside the collision shape
|
// 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 false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the raycast test type (front, back, front-back)
|
// Return the raycast test type (front, back, front-back)
|
||||||
inline TriangleRaycastSide ConcaveShape::getRaycastTestType() const {
|
RP3D_FORCE_INLINE TriangleRaycastSide ConcaveShape::getRaycastTestType() const {
|
||||||
return mRaycastTestType;
|
return mRaycastTestType;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -143,19 +143,19 @@ inline TriangleRaycastSide ConcaveShape::getRaycastTestType() const {
|
||||||
/**
|
/**
|
||||||
* @param testType Raycast test type for the triangle (front, back, front-back)
|
* @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;
|
mRaycastTestType = testType;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the scale of the shape
|
// Return the scale of the shape
|
||||||
inline const Vector3& ConcaveShape::getScale() const {
|
RP3D_FORCE_INLINE const Vector3& ConcaveShape::getScale() const {
|
||||||
return mScale;
|
return mScale;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the scale of the shape
|
// Set the scale of the shape
|
||||||
/// Note that you might want to recompute the inertia tensor and center of mass of the body
|
/// 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
|
/// 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;
|
mScale = scale;
|
||||||
|
|
||||||
notifyColliderAboutChangedSize();
|
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
|
* @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
|
// Default inertia tensor
|
||||||
// Note that this is not very realistic for a concave triangle mesh.
|
// Note that this is not very realistic for a concave triangle mesh.
|
||||||
|
|
|
@ -147,19 +147,19 @@ class ConvexMeshShape : public ConvexPolyhedronShape {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return the number of bytes used by the collision shape
|
// 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 sizeof(ConvexMeshShape);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the scaling vector
|
// Return the scaling vector
|
||||||
inline const Vector3& ConvexMeshShape::getScale() const {
|
RP3D_FORCE_INLINE const Vector3& ConvexMeshShape::getScale() const {
|
||||||
return mScale;
|
return mScale;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the scale
|
// Set the scale
|
||||||
/// Note that you might want to recompute the inertia tensor and center of mass of the body
|
/// 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
|
/// 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;
|
mScale = scale;
|
||||||
recalculateBounds();
|
recalculateBounds();
|
||||||
notifyColliderAboutChangedSize();
|
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 min The minimum bounds of the shape in local-space coordinates
|
||||||
* @param max The maximum 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;
|
min = mMinBounds;
|
||||||
max = mMaxBounds;
|
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
|
* @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 decimal factor = (decimal(1.0) / decimal(3.0)) * mass;
|
||||||
const Vector3 realExtent = decimal(0.5) * (mMaxBounds - mMinBounds);
|
const Vector3 realExtent = decimal(0.5) * (mMaxBounds - mMinBounds);
|
||||||
assert(realExtent.x > 0 && realExtent.y > 0 && realExtent.z > 0);
|
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
|
// 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 mPolyhedronMesh->getHalfEdgeStructure().getNbFaces();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a given face of the polyhedron
|
// 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());
|
assert(faceIndex < getNbFaces());
|
||||||
return mPolyhedronMesh->getHalfEdgeStructure().getFace(faceIndex);
|
return mPolyhedronMesh->getHalfEdgeStructure().getFace(faceIndex);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the number of vertices of the polyhedron
|
// 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 mPolyhedronMesh->getHalfEdgeStructure().getNbVertices();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a given vertex of the polyhedron
|
// 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());
|
assert(vertexIndex < getNbVertices());
|
||||||
return mPolyhedronMesh->getHalfEdgeStructure().getVertex(vertexIndex);
|
return mPolyhedronMesh->getHalfEdgeStructure().getVertex(vertexIndex);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the number of half-edges of the polyhedron
|
// 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 mPolyhedronMesh->getHalfEdgeStructure().getNbHalfEdges();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a given half-edge of the polyhedron
|
// 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());
|
assert(edgeIndex < getNbHalfEdges());
|
||||||
return mPolyhedronMesh->getHalfEdgeStructure().getHalfEdge(edgeIndex);
|
return mPolyhedronMesh->getHalfEdgeStructure().getHalfEdge(edgeIndex);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the position of a given vertex
|
// 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());
|
assert(vertexIndex < getNbVertices());
|
||||||
return mPolyhedronMesh->getVertex(vertexIndex) * mScale;
|
return mPolyhedronMesh->getVertex(vertexIndex) * mScale;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the normal vector of a given face of the polyhedron
|
// 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());
|
assert(faceIndex < getNbFaces());
|
||||||
return mPolyhedronMesh->getFaceNormal(faceIndex);
|
return mPolyhedronMesh->getFaceNormal(faceIndex);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the centroid of the polyhedron
|
// Return the centroid of the polyhedron
|
||||||
inline Vector3 ConvexMeshShape::getCentroid() const {
|
RP3D_FORCE_INLINE Vector3 ConvexMeshShape::getCentroid() const {
|
||||||
return mPolyhedronMesh->getCentroid() * mScale;
|
return mPolyhedronMesh->getCentroid() * mScale;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Compute and return the volume of the collision shape
|
// Compute and return the volume of the collision shape
|
||||||
inline decimal ConvexMeshShape::getVolume() const {
|
RP3D_FORCE_INLINE decimal ConvexMeshShape::getVolume() const {
|
||||||
return mPolyhedronMesh->getVolume();
|
return mPolyhedronMesh->getVolume();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -94,7 +94,7 @@ class ConvexPolyhedronShape : public ConvexShape {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return true if the collision shape is a polyhedron
|
// Return true if the collision shape is a polyhedron
|
||||||
inline bool ConvexPolyhedronShape::isPolyhedron() const {
|
RP3D_FORCE_INLINE bool ConvexPolyhedronShape::isPolyhedron() const {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -83,7 +83,7 @@ class ConvexShape : public CollisionShape {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return true if the collision shape is convex, false if it is concave
|
// Return true if the collision shape is convex, false if it is concave
|
||||||
inline bool ConvexShape::isConvex() const {
|
RP3D_FORCE_INLINE bool ConvexShape::isConvex() const {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -91,7 +91,7 @@ inline bool ConvexShape::isConvex() const {
|
||||||
/**
|
/**
|
||||||
* @return The margin (in meters) around the collision shape
|
* @return The margin (in meters) around the collision shape
|
||||||
*/
|
*/
|
||||||
inline decimal ConvexShape::getMargin() const {
|
RP3D_FORCE_INLINE decimal ConvexShape::getMargin() const {
|
||||||
return mMargin;
|
return mMargin;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -167,27 +167,27 @@ class HeightFieldShape : public ConcaveShape {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return the number of rows in the height field
|
// Return the number of rows in the height field
|
||||||
inline int HeightFieldShape::getNbRows() const {
|
RP3D_FORCE_INLINE int HeightFieldShape::getNbRows() const {
|
||||||
return mNbRows;
|
return mNbRows;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the number of columns in the height field
|
// Return the number of columns in the height field
|
||||||
inline int HeightFieldShape::getNbColumns() const {
|
RP3D_FORCE_INLINE int HeightFieldShape::getNbColumns() const {
|
||||||
return mNbColumns;
|
return mNbColumns;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the type of height value in the height field
|
// 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 mHeightDataType;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the number of bytes used by the collision shape
|
// 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 sizeof(HeightFieldShape);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the height of a given (x,y) point in the height field
|
// 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(x >= 0 && x < mNbColumns);
|
||||||
assert(y >= 0 && y < mNbRows);
|
assert(y >= 0 && y < mNbRows);
|
||||||
|
@ -201,12 +201,12 @@ inline decimal HeightFieldShape::getHeightAt(int x, int y) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the closest inside integer grid value of a given floating grid value
|
// 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);
|
return (value < decimal(0.0)) ? value - decimal(0.5) : value + decimal(0.5);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Compute the shape Id for a given triangle
|
// 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;
|
return (jIndex * (mNbColumns - 1) + iIndex) * 2 + secondTriangleIncrement;
|
||||||
}
|
}
|
||||||
|
|
|
@ -111,7 +111,7 @@ class SphereShape : public ConvexShape {
|
||||||
/**
|
/**
|
||||||
* @return Radius of the sphere
|
* @return Radius of the sphere
|
||||||
*/
|
*/
|
||||||
inline decimal SphereShape::getRadius() const {
|
RP3D_FORCE_INLINE decimal SphereShape::getRadius() const {
|
||||||
return mMargin;
|
return mMargin;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -121,7 +121,7 @@ inline decimal SphereShape::getRadius() const {
|
||||||
/**
|
/**
|
||||||
* @param radius Radius of the sphere
|
* @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));
|
assert(radius > decimal(0.0));
|
||||||
mMargin = radius;
|
mMargin = radius;
|
||||||
|
|
||||||
|
@ -132,7 +132,7 @@ inline void SphereShape::setRadius(decimal radius) {
|
||||||
/**
|
/**
|
||||||
* @return False because the sphere shape is not a polyhedron
|
* @return False because the sphere shape is not a polyhedron
|
||||||
*/
|
*/
|
||||||
inline bool SphereShape::isPolyhedron() const {
|
RP3D_FORCE_INLINE bool SphereShape::isPolyhedron() const {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -140,12 +140,12 @@ inline bool SphereShape::isPolyhedron() const {
|
||||||
/**
|
/**
|
||||||
* @return The size (in bytes) of the sphere shape
|
* @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 sizeof(SphereShape);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a local support point in a given direction without the object margin
|
// 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 the center of the sphere (the radius is taken into account in the object margin)
|
||||||
return Vector3(0.0, 0.0, 0.0);
|
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 min The minimum bounds of the shape in local-space coordinates
|
||||||
* @param max The maximum 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
|
// Maximum bounds
|
||||||
max.x = mMargin;
|
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
|
* @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;
|
decimal diag = decimal(0.4) * mass * mMargin * mMargin;
|
||||||
return Vector3(diag, diag, diag);
|
return Vector3(diag, diag, diag);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Compute and return the volume of the collision shape
|
// 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 decimal(4.0) / decimal(3.0) * reactphysics3d::PI_RP3D * mMargin * mMargin * mMargin;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if a point is inside the collision shape
|
// 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 (localPoint.lengthSquare() < mMargin * mMargin);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the string representation of the shape
|
// 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()) + "}";
|
return "SphereShape{radius=" + std::to_string(getRadius()) + "}";
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -188,12 +188,12 @@ class TriangleShape : public ConvexPolyhedronShape {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return the number of bytes used by the collision shape
|
// 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 sizeof(TriangleShape);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a local support point in a given direction without the object margin
|
// 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]));
|
Vector3 dotProducts(direction.dot(mPoints[0]), direction.dot(mPoints[1]), direction.dot(mPoints[2]));
|
||||||
return mPoints[dotProducts.getMaxAxis()];
|
return mPoints[dotProducts.getMaxAxis()];
|
||||||
}
|
}
|
||||||
|
@ -204,7 +204,7 @@ inline Vector3 TriangleShape::getLocalSupportPointWithoutMargin(const Vector3& d
|
||||||
* @param min The minimum bounds of the shape in local-space coordinates
|
* @param min The minimum bounds of the shape in local-space coordinates
|
||||||
* @param max The maximum 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 xAxis(mPoints[0].x, mPoints[1].x, mPoints[2].x);
|
||||||
const Vector3 yAxis(mPoints[0].y, mPoints[1].y, mPoints[2].y);
|
const Vector3 yAxis(mPoints[0].y, mPoints[1].y, mPoints[2].y);
|
||||||
|
@ -222,33 +222,33 @@ inline void TriangleShape::getLocalBounds(Vector3& min, Vector3& max) const {
|
||||||
* coordinates
|
* coordinates
|
||||||
* @param mass Mass to use to compute the inertia tensor of the collision shape
|
* @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 Vector3(0, 0, 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if a point is inside the collision shape
|
// 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 false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the number of faces of the polyhedron
|
// Return the number of faces of the polyhedron
|
||||||
inline uint TriangleShape::getNbFaces() const {
|
RP3D_FORCE_INLINE uint TriangleShape::getNbFaces() const {
|
||||||
return 2;
|
return 2;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a given face of the polyhedron
|
// Return a given face of the polyhedron
|
||||||
inline const HalfEdgeStructure::Face& TriangleShape::getFace(uint faceIndex) const {
|
RP3D_FORCE_INLINE const HalfEdgeStructure::Face& TriangleShape::getFace(uint faceIndex) const {
|
||||||
assert(faceIndex < 2);
|
assert(faceIndex < 2);
|
||||||
return mFaces[faceIndex];
|
return mFaces[faceIndex];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the number of vertices of the polyhedron
|
// Return the number of vertices of the polyhedron
|
||||||
inline uint TriangleShape::getNbVertices() const {
|
RP3D_FORCE_INLINE uint TriangleShape::getNbVertices() const {
|
||||||
return 3;
|
return 3;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a given vertex of the polyhedron
|
// 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);
|
assert(vertexIndex < 3);
|
||||||
|
|
||||||
HalfEdgeStructure::Vertex vertex(vertexIndex);
|
HalfEdgeStructure::Vertex vertex(vertexIndex);
|
||||||
|
@ -261,35 +261,35 @@ inline HalfEdgeStructure::Vertex TriangleShape::getVertex(uint vertexIndex) cons
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a given half-edge of the polyhedron
|
// Return a given half-edge of the polyhedron
|
||||||
inline const HalfEdgeStructure::Edge& TriangleShape::getHalfEdge(uint edgeIndex) const {
|
RP3D_FORCE_INLINE const HalfEdgeStructure::Edge& TriangleShape::getHalfEdge(uint edgeIndex) const {
|
||||||
assert(edgeIndex < getNbHalfEdges());
|
assert(edgeIndex < getNbHalfEdges());
|
||||||
return mEdges[edgeIndex];
|
return mEdges[edgeIndex];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the position of a given vertex
|
// 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);
|
assert(vertexIndex < 3);
|
||||||
return mPoints[vertexIndex];
|
return mPoints[vertexIndex];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the normal vector of a given face of the polyhedron
|
// 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(faceIndex < 2);
|
||||||
return faceIndex == 0 ? mNormal : -mNormal;
|
return faceIndex == 0 ? mNormal : -mNormal;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the centroid of the box
|
// 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 (mPoints[0] + mPoints[1] + mPoints[2]) / decimal(3.0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the number of half-edges of the polyhedron
|
// Return the number of half-edges of the polyhedron
|
||||||
inline uint TriangleShape::getNbHalfEdges() const {
|
RP3D_FORCE_INLINE uint TriangleShape::getNbHalfEdges() const {
|
||||||
return 6;
|
return 6;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the raycast test type (front, back, front-back)
|
// Return the raycast test type (front, back, front-back)
|
||||||
inline TriangleRaycastSide TriangleShape::getRaycastTestType() const {
|
RP3D_FORCE_INLINE TriangleRaycastSide TriangleShape::getRaycastTestType() const {
|
||||||
return mRaycastTestType;
|
return mRaycastTestType;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -297,18 +297,18 @@ inline TriangleRaycastSide TriangleShape::getRaycastTestType() const {
|
||||||
/**
|
/**
|
||||||
* @param testType Raycast test type for the triangle (front, back, front-back)
|
* @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;
|
mRaycastTestType = testType;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the string representation of the shape
|
// 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() + "," +
|
return "TriangleShape{v1=" + mPoints[0].to_string() + ", v2=" + mPoints[1].to_string() + "," +
|
||||||
"v3=" + mPoints[2].to_string() + "}";
|
"v3=" + mPoints[2].to_string() + "}";
|
||||||
}
|
}
|
||||||
|
|
||||||
// Compute and return the volume of the collision shape
|
// 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);
|
return decimal(0.0);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -188,140 +188,140 @@ class BallAndSocketJointComponents : public Components {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return a pointer to a given joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mJoints[mMapEntityToComponentIndex[jointEntity]];
|
return mJoints[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the joint pointer to a given joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mJoints[mMapEntityToComponentIndex[jointEntity]] = joint;
|
mJoints[mMapEntityToComponentIndex[jointEntity]] = joint;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the local anchor point of body 1 for a given 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]];
|
return mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the local anchor point of body 1 for a given joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]] = localAnchoirPointBody1;
|
mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]] = localAnchoirPointBody1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the local anchor point of body 2 for a given joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]];
|
return mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the local anchor point of body 2 for a given joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]] = localAnchoirPointBody2;
|
mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]] = localAnchoirPointBody2;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the vector from center of body 1 to anchor point in world-space
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mR1World[mMapEntityToComponentIndex[jointEntity]];
|
return mR1World[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the vector from center of body 1 to anchor point in world-space
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mR1World[mMapEntityToComponentIndex[jointEntity]] = r1World;
|
mR1World[mMapEntityToComponentIndex[jointEntity]] = r1World;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the vector from center of body 2 to anchor point in world-space
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mR2World[mMapEntityToComponentIndex[jointEntity]];
|
return mR2World[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the vector from center of body 2 to anchor point in world-space
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mR2World[mMapEntityToComponentIndex[jointEntity]] = r2World;
|
mR2World[mMapEntityToComponentIndex[jointEntity]] = r2World;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the inertia tensor of body 1 (in world-space coordinates)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mI1[mMapEntityToComponentIndex[jointEntity]];
|
return mI1[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the inertia tensor of body 1 (in world-space coordinates)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mI1[mMapEntityToComponentIndex[jointEntity]] = i1;
|
mI1[mMapEntityToComponentIndex[jointEntity]] = i1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the inertia tensor of body 2 (in world-space coordinates)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mI2[mMapEntityToComponentIndex[jointEntity]];
|
return mI2[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the inertia tensor of body 2 (in world-space coordinates)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mI2[mMapEntityToComponentIndex[jointEntity]] = i2;
|
mI2[mMapEntityToComponentIndex[jointEntity]] = i2;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the bias vector for the constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mBiasVector[mMapEntityToComponentIndex[jointEntity]];
|
return mBiasVector[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the bias vector for the constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mBiasVector[mMapEntityToComponentIndex[jointEntity]] = biasVector;
|
mBiasVector[mMapEntityToComponentIndex[jointEntity]] = biasVector;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the inverse mass matrix K=JM^-1J^-t of the constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mInverseMassMatrix[mMapEntityToComponentIndex[jointEntity]];
|
return mInverseMassMatrix[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the inverse mass matrix K=JM^-1J^-t of the constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mInverseMassMatrix[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
|
mInverseMassMatrix[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the accumulated impulse
|
// Return the accumulated impulse
|
||||||
inline Vector3 &BallAndSocketJointComponents::getImpulse(Entity jointEntity) {
|
RP3D_FORCE_INLINE Vector3 &BallAndSocketJointComponents::getImpulse(Entity jointEntity) {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mImpulse[mMapEntityToComponentIndex[jointEntity]];
|
return mImpulse[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the accumulated impulse
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mImpulse[mMapEntityToComponentIndex[jointEntity]] = impulse;
|
mImpulse[mMapEntityToComponentIndex[jointEntity]] = impulse;
|
||||||
|
|
|
@ -213,7 +213,7 @@ class ColliderComponents : public Components {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return the body entity of a given collider
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
|
||||||
|
|
||||||
|
@ -221,7 +221,7 @@ inline Entity ColliderComponents::getBody(Entity colliderEntity) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a pointer to a given collider
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
|
||||||
|
|
||||||
|
@ -229,7 +229,7 @@ inline Collider *ColliderComponents::getCollider(Entity colliderEntity) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the local-to-body transform of a collider
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
|
||||||
|
|
||||||
|
@ -237,7 +237,7 @@ inline const Transform& ColliderComponents::getLocalToBodyTransform(Entity colli
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the local-to-body transform of a collider
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
|
||||||
|
|
||||||
|
@ -245,7 +245,7 @@ inline void ColliderComponents::setLocalToBodyTransform(Entity colliderEntity, c
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a pointer to the collision shape of a collider
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
|
||||||
|
|
||||||
|
@ -253,7 +253,7 @@ inline CollisionShape* ColliderComponents::getCollisionShape(Entity colliderEnti
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the broad-phase id of a given collider
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
|
||||||
|
|
||||||
|
@ -261,7 +261,7 @@ inline int32 ColliderComponents::getBroadPhaseId(Entity colliderEntity) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the broad-phase id of a given collider
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
|
||||||
|
|
||||||
|
@ -269,7 +269,7 @@ inline void ColliderComponents::setBroadPhaseId(Entity colliderEntity, int32 bro
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the collision category bits of a given collider
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
|
||||||
|
|
||||||
|
@ -277,7 +277,7 @@ inline unsigned short ColliderComponents::getCollisionCategoryBits(Entity collid
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the "collide with" mask bits of a given collider
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
|
||||||
|
|
||||||
|
@ -285,7 +285,7 @@ inline unsigned short ColliderComponents::getCollideWithMaskBits(Entity collider
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the collision category bits of a given 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));
|
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
|
||||||
|
|
||||||
|
@ -293,7 +293,7 @@ inline void ColliderComponents::setCollisionCategoryBits(Entity colliderEntity,
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the "collide with" mask bits of a given collider
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
|
||||||
|
|
||||||
|
@ -301,7 +301,7 @@ inline void ColliderComponents::setCollideWithMaskBits(Entity colliderEntity, un
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the local-to-world transform of a collider
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
|
||||||
|
|
||||||
|
@ -309,7 +309,7 @@ inline const Transform& ColliderComponents::getLocalToWorldTransform(Entity coll
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the local-to-world transform of a collider
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
|
||||||
|
|
||||||
|
@ -317,7 +317,7 @@ inline void ColliderComponents::setLocalToWorldTransform(Entity colliderEntity,
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a reference to the list of overlapping pairs for a given collider
|
// Return a reference to the list of overlapping pairs for a given collider
|
||||||
inline List<uint64>& ColliderComponents::getOverlappingPairs(Entity colliderEntity) {
|
RP3D_FORCE_INLINE List<uint64>& ColliderComponents::getOverlappingPairs(Entity colliderEntity) {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
|
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
|
||||||
|
|
||||||
|
@ -325,7 +325,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
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
|
||||||
|
|
||||||
|
@ -333,7 +333,7 @@ inline bool ColliderComponents::getHasCollisionShapeChangedSize(Entity colliderE
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the size of collision shape of the collider has been changed by the user
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
|
||||||
|
|
||||||
|
@ -342,7 +342,7 @@ inline void ColliderComponents::setHasCollisionShapeChangedSize(Entity colliderE
|
||||||
|
|
||||||
|
|
||||||
// Return true if a collider is a trigger
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
|
||||||
|
|
||||||
|
@ -350,7 +350,7 @@ inline bool ColliderComponents::getIsTrigger(Entity colliderEntity) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set whether a collider is a trigger
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(colliderEntity));
|
||||||
|
|
||||||
|
|
|
@ -130,7 +130,7 @@ class CollisionBodyComponents : public Components {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Add a collider to a body component
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -138,7 +138,7 @@ inline void CollisionBodyComponents::addColliderToBody(Entity bodyEntity, Entity
|
||||||
}
|
}
|
||||||
|
|
||||||
// Remove a collider from a body component
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -146,7 +146,7 @@ inline void CollisionBodyComponents::removeColliderFromBody(Entity bodyEntity, E
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a pointer to a body
|
// Return a pointer to a body
|
||||||
inline CollisionBody *CollisionBodyComponents::getBody(Entity bodyEntity) {
|
RP3D_FORCE_INLINE CollisionBody *CollisionBodyComponents::getBody(Entity bodyEntity) {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -154,7 +154,7 @@ inline CollisionBody *CollisionBodyComponents::getBody(Entity bodyEntity) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the list of colliders of a body
|
// Return the list of colliders of a body
|
||||||
inline const List<Entity>& CollisionBodyComponents::getColliders(Entity bodyEntity) const {
|
RP3D_FORCE_INLINE const List<Entity>& CollisionBodyComponents::getColliders(Entity bodyEntity) const {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -162,7 +162,7 @@ inline const List<Entity>& CollisionBodyComponents::getColliders(Entity bodyEnti
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the body is active
|
// 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));
|
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
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -178,7 +178,7 @@ inline void CollisionBodyComponents::setIsActive(Entity bodyEntity, bool isActiv
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the user data associated with the body
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -186,7 +186,7 @@ inline void* CollisionBodyComponents::getUserData(Entity bodyEntity) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the user data associated with the body
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
|
|
@ -127,18 +127,18 @@ class Components {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return true if an entity is sleeping
|
// 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));
|
assert(hasComponent(entity));
|
||||||
return mMapEntityToComponentIndex[entity] >= mDisabledStartIndex;
|
return mMapEntityToComponentIndex[entity] >= mDisabledStartIndex;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if there is a component for a given entity
|
// 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 mMapEntityToComponentIndex.containsKey(entity);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if there is a component for a given entiy and if so set the entity index
|
// Return true if there is a component for a given entiy and if so set the entity index
|
||||||
inline bool Components::hasComponentGetIndex(Entity entity, uint32& entityIndex) const {
|
RP3D_FORCE_INLINE bool Components::hasComponentGetIndex(Entity entity, uint32& entityIndex) const {
|
||||||
|
|
||||||
auto it = mMapEntityToComponentIndex.find(entity);
|
auto it = mMapEntityToComponentIndex.find(entity);
|
||||||
|
|
||||||
|
@ -151,17 +151,17 @@ inline bool Components::hasComponentGetIndex(Entity entity, uint32& entityIndex)
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the number of components
|
// Return the number of components
|
||||||
inline uint32 Components::getNbComponents() const {
|
RP3D_FORCE_INLINE uint32 Components::getNbComponents() const {
|
||||||
return mNbComponents;
|
return mNbComponents;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the number of enabled components
|
// Return the number of enabled components
|
||||||
inline uint32 Components::getNbEnabledComponents() const {
|
RP3D_FORCE_INLINE uint32 Components::getNbEnabledComponents() const {
|
||||||
return mDisabledStartIndex;
|
return mDisabledStartIndex;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the index in the arrays for a given entity
|
// 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));
|
assert(hasComponent(entity));
|
||||||
return mMapEntityToComponentIndex[entity];
|
return mMapEntityToComponentIndex[entity];
|
||||||
}
|
}
|
||||||
|
|
|
@ -224,133 +224,133 @@ class FixedJointComponents : public Components {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return a pointer to a given joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mJoints[mMapEntityToComponentIndex[jointEntity]];
|
return mJoints[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the joint pointer to a given joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mJoints[mMapEntityToComponentIndex[jointEntity]] = joint;
|
mJoints[mMapEntityToComponentIndex[jointEntity]] = joint;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the local anchor point of body 1 for a given 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]];
|
return mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the local anchor point of body 1 for a given joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]] = localAnchorPointBody1;
|
mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]] = localAnchorPointBody1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the local anchor point of body 2 for a given joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]];
|
return mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the local anchor point of body 2 for a given joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]] = localAnchorPointBody2;
|
mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]] = localAnchorPointBody2;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the vector from center of body 1 to anchor point in world-space
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mR1World[mMapEntityToComponentIndex[jointEntity]];
|
return mR1World[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the vector from center of body 1 to anchor point in world-space
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mR1World[mMapEntityToComponentIndex[jointEntity]] = r1World;
|
mR1World[mMapEntityToComponentIndex[jointEntity]] = r1World;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the vector from center of body 2 to anchor point in world-space
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mR2World[mMapEntityToComponentIndex[jointEntity]];
|
return mR2World[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the vector from center of body 2 to anchor point in world-space
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mR2World[mMapEntityToComponentIndex[jointEntity]] = r2World;
|
mR2World[mMapEntityToComponentIndex[jointEntity]] = r2World;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the inertia tensor of body 1 (in world-space coordinates)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mI1[mMapEntityToComponentIndex[jointEntity]];
|
return mI1[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the inertia tensor of body 1 (in world-space coordinates)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mI1[mMapEntityToComponentIndex[jointEntity]] = i1;
|
mI1[mMapEntityToComponentIndex[jointEntity]] = i1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the inertia tensor of body 2 (in world-space coordinates)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mI2[mMapEntityToComponentIndex[jointEntity]];
|
return mI2[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the inertia tensor of body 2 (in world-space coordinates)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mI2[mMapEntityToComponentIndex[jointEntity]] = i2;
|
mI2[mMapEntityToComponentIndex[jointEntity]] = i2;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the translation impulse
|
// Return the translation impulse
|
||||||
inline Vector3& FixedJointComponents::getImpulseTranslation(Entity jointEntity) {
|
RP3D_FORCE_INLINE Vector3& FixedJointComponents::getImpulseTranslation(Entity jointEntity) {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mImpulseTranslation[mMapEntityToComponentIndex[jointEntity]];
|
return mImpulseTranslation[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the translation impulse
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mImpulseTranslation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
|
mImpulseTranslation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the translation impulse
|
// Return the translation impulse
|
||||||
inline Vector3& FixedJointComponents::getImpulseRotation(Entity jointEntity) {
|
RP3D_FORCE_INLINE Vector3& FixedJointComponents::getImpulseRotation(Entity jointEntity) {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mImpulseRotation[mMapEntityToComponentIndex[jointEntity]];
|
return mImpulseRotation[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the translation impulse
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mImpulseRotation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
|
mImpulseRotation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the translation inverse mass matrix of the constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mInverseMassMatrixTranslation[mMapEntityToComponentIndex[jointEntity]];
|
return mInverseMassMatrixTranslation[mMapEntityToComponentIndex[jointEntity]];
|
||||||
|
@ -358,63 +358,63 @@ inline Matrix3x3& FixedJointComponents::getInverseMassMatrixTranslation(Entity j
|
||||||
|
|
||||||
|
|
||||||
// Set the translation inverse mass matrix of the constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mInverseMassMatrixTranslation[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
|
mInverseMassMatrixTranslation[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the rotation inverse mass matrix of the constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mInverseMassMatrixRotation[mMapEntityToComponentIndex[jointEntity]];
|
return mInverseMassMatrixRotation[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the rotation inverse mass matrix of the constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mInverseMassMatrixRotation[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
|
mInverseMassMatrixRotation[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the translation bias
|
// Return the translation bias
|
||||||
inline Vector3& FixedJointComponents::getBiasTranslation(Entity jointEntity) {
|
RP3D_FORCE_INLINE Vector3& FixedJointComponents::getBiasTranslation(Entity jointEntity) {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mBiasTranslation[mMapEntityToComponentIndex[jointEntity]];
|
return mBiasTranslation[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the translation impulse
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mBiasTranslation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
|
mBiasTranslation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the rotation bias
|
// Return the rotation bias
|
||||||
inline Vector3& FixedJointComponents::getBiasRotation(Entity jointEntity) {
|
RP3D_FORCE_INLINE Vector3& FixedJointComponents::getBiasRotation(Entity jointEntity) {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mBiasRotation[mMapEntityToComponentIndex[jointEntity]];
|
return mBiasRotation[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the rotation impulse
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mBiasRotation[mMapEntityToComponentIndex[jointEntity]] = impulseRotation;
|
mBiasRotation[mMapEntityToComponentIndex[jointEntity]] = impulseRotation;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the initial orientation difference
|
// Return the initial orientation difference
|
||||||
inline Quaternion& FixedJointComponents::getInitOrientationDifferenceInv(Entity jointEntity) {
|
RP3D_FORCE_INLINE Quaternion& FixedJointComponents::getInitOrientationDifferenceInv(Entity jointEntity) {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mInitOrientationDifferenceInv[mMapEntityToComponentIndex[jointEntity]];
|
return mInitOrientationDifferenceInv[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the rotation impulse
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mInitOrientationDifferenceInv[mMapEntityToComponentIndex[jointEntity]] = initOrientationDifferenceInv;
|
mInitOrientationDifferenceInv[mMapEntityToComponentIndex[jointEntity]] = initOrientationDifferenceInv;
|
||||||
|
|
|
@ -415,133 +415,133 @@ class HingeJointComponents : public Components {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return a pointer to a given joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mJoints[mMapEntityToComponentIndex[jointEntity]];
|
return mJoints[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the joint pointer to a given joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mJoints[mMapEntityToComponentIndex[jointEntity]] = joint;
|
mJoints[mMapEntityToComponentIndex[jointEntity]] = joint;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the local anchor point of body 1 for a given 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]];
|
return mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the local anchor point of body 1 for a given joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]] = localAnchoirPointBody1;
|
mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]] = localAnchoirPointBody1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the local anchor point of body 2 for a given joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]];
|
return mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the local anchor point of body 2 for a given joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]] = localAnchoirPointBody2;
|
mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]] = localAnchoirPointBody2;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the vector from center of body 1 to anchor point in world-space
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mR1World[mMapEntityToComponentIndex[jointEntity]];
|
return mR1World[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the vector from center of body 1 to anchor point in world-space
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mR1World[mMapEntityToComponentIndex[jointEntity]] = r1World;
|
mR1World[mMapEntityToComponentIndex[jointEntity]] = r1World;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the vector from center of body 2 to anchor point in world-space
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mR2World[mMapEntityToComponentIndex[jointEntity]];
|
return mR2World[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the vector from center of body 2 to anchor point in world-space
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mR2World[mMapEntityToComponentIndex[jointEntity]] = r2World;
|
mR2World[mMapEntityToComponentIndex[jointEntity]] = r2World;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the inertia tensor of body 1 (in world-space coordinates)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mI1[mMapEntityToComponentIndex[jointEntity]];
|
return mI1[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the inertia tensor of body 1 (in world-space coordinates)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mI1[mMapEntityToComponentIndex[jointEntity]] = i1;
|
mI1[mMapEntityToComponentIndex[jointEntity]] = i1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the inertia tensor of body 2 (in world-space coordinates)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mI2[mMapEntityToComponentIndex[jointEntity]];
|
return mI2[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the inertia tensor of body 2 (in world-space coordinates)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mI2[mMapEntityToComponentIndex[jointEntity]] = i2;
|
mI2[mMapEntityToComponentIndex[jointEntity]] = i2;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the translation impulse
|
// Return the translation impulse
|
||||||
inline Vector3& HingeJointComponents::getImpulseTranslation(Entity jointEntity) {
|
RP3D_FORCE_INLINE Vector3& HingeJointComponents::getImpulseTranslation(Entity jointEntity) {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mImpulseTranslation[mMapEntityToComponentIndex[jointEntity]];
|
return mImpulseTranslation[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the translation impulse
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mImpulseTranslation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
|
mImpulseTranslation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the translation impulse
|
// Return the translation impulse
|
||||||
inline Vector2& HingeJointComponents::getImpulseRotation(Entity jointEntity) {
|
RP3D_FORCE_INLINE Vector2& HingeJointComponents::getImpulseRotation(Entity jointEntity) {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mImpulseRotation[mMapEntityToComponentIndex[jointEntity]];
|
return mImpulseRotation[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the translation impulse
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mImpulseRotation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
|
mImpulseRotation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the translation inverse mass matrix of the constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mInverseMassMatrixTranslation[mMapEntityToComponentIndex[jointEntity]];
|
return mInverseMassMatrixTranslation[mMapEntityToComponentIndex[jointEntity]];
|
||||||
|
@ -549,91 +549,91 @@ inline Matrix3x3& HingeJointComponents::getInverseMassMatrixTranslation(Entity j
|
||||||
|
|
||||||
|
|
||||||
// Set the translation inverse mass matrix of the constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mInverseMassMatrixTranslation[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
|
mInverseMassMatrixTranslation[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the rotation inverse mass matrix of the constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mInverseMassMatrixRotation[mMapEntityToComponentIndex[jointEntity]];
|
return mInverseMassMatrixRotation[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the rotation inverse mass matrix of the constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mInverseMassMatrixRotation[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
|
mInverseMassMatrixRotation[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the translation bias
|
// Return the translation bias
|
||||||
inline Vector3& HingeJointComponents::getBiasTranslation(Entity jointEntity) {
|
RP3D_FORCE_INLINE Vector3& HingeJointComponents::getBiasTranslation(Entity jointEntity) {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mBiasTranslation[mMapEntityToComponentIndex[jointEntity]];
|
return mBiasTranslation[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the translation impulse
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mBiasTranslation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
|
mBiasTranslation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the rotation bias
|
// Return the rotation bias
|
||||||
inline Vector2 &HingeJointComponents::getBiasRotation(Entity jointEntity) {
|
RP3D_FORCE_INLINE Vector2 &HingeJointComponents::getBiasRotation(Entity jointEntity) {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mBiasRotation[mMapEntityToComponentIndex[jointEntity]];
|
return mBiasRotation[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the rotation impulse
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mBiasRotation[mMapEntityToComponentIndex[jointEntity]] = impulseRotation;
|
mBiasRotation[mMapEntityToComponentIndex[jointEntity]] = impulseRotation;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the initial orientation difference
|
// Return the initial orientation difference
|
||||||
inline Quaternion& HingeJointComponents::getInitOrientationDifferenceInv(Entity jointEntity) {
|
RP3D_FORCE_INLINE Quaternion& HingeJointComponents::getInitOrientationDifferenceInv(Entity jointEntity) {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mInitOrientationDifferenceInv[mMapEntityToComponentIndex[jointEntity]];
|
return mInitOrientationDifferenceInv[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the rotation impulse
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mInitOrientationDifferenceInv[mMapEntityToComponentIndex[jointEntity]] = initOrientationDifferenceInv;
|
mInitOrientationDifferenceInv[mMapEntityToComponentIndex[jointEntity]] = initOrientationDifferenceInv;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the hinge rotation axis (in local-space coordinates of body 1)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mHingeLocalAxisBody1[mMapEntityToComponentIndex[jointEntity]];
|
return mHingeLocalAxisBody1[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the hinge rotation axis (in local-space coordinates of body 1)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mHingeLocalAxisBody1[mMapEntityToComponentIndex[jointEntity]] = hingeLocalAxisBody1;
|
mHingeLocalAxisBody1[mMapEntityToComponentIndex[jointEntity]] = hingeLocalAxisBody1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the hinge rotation axis (in local-space coordiantes of body 2)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mHingeLocalAxisBody2[mMapEntityToComponentIndex[jointEntity]];
|
return mHingeLocalAxisBody2[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the hinge rotation axis (in local-space coordiantes of body 2)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mHingeLocalAxisBody2[mMapEntityToComponentIndex[jointEntity]] = hingeLocalAxisBody2;
|
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
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mA1[mMapEntityToComponentIndex[jointEntity]];
|
return mA1[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the hinge rotation axis (in world-space coordinates) computed from body 1
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mA1[mMapEntityToComponentIndex[jointEntity]] = a1;
|
mA1[mMapEntityToComponentIndex[jointEntity]] = a1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the cross product of vector b2 and 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mB2CrossA1[mMapEntityToComponentIndex[jointEntity]];
|
return mB2CrossA1[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the cross product of vector b2 and a1
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mB2CrossA1[mMapEntityToComponentIndex[jointEntity]] = b2CrossA1;
|
mB2CrossA1[mMapEntityToComponentIndex[jointEntity]] = b2CrossA1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the cross product of vector c2 and a1;
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mC2CrossA1[mMapEntityToComponentIndex[jointEntity]];
|
return mC2CrossA1[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the cross product of vector c2 and a1;
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mC2CrossA1[mMapEntityToComponentIndex[jointEntity]] = c2CrossA1;
|
mC2CrossA1[mMapEntityToComponentIndex[jointEntity]] = c2CrossA1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the accumulated impulse for the lower limit constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mImpulseLowerLimit[mMapEntityToComponentIndex[jointEntity]];
|
return mImpulseLowerLimit[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the accumulated impulse for the lower limit constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mImpulseLowerLimit[mMapEntityToComponentIndex[jointEntity]] = impulseLowerLimit;
|
mImpulseLowerLimit[mMapEntityToComponentIndex[jointEntity]] = impulseLowerLimit;
|
||||||
|
@ -698,14 +698,14 @@ inline void HingeJointComponents::setImpulseLowerLimit(Entity jointEntity, decim
|
||||||
|
|
||||||
|
|
||||||
// Return the accumulated impulse for the upper limit constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mImpulseUpperLimit[mMapEntityToComponentIndex[jointEntity]];
|
return mImpulseUpperLimit[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the accumulated impulse for the upper limit constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mImpulseUpperLimit[mMapEntityToComponentIndex[jointEntity]] = impulseUpperLimit;
|
mImpulseUpperLimit[mMapEntityToComponentIndex[jointEntity]] = impulseUpperLimit;
|
||||||
|
@ -713,182 +713,182 @@ inline void HingeJointComponents::setImpulseUpperLimit(Entity jointEntity, decim
|
||||||
|
|
||||||
|
|
||||||
// Return the accumulated impulse for the motor constraint;
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mImpulseMotor[mMapEntityToComponentIndex[jointEntity]];
|
return mImpulseMotor[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the accumulated impulse for the motor constraint;
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mImpulseMotor[mMapEntityToComponentIndex[jointEntity]] = impulseMotor;
|
mImpulseMotor[mMapEntityToComponentIndex[jointEntity]] = impulseMotor;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the inverse of mass matrix K=JM^-1J^t for the limits and motor constraints (1x1 matrix)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mInverseMassMatrixLimitMotor[mMapEntityToComponentIndex[jointEntity]];
|
return mInverseMassMatrixLimitMotor[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the inverse of mass matrix K=JM^-1J^t for the limits and motor constraints (1x1 matrix)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mInverseMassMatrixLimitMotor[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrixLimitMotor;
|
mInverseMassMatrixLimitMotor[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrixLimitMotor;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the inverse of mass matrix K=JM^-1J^t for the motor
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mInverseMassMatrixMotor[mMapEntityToComponentIndex[jointEntity]];
|
return mInverseMassMatrixMotor[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the inverse of mass matrix K=JM^-1J^t for the motor
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mInverseMassMatrixMotor[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrixMotor;
|
mInverseMassMatrixMotor[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrixMotor;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the bias of the lower limit constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mBLowerLimit[mMapEntityToComponentIndex[jointEntity]];
|
return mBLowerLimit[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the bias of the lower limit constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mBLowerLimit[mMapEntityToComponentIndex[jointEntity]] = bLowerLimit;
|
mBLowerLimit[mMapEntityToComponentIndex[jointEntity]] = bLowerLimit;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the bias of the upper limit constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mBUpperLimit[mMapEntityToComponentIndex[jointEntity]];
|
return mBUpperLimit[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the bias of the upper limit constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mBUpperLimit[mMapEntityToComponentIndex[jointEntity]] = bUpperLimit;
|
mBUpperLimit[mMapEntityToComponentIndex[jointEntity]] = bUpperLimit;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the joint limits are enabled
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mIsLimitEnabled[mMapEntityToComponentIndex[jointEntity]];
|
return mIsLimitEnabled[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set to true if the joint limits are enabled
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mIsLimitEnabled[mMapEntityToComponentIndex[jointEntity]] = isLimitEnabled;
|
mIsLimitEnabled[mMapEntityToComponentIndex[jointEntity]] = isLimitEnabled;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the motor of the joint in enabled
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mIsMotorEnabled[mMapEntityToComponentIndex[jointEntity]];
|
return mIsMotorEnabled[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set to true if the motor of the joint in enabled
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mIsMotorEnabled[mMapEntityToComponentIndex[jointEntity]] = isMotorEnabled;
|
mIsMotorEnabled[mMapEntityToComponentIndex[jointEntity]] = isMotorEnabled;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the Lower limit (minimum allowed rotation angle in radian)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mLowerLimit[mMapEntityToComponentIndex[jointEntity]];
|
return mLowerLimit[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the Lower limit (minimum allowed rotation angle in radian)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mLowerLimit[mMapEntityToComponentIndex[jointEntity]] = lowerLimit;
|
mLowerLimit[mMapEntityToComponentIndex[jointEntity]] = lowerLimit;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the upper limit (maximum translation distance)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mUpperLimit[mMapEntityToComponentIndex[jointEntity]];
|
return mUpperLimit[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the upper limit (maximum translation distance)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mUpperLimit[mMapEntityToComponentIndex[jointEntity]] = upperLimit;
|
mUpperLimit[mMapEntityToComponentIndex[jointEntity]] = upperLimit;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the lower limit is violated
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mIsLowerLimitViolated[mMapEntityToComponentIndex[jointEntity]];
|
return mIsLowerLimitViolated[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set to true if the lower limit is violated
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mIsLowerLimitViolated[mMapEntityToComponentIndex[jointEntity]] = isLowerLimitViolated;
|
mIsLowerLimitViolated[mMapEntityToComponentIndex[jointEntity]] = isLowerLimitViolated;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the upper limit is violated
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mIsUpperLimitViolated[mMapEntityToComponentIndex[jointEntity]];
|
return mIsUpperLimitViolated[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set to true if the upper limit is violated
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mIsUpperLimitViolated[mMapEntityToComponentIndex[jointEntity]] = isUpperLimitViolated;
|
mIsUpperLimitViolated[mMapEntityToComponentIndex[jointEntity]] = isUpperLimitViolated;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the motor speed (in rad/s)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mMotorSpeed[mMapEntityToComponentIndex[jointEntity]];
|
return mMotorSpeed[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the motor speed (in rad/s)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mMotorSpeed[mMapEntityToComponentIndex[jointEntity]] = motorSpeed;
|
mMotorSpeed[mMapEntityToComponentIndex[jointEntity]] = motorSpeed;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the maximum motor torque (in Newtons) that can be applied to reach to desired motor speed
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mMaxMotorTorque[mMapEntityToComponentIndex[jointEntity]];
|
return mMaxMotorTorque[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the maximum motor torque (in Newtons) that can be applied to reach to desired motor speed
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mMaxMotorTorque[mMapEntityToComponentIndex[jointEntity]] = maxMotorTorque;
|
mMaxMotorTorque[mMapEntityToComponentIndex[jointEntity]] = maxMotorTorque;
|
||||||
|
|
|
@ -160,61 +160,61 @@ class JointComponents : public Components {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return the entity of the first body of a joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mBody1Entities[mMapEntityToComponentIndex[jointEntity]];
|
return mBody1Entities[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the entity of the second body of a joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mBody2Entities[mMapEntityToComponentIndex[jointEntity]];
|
return mBody2Entities[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a pointer to the joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mJoints[mMapEntityToComponentIndex[jointEntity]];
|
return mJoints[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the type of a joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mTypes[mMapEntityToComponentIndex[jointEntity]];
|
return mTypes[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the position correction technique of a joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mPositionCorrectionTechniques[mMapEntityToComponentIndex[jointEntity]];
|
return mPositionCorrectionTechniques[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the position correction technique of a joint
|
// Set the position correction technique of a joint
|
||||||
inline void JointComponents::getPositionCorrectionTechnique(Entity jointEntity, JointsPositionCorrectionTechnique positionCorrectionTechnique) {
|
RP3D_FORCE_INLINE void JointComponents::getPositionCorrectionTechnique(Entity jointEntity, JointsPositionCorrectionTechnique positionCorrectionTechnique) {
|
||||||
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mPositionCorrectionTechniques[mMapEntityToComponentIndex[jointEntity]] = positionCorrectionTechnique;
|
mPositionCorrectionTechniques[mMapEntityToComponentIndex[jointEntity]] = positionCorrectionTechnique;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the collision is enabled between the two bodies of a joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mIsCollisionEnabled[mMapEntityToComponentIndex[jointEntity]];
|
return mIsCollisionEnabled[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set whether the collision is enabled between the two bodies of a joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mIsCollisionEnabled[mMapEntityToComponentIndex[jointEntity]] = isCollisionEnabled;
|
mIsCollisionEnabled[mMapEntityToComponentIndex[jointEntity]] = isCollisionEnabled;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the joint has already been added into an island during island creation
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mIsAlreadyInIsland[mMapEntityToComponentIndex[jointEntity]];
|
return mIsAlreadyInIsland[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set to true if the joint has already been added into an island during island creation
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mIsAlreadyInIsland[mMapEntityToComponentIndex[jointEntity]] = isAlreadyInIsland;
|
mIsAlreadyInIsland[mMapEntityToComponentIndex[jointEntity]] = isAlreadyInIsland;
|
||||||
}
|
}
|
||||||
|
|
|
@ -370,7 +370,7 @@ class RigidBodyComponents : public Components {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return a pointer to a body rigid
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -378,7 +378,7 @@ inline RigidBody* RigidBodyComponents::getRigidBody(Entity bodyEntity) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the body is allowed to sleep
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -386,7 +386,7 @@ inline bool RigidBodyComponents::getIsAllowedToSleep(Entity bodyEntity) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the value to know if the body is allowed to sleep
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -394,7 +394,7 @@ inline void RigidBodyComponents::setIsAllowedToSleep(Entity bodyEntity, bool isA
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the body is sleeping
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -402,7 +402,7 @@ inline bool RigidBodyComponents::getIsSleeping(Entity bodyEntity) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the value to know if the body is sleeping
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -410,7 +410,7 @@ inline void RigidBodyComponents::setIsSleeping(Entity bodyEntity, bool isSleepin
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the sleep time
|
// Return the sleep time
|
||||||
inline decimal RigidBodyComponents::getSleepTime(Entity bodyEntity) const {
|
RP3D_FORCE_INLINE decimal RigidBodyComponents::getSleepTime(Entity bodyEntity) const {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -418,7 +418,7 @@ inline decimal RigidBodyComponents::getSleepTime(Entity bodyEntity) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the sleep time
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -426,7 +426,7 @@ inline void RigidBodyComponents::setSleepTime(Entity bodyEntity, decimal sleepTi
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the body type of a body
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -434,7 +434,7 @@ inline BodyType RigidBodyComponents::getBodyType(Entity bodyEntity) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the body type of a body
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -442,7 +442,7 @@ inline void RigidBodyComponents::setBodyType(Entity bodyEntity, BodyType bodyTyp
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the linear velocity of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -450,7 +450,7 @@ inline const Vector3& RigidBodyComponents::getLinearVelocity(Entity bodyEntity)
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the angular velocity of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -458,7 +458,7 @@ inline const Vector3& RigidBodyComponents::getAngularVelocity(Entity bodyEntity)
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the linear velocity of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -466,7 +466,7 @@ inline void RigidBodyComponents::setLinearVelocity(Entity bodyEntity, const Vect
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the angular velocity of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -474,7 +474,7 @@ inline void RigidBodyComponents::setAngularVelocity(Entity bodyEntity, const Vec
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the external force of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -482,7 +482,7 @@ inline const Vector3& RigidBodyComponents::getExternalForce(Entity bodyEntity) c
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the external torque of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -490,7 +490,7 @@ inline const Vector3& RigidBodyComponents::getExternalTorque(Entity bodyEntity)
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the linear damping factor of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -498,7 +498,7 @@ inline decimal RigidBodyComponents::getLinearDamping(Entity bodyEntity) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the angular damping factor of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -506,7 +506,7 @@ inline decimal RigidBodyComponents::getAngularDamping(Entity bodyEntity) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the mass of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -514,7 +514,7 @@ inline decimal RigidBodyComponents::getMass(Entity bodyEntity) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the inverse mass of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -522,7 +522,7 @@ inline decimal RigidBodyComponents::getMassInverse(Entity bodyEntity) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the inverse local inertia tensor of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -530,7 +530,7 @@ inline const Vector3& RigidBodyComponents::getInertiaTensorLocalInverse(Entity b
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the inverse world inertia tensor of an entity
|
// Return the inverse world inertia tensor of an entity
|
||||||
inline const Matrix3x3& RigidBodyComponents::getInertiaTensorWorldInverse(Entity bodyEntity) {
|
RP3D_FORCE_INLINE const Matrix3x3& RigidBodyComponents::getInertiaTensorWorldInverse(Entity bodyEntity) {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -538,7 +538,7 @@ inline const Matrix3x3& RigidBodyComponents::getInertiaTensorWorldInverse(Entity
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the external force of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -546,7 +546,7 @@ inline void RigidBodyComponents::setExternalForce(Entity bodyEntity, const Vecto
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the external force of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -554,7 +554,7 @@ inline void RigidBodyComponents::setExternalTorque(Entity bodyEntity, const Vect
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the linear damping factor of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -562,7 +562,7 @@ inline void RigidBodyComponents::setLinearDamping(Entity bodyEntity, decimal lin
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the angular damping factor of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -570,7 +570,7 @@ inline void RigidBodyComponents::setAngularDamping(Entity bodyEntity, decimal an
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the mass of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -578,7 +578,7 @@ inline void RigidBodyComponents::setMass(Entity bodyEntity, decimal mass) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the mass inverse of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -586,7 +586,7 @@ inline void RigidBodyComponents::setMassInverse(Entity bodyEntity, decimal inver
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the local inertia tensor of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -594,7 +594,7 @@ inline const Vector3& RigidBodyComponents::getLocalInertiaTensor(Entity bodyEnti
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the local inertia tensor of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -602,7 +602,7 @@ inline void RigidBodyComponents::setLocalInertiaTensor(Entity bodyEntity, const
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the inverse local inertia tensor of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -610,7 +610,7 @@ inline void RigidBodyComponents::setInverseInertiaTensorLocal(Entity bodyEntity,
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the constrained linear velocity of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -618,7 +618,7 @@ inline const Vector3& RigidBodyComponents::getConstrainedLinearVelocity(Entity b
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the constrained angular velocity of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -626,7 +626,7 @@ inline const Vector3& RigidBodyComponents::getConstrainedAngularVelocity(Entity
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the split linear velocity of an 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -634,7 +634,7 @@ inline const Vector3& RigidBodyComponents::getSplitLinearVelocity(Entity bodyEnt
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the split angular velocity of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -642,7 +642,7 @@ inline const Vector3& RigidBodyComponents::getSplitAngularVelocity(Entity bodyEn
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the constrained position of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -650,7 +650,7 @@ inline Vector3& RigidBodyComponents::getConstrainedPosition(Entity bodyEntity) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the constrained orientation of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -658,7 +658,7 @@ inline Quaternion& RigidBodyComponents::getConstrainedOrientation(Entity bodyEnt
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the local center of mass of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -666,7 +666,7 @@ inline const Vector3& RigidBodyComponents::getCenterOfMassLocal(Entity bodyEntit
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the world center of mass of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -674,7 +674,7 @@ inline const Vector3& RigidBodyComponents::getCenterOfMassWorld(Entity bodyEntit
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the constrained linear velocity of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -682,7 +682,7 @@ inline void RigidBodyComponents::setConstrainedLinearVelocity(Entity bodyEntity,
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the constrained angular velocity of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -690,7 +690,7 @@ inline void RigidBodyComponents::setConstrainedAngularVelocity(Entity bodyEntity
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the split linear velocity of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -698,7 +698,7 @@ inline void RigidBodyComponents::setSplitLinearVelocity(Entity bodyEntity, const
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the split angular velocity of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -706,7 +706,7 @@ inline void RigidBodyComponents::setSplitAngularVelocity(Entity bodyEntity, cons
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the constrained position of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -714,7 +714,7 @@ inline void RigidBodyComponents::setConstrainedPosition(Entity bodyEntity, const
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the constrained orientation of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -722,7 +722,7 @@ inline void RigidBodyComponents::setConstrainedOrientation(Entity bodyEntity, co
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the local center of mass of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -730,7 +730,7 @@ inline void RigidBodyComponents::setCenterOfMassLocal(Entity bodyEntity, const V
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the world center of mass of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -738,7 +738,7 @@ inline void RigidBodyComponents::setCenterOfMassWorld(Entity bodyEntity, const V
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if gravity is enabled for this entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -746,7 +746,7 @@ inline bool RigidBodyComponents::getIsGravityEnabled(Entity bodyEntity) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the entity is already in an island
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -754,7 +754,7 @@ inline bool RigidBodyComponents::getIsAlreadyInIsland(Entity bodyEntity) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the value to know if the gravity is enabled for this entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
|
|
||||||
|
@ -762,35 +762,35 @@ inline void RigidBodyComponents::setIsGravityEnabled(Entity bodyEntity, bool isG
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the value to know if the entity is already in an island
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
mIsAlreadyInIsland[mMapEntityToComponentIndex[bodyEntity]] = isAlreadyInIsland;
|
mIsAlreadyInIsland[mMapEntityToComponentIndex[bodyEntity]] = isAlreadyInIsland;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the list of joints of a body
|
// Return the list of joints of a body
|
||||||
inline const List<Entity>& RigidBodyComponents::getJoints(Entity bodyEntity) const {
|
RP3D_FORCE_INLINE const List<Entity>& RigidBodyComponents::getJoints(Entity bodyEntity) const {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
return mJoints[mMapEntityToComponentIndex[bodyEntity]];
|
return mJoints[mMapEntityToComponentIndex[bodyEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Add a joint to a body component
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
mJoints[mMapEntityToComponentIndex[bodyEntity]].add(jointEntity);
|
mJoints[mMapEntityToComponentIndex[bodyEntity]].add(jointEntity);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Remove a joint from a body component
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
mJoints[mMapEntityToComponentIndex[bodyEntity]].remove(jointEntity);
|
mJoints[mMapEntityToComponentIndex[bodyEntity]].remove(jointEntity);
|
||||||
}
|
}
|
||||||
|
|
||||||
// A an associated contact pairs into the contact pairs array of the body
|
// A an associated contact pairs into the contact pairs array of the body
|
||||||
inline void RigidBodyComponents::addContacPair(Entity bodyEntity, uint contactPairIndex) {
|
RP3D_FORCE_INLINE void RigidBodyComponents::addContacPair(Entity bodyEntity, uint contactPairIndex) {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
mContactPairs[mMapEntityToComponentIndex[bodyEntity]].add(contactPairIndex);
|
mContactPairs[mMapEntityToComponentIndex[bodyEntity]].add(contactPairIndex);
|
||||||
|
|
|
@ -460,266 +460,266 @@ class SliderJointComponents : public Components {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return a pointer to a given joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mJoints[mMapEntityToComponentIndex[jointEntity]];
|
return mJoints[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the joint pointer to a given joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mJoints[mMapEntityToComponentIndex[jointEntity]] = joint;
|
mJoints[mMapEntityToComponentIndex[jointEntity]] = joint;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the local anchor point of body 1 for a given 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]];
|
return mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the local anchor point of body 1 for a given joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]] = localAnchoirPointBody1;
|
mLocalAnchorPointBody1[mMapEntityToComponentIndex[jointEntity]] = localAnchoirPointBody1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the local anchor point of body 2 for a given joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]];
|
return mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the local anchor point of body 2 for a given joint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]] = localAnchoirPointBody2;
|
mLocalAnchorPointBody2[mMapEntityToComponentIndex[jointEntity]] = localAnchoirPointBody2;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the inertia tensor of body 1 (in world-space coordinates)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mI1[mMapEntityToComponentIndex[jointEntity]];
|
return mI1[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the inertia tensor of body 1 (in world-space coordinates)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mI1[mMapEntityToComponentIndex[jointEntity]] = i1;
|
mI1[mMapEntityToComponentIndex[jointEntity]] = i1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the inertia tensor of body 2 (in world-space coordinates)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mI2[mMapEntityToComponentIndex[jointEntity]];
|
return mI2[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the inertia tensor of body 2 (in world-space coordinates)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mI2[mMapEntityToComponentIndex[jointEntity]] = i2;
|
mI2[mMapEntityToComponentIndex[jointEntity]] = i2;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the translation impulse
|
// Return the translation impulse
|
||||||
inline Vector2& SliderJointComponents::getImpulseTranslation(Entity jointEntity) {
|
RP3D_FORCE_INLINE Vector2& SliderJointComponents::getImpulseTranslation(Entity jointEntity) {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mImpulseTranslation[mMapEntityToComponentIndex[jointEntity]];
|
return mImpulseTranslation[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the translation impulse
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mImpulseTranslation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
|
mImpulseTranslation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the translation impulse
|
// Return the translation impulse
|
||||||
inline Vector3& SliderJointComponents::getImpulseRotation(Entity jointEntity) {
|
RP3D_FORCE_INLINE Vector3& SliderJointComponents::getImpulseRotation(Entity jointEntity) {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mImpulseRotation[mMapEntityToComponentIndex[jointEntity]];
|
return mImpulseRotation[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the translation impulse
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mImpulseRotation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
|
mImpulseRotation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the translation inverse mass matrix of the constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mInverseMassMatrixTranslation[mMapEntityToComponentIndex[jointEntity]];
|
return mInverseMassMatrixTranslation[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the translation inverse mass matrix of the constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mInverseMassMatrixTranslation[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
|
mInverseMassMatrixTranslation[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the rotation inverse mass matrix of the constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mInverseMassMatrixRotation[mMapEntityToComponentIndex[jointEntity]];
|
return mInverseMassMatrixRotation[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the rotation inverse mass matrix of the constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mInverseMassMatrixRotation[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
|
mInverseMassMatrixRotation[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrix;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the translation bias
|
// Return the translation bias
|
||||||
inline Vector2& SliderJointComponents::getBiasTranslation(Entity jointEntity) {
|
RP3D_FORCE_INLINE Vector2& SliderJointComponents::getBiasTranslation(Entity jointEntity) {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mBiasTranslation[mMapEntityToComponentIndex[jointEntity]];
|
return mBiasTranslation[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the translation impulse
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mBiasTranslation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
|
mBiasTranslation[mMapEntityToComponentIndex[jointEntity]] = impulseTranslation;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the rotation bias
|
// Return the rotation bias
|
||||||
inline Vector3& SliderJointComponents::getBiasRotation(Entity jointEntity) {
|
RP3D_FORCE_INLINE Vector3& SliderJointComponents::getBiasRotation(Entity jointEntity) {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mBiasRotation[mMapEntityToComponentIndex[jointEntity]];
|
return mBiasRotation[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the rotation impulse
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mBiasRotation[mMapEntityToComponentIndex[jointEntity]] = impulseRotation;
|
mBiasRotation[mMapEntityToComponentIndex[jointEntity]] = impulseRotation;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the initial orientation difference
|
// Return the initial orientation difference
|
||||||
inline Quaternion& SliderJointComponents::getInitOrientationDifferenceInv(Entity jointEntity) {
|
RP3D_FORCE_INLINE Quaternion& SliderJointComponents::getInitOrientationDifferenceInv(Entity jointEntity) {
|
||||||
|
|
||||||
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mInitOrientationDifferenceInv[mMapEntityToComponentIndex[jointEntity]];
|
return mInitOrientationDifferenceInv[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the rotation impulse
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mInitOrientationDifferenceInv[mMapEntityToComponentIndex[jointEntity]] = initOrientationDifferenceInv;
|
mInitOrientationDifferenceInv[mMapEntityToComponentIndex[jointEntity]] = initOrientationDifferenceInv;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the slider axis (in local-space coordinates of body 1)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mSliderAxisBody1[mMapEntityToComponentIndex[jointEntity]];
|
return mSliderAxisBody1[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the slider axis (in local-space coordinates of body 1)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mSliderAxisBody1[mMapEntityToComponentIndex[jointEntity]] = sliderAxisBody1;
|
mSliderAxisBody1[mMapEntityToComponentIndex[jointEntity]] = sliderAxisBody1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Retunr the slider axis in world-space coordinates
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mSliderAxisWorld[mMapEntityToComponentIndex[jointEntity]];
|
return mSliderAxisWorld[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the slider axis in world-space coordinates
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mSliderAxisWorld[mMapEntityToComponentIndex[jointEntity]] = sliderAxisWorld;
|
mSliderAxisWorld[mMapEntityToComponentIndex[jointEntity]] = sliderAxisWorld;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the vector r1 in world-space coordinates
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mR1[mMapEntityToComponentIndex[jointEntity]];
|
return mR1[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the vector r1 in world-space coordinates
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mR1[mMapEntityToComponentIndex[jointEntity]] = r1;
|
mR1[mMapEntityToComponentIndex[jointEntity]] = r1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the vector r2 in world-space coordinates
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mR2[mMapEntityToComponentIndex[jointEntity]];
|
return mR2[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the vector r2 in world-space coordinates
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mR2[mMapEntityToComponentIndex[jointEntity]] = r2;
|
mR2[mMapEntityToComponentIndex[jointEntity]] = r2;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the first vector orthogonal to the slider axis local-space of body 1
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mN1[mMapEntityToComponentIndex[jointEntity]];
|
return mN1[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the first vector orthogonal to the slider axis local-space of body 1
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mN1[mMapEntityToComponentIndex[jointEntity]] = n1;
|
mN1[mMapEntityToComponentIndex[jointEntity]] = n1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the second vector orthogonal to the slider axis and mN1 in local-space of body 1
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mN2[mMapEntityToComponentIndex[jointEntity]];
|
return mN2[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the second vector orthogonal to the slider axis and mN1 in local-space of body 1
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mN2[mMapEntityToComponentIndex[jointEntity]] = n2;
|
mN2[mMapEntityToComponentIndex[jointEntity]] = n2;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the accumulated impulse for the lower limit constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mImpulseLowerLimit[mMapEntityToComponentIndex[jointEntity]];
|
return mImpulseLowerLimit[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the accumulated impulse for the lower limit constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mImpulseLowerLimit[mMapEntityToComponentIndex[jointEntity]] = impulseLowerLimit;
|
mImpulseLowerLimit[mMapEntityToComponentIndex[jointEntity]] = impulseLowerLimit;
|
||||||
|
@ -727,14 +727,14 @@ inline void SliderJointComponents::setImpulseLowerLimit(Entity jointEntity, deci
|
||||||
|
|
||||||
|
|
||||||
// Return the accumulated impulse for the upper limit constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mImpulseUpperLimit[mMapEntityToComponentIndex[jointEntity]];
|
return mImpulseUpperLimit[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the accumulated impulse for the upper limit constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mImpulseUpperLimit[mMapEntityToComponentIndex[jointEntity]] = impulseUpperLimit;
|
mImpulseUpperLimit[mMapEntityToComponentIndex[jointEntity]] = impulseUpperLimit;
|
||||||
|
@ -742,266 +742,266 @@ inline void SliderJointComponents::setImpulseUpperLimit(Entity jointEntity, deci
|
||||||
|
|
||||||
|
|
||||||
// Return the accumulated impulse for the motor constraint;
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mImpulseMotor[mMapEntityToComponentIndex[jointEntity]];
|
return mImpulseMotor[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the accumulated impulse for the motor constraint;
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mImpulseMotor[mMapEntityToComponentIndex[jointEntity]] = impulseMotor;
|
mImpulseMotor[mMapEntityToComponentIndex[jointEntity]] = impulseMotor;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the inverse of mass matrix K=JM^-1J^t for the limits (1x1 matrix)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mInverseMassMatrixLimit[mMapEntityToComponentIndex[jointEntity]];
|
return mInverseMassMatrixLimit[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the inverse of mass matrix K=JM^-1J^t for the limits (1x1 matrix)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mInverseMassMatrixLimit[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrixLimitMotor;
|
mInverseMassMatrixLimit[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrixLimitMotor;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the inverse of mass matrix K=JM^-1J^t for the motor
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mInverseMassMatrixMotor[mMapEntityToComponentIndex[jointEntity]];
|
return mInverseMassMatrixMotor[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the inverse of mass matrix K=JM^-1J^t for the motor
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mInverseMassMatrixMotor[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrixMotor;
|
mInverseMassMatrixMotor[mMapEntityToComponentIndex[jointEntity]] = inverseMassMatrixMotor;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the bias of the lower limit constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mBLowerLimit[mMapEntityToComponentIndex[jointEntity]];
|
return mBLowerLimit[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the bias of the lower limit constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mBLowerLimit[mMapEntityToComponentIndex[jointEntity]] = bLowerLimit;
|
mBLowerLimit[mMapEntityToComponentIndex[jointEntity]] = bLowerLimit;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the bias of the upper limit constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mBUpperLimit[mMapEntityToComponentIndex[jointEntity]];
|
return mBUpperLimit[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the bias of the upper limit constraint
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mBUpperLimit[mMapEntityToComponentIndex[jointEntity]] = bUpperLimit;
|
mBUpperLimit[mMapEntityToComponentIndex[jointEntity]] = bUpperLimit;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the joint limits are enabled
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mIsLimitEnabled[mMapEntityToComponentIndex[jointEntity]];
|
return mIsLimitEnabled[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set to true if the joint limits are enabled
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mIsLimitEnabled[mMapEntityToComponentIndex[jointEntity]] = isLimitEnabled;
|
mIsLimitEnabled[mMapEntityToComponentIndex[jointEntity]] = isLimitEnabled;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the motor of the joint in enabled
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mIsMotorEnabled[mMapEntityToComponentIndex[jointEntity]];
|
return mIsMotorEnabled[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set to true if the motor of the joint in enabled
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mIsMotorEnabled[mMapEntityToComponentIndex[jointEntity]] = isMotorEnabled;
|
mIsMotorEnabled[mMapEntityToComponentIndex[jointEntity]] = isMotorEnabled;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the Lower limit (minimum allowed rotation angle in radian)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mLowerLimit[mMapEntityToComponentIndex[jointEntity]];
|
return mLowerLimit[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the Lower limit (minimum allowed rotation angle in radian)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mLowerLimit[mMapEntityToComponentIndex[jointEntity]] = lowerLimit;
|
mLowerLimit[mMapEntityToComponentIndex[jointEntity]] = lowerLimit;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the upper limit (maximum translation distance)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mUpperLimit[mMapEntityToComponentIndex[jointEntity]];
|
return mUpperLimit[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the upper limit (maximum translation distance)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mUpperLimit[mMapEntityToComponentIndex[jointEntity]] = upperLimit;
|
mUpperLimit[mMapEntityToComponentIndex[jointEntity]] = upperLimit;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the lower limit is violated
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mIsLowerLimitViolated[mMapEntityToComponentIndex[jointEntity]];
|
return mIsLowerLimitViolated[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set to true if the lower limit is violated
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mIsLowerLimitViolated[mMapEntityToComponentIndex[jointEntity]] = isLowerLimitViolated;
|
mIsLowerLimitViolated[mMapEntityToComponentIndex[jointEntity]] = isLowerLimitViolated;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the upper limit is violated
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mIsUpperLimitViolated[mMapEntityToComponentIndex[jointEntity]];
|
return mIsUpperLimitViolated[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set to true if the upper limit is violated
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mIsUpperLimitViolated[mMapEntityToComponentIndex[jointEntity]] = isUpperLimitViolated;
|
mIsUpperLimitViolated[mMapEntityToComponentIndex[jointEntity]] = isUpperLimitViolated;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the motor speed (in rad/s)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mMotorSpeed[mMapEntityToComponentIndex[jointEntity]];
|
return mMotorSpeed[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the motor speed (in rad/s)
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mMotorSpeed[mMapEntityToComponentIndex[jointEntity]] = motorSpeed;
|
mMotorSpeed[mMapEntityToComponentIndex[jointEntity]] = motorSpeed;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the maximum motor torque (in Newtons) that can be applied to reach to desired motor speed
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mMaxMotorForce[mMapEntityToComponentIndex[jointEntity]];
|
return mMaxMotorForce[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the maximum motor torque (in Newtons) that can be applied to reach to desired motor speed
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mMaxMotorForce[mMapEntityToComponentIndex[jointEntity]] = maxMotorForce;
|
mMaxMotorForce[mMapEntityToComponentIndex[jointEntity]] = maxMotorForce;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the cross product of r2 and n1
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mR2CrossN1[mMapEntityToComponentIndex[jointEntity]];
|
return mR2CrossN1[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the cross product of r2 and n1
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mR2CrossN1[mMapEntityToComponentIndex[jointEntity]] = r2CrossN1;
|
mR2CrossN1[mMapEntityToComponentIndex[jointEntity]] = r2CrossN1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the cross product of r2 and n2
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mR2CrossN2[mMapEntityToComponentIndex[jointEntity]];
|
return mR2CrossN2[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the cross product of r2 and n2
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mR2CrossN2[mMapEntityToComponentIndex[jointEntity]] = r2CrossN2;
|
mR2CrossN2[mMapEntityToComponentIndex[jointEntity]] = r2CrossN2;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the cross product of r2 and the slider axis
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mR2CrossSliderAxis[mMapEntityToComponentIndex[jointEntity]];
|
return mR2CrossSliderAxis[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the cross product of r2 and the slider axis
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mR2CrossSliderAxis[mMapEntityToComponentIndex[jointEntity]] = r2CrossSliderAxis;
|
mR2CrossSliderAxis[mMapEntityToComponentIndex[jointEntity]] = r2CrossSliderAxis;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the cross product of vector (r1 + u) and n1
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mR1PlusUCrossN1[mMapEntityToComponentIndex[jointEntity]];
|
return mR1PlusUCrossN1[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the cross product of vector (r1 + u) and n1
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mR1PlusUCrossN1[mMapEntityToComponentIndex[jointEntity]] = r1PlusUCrossN1;
|
mR1PlusUCrossN1[mMapEntityToComponentIndex[jointEntity]] = r1PlusUCrossN1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the cross product of vector (r1 + u) and n2
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mR1PlusUCrossN2[mMapEntityToComponentIndex[jointEntity]];
|
return mR1PlusUCrossN2[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the cross product of vector (r1 + u) and n2
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mR1PlusUCrossN2[mMapEntityToComponentIndex[jointEntity]] = r1PlusUCrossN2;
|
mR1PlusUCrossN2[mMapEntityToComponentIndex[jointEntity]] = r1PlusUCrossN2;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the cross product of vector (r1 + u) and the slider axis
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
return mR1PlusUCrossSliderAxis[mMapEntityToComponentIndex[jointEntity]];
|
return mR1PlusUCrossSliderAxis[mMapEntityToComponentIndex[jointEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the cross product of vector (r1 + u) and the slider axis
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(jointEntity));
|
||||||
mR1PlusUCrossSliderAxis[mMapEntityToComponentIndex[jointEntity]] = r1PlusUCrossSliderAxis;
|
mR1PlusUCrossSliderAxis[mMapEntityToComponentIndex[jointEntity]] = r1PlusUCrossSliderAxis;
|
||||||
|
|
|
@ -107,13 +107,13 @@ class TransformComponents : public Components {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return the transform of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
return mTransforms[mMapEntityToComponentIndex[bodyEntity]];
|
return mTransforms[mMapEntityToComponentIndex[bodyEntity]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the transform of an entity
|
// 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));
|
assert(mMapEntityToComponentIndex.containsKey(bodyEntity));
|
||||||
mTransforms[mMapEntityToComponentIndex[bodyEntity]] = transform;
|
mTransforms[mMapEntityToComponentIndex[bodyEntity]] = transform;
|
||||||
}
|
}
|
||||||
|
|
|
@ -55,7 +55,7 @@
|
||||||
#define RP3D_COMPILER_UNKNOWN
|
#define RP3D_COMPILER_UNKNOWN
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Force inline macro
|
// Force RP3D_FORCE_INLINE macro
|
||||||
#if defined(RP3D_COMPILER_VISUAL_STUDIO)
|
#if defined(RP3D_COMPILER_VISUAL_STUDIO)
|
||||||
#define RP3D_FORCE_INLINE __forceinline
|
#define RP3D_FORCE_INLINE __forceinline
|
||||||
#elif defined(RP3D_COMPILER_GCC) || defined(RP3D_COMPILER_CLANG)
|
#elif defined(RP3D_COMPILER_GCC) || defined(RP3D_COMPILER_CLANG)
|
||||||
|
|
|
@ -129,7 +129,7 @@ class BallAndSocketJoint : public Joint {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return the number of bytes used by the 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);
|
return sizeof(BallAndSocketJoint);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -144,7 +144,7 @@ class ContactPoint {
|
||||||
/**
|
/**
|
||||||
* @return The contact normal
|
* @return The contact normal
|
||||||
*/
|
*/
|
||||||
inline const Vector3& ContactPoint::getNormal() const {
|
RP3D_FORCE_INLINE const Vector3& ContactPoint::getNormal() const {
|
||||||
return mNormal;
|
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
|
* @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;
|
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
|
* @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;
|
return mLocalPointOnShape2;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -168,12 +168,12 @@ inline const Vector3& ContactPoint::getLocalPointOnShape2() const {
|
||||||
/**
|
/**
|
||||||
* @return The penetration impulse
|
* @return The penetration impulse
|
||||||
*/
|
*/
|
||||||
inline decimal ContactPoint::getPenetrationImpulse() const {
|
RP3D_FORCE_INLINE decimal ContactPoint::getPenetrationImpulse() const {
|
||||||
return mPenetrationImpulse;
|
return mPenetrationImpulse;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the contact point is similar (close enougth) to another given contact point
|
// 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 *
|
return (localContactPointBody1->localPoint1 - mLocalPointOnShape1).lengthSquare() <= (mPersistentContactDistanceThreshold *
|
||||||
mPersistentContactDistanceThreshold);
|
mPersistentContactDistanceThreshold);
|
||||||
}
|
}
|
||||||
|
@ -182,7 +182,7 @@ inline bool ContactPoint::isSimilarWithContactPoint(const ContactPointInfo* loca
|
||||||
/**
|
/**
|
||||||
* @param impulse Penetration impulse
|
* @param impulse Penetration impulse
|
||||||
*/
|
*/
|
||||||
inline void ContactPoint::setPenetrationImpulse(decimal impulse) {
|
RP3D_FORCE_INLINE void ContactPoint::setPenetrationImpulse(decimal impulse) {
|
||||||
mPenetrationImpulse = impulse;
|
mPenetrationImpulse = impulse;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -190,7 +190,7 @@ inline void ContactPoint::setPenetrationImpulse(decimal impulse) {
|
||||||
/**
|
/**
|
||||||
* @return True if it is a resting contact
|
* @return True if it is a resting contact
|
||||||
*/
|
*/
|
||||||
inline bool ContactPoint::getIsRestingContact() const {
|
RP3D_FORCE_INLINE bool ContactPoint::getIsRestingContact() const {
|
||||||
return mIsRestingContact;
|
return mIsRestingContact;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -198,7 +198,7 @@ inline bool ContactPoint::getIsRestingContact() const {
|
||||||
/**
|
/**
|
||||||
* @param isRestingContact True if it is a resting contact
|
* @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;
|
mIsRestingContact = isRestingContact;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -206,7 +206,7 @@ inline void ContactPoint::setIsRestingContact(bool isRestingContact) {
|
||||||
/**
|
/**
|
||||||
* @return the penetration depth (in meters)
|
* @return the penetration depth (in meters)
|
||||||
*/
|
*/
|
||||||
inline decimal ContactPoint::getPenetrationDepth() const {
|
RP3D_FORCE_INLINE decimal ContactPoint::getPenetrationDepth() const {
|
||||||
return mPenetrationDepth;
|
return mPenetrationDepth;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -214,7 +214,7 @@ inline decimal ContactPoint::getPenetrationDepth() const {
|
||||||
/**
|
/**
|
||||||
* @return The size of the contact point in memory (in bytes)
|
* @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);
|
return sizeof(ContactPoint);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -119,7 +119,7 @@ class FixedJoint : public Joint {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return the number of bytes used by the 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);
|
return sizeof(FixedJoint);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -157,7 +157,7 @@ class Joint {
|
||||||
/**
|
/**
|
||||||
* @return The entity of the joint
|
* @return The entity of the joint
|
||||||
*/
|
*/
|
||||||
inline Entity Joint::getEntity() const {
|
RP3D_FORCE_INLINE Entity Joint::getEntity() const {
|
||||||
return mEntity;
|
return mEntity;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -309,7 +309,7 @@ class SliderJoint : public Joint {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return the number of bytes used by the 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);
|
return sizeof(SliderJoint);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -93,20 +93,20 @@ class LinkedList {
|
||||||
|
|
||||||
// Return the first element of the list
|
// Return the first element of the list
|
||||||
template<typename T>
|
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;
|
return mListHead;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Insert an element at the beginning of the linked list
|
// Insert an element at the beginning of the linked list
|
||||||
template<typename T>
|
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);
|
ListElement* element = new (mAllocator.allocate(sizeof(ListElement))) ListElement(data, mListHead);
|
||||||
mListHead = element;
|
mListHead = element;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Remove all the elements of the list
|
// Remove all the elements of the list
|
||||||
template<typename T>
|
template<typename T>
|
||||||
inline void LinkedList<T>::reset() {
|
RP3D_FORCE_INLINE void LinkedList<T>::reset() {
|
||||||
|
|
||||||
// Release all the list elements
|
// Release all the list elements
|
||||||
ListElement* element = mListHead;
|
ListElement* element = mListHead;
|
||||||
|
|
|
@ -29,6 +29,7 @@
|
||||||
// Libraries
|
// Libraries
|
||||||
#include <cstddef>
|
#include <cstddef>
|
||||||
#include <functional>
|
#include <functional>
|
||||||
|
#include <reactphysics3d/configuration.h>
|
||||||
|
|
||||||
namespace reactphysics3d {
|
namespace reactphysics3d {
|
||||||
|
|
||||||
|
|
|
@ -107,23 +107,23 @@ struct Entity {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return the lookup index of the entity in a array
|
// 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 id & ENTITY_INDEX_MASK;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the generation number of the entity
|
// 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;
|
return (id >> ENTITY_INDEX_BITS) & ENTITY_GENERATION_MASK;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Equality operator
|
// Equality operator
|
||||||
inline bool Entity::operator==(const Entity& entity) const {
|
RP3D_FORCE_INLINE bool Entity::operator==(const Entity& entity) const {
|
||||||
|
|
||||||
return entity.id == id;
|
return entity.id == id;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Inequality operator
|
// Inequality operator
|
||||||
inline bool Entity::operator!=(const Entity& entity) const {
|
RP3D_FORCE_INLINE bool Entity::operator!=(const Entity& entity) const {
|
||||||
return entity.id != id;
|
return entity.id != id;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -71,7 +71,7 @@ class EntityManager {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return true if the entity is still valid (not destroyed)
|
// 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();
|
return mGenerations[entity.getIndex()] == entity.getGeneration();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -105,35 +105,35 @@ class Island {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Add a body into the island
|
// Add a body into the island
|
||||||
inline void Island::addBody(RigidBody* body) {
|
RP3D_FORCE_INLINE void Island::addBody(RigidBody* body) {
|
||||||
assert(!body->isSleeping());
|
assert(!body->isSleeping());
|
||||||
mBodies[mNbBodies] = body;
|
mBodies[mNbBodies] = body;
|
||||||
mNbBodies++;
|
mNbBodies++;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Add a contact manifold into the island
|
// Add a contact manifold into the island
|
||||||
inline void Island::addContactManifold(ContactManifold* contactManifold) {
|
RP3D_FORCE_INLINE void Island::addContactManifold(ContactManifold* contactManifold) {
|
||||||
mContactManifolds[mNbContactManifolds] = contactManifold;
|
mContactManifolds[mNbContactManifolds] = contactManifold;
|
||||||
mNbContactManifolds++;
|
mNbContactManifolds++;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the number of bodies in the island
|
// Return the number of bodies in the island
|
||||||
inline uint Island::getNbBodies() const {
|
RP3D_FORCE_INLINE uint Island::getNbBodies() const {
|
||||||
return mNbBodies;
|
return mNbBodies;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the number of contact manifolds in the island
|
// Return the number of contact manifolds in the island
|
||||||
inline uint Island::getNbContactManifolds() const {
|
RP3D_FORCE_INLINE uint Island::getNbContactManifolds() const {
|
||||||
return mNbContactManifolds;
|
return mNbContactManifolds;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a pointer to the array of bodies
|
// Return a pointer to the array of bodies
|
||||||
inline RigidBody** Island::getBodies() {
|
RP3D_FORCE_INLINE RigidBody** Island::getBodies() {
|
||||||
return mBodies;
|
return mBodies;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a pointer to the array of contact manifolds
|
// Return a pointer to the array of contact manifolds
|
||||||
inline ContactManifold** Island::getContactManifolds() {
|
RP3D_FORCE_INLINE ContactManifold** Island::getContactManifolds() {
|
||||||
return mContactManifolds;
|
return mContactManifolds;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -111,7 +111,7 @@ class Material {
|
||||||
/**
|
/**
|
||||||
* @return Bounciness factor (between 0 and 1) where 1 is very bouncy
|
* @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;
|
return mBounciness;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -121,7 +121,7 @@ inline decimal Material::getBounciness() const {
|
||||||
/**
|
/**
|
||||||
* @param bounciness Bounciness factor (between 0 and 1) where 1 is very bouncy
|
* @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));
|
assert(bounciness >= decimal(0.0) && bounciness <= decimal(1.0));
|
||||||
mBounciness = bounciness;
|
mBounciness = bounciness;
|
||||||
}
|
}
|
||||||
|
@ -130,7 +130,7 @@ inline void Material::setBounciness(decimal bounciness) {
|
||||||
/**
|
/**
|
||||||
* @return Friction coefficient (positive value)
|
* @return Friction coefficient (positive value)
|
||||||
*/
|
*/
|
||||||
inline decimal Material::getFrictionCoefficient() const {
|
RP3D_FORCE_INLINE decimal Material::getFrictionCoefficient() const {
|
||||||
return mFrictionCoefficient;
|
return mFrictionCoefficient;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -140,7 +140,7 @@ inline decimal Material::getFrictionCoefficient() const {
|
||||||
/**
|
/**
|
||||||
* @param frictionCoefficient Friction coefficient (positive value)
|
* @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));
|
assert(frictionCoefficient >= decimal(0.0));
|
||||||
mFrictionCoefficient = frictionCoefficient;
|
mFrictionCoefficient = frictionCoefficient;
|
||||||
}
|
}
|
||||||
|
@ -151,7 +151,7 @@ inline void Material::setFrictionCoefficient(decimal frictionCoefficient) {
|
||||||
/**
|
/**
|
||||||
* @return The rolling resistance factor (positive value)
|
* @return The rolling resistance factor (positive value)
|
||||||
*/
|
*/
|
||||||
inline decimal Material::getRollingResistance() const {
|
RP3D_FORCE_INLINE decimal Material::getRollingResistance() const {
|
||||||
return mRollingResistance;
|
return mRollingResistance;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -161,13 +161,13 @@ inline decimal Material::getRollingResistance() const {
|
||||||
/**
|
/**
|
||||||
* @param rollingResistance The rolling resistance factor
|
* @param rollingResistance The rolling resistance factor
|
||||||
*/
|
*/
|
||||||
inline void Material::setRollingResistance(decimal rollingResistance) {
|
RP3D_FORCE_INLINE void Material::setRollingResistance(decimal rollingResistance) {
|
||||||
assert(rollingResistance >= 0);
|
assert(rollingResistance >= 0);
|
||||||
mRollingResistance = rollingResistance;
|
mRollingResistance = rollingResistance;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the mass density of the collider
|
// Return the mass density of the collider
|
||||||
inline decimal Material::getMassDensity() const {
|
RP3D_FORCE_INLINE decimal Material::getMassDensity() const {
|
||||||
return mMassDensity;
|
return mMassDensity;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -175,12 +175,12 @@ inline decimal Material::getMassDensity() const {
|
||||||
/**
|
/**
|
||||||
* @param massDensity The mass density of the collider
|
* @param massDensity The mass density of the collider
|
||||||
*/
|
*/
|
||||||
inline void Material::setMassDensity(decimal massDensity) {
|
RP3D_FORCE_INLINE void Material::setMassDensity(decimal massDensity) {
|
||||||
mMassDensity = massDensity;
|
mMassDensity = massDensity;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a string representation for the material
|
// 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;
|
std::stringstream ss;
|
||||||
|
|
||||||
|
@ -192,7 +192,7 @@ inline std::string Material::to_string() const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded assignment operator
|
// Overloaded assignment operator
|
||||||
inline Material& Material::operator=(const Material& material) {
|
RP3D_FORCE_INLINE Material& Material::operator=(const Material& material) {
|
||||||
|
|
||||||
// Check for self-assignment
|
// Check for self-assignment
|
||||||
if (this != &material) {
|
if (this != &material) {
|
||||||
|
|
|
@ -313,21 +313,21 @@ class OverlappingPairs {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return the entity of the first collider
|
// Return the entity of the first collider
|
||||||
inline Entity OverlappingPairs::getCollider1(uint64 pairId) const {
|
RP3D_FORCE_INLINE Entity OverlappingPairs::getCollider1(uint64 pairId) const {
|
||||||
assert(mMapPairIdToPairIndex.containsKey(pairId));
|
assert(mMapPairIdToPairIndex.containsKey(pairId));
|
||||||
assert(mMapPairIdToPairIndex[pairId] < mNbPairs);
|
assert(mMapPairIdToPairIndex[pairId] < mNbPairs);
|
||||||
return mColliders1[mMapPairIdToPairIndex[pairId]];
|
return mColliders1[mMapPairIdToPairIndex[pairId]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the entity of the second collider
|
// Return the entity of the second collider
|
||||||
inline Entity OverlappingPairs::getCollider2(uint64 pairId) const {
|
RP3D_FORCE_INLINE Entity OverlappingPairs::getCollider2(uint64 pairId) const {
|
||||||
assert(mMapPairIdToPairIndex.containsKey(pairId));
|
assert(mMapPairIdToPairIndex.containsKey(pairId));
|
||||||
assert(mMapPairIdToPairIndex[pairId] < mNbPairs);
|
assert(mMapPairIdToPairIndex[pairId] < mNbPairs);
|
||||||
return mColliders2[mMapPairIdToPairIndex[pairId]];
|
return mColliders2[mMapPairIdToPairIndex[pairId]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Notify if a given pair is active or not
|
// Notify if a given pair is active or not
|
||||||
inline void OverlappingPairs::setIsPairActive(uint64 pairId, bool isActive) {
|
RP3D_FORCE_INLINE void OverlappingPairs::setIsPairActive(uint64 pairId, bool isActive) {
|
||||||
|
|
||||||
assert(mMapPairIdToPairIndex.containsKey(pairId));
|
assert(mMapPairIdToPairIndex.containsKey(pairId));
|
||||||
assert(mMapPairIdToPairIndex[pairId] < mNbPairs);
|
assert(mMapPairIdToPairIndex[pairId] < mNbPairs);
|
||||||
|
@ -335,13 +335,13 @@ inline void OverlappingPairs::setIsPairActive(uint64 pairId, bool isActive) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the index of a given overlapping pair in the internal array
|
// Return the index of a given overlapping pair in the internal array
|
||||||
inline uint64 OverlappingPairs::getPairIndex(uint64 pairId) const {
|
RP3D_FORCE_INLINE uint64 OverlappingPairs::getPairIndex(uint64 pairId) const {
|
||||||
assert(mMapPairIdToPairIndex.containsKey(pairId));
|
assert(mMapPairIdToPairIndex.containsKey(pairId));
|
||||||
return mMapPairIdToPairIndex[pairId];
|
return mMapPairIdToPairIndex[pairId];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the last frame collision info for a given shape id or nullptr if none is found
|
// 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) {
|
RP3D_FORCE_INLINE LastFrameCollisionInfo* OverlappingPairs::getLastFrameCollisionInfo(uint64 pairId, uint64 shapesId) {
|
||||||
|
|
||||||
assert(mMapPairIdToPairIndex.containsKey(pairId));
|
assert(mMapPairIdToPairIndex.containsKey(pairId));
|
||||||
const uint64 index = mMapPairIdToPairIndex[pairId];
|
const uint64 index = mMapPairIdToPairIndex[pairId];
|
||||||
|
@ -356,7 +356,7 @@ inline LastFrameCollisionInfo* OverlappingPairs::getLastFrameCollisionInfo(uint6
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the pair of bodies index
|
// 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
|
// Construct the pair of body index
|
||||||
bodypair indexPair = body1Entity.id < body2Entity.id ?
|
bodypair indexPair = body1Entity.id < body2Entity.id ?
|
||||||
|
@ -367,44 +367,44 @@ inline bodypair OverlappingPairs::computeBodiesIndexPair(Entity body1Entity, Ent
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the number of pairs
|
// Return the number of pairs
|
||||||
inline uint64 OverlappingPairs::getNbPairs() const {
|
RP3D_FORCE_INLINE uint64 OverlappingPairs::getNbPairs() const {
|
||||||
return mNbPairs;
|
return mNbPairs;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the number of convex vs convex pairs
|
// Return the number of convex vs convex pairs
|
||||||
inline uint64 OverlappingPairs::getNbConvexVsConvexPairs() const {
|
RP3D_FORCE_INLINE uint64 OverlappingPairs::getNbConvexVsConvexPairs() const {
|
||||||
return mConcavePairsStartIndex;
|
return mConcavePairsStartIndex;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the number of convex vs concave pairs
|
// Return the number of convex vs concave pairs
|
||||||
inline uint64 OverlappingPairs::getNbConvexVsConcavePairs() const {
|
RP3D_FORCE_INLINE uint64 OverlappingPairs::getNbConvexVsConcavePairs() const {
|
||||||
return mNbPairs - mConcavePairsStartIndex;
|
return mNbPairs - mConcavePairsStartIndex;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the starting index of the convex vs concave pairs
|
// Return the starting index of the convex vs concave pairs
|
||||||
inline uint64 OverlappingPairs::getConvexVsConcavePairsStartIndex() const {
|
RP3D_FORCE_INLINE uint64 OverlappingPairs::getConvexVsConcavePairsStartIndex() const {
|
||||||
return mConcavePairsStartIndex;
|
return mConcavePairsStartIndex;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a reference to the temporary memory allocator
|
// Return a reference to the temporary memory allocator
|
||||||
inline MemoryAllocator& OverlappingPairs::getTemporaryAllocator() {
|
RP3D_FORCE_INLINE MemoryAllocator& OverlappingPairs::getTemporaryAllocator() {
|
||||||
return mTempMemoryAllocator;
|
return mTempMemoryAllocator;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set if we need to test a given pair for overlap
|
// Set if we need to test a given pair for overlap
|
||||||
inline void OverlappingPairs::setNeedToTestOverlap(uint64 pairId, bool needToTestOverlap) {
|
RP3D_FORCE_INLINE void OverlappingPairs::setNeedToTestOverlap(uint64 pairId, bool needToTestOverlap) {
|
||||||
assert(mMapPairIdToPairIndex.containsKey(pairId));
|
assert(mMapPairIdToPairIndex.containsKey(pairId));
|
||||||
mNeedToTestOverlap[mMapPairIdToPairIndex[pairId]] = needToTestOverlap;
|
mNeedToTestOverlap[mMapPairIdToPairIndex[pairId]] = needToTestOverlap;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the two colliders of the pair were already colliding the previous frame
|
// Return true if the two colliders of the pair were already colliding the previous frame
|
||||||
inline bool OverlappingPairs::getCollidingInPreviousFrame(uint64 pairId) const {
|
RP3D_FORCE_INLINE bool OverlappingPairs::getCollidingInPreviousFrame(uint64 pairId) const {
|
||||||
assert(mMapPairIdToPairIndex.containsKey(pairId));
|
assert(mMapPairIdToPairIndex.containsKey(pairId));
|
||||||
return mCollidingInPreviousFrame[mMapPairIdToPairIndex[pairId]];
|
return mCollidingInPreviousFrame[mMapPairIdToPairIndex[pairId]];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set to true if the two colliders of the pair were already colliding the previous frame
|
// Set to true if the two colliders of the pair were already colliding the previous frame
|
||||||
inline void OverlappingPairs::setCollidingInPreviousFrame(uint64 pairId, bool wereCollidingInPreviousFrame) {
|
RP3D_FORCE_INLINE void OverlappingPairs::setCollidingInPreviousFrame(uint64 pairId, bool wereCollidingInPreviousFrame) {
|
||||||
assert(mMapPairIdToPairIndex.containsKey(pairId));
|
assert(mMapPairIdToPairIndex.containsKey(pairId));
|
||||||
mCollidingInPreviousFrame[mMapPairIdToPairIndex[pairId]] = wereCollidingInPreviousFrame;
|
mCollidingInPreviousFrame[mMapPairIdToPairIndex[pairId]] = wereCollidingInPreviousFrame;
|
||||||
}
|
}
|
||||||
|
@ -412,7 +412,7 @@ inline void OverlappingPairs::setCollidingInPreviousFrame(uint64 pairId, bool we
|
||||||
#ifdef IS_RP3D_PROFILING_ENABLED
|
#ifdef IS_RP3D_PROFILING_ENABLED
|
||||||
|
|
||||||
// Set the profiler
|
// Set the profiler
|
||||||
inline void OverlappingPairs::setProfiler(Profiler* profiler) {
|
RP3D_FORCE_INLINE void OverlappingPairs::setProfiler(Profiler* profiler) {
|
||||||
mProfiler = profiler;
|
mProfiler = profiler;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -193,7 +193,7 @@ class PhysicsCommon {
|
||||||
/**
|
/**
|
||||||
* @return A pointer to the current logger
|
* @return A pointer to the current logger
|
||||||
*/
|
*/
|
||||||
inline Logger* PhysicsCommon::getLogger() {
|
RP3D_FORCE_INLINE Logger* PhysicsCommon::getLogger() {
|
||||||
return mLogger;
|
return mLogger;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -201,7 +201,7 @@ inline Logger* PhysicsCommon::getLogger() {
|
||||||
/**
|
/**
|
||||||
* @param logger A pointer to the logger to use
|
* @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;
|
mLogger = logger;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -489,7 +489,7 @@ class PhysicsWorld {
|
||||||
* @param CollisionDispatch Pointer to a collision dispatch object describing
|
* @param CollisionDispatch Pointer to a collision dispatch object describing
|
||||||
* which collision detection algorithm to use for two given collision shapes
|
* which collision detection algorithm to use for two given collision shapes
|
||||||
*/
|
*/
|
||||||
inline CollisionDispatch& PhysicsWorld::getCollisionDispatch() {
|
RP3D_FORCE_INLINE CollisionDispatch& PhysicsWorld::getCollisionDispatch() {
|
||||||
return mCollisionDetection.getCollisionDispatch();
|
return mCollisionDetection.getCollisionDispatch();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -500,7 +500,7 @@ inline CollisionDispatch& PhysicsWorld::getCollisionDispatch() {
|
||||||
* @param raycastWithCategoryMaskBits Bits mask corresponding to the category of
|
* @param raycastWithCategoryMaskBits Bits mask corresponding to the category of
|
||||||
* bodies to be raycasted
|
* bodies to be raycasted
|
||||||
*/
|
*/
|
||||||
inline void PhysicsWorld::raycast(const Ray& ray,
|
RP3D_FORCE_INLINE void PhysicsWorld::raycast(const Ray& ray,
|
||||||
RaycastCallback* raycastCallback,
|
RaycastCallback* raycastCallback,
|
||||||
unsigned short raycastWithCategoryMaskBits) const {
|
unsigned short raycastWithCategoryMaskBits) const {
|
||||||
mCollisionDetection.raycast(raycastCallback, ray, raycastWithCategoryMaskBits);
|
mCollisionDetection.raycast(raycastCallback, ray, raycastWithCategoryMaskBits);
|
||||||
|
@ -516,7 +516,7 @@ inline void PhysicsWorld::raycast(const Ray& ray,
|
||||||
* @param body2 Pointer to the second body to test
|
* @param body2 Pointer to the second body to test
|
||||||
* @param callback Pointer to the object with the callback method
|
* @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);
|
mCollisionDetection.testCollision(body1, body2, callback);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -529,7 +529,7 @@ inline void PhysicsWorld::testCollision(CollisionBody* body1, CollisionBody* bod
|
||||||
* @param body Pointer to the body against which we need to test collision
|
* @param body Pointer to the body against which we need to test collision
|
||||||
* @param callback Pointer to the object with the callback method to report contacts
|
* @param 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);
|
mCollisionDetection.testCollision(body, callback);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -541,7 +541,7 @@ inline void PhysicsWorld::testCollision(CollisionBody* body, CollisionCallback&
|
||||||
/**
|
/**
|
||||||
* @param callback Pointer to the object with the callback method to report contacts
|
* @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);
|
mCollisionDetection.testCollision(callback);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -553,7 +553,7 @@ inline void PhysicsWorld::testCollision(CollisionCallback& callback) {
|
||||||
* @param body Pointer to the collision body to test overlap with
|
* @param body Pointer to the collision body to test overlap with
|
||||||
* @param overlapCallback Pointer to the callback class to report overlap
|
* @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);
|
mCollisionDetection.testOverlap(body, overlapCallback);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -564,12 +564,12 @@ inline void PhysicsWorld::testOverlap(CollisionBody* body, OverlapCallback& over
|
||||||
/**
|
/**
|
||||||
* @param overlapCallback Pointer to the callback class to report overlap
|
* @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);
|
mCollisionDetection.testOverlap(overlapCallback);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a reference to the memory manager of the world
|
// Return a reference to the memory manager of the world
|
||||||
inline MemoryManager& PhysicsWorld::getMemoryManager() {
|
RP3D_FORCE_INLINE MemoryManager& PhysicsWorld::getMemoryManager() {
|
||||||
return mMemoryManager;
|
return mMemoryManager;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -577,7 +577,7 @@ inline MemoryManager& PhysicsWorld::getMemoryManager() {
|
||||||
/**
|
/**
|
||||||
* @return Name of the world
|
* @return Name of the world
|
||||||
*/
|
*/
|
||||||
inline const std::string& PhysicsWorld::getName() const {
|
RP3D_FORCE_INLINE const std::string& PhysicsWorld::getName() const {
|
||||||
return mName;
|
return mName;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -587,7 +587,7 @@ inline const std::string& PhysicsWorld::getName() const {
|
||||||
/**
|
/**
|
||||||
* @return A pointer to the profiler
|
* @return A pointer to the profiler
|
||||||
*/
|
*/
|
||||||
inline Profiler* PhysicsWorld::getProfiler() {
|
RP3D_FORCE_INLINE Profiler* PhysicsWorld::getProfiler() {
|
||||||
return mProfiler;
|
return mProfiler;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -597,7 +597,7 @@ inline Profiler* PhysicsWorld::getProfiler() {
|
||||||
/**
|
/**
|
||||||
* @return The number of iterations of the velocity constraint solver
|
* @return The number of iterations of the velocity constraint solver
|
||||||
*/
|
*/
|
||||||
inline uint PhysicsWorld::getNbIterationsVelocitySolver() const {
|
RP3D_FORCE_INLINE uint PhysicsWorld::getNbIterationsVelocitySolver() const {
|
||||||
return mNbVelocitySolverIterations;
|
return mNbVelocitySolverIterations;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -605,7 +605,7 @@ inline uint PhysicsWorld::getNbIterationsVelocitySolver() const {
|
||||||
/**
|
/**
|
||||||
* @return The number of iterations of the position constraint solver
|
* @return The number of iterations of the position constraint solver
|
||||||
*/
|
*/
|
||||||
inline uint PhysicsWorld::getNbIterationsPositionSolver() const {
|
RP3D_FORCE_INLINE uint PhysicsWorld::getNbIterationsPositionSolver() const {
|
||||||
return mNbPositionSolverIterations;
|
return mNbPositionSolverIterations;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -613,7 +613,7 @@ inline uint PhysicsWorld::getNbIterationsPositionSolver() const {
|
||||||
/**
|
/**
|
||||||
* @param technique Technique used for the position correction (Baumgarte or Split Impulses)
|
* @param technique Technique used for the position correction (Baumgarte or Split Impulses)
|
||||||
*/
|
*/
|
||||||
inline void PhysicsWorld::setContactsPositionCorrectionTechnique(
|
RP3D_FORCE_INLINE void PhysicsWorld::setContactsPositionCorrectionTechnique(
|
||||||
ContactsPositionCorrectionTechnique technique) {
|
ContactsPositionCorrectionTechnique technique) {
|
||||||
if (technique == ContactsPositionCorrectionTechnique::BAUMGARTE_CONTACTS) {
|
if (technique == ContactsPositionCorrectionTechnique::BAUMGARTE_CONTACTS) {
|
||||||
mContactSolverSystem.setIsSplitImpulseActive(false);
|
mContactSolverSystem.setIsSplitImpulseActive(false);
|
||||||
|
@ -627,7 +627,7 @@ inline void PhysicsWorld::setContactsPositionCorrectionTechnique(
|
||||||
/**
|
/**
|
||||||
* @return The current gravity vector (in meter per seconds squared)
|
* @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;
|
return mConfig.gravity;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -635,7 +635,7 @@ inline Vector3 PhysicsWorld::getGravity() const {
|
||||||
/**
|
/**
|
||||||
* @return True if the gravity is enabled in the world
|
* @return True if the gravity is enabled in the world
|
||||||
*/
|
*/
|
||||||
inline bool PhysicsWorld::isGravityEnabled() const {
|
RP3D_FORCE_INLINE bool PhysicsWorld::isGravityEnabled() const {
|
||||||
return mIsGravityEnabled;
|
return mIsGravityEnabled;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -643,7 +643,7 @@ inline bool PhysicsWorld::isGravityEnabled() const {
|
||||||
/**
|
/**
|
||||||
* @return True if the sleeping technique is enabled and false otherwise
|
* @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;
|
return mIsSleepingEnabled;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -651,7 +651,7 @@ inline bool PhysicsWorld::isSleepingEnabled() const {
|
||||||
/**
|
/**
|
||||||
* @return The sleep linear velocity (in meters per second)
|
* @return The sleep linear velocity (in meters per second)
|
||||||
*/
|
*/
|
||||||
inline decimal PhysicsWorld::getSleepLinearVelocity() const {
|
RP3D_FORCE_INLINE decimal PhysicsWorld::getSleepLinearVelocity() const {
|
||||||
return mSleepLinearVelocity;
|
return mSleepLinearVelocity;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -659,7 +659,7 @@ inline decimal PhysicsWorld::getSleepLinearVelocity() const {
|
||||||
/**
|
/**
|
||||||
* @return The sleep angular velocity (in radian per second)
|
* @return The sleep angular velocity (in radian per second)
|
||||||
*/
|
*/
|
||||||
inline decimal PhysicsWorld::getSleepAngularVelocity() const {
|
RP3D_FORCE_INLINE decimal PhysicsWorld::getSleepAngularVelocity() const {
|
||||||
return mSleepAngularVelocity;
|
return mSleepAngularVelocity;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -667,7 +667,7 @@ inline decimal PhysicsWorld::getSleepAngularVelocity() const {
|
||||||
/**
|
/**
|
||||||
* @return Time a body is required to stay still before sleeping (in seconds)
|
* @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;
|
return mTimeBeforeSleep;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -677,7 +677,7 @@ inline decimal PhysicsWorld::getTimeBeforeSleep() const {
|
||||||
* @param eventListener Pointer to the event listener object that will receive
|
* @param eventListener Pointer to the event listener object that will receive
|
||||||
* event callbacks during the simulation
|
* event callbacks during the simulation
|
||||||
*/
|
*/
|
||||||
inline void PhysicsWorld::setEventListener(EventListener* eventListener) {
|
RP3D_FORCE_INLINE void PhysicsWorld::setEventListener(EventListener* eventListener) {
|
||||||
mEventListener = eventListener;
|
mEventListener = eventListener;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -686,7 +686,7 @@ inline void PhysicsWorld::setEventListener(EventListener* eventListener) {
|
||||||
/**
|
/**
|
||||||
* @return The number of collision bodies in the physics world
|
* @return The number of collision bodies in the physics world
|
||||||
*/
|
*/
|
||||||
inline uint PhysicsWorld::getNbCollisionBodies() const {
|
RP3D_FORCE_INLINE uint PhysicsWorld::getNbCollisionBodies() const {
|
||||||
return mCollisionBodies.size();
|
return mCollisionBodies.size();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -694,7 +694,7 @@ inline uint PhysicsWorld::getNbCollisionBodies() const {
|
||||||
/**
|
/**
|
||||||
* @return The number of rigid bodies in the physics world
|
* @return The number of rigid bodies in the physics world
|
||||||
*/
|
*/
|
||||||
inline uint PhysicsWorld::getNbRigidBodies() const {
|
RP3D_FORCE_INLINE uint PhysicsWorld::getNbRigidBodies() const {
|
||||||
return mRigidBodies.size();
|
return mRigidBodies.size();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -702,7 +702,7 @@ inline uint PhysicsWorld::getNbRigidBodies() const {
|
||||||
/**
|
/**
|
||||||
* @return True if the debug rendering is enabled and false otherwise
|
* @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;
|
return mIsDebugRenderingEnabled;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -710,7 +710,7 @@ inline bool PhysicsWorld::getIsDebugRenderingEnabled() const {
|
||||||
/**
|
/**
|
||||||
* @param isEnabled True if you want to enable the debug rendering and false otherwise
|
* @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;
|
mIsDebugRenderingEnabled = isEnabled;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -718,7 +718,7 @@ inline void PhysicsWorld::setIsDebugRenderingEnabled(bool isEnabled) {
|
||||||
/**
|
/**
|
||||||
* @return A reference to the DebugRenderer object of the world
|
* @return A reference to the DebugRenderer object of the world
|
||||||
*/
|
*/
|
||||||
inline DebugRenderer& PhysicsWorld::getDebugRenderer() {
|
RP3D_FORCE_INLINE DebugRenderer& PhysicsWorld::getDebugRenderer() {
|
||||||
return mDebugRenderer;
|
return mDebugRenderer;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -120,28 +120,28 @@ class Timer {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return the timestep of the physics engine
|
// Return the timestep of the physics engine
|
||||||
inline double Timer::getTimeStep() const {
|
RP3D_FORCE_INLINE double Timer::getTimeStep() const {
|
||||||
return mTimeStep;
|
return mTimeStep;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the timestep of the physics engine
|
// 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);
|
assert(timeStep > 0.0f);
|
||||||
mTimeStep = timeStep;
|
mTimeStep = timeStep;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the current time
|
// Return the current time
|
||||||
inline long double Timer::getPhysicsTime() const {
|
RP3D_FORCE_INLINE long double Timer::getPhysicsTime() const {
|
||||||
return mLastUpdateTime;
|
return mLastUpdateTime;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return if the timer is running
|
// Return if the timer is running
|
||||||
inline bool Timer::getIsRunning() const {
|
RP3D_FORCE_INLINE bool Timer::getIsRunning() const {
|
||||||
return mIsRunning;
|
return mIsRunning;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Start the timer
|
// Start the timer
|
||||||
inline void Timer::start() {
|
RP3D_FORCE_INLINE void Timer::start() {
|
||||||
if (!mIsRunning) {
|
if (!mIsRunning) {
|
||||||
|
|
||||||
// Get the current system time
|
// Get the current system time
|
||||||
|
@ -153,17 +153,17 @@ inline void Timer::start() {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Stop the timer
|
// Stop the timer
|
||||||
inline void Timer::stop() {
|
RP3D_FORCE_INLINE void Timer::stop() {
|
||||||
mIsRunning = false;
|
mIsRunning = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// True if it's possible to take a new step
|
// 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);
|
return (mAccumulator >= mTimeStep);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Take a new step => update the timer by adding the timeStep value to the current time
|
// 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);
|
assert(mIsRunning);
|
||||||
|
|
||||||
// Update the accumulator value
|
// Update the accumulator value
|
||||||
|
@ -171,12 +171,12 @@ inline void Timer::nextStep() {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Compute the interpolation factor
|
// Compute the interpolation factor
|
||||||
inline decimal Timer::computeInterpolationFactor() {
|
RP3D_FORCE_INLINE decimal Timer::computeInterpolationFactor() {
|
||||||
return (decimal(mAccumulator / mTimeStep));
|
return (decimal(mAccumulator / mTimeStep));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Compute the time since the last update() call and add it to the accumulator
|
// 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
|
// Get the current system time
|
||||||
long double currentTime = getCurrentSystemTime();
|
long double currentTime = getCurrentSystemTime();
|
||||||
|
|
|
@ -151,57 +151,57 @@ class Matrix2x2 {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Constructor of the class Matrix2x2
|
// Constructor of the class Matrix2x2
|
||||||
inline Matrix2x2::Matrix2x2() {
|
RP3D_FORCE_INLINE Matrix2x2::Matrix2x2() {
|
||||||
|
|
||||||
// Initialize all values in the matrix to zero
|
// Initialize all values in the matrix to zero
|
||||||
setAllValues(0.0, 0.0, 0.0, 0.0);
|
setAllValues(0.0, 0.0, 0.0, 0.0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Constructor
|
// Constructor
|
||||||
inline Matrix2x2::Matrix2x2(decimal value) {
|
RP3D_FORCE_INLINE Matrix2x2::Matrix2x2(decimal value) {
|
||||||
setAllValues(value, value, value, value);
|
setAllValues(value, value, value, value);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Constructor with arguments
|
// 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
|
// Initialize the matrix with the values
|
||||||
setAllValues(a1, a2, b1, b2);
|
setAllValues(a1, a2, b1, b2);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Copy-constructor
|
// 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],
|
setAllValues(matrix.mRows[0][0], matrix.mRows[0][1],
|
||||||
matrix.mRows[1][0], matrix.mRows[1][1]);
|
matrix.mRows[1][0], matrix.mRows[1][1]);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Method to set all the values in the matrix
|
// 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) {
|
decimal b1, decimal b2) {
|
||||||
mRows[0][0] = a1; mRows[0][1] = a2;
|
mRows[0][0] = a1; mRows[0][1] = a2;
|
||||||
mRows[1][0] = b1; mRows[1][1] = b2;
|
mRows[1][0] = b1; mRows[1][1] = b2;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the matrix to zero
|
// Set the matrix to zero
|
||||||
inline void Matrix2x2::setToZero() {
|
RP3D_FORCE_INLINE void Matrix2x2::setToZero() {
|
||||||
mRows[0].setToZero();
|
mRows[0].setToZero();
|
||||||
mRows[1].setToZero();
|
mRows[1].setToZero();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a column
|
// Return a column
|
||||||
inline Vector2 Matrix2x2::getColumn(int i) const {
|
RP3D_FORCE_INLINE Vector2 Matrix2x2::getColumn(int i) const {
|
||||||
assert(i>= 0 && i<2);
|
assert(i>= 0 && i<2);
|
||||||
return Vector2(mRows[0][i], mRows[1][i]);
|
return Vector2(mRows[0][i], mRows[1][i]);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a row
|
// Return a row
|
||||||
inline Vector2 Matrix2x2::getRow(int i) const {
|
RP3D_FORCE_INLINE Vector2 Matrix2x2::getRow(int i) const {
|
||||||
assert(i>= 0 && i<2);
|
assert(i>= 0 && i<2);
|
||||||
return mRows[i];
|
return mRows[i];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the transpose matrix
|
// Return the transpose matrix
|
||||||
inline Matrix2x2 Matrix2x2::getTranspose() const {
|
RP3D_FORCE_INLINE Matrix2x2 Matrix2x2::getTranspose() const {
|
||||||
|
|
||||||
// Return the transpose matrix
|
// Return the transpose matrix
|
||||||
return Matrix2x2(mRows[0][0], mRows[1][0],
|
return Matrix2x2(mRows[0][0], mRows[1][0],
|
||||||
|
@ -209,45 +209,45 @@ inline Matrix2x2 Matrix2x2::getTranspose() const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the determinant of the matrix
|
// 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
|
// Compute and return the determinant of the matrix
|
||||||
return mRows[0][0] * mRows[1][1] - mRows[1][0] * mRows[0][1];
|
return mRows[0][0] * mRows[1][1] - mRows[1][0] * mRows[0][1];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the trace of the matrix
|
// Return the trace of the matrix
|
||||||
inline decimal Matrix2x2::getTrace() const {
|
RP3D_FORCE_INLINE decimal Matrix2x2::getTrace() const {
|
||||||
|
|
||||||
// Compute and return the trace
|
// Compute and return the trace
|
||||||
return (mRows[0][0] + mRows[1][1]);
|
return (mRows[0][0] + mRows[1][1]);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the matrix to the identity matrix
|
// 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[0][0] = 1.0; mRows[0][1] = 0.0;
|
||||||
mRows[1][0] = 0.0; mRows[1][1] = 1.0;
|
mRows[1][0] = 0.0; mRows[1][1] = 1.0;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the 2x2 identity matrix
|
// Return the 2x2 identity matrix
|
||||||
inline Matrix2x2 Matrix2x2::identity() {
|
RP3D_FORCE_INLINE Matrix2x2 Matrix2x2::identity() {
|
||||||
|
|
||||||
// Return the isdentity matrix
|
// Return the isdentity matrix
|
||||||
return Matrix2x2(1.0, 0.0, 0.0, 1.0);
|
return Matrix2x2(1.0, 0.0, 0.0, 1.0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the 2x2 zero matrix
|
// 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 Matrix2x2(0.0, 0.0, 0.0, 0.0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the matrix with absolute values
|
// Return the matrix with absolute values
|
||||||
inline Matrix2x2 Matrix2x2::getAbsoluteMatrix() const {
|
RP3D_FORCE_INLINE Matrix2x2 Matrix2x2::getAbsoluteMatrix() const {
|
||||||
return Matrix2x2(fabs(mRows[0][0]), fabs(mRows[0][1]),
|
return Matrix2x2(fabs(mRows[0][0]), fabs(mRows[0][1]),
|
||||||
fabs(mRows[1][0]), fabs(mRows[1][1]));
|
fabs(mRows[1][0]), fabs(mRows[1][1]));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for addition
|
// 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],
|
return Matrix2x2(matrix1.mRows[0][0] + matrix2.mRows[0][0],
|
||||||
matrix1.mRows[0][1] + matrix2.mRows[0][1],
|
matrix1.mRows[0][1] + matrix2.mRows[0][1],
|
||||||
matrix1.mRows[1][0] + matrix2.mRows[1][0],
|
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
|
// 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],
|
return Matrix2x2(matrix1.mRows[0][0] - matrix2.mRows[0][0],
|
||||||
matrix1.mRows[0][1] - matrix2.mRows[0][1],
|
matrix1.mRows[0][1] - matrix2.mRows[0][1],
|
||||||
matrix1.mRows[1][0] - matrix2.mRows[1][0],
|
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
|
// 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],
|
return Matrix2x2(-matrix.mRows[0][0], -matrix.mRows[0][1],
|
||||||
-matrix.mRows[1][0], -matrix.mRows[1][1]);
|
-matrix.mRows[1][0], -matrix.mRows[1][1]);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for multiplication with a number
|
// 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,
|
return Matrix2x2(matrix.mRows[0][0] * nb, matrix.mRows[0][1] * nb,
|
||||||
matrix.mRows[1][0] * nb, matrix.mRows[1][1] * nb);
|
matrix.mRows[1][0] * nb, matrix.mRows[1][1] * nb);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for multiplication with a matrix
|
// 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;
|
return nb * matrix;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for matrix multiplication
|
// 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] *
|
return Matrix2x2(matrix1.mRows[0][0] * matrix2.mRows[0][0] + matrix1.mRows[0][1] *
|
||||||
matrix2.mRows[1][0],
|
matrix2.mRows[1][0],
|
||||||
matrix1.mRows[0][0] * matrix2.mRows[0][1] + matrix1.mRows[0][1] *
|
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
|
// 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,
|
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);
|
matrix.mRows[1][0]*vector.x + matrix.mRows[1][1]*vector.y);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for equality condition
|
// 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] &&
|
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]);
|
mRows[1][0] == matrix.mRows[1][0] && mRows[1][1] == matrix.mRows[1][1]);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for the is different condition
|
// 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);
|
return !(*this == matrix);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for addition with assignment
|
// 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[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];
|
mRows[1][0] += matrix.mRows[1][0]; mRows[1][1] += matrix.mRows[1][1];
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for substraction with assignment
|
// 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[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];
|
mRows[1][0] -= matrix.mRows[1][0]; mRows[1][1] -= matrix.mRows[1][1];
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for multiplication with a number with assignment
|
// 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[0][0] *= nb; mRows[0][1] *= nb;
|
||||||
mRows[1][0] *= nb; mRows[1][1] *= nb;
|
mRows[1][0] *= nb; mRows[1][1] *= nb;
|
||||||
return *this;
|
return *this;
|
||||||
|
@ -332,19 +332,19 @@ inline Matrix2x2& Matrix2x2::operator*=(decimal nb) {
|
||||||
// Overloaded operator to return a row of the matrix.
|
// Overloaded operator to return a row of the matrix.
|
||||||
/// This operator is also used to access a matrix value using the syntax
|
/// This operator is also used to access a matrix value using the syntax
|
||||||
/// matrix[row][col].
|
/// matrix[row][col].
|
||||||
inline const Vector2& Matrix2x2::operator[](int row) const {
|
RP3D_FORCE_INLINE const Vector2& Matrix2x2::operator[](int row) const {
|
||||||
return mRows[row];
|
return mRows[row];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator to return a row of the matrix.
|
// Overloaded operator to return a row of the matrix.
|
||||||
/// This operator is also used to access a matrix value using the syntax
|
/// This operator is also used to access a matrix value using the syntax
|
||||||
/// matrix[row][col].
|
/// matrix[row][col].
|
||||||
inline Vector2& Matrix2x2::operator[](int row) {
|
RP3D_FORCE_INLINE Vector2& Matrix2x2::operator[](int row) {
|
||||||
return mRows[row];
|
return mRows[row];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get the string representation
|
// 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]) + "," +
|
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]) + ")";
|
std::to_string(mRows[1][0]) + "," + std::to_string(mRows[1][1]) + ")";
|
||||||
}
|
}
|
||||||
|
|
|
@ -158,18 +158,18 @@ class Matrix3x3 {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Constructor of the class Matrix3x3
|
// Constructor of the class Matrix3x3
|
||||||
inline Matrix3x3::Matrix3x3() {
|
RP3D_FORCE_INLINE Matrix3x3::Matrix3x3() {
|
||||||
// Initialize all values in the matrix to zero
|
// 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);
|
setAllValues(0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Constructor
|
// Constructor
|
||||||
inline Matrix3x3::Matrix3x3(decimal value) {
|
RP3D_FORCE_INLINE Matrix3x3::Matrix3x3(decimal value) {
|
||||||
setAllValues(value, value, value, value, value, value, value, value, value);
|
setAllValues(value, value, value, value, value, value, value, value, value);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Constructor with arguments
|
// 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 b1, decimal b2, decimal b3,
|
||||||
decimal c1, decimal c2, decimal c3) {
|
decimal c1, decimal c2, decimal c3) {
|
||||||
// Initialize the matrix with the values
|
// Initialize the matrix with the values
|
||||||
|
@ -177,14 +177,14 @@ inline Matrix3x3::Matrix3x3(decimal a1, decimal a2, decimal a3,
|
||||||
}
|
}
|
||||||
|
|
||||||
// Copy-constructor
|
// 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],
|
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[1][0], matrix.mRows[1][1], matrix.mRows[1][2],
|
||||||
matrix.mRows[2][0], matrix.mRows[2][1], matrix.mRows[2][2]);
|
matrix.mRows[2][0], matrix.mRows[2][1], matrix.mRows[2][2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Method to set all the values in the matrix
|
// 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 b1, decimal b2, decimal b3,
|
||||||
decimal c1, decimal c2, decimal c3) {
|
decimal c1, decimal c2, decimal c3) {
|
||||||
mRows[0][0] = a1; mRows[0][1] = a2; mRows[0][2] = a3;
|
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
|
// Set the matrix to zero
|
||||||
inline void Matrix3x3::setToZero() {
|
RP3D_FORCE_INLINE void Matrix3x3::setToZero() {
|
||||||
mRows[0].setToZero();
|
mRows[0].setToZero();
|
||||||
mRows[1].setToZero();
|
mRows[1].setToZero();
|
||||||
mRows[2].setToZero();
|
mRows[2].setToZero();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a column
|
// Return a column
|
||||||
inline Vector3 Matrix3x3::getColumn(int i) const {
|
RP3D_FORCE_INLINE Vector3 Matrix3x3::getColumn(int i) const {
|
||||||
assert(i>= 0 && i<3);
|
assert(i>= 0 && i<3);
|
||||||
return Vector3(mRows[0][i], mRows[1][i], mRows[2][i]);
|
return Vector3(mRows[0][i], mRows[1][i], mRows[2][i]);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a row
|
// Return a row
|
||||||
inline Vector3 Matrix3x3::getRow(int i) const {
|
RP3D_FORCE_INLINE Vector3 Matrix3x3::getRow(int i) const {
|
||||||
assert(i>= 0 && i<3);
|
assert(i>= 0 && i<3);
|
||||||
return mRows[i];
|
return mRows[i];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the transpose matrix
|
// Return the transpose matrix
|
||||||
inline Matrix3x3 Matrix3x3::getTranspose() const {
|
RP3D_FORCE_INLINE Matrix3x3 Matrix3x3::getTranspose() const {
|
||||||
|
|
||||||
// Return the transpose matrix
|
// Return the transpose matrix
|
||||||
return Matrix3x3(mRows[0][0], mRows[1][0], mRows[2][0],
|
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
|
// 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
|
// Compute and return the determinant of the matrix
|
||||||
return (mRows[0][0]*(mRows[1][1]*mRows[2][2]-mRows[2][1]*mRows[1][2]) -
|
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
|
// Return the trace of the matrix
|
||||||
inline decimal Matrix3x3::getTrace() const {
|
RP3D_FORCE_INLINE decimal Matrix3x3::getTrace() const {
|
||||||
|
|
||||||
// Compute and return the trace
|
// Compute and return the trace
|
||||||
return (mRows[0][0] + mRows[1][1] + mRows[2][2]);
|
return (mRows[0][0] + mRows[1][1] + mRows[2][2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the matrix to the identity matrix
|
// 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[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[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;
|
mRows[2][0] = 0.0; mRows[2][1] = 0.0; mRows[2][2] = 1.0;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the 3x3 identity matrix
|
// 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 Matrix3x3(1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the 3x3 zero matrix
|
// 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 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
|
// Return a skew-symmetric matrix using a given vector that can be used
|
||||||
// to compute cross product with another vector using matrix multiplication
|
// 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 Matrix3x3(0, -vector.z, vector.y, vector.z, 0, -vector.x, -vector.y, vector.x, 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the matrix with absolute values
|
// Return the matrix with absolute values
|
||||||
inline Matrix3x3 Matrix3x3::getAbsoluteMatrix() const {
|
RP3D_FORCE_INLINE Matrix3x3 Matrix3x3::getAbsoluteMatrix() const {
|
||||||
return Matrix3x3(std::fabs(mRows[0][0]), std::fabs(mRows[0][1]), std::fabs(mRows[0][2]),
|
return Matrix3x3(std::fabs(mRows[0][0]), std::fabs(mRows[0][1]), std::fabs(mRows[0][2]),
|
||||||
std::fabs(mRows[1][0]), std::fabs(mRows[1][1]), std::fabs(mRows[1][2]),
|
std::fabs(mRows[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]));
|
std::fabs(mRows[2][0]), std::fabs(mRows[2][1]), std::fabs(mRows[2][2]));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for addition
|
// 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] +
|
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],
|
matrix2.mRows[0][1], matrix1.mRows[0][2] + matrix2.mRows[0][2],
|
||||||
matrix1.mRows[1][0] + matrix2.mRows[1][0], matrix1.mRows[1][1] +
|
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
|
// 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] -
|
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],
|
matrix2.mRows[0][1], matrix1.mRows[0][2] - matrix2.mRows[0][2],
|
||||||
matrix1.mRows[1][0] - matrix2.mRows[1][0], matrix1.mRows[1][1] -
|
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
|
// 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],
|
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[1][0], -matrix.mRows[1][1], -matrix.mRows[1][2],
|
||||||
-matrix.mRows[2][0], -matrix.mRows[2][1], -matrix.mRows[2][2]);
|
-matrix.mRows[2][0], -matrix.mRows[2][1], -matrix.mRows[2][2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for multiplication with a number
|
// 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,
|
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[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);
|
matrix.mRows[2][0] * nb, matrix.mRows[2][1] * nb, matrix.mRows[2][2] * nb);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for multiplication with a matrix
|
// 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;
|
return nb * matrix;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for matrix multiplication
|
// 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] *
|
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],
|
matrix2.mRows[1][0] + matrix1.mRows[0][2]*matrix2.mRows[2][0],
|
||||||
matrix1.mRows[0][0]*matrix2.mRows[0][1] + matrix1.mRows[0][1] *
|
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
|
// 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 +
|
return Vector3(matrix.mRows[0][0]*vector.x + matrix.mRows[0][1]*vector.y +
|
||||||
matrix.mRows[0][2]*vector.z,
|
matrix.mRows[0][2]*vector.z,
|
||||||
matrix.mRows[1][0]*vector.x + matrix.mRows[1][1]*vector.y +
|
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
|
// 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] &&
|
return (mRows[0][0] == matrix.mRows[0][0] && mRows[0][1] == matrix.mRows[0][1] &&
|
||||||
mRows[0][2] == matrix.mRows[0][2] &&
|
mRows[0][2] == matrix.mRows[0][2] &&
|
||||||
mRows[1][0] == matrix.mRows[1][0] && mRows[1][1] == matrix.mRows[1][1] &&
|
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
|
// 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);
|
return !(*this == matrix);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for addition with assignment
|
// 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][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[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];
|
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
|
// 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][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[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];
|
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
|
// 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[0][0] *= nb; mRows[0][1] *= nb; mRows[0][2] *= nb;
|
||||||
mRows[1][0] *= nb; mRows[1][1] *= nb; mRows[1][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;
|
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.
|
// Overloaded operator to return a row of the matrix.
|
||||||
/// This operator is also used to access a matrix value using the syntax
|
/// This operator is also used to access a matrix value using the syntax
|
||||||
/// matrix[row][col].
|
/// matrix[row][col].
|
||||||
inline const Vector3& Matrix3x3::operator[](int row) const {
|
RP3D_FORCE_INLINE const Vector3& Matrix3x3::operator[](int row) const {
|
||||||
return mRows[row];
|
return mRows[row];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator to return a row of the matrix.
|
// Overloaded operator to return a row of the matrix.
|
||||||
/// This operator is also used to access a matrix value using the syntax
|
/// This operator is also used to access a matrix value using the syntax
|
||||||
/// matrix[row][col].
|
/// matrix[row][col].
|
||||||
inline Vector3& Matrix3x3::operator[](int row) {
|
RP3D_FORCE_INLINE Vector3& Matrix3x3::operator[](int row) {
|
||||||
return mRows[row];
|
return mRows[row];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get the string representation
|
// 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]) + "," +
|
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[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]) + ")";
|
std::to_string(mRows[2][0]) + "," + std::to_string(mRows[2][1]) + "," + std::to_string(mRows[2][2]) + ")";
|
||||||
|
|
|
@ -182,28 +182,28 @@ struct Quaternion {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Constructor of the class
|
// 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
|
// 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) {
|
:x(newX), y(newY), z(newZ), w(newW) {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Constructor with the component w and the vector v=(x y z)
|
// 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)
|
// 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
|
// 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;
|
x = newX;
|
||||||
y = newY;
|
y = newY;
|
||||||
z = newZ;
|
z = newZ;
|
||||||
|
@ -211,7 +211,7 @@ inline void Quaternion::setAllValues(decimal newX, decimal newY, decimal newZ, d
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the quaternion to zero
|
// Set the quaternion to zero
|
||||||
inline void Quaternion::setToZero() {
|
RP3D_FORCE_INLINE void Quaternion::setToZero() {
|
||||||
x = 0;
|
x = 0;
|
||||||
y = 0;
|
y = 0;
|
||||||
z = 0;
|
z = 0;
|
||||||
|
@ -219,7 +219,7 @@ inline void Quaternion::setToZero() {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set to the identity quaternion
|
// Set to the identity quaternion
|
||||||
inline void Quaternion::setToIdentity() {
|
RP3D_FORCE_INLINE void Quaternion::setToIdentity() {
|
||||||
x = 0;
|
x = 0;
|
||||||
y = 0;
|
y = 0;
|
||||||
z = 0;
|
z = 0;
|
||||||
|
@ -227,24 +227,24 @@ inline void Quaternion::setToIdentity() {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the vector v=(x y z) of the quaternion
|
// 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 the vector v
|
||||||
return Vector3(x, y, z);
|
return Vector3(x, y, z);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the length of the quaternion (inline)
|
// Return the length of the quaternion (RP3D_FORCE_INLINE)
|
||||||
inline decimal Quaternion::length() const {
|
RP3D_FORCE_INLINE decimal Quaternion::length() const {
|
||||||
return std::sqrt(x*x + y*y + z*z + w*w);
|
return std::sqrt(x*x + y*y + z*z + w*w);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the square of the length of the quaternion
|
// 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;
|
return x*x + y*y + z*z + w*w;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Normalize the quaternion
|
// Normalize the quaternion
|
||||||
inline void Quaternion::normalize() {
|
RP3D_FORCE_INLINE void Quaternion::normalize() {
|
||||||
|
|
||||||
decimal l = length();
|
decimal l = length();
|
||||||
|
|
||||||
|
@ -258,7 +258,7 @@ inline void Quaternion::normalize() {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Inverse the quaternion
|
// Inverse the quaternion
|
||||||
inline void Quaternion::inverse() {
|
RP3D_FORCE_INLINE void Quaternion::inverse() {
|
||||||
|
|
||||||
// Use the conjugate of the current quaternion
|
// Use the conjugate of the current quaternion
|
||||||
x = -x;
|
x = -x;
|
||||||
|
@ -267,7 +267,7 @@ inline void Quaternion::inverse() {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the unit quaternion
|
// Return the unit quaternion
|
||||||
inline Quaternion Quaternion::getUnit() const {
|
RP3D_FORCE_INLINE Quaternion Quaternion::getUnit() const {
|
||||||
decimal lengthQuaternion = length();
|
decimal lengthQuaternion = length();
|
||||||
|
|
||||||
// Check if the length is not equal to zero
|
// Check if the length is not equal to zero
|
||||||
|
@ -279,60 +279,60 @@ inline Quaternion Quaternion::getUnit() const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the identity quaternion
|
// 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 Quaternion(0.0, 0.0, 0.0, 1.0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the conjugate of the quaternion (inline)
|
// Return the conjugate of the quaternion (RP3D_FORCE_INLINE)
|
||||||
inline Quaternion Quaternion::getConjugate() const {
|
RP3D_FORCE_INLINE Quaternion Quaternion::getConjugate() const {
|
||||||
return Quaternion(-x, -y, -z, w);
|
return Quaternion(-x, -y, -z, w);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the inverse of the quaternion (inline)
|
// Return the inverse of the quaternion (RP3D_FORCE_INLINE)
|
||||||
inline Quaternion Quaternion::getInverse() const {
|
RP3D_FORCE_INLINE Quaternion Quaternion::getInverse() const {
|
||||||
|
|
||||||
// Return the conjugate quaternion
|
// Return the conjugate quaternion
|
||||||
return Quaternion(-x, -y, -z, w);
|
return Quaternion(-x, -y, -z, w);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Scalar product between two quaternions
|
// 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 (x*quaternion.x + y*quaternion.y + z*quaternion.z + w*quaternion.w);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the values are not NAN OR INF
|
// 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 std::isfinite(x) && std::isfinite(y) && std::isfinite(z) && std::isfinite(w);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if it is a unit quaternion
|
// 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 length = std::sqrt(x*x + y*y + z*z + w*w);
|
||||||
const decimal tolerance = 1e-5f;
|
const decimal tolerance = 1e-5f;
|
||||||
return std::abs(length - decimal(1.0)) < tolerance;
|
return std::abs(length - decimal(1.0)) < tolerance;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if it is a valid quaternion
|
// Return true if it is a valid quaternion
|
||||||
inline bool Quaternion::isValid() const {
|
RP3D_FORCE_INLINE bool Quaternion::isValid() const {
|
||||||
return isFinite() && isUnit();
|
return isFinite() && isUnit();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for the addition of two quaternions
|
// 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 the result quaternion
|
||||||
return Quaternion(x + quaternion.x, y + quaternion.y, z + quaternion.z, w + quaternion.w);
|
return Quaternion(x + quaternion.x, y + quaternion.y, z + quaternion.z, w + quaternion.w);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for the substraction of two quaternions
|
// 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 the result of the substraction
|
||||||
return Quaternion(x - quaternion.x, y - quaternion.y, z - quaternion.z, w - quaternion.w);
|
return Quaternion(x - quaternion.x, y - quaternion.y, z - quaternion.z, w - quaternion.w);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for addition with assignment
|
// 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;
|
x += quaternion.x;
|
||||||
y += quaternion.y;
|
y += quaternion.y;
|
||||||
z += quaternion.z;
|
z += quaternion.z;
|
||||||
|
@ -341,7 +341,7 @@ inline Quaternion& Quaternion::operator+=(const Quaternion& quaternion) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for substraction with assignment
|
// 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;
|
x -= quaternion.x;
|
||||||
y -= quaternion.y;
|
y -= quaternion.y;
|
||||||
z -= quaternion.z;
|
z -= quaternion.z;
|
||||||
|
@ -350,12 +350,12 @@ inline Quaternion& Quaternion::operator-=(const Quaternion& quaternion) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for the multiplication with a constant
|
// 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);
|
return Quaternion(nb * x, nb * y, nb * z, nb * w);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for the multiplication of two quaternions
|
// 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
|
/* The followin code is equivalent to this
|
||||||
return Quaternion(w * quaternion.w - getVectorV().dot(quaternion.getVectorV()),
|
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.
|
// Overloaded operator for the multiplication with a vector.
|
||||||
/// This methods rotates a point given the rotation of a quaternion.
|
/// 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
|
/* The following code is equivalent to this
|
||||||
* Quaternion p(point.x, point.y, point.z, 0.0);
|
* 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
|
// 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
|
// Check for self-assignment
|
||||||
if (this != &quaternion) {
|
if (this != &quaternion) {
|
||||||
|
@ -403,13 +403,13 @@ inline Quaternion& Quaternion::operator=(const Quaternion& quaternion) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for equality condition
|
// 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 &&
|
return (x == quaternion.x && y == quaternion.y &&
|
||||||
z == quaternion.z && w == quaternion.w);
|
z == quaternion.z && w == quaternion.w);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get the string representation
|
// 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) + "," +
|
return "Quaternion(" + std::to_string(x) + "," + std::to_string(y) + "," + std::to_string(z) + "," +
|
||||||
std::to_string(w) + ")";
|
std::to_string(w) + ")";
|
||||||
}
|
}
|
||||||
|
|
|
@ -125,62 +125,62 @@ class Transform {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Constructor
|
// 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
|
// 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)) {
|
: mPosition(position), mOrientation(Quaternion(orientation)) {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Constructor
|
// 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) {
|
: mPosition(position), mOrientation(orientation) {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Copy-constructor
|
// Copy-constructor
|
||||||
inline Transform::Transform(const Transform& transform)
|
RP3D_FORCE_INLINE Transform::Transform(const Transform& transform)
|
||||||
: mPosition(transform.mPosition), mOrientation(transform.mOrientation) {
|
: mPosition(transform.mPosition), mOrientation(transform.mOrientation) {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the position of the transform
|
// Return the position of the transform
|
||||||
inline const Vector3& Transform::getPosition() const {
|
RP3D_FORCE_INLINE const Vector3& Transform::getPosition() const {
|
||||||
return mPosition;
|
return mPosition;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the origin of the transform
|
// Set the origin of the transform
|
||||||
inline void Transform::setPosition(const Vector3& position) {
|
RP3D_FORCE_INLINE void Transform::setPosition(const Vector3& position) {
|
||||||
mPosition = position;
|
mPosition = position;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the rotation matrix
|
// Return the rotation matrix
|
||||||
inline const Quaternion& Transform::getOrientation() const {
|
RP3D_FORCE_INLINE const Quaternion& Transform::getOrientation() const {
|
||||||
return mOrientation;
|
return mOrientation;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the rotation matrix of the transform
|
// 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;
|
mOrientation = orientation;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the transform to the identity transform
|
// 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);
|
mPosition = Vector3(0.0, 0.0, 0.0);
|
||||||
mOrientation = Quaternion::identity();
|
mOrientation = Quaternion::identity();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the inverse of the transform
|
// Return the inverse of the transform
|
||||||
inline Transform Transform::getInverse() const {
|
RP3D_FORCE_INLINE Transform Transform::getInverse() const {
|
||||||
const Quaternion& invQuaternion = mOrientation.getInverse();
|
const Quaternion& invQuaternion = mOrientation.getInverse();
|
||||||
return Transform(invQuaternion * (-mPosition), invQuaternion);
|
return Transform(invQuaternion * (-mPosition), invQuaternion);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return an interpolated transform
|
// Return an interpolated transform
|
||||||
inline Transform Transform::interpolateTransforms(const Transform& oldTransform,
|
RP3D_FORCE_INLINE Transform Transform::interpolateTransforms(const Transform& oldTransform,
|
||||||
const Transform& newTransform,
|
const Transform& newTransform,
|
||||||
decimal interpolationFactor) {
|
decimal interpolationFactor) {
|
||||||
|
|
||||||
|
@ -195,22 +195,22 @@ inline Transform Transform::interpolateTransforms(const Transform& oldTransform,
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the identity transform
|
// Return the identity transform
|
||||||
inline Transform Transform::identity() {
|
RP3D_FORCE_INLINE Transform Transform::identity() {
|
||||||
return Transform(Vector3(0, 0, 0), Quaternion::identity());
|
return Transform(Vector3(0, 0, 0), Quaternion::identity());
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if it is a valid transform
|
// 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 mPosition.isFinite() && mOrientation.isValid();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the transformed vector
|
// 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;
|
return (mOrientation * vector) + mPosition;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Operator of multiplication of a transform with another one
|
// 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
|
// The following code is equivalent to this
|
||||||
//return Transform(mPosition + mOrientation * transform2.mPosition,
|
//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
|
// 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 (mPosition == transform2.mPosition) && (mOrientation == transform2.mOrientation);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the two transforms are different
|
// 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);
|
return !(*this == transform2);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Assignment operator
|
// Assignment operator
|
||||||
inline Transform& Transform::operator=(const Transform& transform) {
|
RP3D_FORCE_INLINE Transform& Transform::operator=(const Transform& transform) {
|
||||||
if (&transform != this) {
|
if (&transform != this) {
|
||||||
mPosition = transform.mPosition;
|
mPosition = transform.mPosition;
|
||||||
mOrientation = transform.mOrientation;
|
mOrientation = transform.mOrientation;
|
||||||
|
@ -258,7 +258,7 @@ inline Transform& Transform::operator=(const Transform& transform) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get the string representation
|
// 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() + ")";
|
return "Transform(" + mPosition.to_string() + "," + mOrientation.to_string() + ")";
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -161,50 +161,50 @@ struct Vector2 {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Constructor
|
// Constructor
|
||||||
inline Vector2::Vector2() : x(0.0), y(0.0) {
|
RP3D_FORCE_INLINE Vector2::Vector2() : x(0.0), y(0.0) {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Constructor with arguments
|
// 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
|
// 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
|
// Set the vector to zero
|
||||||
inline void Vector2::setToZero() {
|
RP3D_FORCE_INLINE void Vector2::setToZero() {
|
||||||
x = 0;
|
x = 0;
|
||||||
y = 0;
|
y = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set all the values of the vector
|
// 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;
|
x = newX;
|
||||||
y = newY;
|
y = newY;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the length of the vector
|
// 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 std::sqrt(x*x + y*y);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the square of the length of the vector
|
// 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;
|
return x*x + y*y;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Scalar product of two vectors (inline)
|
// Scalar product of two vectors (RP3D_FORCE_INLINE)
|
||||||
inline decimal Vector2::dot(const Vector2& vector) const {
|
RP3D_FORCE_INLINE decimal Vector2::dot(const Vector2& vector) const {
|
||||||
return (x*vector.x + y*vector.y);
|
return (x*vector.x + y*vector.y);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Normalize the vector
|
// Normalize the vector
|
||||||
inline void Vector2::normalize() {
|
RP3D_FORCE_INLINE void Vector2::normalize() {
|
||||||
decimal l = length();
|
decimal l = length();
|
||||||
if (l < MACHINE_EPSILON) {
|
if (l < MACHINE_EPSILON) {
|
||||||
return;
|
return;
|
||||||
|
@ -214,68 +214,68 @@ inline void Vector2::normalize() {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the corresponding absolute value vector
|
// 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 Vector2(std::abs(x), std::abs(y));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the axis with the minimal value
|
// 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 (x < y ? 0 : 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the axis with the maximal value
|
// 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 (x < y ? 1 : 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the vector is unit and false otherwise
|
// Return true if the vector is unit and false otherwise
|
||||||
inline bool Vector2::isUnit() const {
|
RP3D_FORCE_INLINE bool Vector2::isUnit() const {
|
||||||
return approxEqual(lengthSquare(), 1.0);
|
return approxEqual(lengthSquare(), 1.0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the values are not NAN OR INF
|
// 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 std::isfinite(x) && std::isfinite(y);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the vector is the zero vector
|
// Return true if the vector is the zero vector
|
||||||
inline bool Vector2::isZero() const {
|
RP3D_FORCE_INLINE bool Vector2::isZero() const {
|
||||||
return approxEqual(lengthSquare(), 0.0);
|
return approxEqual(lengthSquare(), 0.0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for the equality condition
|
// 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);
|
return (x == vector.x && y == vector.y);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for the is different condition
|
// 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);
|
return !(*this == vector);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for addition with assignment
|
// 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;
|
x += vector.x;
|
||||||
y += vector.y;
|
y += vector.y;
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for substraction with assignment
|
// 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;
|
x -= vector.x;
|
||||||
y -= vector.y;
|
y -= vector.y;
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for multiplication with a number with assignment
|
// 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;
|
x *= number;
|
||||||
y *= number;
|
y *= number;
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for division by a number with assignment
|
// 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());
|
assert(number > std::numeric_limits<decimal>::epsilon());
|
||||||
x /= number;
|
x /= number;
|
||||||
y /= number;
|
y /= number;
|
||||||
|
@ -283,60 +283,60 @@ inline Vector2& Vector2::operator/=(decimal number) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for value access
|
// Overloaded operator for value access
|
||||||
inline decimal& Vector2::operator[] (int index) {
|
RP3D_FORCE_INLINE decimal& Vector2::operator[] (int index) {
|
||||||
return (&x)[index];
|
return (&x)[index];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for value access
|
// 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];
|
return (&x)[index];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for addition
|
// 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);
|
return Vector2(vector1.x + vector2.x, vector1.y + vector2.y);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for substraction
|
// 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);
|
return Vector2(vector1.x - vector2.x, vector1.y - vector2.y);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for the negative of a vector
|
// 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);
|
return Vector2(-vector.x, -vector.y);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for multiplication with a number
|
// 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);
|
return Vector2(number * vector.x, number * vector.y);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for multiplication of two vectors
|
// 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);
|
return Vector2(vector1.x * vector2.x, vector1.y * vector2.y);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for division by a number
|
// 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);
|
assert(number > MACHINE_EPSILON);
|
||||||
return Vector2(vector.x / number, vector.y / number);
|
return Vector2(vector.x / number, vector.y / number);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overload operator for division between two vectors
|
// 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.x > MACHINE_EPSILON);
|
||||||
assert(vector2.y > MACHINE_EPSILON);
|
assert(vector2.y > MACHINE_EPSILON);
|
||||||
return Vector2(vector1.x / vector2.x, vector1.y / vector2.y);
|
return Vector2(vector1.x / vector2.x, vector1.y / vector2.y);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for multiplication with a number
|
// 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;
|
return vector * number;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Assignment operator
|
// Assignment operator
|
||||||
inline Vector2& Vector2::operator=(const Vector2& vector) {
|
RP3D_FORCE_INLINE Vector2& Vector2::operator=(const Vector2& vector) {
|
||||||
if (&vector != this) {
|
if (&vector != this) {
|
||||||
x = vector.x;
|
x = vector.x;
|
||||||
y = vector.y;
|
y = vector.y;
|
||||||
|
@ -345,29 +345,29 @@ inline Vector2& Vector2::operator=(const Vector2& vector) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded less than operator for ordering to be used inside std::set for instance
|
// 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 (x == vector.x ? y < vector.y : x < vector.x);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a vector taking the minimum components of two vectors
|
// 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),
|
return Vector2(std::min(vector1.x, vector2.x),
|
||||||
std::min(vector1.y, vector2.y));
|
std::min(vector1.y, vector2.y));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a vector taking the maximum components of two vectors
|
// 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),
|
return Vector2(std::max(vector1.x, vector2.x),
|
||||||
std::max(vector1.y, vector2.y));
|
std::max(vector1.y, vector2.y));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get the string representation
|
// 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 "Vector2(" + std::to_string(x) + "," + std::to_string(y) + ")";
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the zero vector
|
// Return the zero vector
|
||||||
inline Vector2 Vector2::zero() {
|
RP3D_FORCE_INLINE Vector2 Vector2::zero() {
|
||||||
return Vector2(0, 0);
|
return Vector2(0, 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -30,6 +30,7 @@
|
||||||
#include <cassert>
|
#include <cassert>
|
||||||
#include <reactphysics3d/mathematics/mathematics_functions.h>
|
#include <reactphysics3d/mathematics/mathematics_functions.h>
|
||||||
#include <reactphysics3d/decimal.h>
|
#include <reactphysics3d/decimal.h>
|
||||||
|
#include <reactphysics3d/configuration.h>
|
||||||
|
|
||||||
/// ReactPhysics3D namespace
|
/// ReactPhysics3D namespace
|
||||||
namespace reactphysics3d {
|
namespace reactphysics3d {
|
||||||
|
@ -173,58 +174,58 @@ struct Vector3 {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Constructor of the 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
|
// 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
|
// 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
|
// Set the vector to zero
|
||||||
inline void Vector3::setToZero() {
|
RP3D_FORCE_INLINE void Vector3::setToZero() {
|
||||||
x = 0;
|
x = 0;
|
||||||
y = 0;
|
y = 0;
|
||||||
z = 0;
|
z = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set all the values of the vector
|
// 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;
|
x = newX;
|
||||||
y = newY;
|
y = newY;
|
||||||
z = newZ;
|
z = newZ;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the length of the vector
|
// 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 std::sqrt(x*x + y*y + z*z);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the square of the length of the vector
|
// 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;
|
return x*x + y*y + z*z;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Scalar product of two vectors (inline)
|
// Scalar product of two vectors (RP3D_FORCE_INLINE)
|
||||||
inline decimal Vector3::dot(const Vector3& vector) const {
|
RP3D_FORCE_INLINE decimal Vector3::dot(const Vector3& vector) const {
|
||||||
return (x*vector.x + y*vector.y + z*vector.z);
|
return (x*vector.x + y*vector.y + z*vector.z);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Cross product of two vectors (inline)
|
// Cross product of two vectors (RP3D_FORCE_INLINE)
|
||||||
inline Vector3 Vector3::cross(const Vector3& vector) const {
|
RP3D_FORCE_INLINE Vector3 Vector3::cross(const Vector3& vector) const {
|
||||||
return Vector3(y * vector.z - z * vector.y,
|
return Vector3(y * vector.z - z * vector.y,
|
||||||
z * vector.x - x * vector.z,
|
z * vector.x - x * vector.z,
|
||||||
x * vector.y - y * vector.x);
|
x * vector.y - y * vector.x);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Normalize the vector
|
// Normalize the vector
|
||||||
inline void Vector3::normalize() {
|
RP3D_FORCE_INLINE void Vector3::normalize() {
|
||||||
decimal l = length();
|
decimal l = length();
|
||||||
if (l < MACHINE_EPSILON) {
|
if (l < MACHINE_EPSILON) {
|
||||||
return;
|
return;
|
||||||
|
@ -235,47 +236,47 @@ inline void Vector3::normalize() {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the corresponding absolute value vector
|
// 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 Vector3(std::abs(x), std::abs(y), std::abs(z));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the axis with the minimal value
|
// 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 (x < y ? (x < z ? 0 : 2) : (y < z ? 1 : 2));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the axis with the maximal value
|
// 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 (x < y ? (y < z ? 2 : 1) : (x < z ? 2 : 0));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the vector is unit and false otherwise
|
// Return true if the vector is unit and false otherwise
|
||||||
inline bool Vector3::isUnit() const {
|
RP3D_FORCE_INLINE bool Vector3::isUnit() const {
|
||||||
return approxEqual(lengthSquare(), 1.0);
|
return approxEqual(lengthSquare(), 1.0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the values are not NAN OR INF
|
// 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 std::isfinite(x) && std::isfinite(y) && std::isfinite(z);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if the vector is the zero vector
|
// Return true if the vector is the zero vector
|
||||||
inline bool Vector3::isZero() const {
|
RP3D_FORCE_INLINE bool Vector3::isZero() const {
|
||||||
return approxEqual(lengthSquare(), 0.0);
|
return approxEqual(lengthSquare(), 0.0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for the equality condition
|
// 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);
|
return (x == vector.x && y == vector.y && z == vector.z);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for the is different condition
|
// 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);
|
return !(*this == vector);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for addition with assignment
|
// 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;
|
x += vector.x;
|
||||||
y += vector.y;
|
y += vector.y;
|
||||||
z += vector.z;
|
z += vector.z;
|
||||||
|
@ -283,7 +284,7 @@ inline Vector3& Vector3::operator+=(const Vector3& vector) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for substraction with assignment
|
// 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;
|
x -= vector.x;
|
||||||
y -= vector.y;
|
y -= vector.y;
|
||||||
z -= vector.z;
|
z -= vector.z;
|
||||||
|
@ -291,7 +292,7 @@ inline Vector3& Vector3::operator-=(const Vector3& vector) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for multiplication with a number with assignment
|
// 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;
|
x *= number;
|
||||||
y *= number;
|
y *= number;
|
||||||
z *= number;
|
z *= number;
|
||||||
|
@ -299,7 +300,7 @@ inline Vector3& Vector3::operator*=(decimal number) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for division by a number with assignment
|
// 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());
|
assert(number > std::numeric_limits<decimal>::epsilon());
|
||||||
x /= number;
|
x /= number;
|
||||||
y /= number;
|
y /= number;
|
||||||
|
@ -308,43 +309,43 @@ inline Vector3& Vector3::operator/=(decimal number) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for value access
|
// Overloaded operator for value access
|
||||||
inline decimal& Vector3::operator[] (int index) {
|
RP3D_FORCE_INLINE decimal& Vector3::operator[] (int index) {
|
||||||
return (&x)[index];
|
return (&x)[index];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for value access
|
// 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];
|
return (&x)[index];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for addition
|
// 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);
|
return Vector3(vector1.x + vector2.x, vector1.y + vector2.y, vector1.z + vector2.z);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for substraction
|
// 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);
|
return Vector3(vector1.x - vector2.x, vector1.y - vector2.y, vector1.z - vector2.z);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for the negative of a vector
|
// 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);
|
return Vector3(-vector.x, -vector.y, -vector.z);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for multiplication with a number
|
// 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);
|
return Vector3(number * vector.x, number * vector.y, number * vector.z);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for division by a number
|
// 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);
|
assert(number > MACHINE_EPSILON);
|
||||||
return Vector3(vector.x / number, vector.y / number, vector.z / number);
|
return Vector3(vector.x / number, vector.y / number, vector.z / number);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overload operator for division between two vectors
|
// 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.x > MACHINE_EPSILON);
|
||||||
assert(vector2.y > MACHINE_EPSILON);
|
assert(vector2.y > MACHINE_EPSILON);
|
||||||
assert(vector2.z > MACHINE_EPSILON);
|
assert(vector2.z > MACHINE_EPSILON);
|
||||||
|
@ -352,17 +353,17 @@ inline Vector3 operator/(const Vector3& vector1, const Vector3& vector2) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded operator for multiplication with a number
|
// 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;
|
return vector * number;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overload operator for multiplication between two vectors
|
// 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);
|
return Vector3(vector1.x * vector2.x, vector1.y * vector2.y, vector1.z * vector2.z);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Assignment operator
|
// Assignment operator
|
||||||
inline Vector3& Vector3::operator=(const Vector3& vector) {
|
RP3D_FORCE_INLINE Vector3& Vector3::operator=(const Vector3& vector) {
|
||||||
if (&vector != this) {
|
if (&vector != this) {
|
||||||
x = vector.x;
|
x = vector.x;
|
||||||
y = vector.y;
|
y = vector.y;
|
||||||
|
@ -372,41 +373,41 @@ inline Vector3& Vector3::operator=(const Vector3& vector) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overloaded less than operator for ordering to be used inside std::set for instance
|
// 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 (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
|
// 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),
|
return Vector3(std::min(vector1.x, vector2.x),
|
||||||
std::min(vector1.y, vector2.y),
|
std::min(vector1.y, vector2.y),
|
||||||
std::min(vector1.z, vector2.z));
|
std::min(vector1.z, vector2.z));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a vector taking the maximum components of two vectors
|
// 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),
|
return Vector3(std::max(vector1.x, vector2.x),
|
||||||
std::max(vector1.y, vector2.y),
|
std::max(vector1.y, vector2.y),
|
||||||
std::max(vector1.z, vector2.z));
|
std::max(vector1.z, vector2.z));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the minimum value among the three components of a vector
|
// 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 std::min(std::min(x, y), z);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the maximum value among the three components of a vector
|
// 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);
|
return std::max(std::max(x, y), z);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get the string representation
|
// 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 "Vector3(" + std::to_string(x) + "," + std::to_string(y) + "," + std::to_string(z) + ")";
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the zero vector
|
// Return the zero vector
|
||||||
inline Vector3 Vector3::zero() {
|
RP3D_FORCE_INLINE Vector3 Vector3::zero() {
|
||||||
return Vector3(0, 0, 0);
|
return Vector3(0, 0, 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -44,7 +44,7 @@ struct Vector2;
|
||||||
|
|
||||||
/// Function to test if two real numbers are (almost) equal
|
/// 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]
|
/// 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) {
|
RP3D_FORCE_INLINE bool approxEqual(decimal a, decimal b, decimal epsilon = MACHINE_EPSILON) {
|
||||||
return (std::fabs(a - b) < epsilon);
|
return (std::fabs(a - b) < epsilon);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -56,30 +56,30 @@ bool approxEqual(const Vector2& vec1, const Vector2& vec2, decimal epsilon = MAC
|
||||||
|
|
||||||
/// Function that returns the result of the "value" clamped by
|
/// Function that returns the result of the "value" clamped by
|
||||||
/// two others values "lowerLimit" and "upperLimit"
|
/// 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);
|
assert(lowerLimit <= upperLimit);
|
||||||
return std::min(std::max(value, lowerLimit), upperLimit);
|
return std::min(std::max(value, lowerLimit), upperLimit);
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Function that returns the result of the "value" clamped by
|
/// Function that returns the result of the "value" clamped by
|
||||||
/// two others values "lowerLimit" and "upperLimit"
|
/// 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);
|
assert(lowerLimit <= upperLimit);
|
||||||
return std::min(std::max(value, lowerLimit), upperLimit);
|
return std::min(std::max(value, lowerLimit), upperLimit);
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Return the minimum value among three values
|
/// 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 std::min(std::min(a, b), c);
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Return the maximum value among three values
|
/// 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 std::max(std::max(a, b), c);
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Return true if two values have the same sign
|
/// 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 a * b >= decimal(0.0);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -102,7 +102,7 @@ class MemoryManager {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Allocate memory of a given type
|
// 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) {
|
switch (allocationType) {
|
||||||
case AllocationType::Base: return mBaseAllocator->allocate(size);
|
case AllocationType::Base: return mBaseAllocator->allocate(size);
|
||||||
|
@ -115,7 +115,7 @@ inline void* MemoryManager::allocate(AllocationType allocationType, size_t size)
|
||||||
}
|
}
|
||||||
|
|
||||||
// Release previously allocated memory.
|
// 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) {
|
switch (allocationType) {
|
||||||
case AllocationType::Base: mBaseAllocator->release(pointer, size); break;
|
case AllocationType::Base: mBaseAllocator->release(pointer, size); break;
|
||||||
|
@ -126,22 +126,22 @@ inline void MemoryManager::release(AllocationType allocationType, void* pointer,
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the pool allocator
|
// Return the pool allocator
|
||||||
inline PoolAllocator& MemoryManager::getPoolAllocator() {
|
RP3D_FORCE_INLINE PoolAllocator& MemoryManager::getPoolAllocator() {
|
||||||
return mPoolAllocator;
|
return mPoolAllocator;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the single frame stack allocator
|
// Return the single frame stack allocator
|
||||||
inline SingleFrameAllocator& MemoryManager::getSingleFrameAllocator() {
|
RP3D_FORCE_INLINE SingleFrameAllocator& MemoryManager::getSingleFrameAllocator() {
|
||||||
return mSingleFrameAllocator;
|
return mSingleFrameAllocator;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the heap allocator
|
// Return the heap allocator
|
||||||
inline HeapAllocator& MemoryManager::getHeapAllocator() {
|
RP3D_FORCE_INLINE HeapAllocator& MemoryManager::getHeapAllocator() {
|
||||||
return mHeapAllocator;
|
return mHeapAllocator;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Reset the single frame allocator
|
// Reset the single frame allocator
|
||||||
inline void MemoryManager::resetFrameAllocator() {
|
RP3D_FORCE_INLINE void MemoryManager::resetFrameAllocator() {
|
||||||
mSingleFrameAllocator.reset();
|
mSingleFrameAllocator.reset();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -208,27 +208,27 @@ class BroadPhaseSystem {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return the fat AABB of a given broad-phase shape
|
// 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);
|
return mDynamicAABBTree.getFatAABB(broadPhaseId);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Remove a collider from the array of colliders that have moved in the last simulation step
|
// 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.
|
// 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
|
// Remove the broad-phase ID from the set
|
||||||
mMovedShapes.remove(broadPhaseID);
|
mMovedShapes.remove(broadPhaseID);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the collider corresponding to the broad-phase node id in parameter
|
// 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));
|
return static_cast<Collider*>(mDynamicAABBTree.getNodeDataPointer(broadPhaseId));
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef IS_RP3D_PROFILING_ENABLED
|
#ifdef IS_RP3D_PROFILING_ENABLED
|
||||||
|
|
||||||
// Set the profiler
|
// Set the profiler
|
||||||
inline void BroadPhaseSystem::setProfiler(Profiler* profiler) {
|
RP3D_FORCE_INLINE void BroadPhaseSystem::setProfiler(Profiler* profiler) {
|
||||||
mProfiler = profiler;
|
mProfiler = profiler;
|
||||||
mDynamicAABBTree.setProfiler(profiler);
|
mDynamicAABBTree.setProfiler(profiler);
|
||||||
}
|
}
|
||||||
|
|
|
@ -373,12 +373,12 @@ class CollisionDetectionSystem {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return a reference to the collision dispatch configuration
|
// Return a reference to the collision dispatch configuration
|
||||||
inline CollisionDispatch& CollisionDetectionSystem::getCollisionDispatch() {
|
RP3D_FORCE_INLINE CollisionDispatch& CollisionDetectionSystem::getCollisionDispatch() {
|
||||||
return mCollisionDispatch;
|
return mCollisionDispatch;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Add a body to the collision detection
|
// 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
|
// Add the body to the broad-phase
|
||||||
mBroadPhaseSystem.addCollider(collider, aabb);
|
mBroadPhaseSystem.addCollider(collider, aabb);
|
||||||
|
@ -392,19 +392,19 @@ inline void CollisionDetectionSystem::addCollider(Collider* collider, const AABB
|
||||||
}
|
}
|
||||||
|
|
||||||
// Add a pair of bodies that cannot collide with each other
|
// 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));
|
mNoCollisionPairs.add(OverlappingPairs::computeBodiesIndexPair(body1Entity, body2Entity));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Remove a pair of bodies that cannot collide with each other
|
// 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));
|
mNoCollisionPairs.remove(OverlappingPairs::computeBodiesIndexPair(body1Entity, body2Entity));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Ask for a collision shape to be tested again during broad-phase.
|
// 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 list of collision shape that have moved in the
|
||||||
/// previous frame so that it is tested for collision again in the broad-phase.
|
/// 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) {
|
if (collider->getBroadPhaseId() != -1) {
|
||||||
mBroadPhaseSystem.addMovedCollider(collider->getBroadPhaseId(), collider);
|
mBroadPhaseSystem.addMovedCollider(collider->getBroadPhaseId(), collider);
|
||||||
|
@ -412,31 +412,31 @@ inline void CollisionDetectionSystem::askForBroadPhaseCollisionCheck(Collider* c
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a pointer to the world
|
// Return a pointer to the world
|
||||||
inline PhysicsWorld* CollisionDetectionSystem::getWorld() {
|
RP3D_FORCE_INLINE PhysicsWorld* CollisionDetectionSystem::getWorld() {
|
||||||
return mWorld;
|
return mWorld;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a reference to the memory manager
|
// Return a reference to the memory manager
|
||||||
inline MemoryManager& CollisionDetectionSystem::getMemoryManager() const {
|
RP3D_FORCE_INLINE MemoryManager& CollisionDetectionSystem::getMemoryManager() const {
|
||||||
return mMemoryManager;
|
return mMemoryManager;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Update a collider (that has moved for instance)
|
// 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
|
// Update the collider component
|
||||||
mBroadPhaseSystem.updateCollider(colliderEntity, timeStep);
|
mBroadPhaseSystem.updateCollider(colliderEntity, timeStep);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Update all the enabled colliders
|
// Update all the enabled colliders
|
||||||
inline void CollisionDetectionSystem::updateColliders(decimal timeStep) {
|
RP3D_FORCE_INLINE void CollisionDetectionSystem::updateColliders(decimal timeStep) {
|
||||||
mBroadPhaseSystem.updateColliders(timeStep);
|
mBroadPhaseSystem.updateColliders(timeStep);
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef IS_RP3D_PROFILING_ENABLED
|
#ifdef IS_RP3D_PROFILING_ENABLED
|
||||||
|
|
||||||
// Set the profiler
|
// Set the profiler
|
||||||
inline void CollisionDetectionSystem::setProfiler(Profiler* profiler) {
|
RP3D_FORCE_INLINE void CollisionDetectionSystem::setProfiler(Profiler* profiler) {
|
||||||
mProfiler = profiler;
|
mProfiler = profiler;
|
||||||
mBroadPhaseSystem.setProfiler(profiler);
|
mBroadPhaseSystem.setProfiler(profiler);
|
||||||
mCollisionDispatch.setProfiler(profiler);
|
mCollisionDispatch.setProfiler(profiler);
|
||||||
|
|
|
@ -215,7 +215,7 @@ class ConstraintSolverSystem {
|
||||||
#ifdef IS_RP3D_PROFILING_ENABLED
|
#ifdef IS_RP3D_PROFILING_ENABLED
|
||||||
|
|
||||||
// Set the profiler
|
// Set the profiler
|
||||||
inline void ConstraintSolverSystem::setProfiler(Profiler* profiler) {
|
RP3D_FORCE_INLINE void ConstraintSolverSystem::setProfiler(Profiler* profiler) {
|
||||||
mProfiler = profiler;
|
mProfiler = profiler;
|
||||||
mSolveBallAndSocketJointSystem.setProfiler(profiler);
|
mSolveBallAndSocketJointSystem.setProfiler(profiler);
|
||||||
mSolveFixedJointSystem.setProfiler(profiler);
|
mSolveFixedJointSystem.setProfiler(profiler);
|
||||||
|
|
|
@ -398,19 +398,19 @@ class ContactSolverSystem {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Return true if the split impulses position correction technique is used for contacts
|
// 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;
|
return mIsSplitImpulseActive;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Activate or Deactivate the split impulses for contacts
|
// Activate or Deactivate the split impulses for contacts
|
||||||
inline void ContactSolverSystem::setIsSplitImpulseActive(bool isActive) {
|
RP3D_FORCE_INLINE void ContactSolverSystem::setIsSplitImpulseActive(bool isActive) {
|
||||||
mIsSplitImpulseActive = isActive;
|
mIsSplitImpulseActive = isActive;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef IS_RP3D_PROFILING_ENABLED
|
#ifdef IS_RP3D_PROFILING_ENABLED
|
||||||
|
|
||||||
// Set the profiler
|
// Set the profiler
|
||||||
inline void ContactSolverSystem::setProfiler(Profiler* profiler) {
|
RP3D_FORCE_INLINE void ContactSolverSystem::setProfiler(Profiler* profiler) {
|
||||||
|
|
||||||
mProfiler = profiler;
|
mProfiler = profiler;
|
||||||
}
|
}
|
||||||
|
|
|
@ -114,7 +114,7 @@ class DynamicsSystem {
|
||||||
#ifdef IS_RP3D_PROFILING_ENABLED
|
#ifdef IS_RP3D_PROFILING_ENABLED
|
||||||
|
|
||||||
// Set the profiler
|
// Set the profiler
|
||||||
inline void DynamicsSystem::setProfiler(Profiler* profiler) {
|
RP3D_FORCE_INLINE void DynamicsSystem::setProfiler(Profiler* profiler) {
|
||||||
mProfiler = profiler;
|
mProfiler = profiler;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -123,20 +123,20 @@ class SolveBallAndSocketJointSystem {
|
||||||
#ifdef IS_RP3D_PROFILING_ENABLED
|
#ifdef IS_RP3D_PROFILING_ENABLED
|
||||||
|
|
||||||
// Set the profiler
|
// Set the profiler
|
||||||
inline void SolveBallAndSocketJointSystem::setProfiler(Profiler* profiler) {
|
RP3D_FORCE_INLINE void SolveBallAndSocketJointSystem::setProfiler(Profiler* profiler) {
|
||||||
mProfiler = profiler;
|
mProfiler = profiler;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Set the time step
|
// Set the time step
|
||||||
inline void SolveBallAndSocketJointSystem::setTimeStep(decimal timeStep) {
|
RP3D_FORCE_INLINE void SolveBallAndSocketJointSystem::setTimeStep(decimal timeStep) {
|
||||||
assert(timeStep > decimal(0.0));
|
assert(timeStep > decimal(0.0));
|
||||||
mTimeStep = timeStep;
|
mTimeStep = timeStep;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set to true to enable warm starting
|
// Set to true to enable warm starting
|
||||||
inline void SolveBallAndSocketJointSystem::setIsWarmStartingActive(bool isWarmStartingActive) {
|
RP3D_FORCE_INLINE void SolveBallAndSocketJointSystem::setIsWarmStartingActive(bool isWarmStartingActive) {
|
||||||
mIsWarmStartingActive = isWarmStartingActive;
|
mIsWarmStartingActive = isWarmStartingActive;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -120,20 +120,20 @@ class SolveFixedJointSystem {
|
||||||
#ifdef IS_RP3D_PROFILING_ENABLED
|
#ifdef IS_RP3D_PROFILING_ENABLED
|
||||||
|
|
||||||
// Set the profiler
|
// Set the profiler
|
||||||
inline void SolveFixedJointSystem::setProfiler(Profiler* profiler) {
|
RP3D_FORCE_INLINE void SolveFixedJointSystem::setProfiler(Profiler* profiler) {
|
||||||
mProfiler = profiler;
|
mProfiler = profiler;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Set the time step
|
// Set the time step
|
||||||
inline void SolveFixedJointSystem::setTimeStep(decimal timeStep) {
|
RP3D_FORCE_INLINE void SolveFixedJointSystem::setTimeStep(decimal timeStep) {
|
||||||
assert(timeStep > decimal(0.0));
|
assert(timeStep > decimal(0.0));
|
||||||
mTimeStep = timeStep;
|
mTimeStep = timeStep;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set to true to enable warm starting
|
// Set to true to enable warm starting
|
||||||
inline void SolveFixedJointSystem::setIsWarmStartingActive(bool isWarmStartingActive) {
|
RP3D_FORCE_INLINE void SolveFixedJointSystem::setIsWarmStartingActive(bool isWarmStartingActive) {
|
||||||
mIsWarmStartingActive = isWarmStartingActive;
|
mIsWarmStartingActive = isWarmStartingActive;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -138,20 +138,20 @@ class SolveHingeJointSystem {
|
||||||
#ifdef IS_RP3D_PROFILING_ENABLED
|
#ifdef IS_RP3D_PROFILING_ENABLED
|
||||||
|
|
||||||
// Set the profiler
|
// Set the profiler
|
||||||
inline void SolveHingeJointSystem::setProfiler(Profiler* profiler) {
|
RP3D_FORCE_INLINE void SolveHingeJointSystem::setProfiler(Profiler* profiler) {
|
||||||
mProfiler = profiler;
|
mProfiler = profiler;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Set the time step
|
// Set the time step
|
||||||
inline void SolveHingeJointSystem::setTimeStep(decimal timeStep) {
|
RP3D_FORCE_INLINE void SolveHingeJointSystem::setTimeStep(decimal timeStep) {
|
||||||
assert(timeStep > decimal(0.0));
|
assert(timeStep > decimal(0.0));
|
||||||
mTimeStep = timeStep;
|
mTimeStep = timeStep;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set to true to enable warm starting
|
// Set to true to enable warm starting
|
||||||
inline void SolveHingeJointSystem::setIsWarmStartingActive(bool isWarmStartingActive) {
|
RP3D_FORCE_INLINE void SolveHingeJointSystem::setIsWarmStartingActive(bool isWarmStartingActive) {
|
||||||
mIsWarmStartingActive = isWarmStartingActive;
|
mIsWarmStartingActive = isWarmStartingActive;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -124,20 +124,20 @@ class SolveSliderJointSystem {
|
||||||
#ifdef IS_RP3D_PROFILING_ENABLED
|
#ifdef IS_RP3D_PROFILING_ENABLED
|
||||||
|
|
||||||
// Set the profiler
|
// Set the profiler
|
||||||
inline void SolveSliderJointSystem::setProfiler(Profiler* profiler) {
|
RP3D_FORCE_INLINE void SolveSliderJointSystem::setProfiler(Profiler* profiler) {
|
||||||
mProfiler = profiler;
|
mProfiler = profiler;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Set the time step
|
// Set the time step
|
||||||
inline void SolveSliderJointSystem::setTimeStep(decimal timeStep) {
|
RP3D_FORCE_INLINE void SolveSliderJointSystem::setTimeStep(decimal timeStep) {
|
||||||
assert(timeStep > decimal(0.0));
|
assert(timeStep > decimal(0.0));
|
||||||
mTimeStep = timeStep;
|
mTimeStep = timeStep;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set to true to enable warm starting
|
// Set to true to enable warm starting
|
||||||
inline void SolveSliderJointSystem::setIsWarmStartingActive(bool isWarmStartingActive) {
|
RP3D_FORCE_INLINE void SolveSliderJointSystem::setIsWarmStartingActive(bool isWarmStartingActive) {
|
||||||
mIsWarmStartingActive = isWarmStartingActive;
|
mIsWarmStartingActive = isWarmStartingActive;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -263,7 +263,7 @@ class DebugRenderer : public EventListener {
|
||||||
/**
|
/**
|
||||||
* @return The number of lines in the array of lines to draw
|
* @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 mLines.size();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -271,7 +271,7 @@ inline uint32 DebugRenderer::getNbLines() const {
|
||||||
/**
|
/**
|
||||||
* @return The list of lines to draw
|
* @return The list of lines to draw
|
||||||
*/
|
*/
|
||||||
inline const List<DebugRenderer::DebugLine>& DebugRenderer::getLines() const {
|
RP3D_FORCE_INLINE const List<DebugRenderer::DebugLine>& DebugRenderer::getLines() const {
|
||||||
return mLines;
|
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
|
* @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]);
|
return &(mLines[0]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -287,7 +287,7 @@ inline const DebugRenderer::DebugLine* DebugRenderer::getLinesArray() const {
|
||||||
/**
|
/**
|
||||||
* @return The number of triangles in the array of triangles to draw
|
* @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 mTriangles.size();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -295,7 +295,7 @@ inline uint32 DebugRenderer::getNbTriangles() const {
|
||||||
/**
|
/**
|
||||||
* @return The list of triangles to draw
|
* @return The list of triangles to draw
|
||||||
*/
|
*/
|
||||||
inline const List<DebugRenderer::DebugTriangle>& DebugRenderer::getTriangles() const {
|
RP3D_FORCE_INLINE const List<DebugRenderer::DebugTriangle>& DebugRenderer::getTriangles() const {
|
||||||
return mTriangles;
|
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
|
* @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]);
|
return &(mTriangles[0]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -312,7 +312,7 @@ inline const DebugRenderer::DebugTriangle* DebugRenderer::getTrianglesArray() co
|
||||||
* @param item A debug item
|
* @param item A debug item
|
||||||
* @return True if the given debug item is being displayed and false otherwise
|
* @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);
|
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 item A debug item to draw
|
||||||
* @param isDisplayed True if the given debug item has to be displayed and false otherwise
|
* @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);
|
const uint32 itemFlag = static_cast<uint32>(item);
|
||||||
uint32 resetBit = ~(itemFlag);
|
uint32 resetBit = ~(itemFlag);
|
||||||
mDisplayedDebugItems &= resetBit;
|
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
|
* @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;
|
return mContactPointSphereRadius;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -342,7 +342,7 @@ inline decimal DebugRenderer::getContactPointSphereRadius() const {
|
||||||
/**
|
/**
|
||||||
* @param radius The radius of the sphere used to display a contact point
|
* @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));
|
assert(radius > decimal(0.0));
|
||||||
mContactPointSphereRadius = radius;
|
mContactPointSphereRadius = radius;
|
||||||
}
|
}
|
||||||
|
@ -352,7 +352,7 @@ inline void DebugRenderer::setContactPointSphereRadius(decimal radius) {
|
||||||
/**
|
/**
|
||||||
* @return The length of the contact normal to display
|
* @return The length of the contact normal to display
|
||||||
*/
|
*/
|
||||||
inline decimal DebugRenderer::getContactNormalLength() const {
|
RP3D_FORCE_INLINE decimal DebugRenderer::getContactNormalLength() const {
|
||||||
return mContactNormalLength;
|
return mContactNormalLength;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -360,7 +360,7 @@ inline decimal DebugRenderer::getContactNormalLength() const {
|
||||||
/**
|
/**
|
||||||
* @param contactNormalLength The length of the contact normal to display
|
* @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;
|
mContactNormalLength = contactNormalLength;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -401,113 +401,113 @@ class ProfileSample {
|
||||||
#define RP3D_PROFILE(name, profiler) ProfileSample profileSample(name, profiler)
|
#define RP3D_PROFILE(name, profiler) ProfileSample profileSample(name, profiler)
|
||||||
|
|
||||||
// Return true if we are at the root of the profiler tree
|
// 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 (mCurrentParentNode->getParentNode() == nullptr);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if we are at the end of a branch of the profiler tree
|
// 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 (mCurrentChildNode == nullptr);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the name of the current node
|
// Return the name of the current node
|
||||||
inline const char* ProfileNodeIterator::getCurrentName() {
|
RP3D_FORCE_INLINE const char* ProfileNodeIterator::getCurrentName() {
|
||||||
return mCurrentChildNode->getName();
|
return mCurrentChildNode->getName();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the total time of the current node
|
// Return the total time of the current node
|
||||||
inline long double ProfileNodeIterator::getCurrentTotalTime() {
|
RP3D_FORCE_INLINE long double ProfileNodeIterator::getCurrentTotalTime() {
|
||||||
return mCurrentChildNode->getTotalTime();
|
return mCurrentChildNode->getTotalTime();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the total number of calls of the current node
|
// Return the total number of calls of the current node
|
||||||
inline uint ProfileNodeIterator::getCurrentNbTotalCalls() {
|
RP3D_FORCE_INLINE uint ProfileNodeIterator::getCurrentNbTotalCalls() {
|
||||||
return mCurrentChildNode->getNbTotalCalls();
|
return mCurrentChildNode->getNbTotalCalls();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the name of the current parent node
|
// Return the name of the current parent node
|
||||||
inline const char* ProfileNodeIterator::getCurrentParentName() {
|
RP3D_FORCE_INLINE const char* ProfileNodeIterator::getCurrentParentName() {
|
||||||
return mCurrentParentNode->getName();
|
return mCurrentParentNode->getName();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the total time of the current parent node
|
// 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 mCurrentParentNode->getTotalTime();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the total number of calls of the current parent node
|
// Return the total number of calls of the current parent node
|
||||||
inline uint ProfileNodeIterator::getCurrentParentNbTotalCalls() {
|
RP3D_FORCE_INLINE uint ProfileNodeIterator::getCurrentParentNbTotalCalls() {
|
||||||
return mCurrentParentNode->getNbTotalCalls();
|
return mCurrentParentNode->getNbTotalCalls();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Go to the first node
|
// Go to the first node
|
||||||
inline void ProfileNodeIterator::first() {
|
RP3D_FORCE_INLINE void ProfileNodeIterator::first() {
|
||||||
mCurrentChildNode = mCurrentParentNode->getChildNode();
|
mCurrentChildNode = mCurrentParentNode->getChildNode();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Go to the next node
|
// Go to the next node
|
||||||
inline void ProfileNodeIterator::next() {
|
RP3D_FORCE_INLINE void ProfileNodeIterator::next() {
|
||||||
mCurrentChildNode = mCurrentChildNode->getSiblingNode();
|
mCurrentChildNode = mCurrentChildNode->getSiblingNode();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a pointer to the parent node
|
// Return a pointer to the parent node
|
||||||
inline ProfileNode* ProfileNode::getParentNode() {
|
RP3D_FORCE_INLINE ProfileNode* ProfileNode::getParentNode() {
|
||||||
return mParentNode;
|
return mParentNode;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a pointer to a sibling node
|
// Return a pointer to a sibling node
|
||||||
inline ProfileNode* ProfileNode::getSiblingNode() {
|
RP3D_FORCE_INLINE ProfileNode* ProfileNode::getSiblingNode() {
|
||||||
return mSiblingNode;
|
return mSiblingNode;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a pointer to a child node
|
// Return a pointer to a child node
|
||||||
inline ProfileNode* ProfileNode::getChildNode() {
|
RP3D_FORCE_INLINE ProfileNode* ProfileNode::getChildNode() {
|
||||||
return mChildNode;
|
return mChildNode;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the name of the node
|
// Return the name of the node
|
||||||
inline const char* ProfileNode::getName() {
|
RP3D_FORCE_INLINE const char* ProfileNode::getName() {
|
||||||
return mName;
|
return mName;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the total number of call of the corresponding block of code
|
// 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 mNbTotalCalls;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the total time spent in the block of code
|
// 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 mTotalTime;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the number of frames
|
// Return the number of frames
|
||||||
inline uint Profiler::getNbFrames() {
|
RP3D_FORCE_INLINE uint Profiler::getNbFrames() {
|
||||||
return mFrameCounter;
|
return mFrameCounter;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the elasped time since the start/reset of the profiling
|
// 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;
|
long double currentTime = Timer::getCurrentSystemTime() * 1000.0L;
|
||||||
return currentTime - mProfilingStartTime;
|
return currentTime - mProfilingStartTime;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Increment the frame counter
|
// Increment the frame counter
|
||||||
inline void Profiler::incrementFrameCounter() {
|
RP3D_FORCE_INLINE void Profiler::incrementFrameCounter() {
|
||||||
mFrameCounter++;
|
mFrameCounter++;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return an iterator over the profiler tree starting at the root
|
// 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);
|
return new ProfileNodeIterator(&mRootNode);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Destroy a previously allocated iterator
|
// Destroy a previously allocated iterator
|
||||||
inline void Profiler::destroyIterator(ProfileNodeIterator* iterator) {
|
RP3D_FORCE_INLINE void Profiler::destroyIterator(ProfileNodeIterator* iterator) {
|
||||||
delete iterator;
|
delete iterator;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Destroy the profiler (release the memory)
|
// Destroy the profiler (release the memory)
|
||||||
inline void Profiler::destroy() {
|
RP3D_FORCE_INLINE void Profiler::destroy() {
|
||||||
mRootNode.destroy();
|
mRootNode.destroy();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -43,43 +43,6 @@ NarrowPhaseInfoBatch::~NarrowPhaseInfoBatch() {
|
||||||
clear();
|
clear();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Add shapes to be tested during narrow-phase collision detection into the batch
|
|
||||||
void NarrowPhaseInfoBatch::addNarrowPhaseInfo(uint64 pairId, uint64 pairIndex, Entity collider1, Entity collider2, CollisionShape* shape1,
|
|
||||||
CollisionShape* shape2, const Transform& shape1Transform, const Transform& shape2Transform,
|
|
||||||
bool needToReportContacts, MemoryAllocator& shapeAllocator) {
|
|
||||||
|
|
||||||
// Add a collision info for the two collision shapes into the overlapping pair (if not present yet)
|
|
||||||
// TODO OPTI : Can we better manage this
|
|
||||||
LastFrameCollisionInfo* lastFrameInfo = mOverlappingPairs.addLastFrameInfoIfNecessary(pairIndex, shape1->getId(), shape2->getId());
|
|
||||||
|
|
||||||
// Create a meta data object
|
|
||||||
narrowPhaseInfos.emplace(pairId, collider1, collider2, lastFrameInfo, shapeAllocator, shape1Transform, shape2Transform, shape1, shape2, needToReportContacts);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Add a new contact point
|
|
||||||
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
|
|
||||||
void NarrowPhaseInfoBatch::resetContactPoints(uint index) {
|
|
||||||
|
|
||||||
narrowPhaseInfos[index].nbContactPoints = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Initialize the containers using cached capacity
|
// Initialize the containers using cached capacity
|
||||||
void NarrowPhaseInfoBatch::reserveMemory() {
|
void NarrowPhaseInfoBatch::reserveMemory() {
|
||||||
|
|
||||||
|
|
|
@ -25,7 +25,6 @@
|
||||||
|
|
||||||
// Libraries
|
// Libraries
|
||||||
#include <reactphysics3d/collision/narrowphase/NarrowPhaseInput.h>
|
#include <reactphysics3d/collision/narrowphase/NarrowPhaseInput.h>
|
||||||
#include <reactphysics3d/collision/narrowphase/CollisionDispatch.h>
|
|
||||||
|
|
||||||
using namespace reactphysics3d;
|
using namespace reactphysics3d;
|
||||||
|
|
||||||
|
@ -38,37 +37,6 @@ NarrowPhaseInput::NarrowPhaseInput(MemoryAllocator& allocator, OverlappingPairs&
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Add shapes to be tested during narrow-phase collision detection into the batch
|
|
||||||
void NarrowPhaseInput::addNarrowPhaseTest(uint64 pairId, uint64 pairIndex, Entity collider1, Entity collider2, CollisionShape* shape1, CollisionShape* shape2,
|
|
||||||
const Transform& shape1Transform, const Transform& shape2Transform,
|
|
||||||
NarrowPhaseAlgorithmType narrowPhaseAlgorithmType, bool reportContacts, MemoryAllocator& shapeAllocator) {
|
|
||||||
|
|
||||||
switch (narrowPhaseAlgorithmType) {
|
|
||||||
case NarrowPhaseAlgorithmType::SphereVsSphere:
|
|
||||||
mSphereVsSphereBatch.addNarrowPhaseInfo(pairId, pairIndex, collider1, collider2, shape1, shape2, shape1Transform, shape2Transform, reportContacts, shapeAllocator);
|
|
||||||
break;
|
|
||||||
case NarrowPhaseAlgorithmType::SphereVsCapsule:
|
|
||||||
mSphereVsCapsuleBatch.addNarrowPhaseInfo(pairId, pairIndex, collider1, collider2, shape1, shape2, shape1Transform, shape2Transform, reportContacts, shapeAllocator);
|
|
||||||
break;
|
|
||||||
case NarrowPhaseAlgorithmType::CapsuleVsCapsule:
|
|
||||||
mCapsuleVsCapsuleBatch.addNarrowPhaseInfo(pairId, pairIndex, collider1, collider2, shape1, shape2, shape1Transform, shape2Transform, reportContacts, shapeAllocator);
|
|
||||||
break;
|
|
||||||
case NarrowPhaseAlgorithmType::SphereVsConvexPolyhedron:
|
|
||||||
mSphereVsConvexPolyhedronBatch.addNarrowPhaseInfo(pairId, pairIndex, collider1, collider2, shape1, shape2, shape1Transform, shape2Transform, reportContacts, shapeAllocator);
|
|
||||||
break;
|
|
||||||
case NarrowPhaseAlgorithmType::CapsuleVsConvexPolyhedron:
|
|
||||||
mCapsuleVsConvexPolyhedronBatch.addNarrowPhaseInfo(pairId, pairIndex, collider1, collider2, shape1, shape2, shape1Transform, shape2Transform, reportContacts, shapeAllocator);
|
|
||||||
break;
|
|
||||||
case NarrowPhaseAlgorithmType::ConvexPolyhedronVsConvexPolyhedron:
|
|
||||||
mConvexPolyhedronVsConvexPolyhedronBatch.addNarrowPhaseInfo(pairId, pairIndex, collider1, collider2, shape1, shape2, shape1Transform, shape2Transform, reportContacts, shapeAllocator);
|
|
||||||
break;
|
|
||||||
case NarrowPhaseAlgorithmType::None:
|
|
||||||
// Must never happen
|
|
||||||
assert(false);
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/// Reserve memory for the containers with cached capacity
|
/// Reserve memory for the containers with cached capacity
|
||||||
void NarrowPhaseInput::reserveMemory() {
|
void NarrowPhaseInput::reserveMemory() {
|
||||||
|
|
||||||
|
|
|
@ -818,7 +818,7 @@ decimal ContactSolverSystem::computeMixedFrictionCoefficient(Collider* collider1
|
||||||
}
|
}
|
||||||
|
|
||||||
// Compute th mixed rolling resistance factor between two colliders
|
// Compute th mixed rolling resistance factor between two colliders
|
||||||
inline decimal ContactSolverSystem::computeMixedRollingResistance(Collider* collider1, Collider* collider2) const {
|
RP3D_FORCE_INLINE decimal ContactSolverSystem::computeMixedRollingResistance(Collider* collider1, Collider* collider2) const {
|
||||||
return decimal(0.5f) * (collider1->getMaterial().getRollingResistance() + collider2->getMaterial().getRollingResistance());
|
return decimal(0.5f) * (collider1->getMaterial().getRollingResistance() + collider2->getMaterial().getRollingResistance());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue
Block a user